From 8f6b62b18454a1c9a0807ff100e2470d047d9a5a Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Wed, 22 Nov 2023 13:51:50 +0800 Subject: [PATCH 001/128] refactor(operation_mode_transition_manager): rework parameters (#5601) * refactor(operation_mode_transition_manager): rework parameters Signed-off-by: PhoebeWu21 * refactor(operation_mode_transition_manager): rework parameters Signed-off-by: PhoebeWu21 * refactor(operation_mode_transition_manager): rework parameters Signed-off-by: PhoebeWu21 --------- Signed-off-by: PhoebeWu21 --- .../README.md | 2 + ...ration_mode_transition_manager.schema.json | 168 ++++++++++++++++++ 2 files changed, 170 insertions(+) create mode 100644 control/operation_mode_transition_manager/schema/operation_mode_transition_manager.schema.json diff --git a/control/operation_mode_transition_manager/README.md b/control/operation_mode_transition_manager/README.md index 3cb07a9bd7821..ea0688e88d9f1 100644 --- a/control/operation_mode_transition_manager/README.md +++ b/control/operation_mode_transition_manager/README.md @@ -83,6 +83,8 @@ For the backward compatibility (to be removed): ## Parameters +{{ json_to_markdown("control/operation_mode_transition_manager/schema/operation_mode_transition_manager.schema.json") }} + | Name | Type | Description | Default value | | :--------------------------------- | :------- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | | `transition_timeout` | `double` | If the state transition is not completed within this time, it is considered a transition failure. | 10.0 | diff --git a/control/operation_mode_transition_manager/schema/operation_mode_transition_manager.schema.json b/control/operation_mode_transition_manager/schema/operation_mode_transition_manager.schema.json new file mode 100644 index 0000000000000..8ce8eda4c6c1c --- /dev/null +++ b/control/operation_mode_transition_manager/schema/operation_mode_transition_manager.schema.json @@ -0,0 +1,168 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Operation Mode Transition Manager Node", + "type": "object", + "definitions": { + "operation_mode_transition_manager": { + "type": "object", + "properties": { + "transition_timeout": { + "type": "number", + "description": "If the state transition is not completed within this time, it is considered a transition failure.", + "default": "10.0", + "minimum": 0.0 + }, + "frequency_hz": { + "type": "number", + "description": "running hz", + "default": "10.0", + "minimum": 0.0 + }, + "enable_engage_on_driving": { + "type": "boolean", + "description": "Set true if you want to engage the autonomous driving mode while the vehicle is driving. If set to false, it will deny Engage in any situation where the vehicle speed is not zero. Note that if you use this feature without adjusting the parameters, it may cause issues like sudden deceleration. Before using, please ensure the engage condition and the vehicle_cmd_gate transition filter are appropriately adjusted.", + "default": "false" + }, + "check_engage_condition": { + "type": "boolean", + "description": "If false, autonomous transition is always available.", + "default": "false" + }, + "nearest_dist_deviation_threshold": { + "type": "number", + "description": "distance threshold used to find nearest trajectory point [m]", + "default": "3.0", + "minimum": 0.0 + }, + "nearest_yaw_deviation_threshold": { + "type": "number", + "description": "angle threshold used to find nearest trajectory point [rad]", + "default": "1.57", + "minimum": -3.142 + }, + "engage_acceptable_limits": { + "type": "object", + "properties": { + "allow_autonomous_in_stopped": { + "type": "boolean", + "description": "If true, autonomous transition is available when the vehicle is stopped even if other checks fail.", + "default": "true" + }, + "dist_threshold": { + "type": "number", + "description": "The distance between the trajectory and ego vehicle must be within this distance for Autonomous transition.", + "default": "1.5", + "minimum": 0.0 + }, + "yaw_threshold": { + "type": "number", + "description": "The yaw angle between trajectory and ego vehicle must be within this threshold for Autonomous transition.", + "default": "0.524", + "minimum": -3.142 + }, + "speed_upper_threshold": { + "type": "number", + "description": "The velocity deviation between control command and ego vehicle must be within this threshold for Autonomous transition.", + "default": "10.0" + }, + "speed_lower_threshold": { + "type": "number", + "description": "The velocity deviation between control command and ego vehicle must be within this threshold for Autonomous transition.", + "default": "-10.0" + }, + "acc_threshold": { + "type": "number", + "description": "The control command acceleration must be less than this threshold for Autonomous transition.", + "default": "1.5", + "minimum": 0.0 + }, + "lateral_acc_threshold": { + "type": "number", + "description": "The control command lateral acceleration must be less than this threshold for Autonomous transition.", + "default": "1.0", + "minimum": 0.0 + }, + "lateral_acc_diff_threshold": { + "type": "number", + "description": "The lateral acceleration deviation between the control command must be less than this threshold for Autonomous transition.", + "default": "0.5", + "minimum": 0.0 + } + }, + "required": [ + "allow_autonomous_in_stopped", + "dist_threshold", + "yaw_threshold", + "speed_upper_threshold", + "speed_lower_threshold", + "acc_threshold", + "lateral_acc_threshold", + "lateral_acc_diff_threshold" + ] + }, + "stable_check": { + "type": "object", + "properties": { + "duration": { + "type": "number", + "description": "The stable condition must be satisfied for this duration to complete the transition.", + "default": "0.1", + "minimum": 0.0 + }, + "dist_threshold": { + "type": "number", + "description": "The distance between the trajectory and ego vehicle must be within this distance to complete Autonomous transition.", + "default": "1.5", + "minimum": 0.0 + }, + "speed_upper_threshold": { + "type": "number", + "description": "The velocity deviation between control command and ego vehicle must be within this threshold to complete Autonomous transition.", + "default": "2.0" + }, + "speed_lower_threshold": { + "type": "number", + "description": "The velocity deviation between control command and ego vehicle must be within this threshold to complete Autonomous transition.", + "default": "-2.0" + }, + "yaw_threshold": { + "type": "number", + "description": "The yaw angle between trajectory and ego vehicle must be within this threshold to complete Autonomous transition.", + "default": "0,262", + "minimum": -3.142 + } + }, + "required": [ + "duration", + "dist_threshold", + "speed_upper_threshold", + "speed_lower_threshold", + "yaw_threshold" + ] + } + }, + "required": [ + "transition_timeout", + "frequency_hz", + "enable_engage_on_driving", + "check_engage_condition", + "nearest_dist_deviation_threshold", + "nearest_yaw_deviation_threshold", + "engage_acceptable_limits", + "stable_check" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/operation_mode_transition_manager" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From bae5ea79c0879d02aab728e355205a0fb17e6fdc Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Wed, 22 Nov 2023 13:54:48 +0800 Subject: [PATCH 002/128] refactor(shift_decider): rework parameters (#5380) * refactor(shift_decider): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix --------- Signed-off-by: PhoebeWu21 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../schema/shift_decider.schema.json | 30 +++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100644 control/shift_decider/schema/shift_decider.schema.json diff --git a/control/shift_decider/schema/shift_decider.schema.json b/control/shift_decider/schema/shift_decider.schema.json new file mode 100644 index 0000000000000..faba3c4e12064 --- /dev/null +++ b/control/shift_decider/schema/shift_decider.schema.json @@ -0,0 +1,30 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Shift Decider Node", + "type": "object", + "definitions": { + "shift_decider": { + "type": "object", + "properties": { + "park_on_goal": { + "type": "boolean", + "description": "Setting true to part on goal.", + "default": "true" + } + }, + "required": ["park_on_goal"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/shift_decider" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 033edffa6872d5fdc190437015560a898b8d7754 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 23 Nov 2023 08:04:17 +0900 Subject: [PATCH 003/128] fix(motion_velocity_smoother): remove steer rate noise (#5629) * fix(motion_velocity_smoother): apply mean filter for steer rate Signed-off-by: satoshi-ota * refactor(motion_velocity_smoother): clean up Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/smoother/smoother_base.cpp | 135 +++++++++++------- 1 file changed, 86 insertions(+), 49 deletions(-) diff --git a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp index 4e5efdbfc32e4..bb15feb32a06e 100644 --- a/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/motion_velocity_smoother/src/smoother/smoother_base.cpp @@ -29,6 +29,37 @@ namespace motion_velocity_smoother { +namespace +{ +TrajectoryPoints applyPreProcess( + const TrajectoryPoints & input, const double interval, const bool use_resampling) +{ + using motion_utils::calcArcLength; + using motion_utils::convertToTrajectory; + using motion_utils::convertToTrajectoryPointArray; + using motion_utils::resampleTrajectory; + + if (!use_resampling) { + return input; + } + + TrajectoryPoints output; + std::vector arc_length; + + // since the resampling takes a long time, omit the resampling when it is not requested + const auto traj_length = calcArcLength(input); + for (double s = 0; s < traj_length; s += interval) { + arc_length.push_back(s); + } + + const auto points = resampleTrajectory(convertToTrajectory(input), arc_length); + output = convertToTrajectoryPointArray(points); + output.back() = input.back(); // keep the final speed. + + return output; +} +} // namespace + SmootherBase::SmootherBase(rclcpp::Node & node) { auto & p = base_param_; @@ -173,61 +204,67 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit( // Interpolate with constant interval distance for lateral acceleration calculation. const double points_interval = use_resampling ? base_param_.sample_ds : input_points_interval; - TrajectoryPoints output; - // since the resampling takes a long time, omit the resampling when it is not requested - if (use_resampling) { - std::vector out_arclength; - const auto traj_length = motion_utils::calcArcLength(input); - for (double s = 0; s < traj_length; s += points_interval) { - out_arclength.push_back(s); - } - const auto output_traj = - motion_utils::resampleTrajectory(motion_utils::convertToTrajectory(input), out_arclength); - output = motion_utils::convertToTrajectoryPointArray(output_traj); - output.back() = input.back(); // keep the final speed. - } else { - output = input; - } + + auto output = applyPreProcess(input, points_interval, use_resampling); const size_t idx_dist = static_cast( std::max(static_cast((base_param_.curvature_calculation_distance) / points_interval), 1)); - // Calculate curvature assuming the trajectory points interval is constant + // Step1. Calculate curvature assuming the trajectory points interval is constant. const auto curvature_v = trajectory_utils::calcTrajectoryCurvatureFrom3Points(output, idx_dist); - for (size_t i = 0; i + 1 < output.size(); i++) { - if (fabs(curvature_v.at(i)) > base_param_.curvature_threshold) { - // calculate the just 2 steering angle - output.at(i).front_wheel_angle_rad = std::atan(base_param_.wheel_base * curvature_v.at(i)); - output.at(i + 1).front_wheel_angle_rad = - std::atan(base_param_.wheel_base * curvature_v.at(i + 1)); - - const double mean_vel = - (output.at(i).longitudinal_velocity_mps + output.at(i + 1).longitudinal_velocity_mps) / 2.0; - const double dt = - std::max(points_interval / mean_vel, std::numeric_limits::epsilon()); - const double steering_diff = - fabs(output.at(i).front_wheel_angle_rad - output.at(i + 1).front_wheel_angle_rad); - const double dt_steering = - steering_diff / tier4_autoware_utils::deg2rad(base_param_.max_steering_angle_rate); - - if (dt_steering > dt) { - const double target_mean_vel = (points_interval / dt_steering); - for (size_t k = 0; k < 2; k++) { - const double temp_vel = - output.at(i + k).longitudinal_velocity_mps * (target_mean_vel / mean_vel); - if (temp_vel < output.at(i + k).longitudinal_velocity_mps) { - output.at(i + k).longitudinal_velocity_mps = temp_vel; - } else { - if (target_mean_vel < output.at(i + k).longitudinal_velocity_mps) { - output.at(i + k).longitudinal_velocity_mps = target_mean_vel; - } - } - if (output.at(i + k).longitudinal_velocity_mps < base_param_.min_curve_velocity) { - output.at(i + k).longitudinal_velocity_mps = base_param_.min_curve_velocity; - } - } - } + // Step2. Calculate steer rate for each trajectory point. + std::vector steer_rate_arr(output.size(), 0.0); + for (size_t i = 1; i < output.size() - 1; i++) { + // velocity + const auto & v_front = output.at(i + 1).longitudinal_velocity_mps; + const auto & v_back = output.at(i).longitudinal_velocity_mps; + // steer + auto & steer_front = output.at(i + 1).front_wheel_angle_rad; + 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)); + + const auto mean_vel = 0.5 * (v_front + v_back); + const auto dt = std::max(points_interval / mean_vel, std::numeric_limits::epsilon()); + const auto steering_diff = std::fabs(steer_front - steer_back); + + steer_rate_arr.at(i) = steering_diff / dt; + } + + steer_rate_arr.at(0) = steer_rate_arr.at(1); + steer_rate_arr.back() = steer_rate_arr.at((output.size() - 2)); + + // Step3. Remove noise by mean filter. + for (size_t i = 1; i < steer_rate_arr.size() - 1; i++) { + steer_rate_arr.at(i) = + (steer_rate_arr.at(i - 1) + steer_rate_arr.at(i) + steer_rate_arr.at(i + 1)) / 3.0; + } + + // Step4. Limit velocity by steer rate. + for (size_t i = 0; i < output.size() - 1; i++) { + if (fabs(curvature_v.at(i)) < base_param_.curvature_threshold) { + continue; + } + + const auto steer_rate = steer_rate_arr.at(i); + if (steer_rate < tier4_autoware_utils::deg2rad(base_param_.max_steering_angle_rate)) { + continue; + } + + const auto mean_vel = + (output.at(i).longitudinal_velocity_mps + output.at(i + 1).longitudinal_velocity_mps) / 2.0; + const auto target_mean_vel = + mean_vel * (tier4_autoware_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate); + + for (size_t k = 0; k < 2; k++) { + auto & velocity = output.at(i + k).longitudinal_velocity_mps; + const float target_velocity = std::max( + base_param_.min_curve_velocity, + std::min(target_mean_vel, velocity * (target_mean_vel / mean_vel))); + velocity = std::min(velocity, target_velocity); } } From 27ac617dfb32fbadb300e0ba07432f93dba79462 Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Thu, 23 Nov 2023 08:08:34 +0800 Subject: [PATCH 004/128] refactor(scenario_selector): rework parameters (#5218) * refactor(scenario_selector): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix * refactor(scenario_selector): rework parameters Signed-off-by: PhoebeWu21 * refactor(scenario_selector): 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> --- planning/scenario_selector/CMakeLists.txt | 1 + planning/scenario_selector/README.md | 8 +-- .../config/scenario_selector.param.yaml | 7 +++ .../launch/scenario_selector.launch.xml | 10 ++- .../schema/scenario_selector.schema.json | 61 +++++++++++++++++++ 5 files changed, 74 insertions(+), 13 deletions(-) create mode 100644 planning/scenario_selector/config/scenario_selector.param.yaml create mode 100644 planning/scenario_selector/schema/scenario_selector.schema.json diff --git a/planning/scenario_selector/CMakeLists.txt b/planning/scenario_selector/CMakeLists.txt index e278812cb211d..d2e9e051d721a 100644 --- a/planning/scenario_selector/CMakeLists.txt +++ b/planning/scenario_selector/CMakeLists.txt @@ -25,4 +25,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/planning/scenario_selector/README.md b/planning/scenario_selector/README.md index 3e02a3dbb84d9..0aea2c876cf35 100644 --- a/planning/scenario_selector/README.md +++ b/planning/scenario_selector/README.md @@ -34,13 +34,7 @@ None ### Parameters -| Parameter | Type | Description | -| -------------------------- | ------ | ------------------------------------------------------------------------------- | -| `update_rate` | double | timer's update rate | -| `th_max_message_delay_sec` | double | threshold time of input messages' maximum delay | -| `th_arrived_distance_m` | double | threshold distance to check if vehicle has arrived at the trajectory's endpoint | -| `th_stopped_time_sec` | double | threshold time to check if vehicle is stopped | -| `th_stopped_velocity_mps` | double | threshold velocity to check if vehicle is stopped | +{{ json_to_markdown("planning/scenario_selector/schema/scenario_selector.schema.json") }} ### Flowchart diff --git a/planning/scenario_selector/config/scenario_selector.param.yaml b/planning/scenario_selector/config/scenario_selector.param.yaml new file mode 100644 index 0000000000000..5e115c19a5e47 --- /dev/null +++ b/planning/scenario_selector/config/scenario_selector.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + update_rate: 10.0 + th_max_message_delay_sec: 1.0 + th_arrived_distance_m: 1.0 + th_stopped_time_sec: 1.0 + th_stopped_velocity_mps: 0.01 diff --git a/planning/scenario_selector/launch/scenario_selector.launch.xml b/planning/scenario_selector/launch/scenario_selector.launch.xml index 1c1a5cb6102b4..fdf176405d7b0 100644 --- a/planning/scenario_selector/launch/scenario_selector.launch.xml +++ b/planning/scenario_selector/launch/scenario_selector.launch.xml @@ -8,6 +8,8 @@ + + @@ -19,11 +21,7 @@ - - - - - - + + diff --git a/planning/scenario_selector/schema/scenario_selector.schema.json b/planning/scenario_selector/schema/scenario_selector.schema.json new file mode 100644 index 0000000000000..8ccb75106c6a5 --- /dev/null +++ b/planning/scenario_selector/schema/scenario_selector.schema.json @@ -0,0 +1,61 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Scenario Selector Node", + "type": "object", + "definitions": { + "scenario_selector": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "description": "timer's update rate", + "default": "10.0", + "minimum": 0.0 + }, + "th_max_message_delay_sec": { + "type": "number", + "description": "threshold time of input messages' maximum delay", + "default": "1.0", + "minimum": 0.0 + }, + "th_arrived_distance_m": { + "type": "number", + "description": "threshold distance to check if vehicle has arrived at the trajectory's endpoint", + "default": "1.0", + "minimum": 0.0 + }, + "th_stopped_time_sec": { + "type": "number", + "description": "threshold time to check if vehicle is stopped", + "default": "1.0", + "minimum": 0.0 + }, + "th_stopped_velocity_mps": { + "type": "number", + "description": "threshold velocity to check if vehicle is stopped", + "default": "0.01", + "minimum": 0.0 + } + }, + "required": [ + "update_rate", + "th_max_message_delay_sec", + "th_arrived_distance_m", + "th_stopped_time_sec", + "th_stopped_velocity_mps" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/scenario_selector" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 4bc4332ea9407540653590d0d8f368b0d12283de Mon Sep 17 00:00:00 2001 From: Yuqi Huai <34195403+YuqiHuai@users.noreply.github.com> Date: Wed, 22 Nov 2023 16:26:38 -0800 Subject: [PATCH 005/128] refactor(emergency_handler): rework parameters (#5242) * refactor(emergency_handler): rework parameters Signed-off-by: Yuqi Huai * style(pre-commit): autofix --------- Signed-off-by: Yuqi Huai Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- system/emergency_handler/README.md | 15 +--- .../schema/emergency_handler.schema.json | 77 +++++++++++++++++++ .../emergency_handler_core.cpp | 14 ++-- 3 files changed, 85 insertions(+), 21 deletions(-) create mode 100644 system/emergency_handler/schema/emergency_handler.schema.json diff --git a/system/emergency_handler/README.md b/system/emergency_handler/README.md index 92aa248733db1..3d658dbb4586f 100644 --- a/system/emergency_handler/README.md +++ b/system/emergency_handler/README.md @@ -35,20 +35,7 @@ Emergency Handler is a node to select proper MRM from from system failure state ## Parameters -### Node Parameters - -| Name | Type | Default Value | Explanation | -| ----------- | ---- | ------------- | ---------------------- | -| update_rate | int | `10` | Timer callback period. | - -### Core Parameters - -| Name | Type | Default Value | Explanation | -| --------------------------- | ------ | ------------- | --------------------------------------------------------------------------------------------------------------------------------- | -| timeout_hazard_status | double | `0.5` | If the input `hazard_status` topic cannot be received for more than `timeout_hazard_status`, vehicle will make an emergency stop. | -| use_parking_after_stopped | bool | `false` | If this parameter is true, it will publish PARKING shift command. | -| turning_hazard_on.emergency | bool | `true` | If this parameter is true, hazard lamps will be turned on during emergency state. | -| use_comfortable_stop | bool | `false` | If this parameter is true, operate comfortable stop when latent faults occur. | +{{ json_to_markdown("system/emergency_handler/schema/emergency_handler.schema.json") }} ## Assumptions / Known limits diff --git a/system/emergency_handler/schema/emergency_handler.schema.json b/system/emergency_handler/schema/emergency_handler.schema.json new file mode 100644 index 0000000000000..8295a5c6efb6b --- /dev/null +++ b/system/emergency_handler/schema/emergency_handler.schema.json @@ -0,0 +1,77 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for emergency handler", + "type": "object", + "definitions": { + "emergency_handler": { + "type": "object", + "properties": { + "update_rate": { + "type": "integer", + "description": "Timer callback period.", + "default": 10 + }, + "timeout_hazard_status": { + "type": "number", + "description": "If the input `hazard_status` topic cannot be received for more than `timeout_hazard_status`, vehicle will make an emergency stop.", + "default": 0.5 + }, + "timeout_takeover_request": { + "type": "number", + "description": "Transition to MRR_OPERATING if the time from the last takeover request exceeds `timeout_takeover_request`.", + "default": 10.0 + }, + "use_takeover_request": { + "type": "boolean", + "description": "If this parameter is true, the handler will record the time and make take over request to the driver when emergency state occurs.", + "default": "false" + }, + "use_parking_after_stopped": { + "type": "boolean", + "description": "If this parameter is true, it will publish PARKING shift command.", + "default": "false" + }, + "use_comfortable_stop": { + "type": "boolean", + "description": "If this parameter is true, operate comfortable stop when latent faults occur.", + "default": "false" + }, + "turning_hazard_on": { + "type": "object", + "properties": { + "emergency": { + "type": "boolean", + "description": "If this parameter is true, hazard lamps will be turned on during emergency state.", + "default": "true" + } + }, + "required": ["emergency"] + } + }, + "required": [ + "update_rate", + "timeout_hazard_status", + "timeout_takeover_request", + "use_takeover_request", + "use_parking_after_stopped", + "use_comfortable_stop", + "turning_hazard_on" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/emergency_handler" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp index 405359e2020ff..db6d11f98b5ba 100644 --- a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp +++ b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp @@ -21,13 +21,13 @@ EmergencyHandler::EmergencyHandler() : Node("emergency_handler") { // Parameter - param_.update_rate = declare_parameter("update_rate", 10); - param_.timeout_hazard_status = declare_parameter("timeout_hazard_status", 0.5); - param_.timeout_takeover_request = declare_parameter("timeout_takeover_request", 10.0); - param_.use_takeover_request = declare_parameter("use_takeover_request", false); - param_.use_parking_after_stopped = declare_parameter("use_parking_after_stopped", false); - param_.use_comfortable_stop = declare_parameter("use_comfortable_stop", false); - param_.turning_hazard_on.emergency = declare_parameter("turning_hazard_on.emergency", true); + param_.update_rate = declare_parameter("update_rate"); + param_.timeout_hazard_status = declare_parameter("timeout_hazard_status"); + param_.timeout_takeover_request = declare_parameter("timeout_takeover_request"); + param_.use_takeover_request = declare_parameter("use_takeover_request"); + param_.use_parking_after_stopped = declare_parameter("use_parking_after_stopped"); + param_.use_comfortable_stop = declare_parameter("use_comfortable_stop"); + param_.turning_hazard_on.emergency = declare_parameter("turning_hazard_on.emergency"); using std::placeholders::_1; From 3c6015273c3e8d5e77af9e70b18a43703e132a51 Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Thu, 23 Nov 2023 07:11:54 +0530 Subject: [PATCH 006/128] refactor(obstacle_collision_checker): rework parameters (#5654) Update-parameters-obstacle-collision-checker Signed-off-by: karishma --- .../schema/obstacle_collision_checker.json | 60 +++++++++++++++++++ 1 file changed, 60 insertions(+) create mode 100644 control/obstacle_collision_checker/schema/obstacle_collision_checker.json diff --git a/control/obstacle_collision_checker/schema/obstacle_collision_checker.json b/control/obstacle_collision_checker/schema/obstacle_collision_checker.json new file mode 100644 index 0000000000000..d1ba379a732df --- /dev/null +++ b/control/obstacle_collision_checker/schema/obstacle_collision_checker.json @@ -0,0 +1,60 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for obstacle collision checker", + "type": "object", + "definitions": { + "vehicle_cmd_gate": { + "type": "object", + "properties": { + "delay_time": { + "type": "number", + "default": 0.3, + "description": "Delay time of vehicles." + }, + "update_rate": { + "type": "number" + }, + "footprint_margin": { + "type": "number", + "default": 0.0, + "description": "Foot print margin." + }, + "max_deceleration": { + "type": "number", + "default": 2.0, + "description": "Max deceleration for ego vehicle to stop." + }, + "resample_interval": { + "type": "number", + "default": 0.3, + "description": "Interval for resampling trajectory." + }, + "search_radius": { + "type": "number", + "default": 5.0, + "description": "Search distance from trajectory to point cloud" + } + }, + "required": [ + "delay_time", + "footprint_margin", + "max_deceleration", + "resample_interval", + "search_radius", + "update_rate" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/obstacle_collision_checker" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From c171d1c80c13d64da73e5cdf9c81c19df5d29e95 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 23 Nov 2023 15:27:22 +0900 Subject: [PATCH 007/128] refactor(processing_time_checker): display in alphabetical order (#5538) Signed-off-by: Takamasa Horibe --- .../planning_debug_tools/scripts/processing_time_checker.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/planning_debug_tools/scripts/processing_time_checker.py b/planning/planning_debug_tools/scripts/processing_time_checker.py index fa6bc57fb7ae5..39e94ebcc1346 100755 --- a/planning/planning_debug_tools/scripts/processing_time_checker.py +++ b/planning/planning_debug_tools/scripts/processing_time_checker.py @@ -96,7 +96,9 @@ def print_data(self): print("-" * len(header_str)) # Print each topic's data - for topic, data in self.data_map.items(): + for topic in sorted(self.data_map.keys()): + # Fetch the data for the current topic + data = self.data_map[topic] # Round the data to the third decimal place for display data_rounded = round(data, 3) # Calculate the number of bars to be displayed (clamped to max_display_time) From 852f9ca50450c65883b3f9859251051fedf1370b Mon Sep 17 00:00:00 2001 From: Yuntianyi Chen Date: Thu, 23 Nov 2023 16:20:29 -0800 Subject: [PATCH 008/128] refactor(behavior_velocity_planner): rework parameters (#5263) * refactor node behavior_velocity_planner Signed-off-by: yuntianyi-chen * delete some statements in launch file Signed-off-by: yuntianyi-chen * Modify the launch file Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * update launch file Signed-off-by: yuntianyi-chen * style(pre-commit): autofix --------- Signed-off-by: yuntianyi-chen 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> --- .../behavior_velocity_planner.launch.xml | 3 + .../behavior_velocity_planner.schema.json | 77 +++++++++++++++++++ .../behavior_velocity_planner/src/node.cpp | 12 ++- 3 files changed, 85 insertions(+), 7 deletions(-) create mode 100644 planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json 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 46472619d5fb0..22220ccd182a1 100644 --- a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -27,6 +27,7 @@ + @@ -69,5 +70,7 @@ + + diff --git a/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json b/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json new file mode 100644 index 0000000000000..7291b4ea42015 --- /dev/null +++ b/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json @@ -0,0 +1,77 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Behavior Velocity Planner", + "type": "object", + "definitions": { + "behavior_velocity_planner": { + "type": "object", + "properties": { + "forward_path_length": { + "type": "number", + "default": "1000.0", + "description": "forward path" + }, + "backward_path_length": { + "type": "number", + "default": "5.0", + "description": "backward path" + }, + "max_accel": { + "type": "number", + "default": "-2.8", + "description": "(to be a global parameter) max acceleration of the vehicle" + }, + "system_delay": { + "type": "number", + "default": "0.5", + "description": "(to be a global parameter) delay time until output control command" + }, + "delay_response_time": { + "type": "number", + "default": "0.5", + "description": "(to be a global parameter) delay time of the vehicle's response to control commands" + }, + "stop_line_extend_length": { + "type": "number", + "default": "5.0", + "description": "extend length of stop line" + }, + "max_jerk": { + "type": "number", + "default": "-5.0", + "description": "max jerk of the vehicle" + }, + "is_publish_debug_path": { + "type": "number", + "default": "false", + "description": "is publish debug path?" + } + }, + "required": [ + "forward_path_length", + "backward_path_length", + "max_accel", + "system_delay", + "delay_response_time", + "stop_line_extend_length", + "max_jerk", + "is_publish_debug_path" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/behavior_velocity_planner" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index ec28656d8f866..4a7c76384ec35 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -136,16 +136,14 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio debug_viz_pub_ = this->create_publisher("~/debug/path", 1); // Parameters - forward_path_length_ = this->declare_parameter("forward_path_length"); - backward_path_length_ = this->declare_parameter("backward_path_length"); - planner_data_.stop_line_extend_length = - this->declare_parameter("stop_line_extend_length"); + forward_path_length_ = declare_parameter("forward_path_length"); + backward_path_length_ = declare_parameter("backward_path_length"); + planner_data_.stop_line_extend_length = declare_parameter("stop_line_extend_length"); // nearest search planner_data_.ego_nearest_dist_threshold = - this->declare_parameter("ego_nearest_dist_threshold"); - planner_data_.ego_nearest_yaw_threshold = - this->declare_parameter("ego_nearest_yaw_threshold"); + declare_parameter("ego_nearest_dist_threshold"); + planner_data_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); // Initialize PlannerManager for (const auto & name : declare_parameter>("launch_modules")) { From 19dab56af8fffde3b5778cf2c8ab6d20a4237f7d Mon Sep 17 00:00:00 2001 From: Yuqi Huai <34195403+YuqiHuai@users.noreply.github.com> Date: Thu, 23 Nov 2023 16:23:16 -0800 Subject: [PATCH 009/128] refactor(external_velocity_limit_selector): rework parameter (#5238) * refactor(external_velocity_limit_selector): rework parameter Signed-off-by: Yuqi Huai * style(pre-commit): autofix * doc(external_velocity_limit_selector): fix parameter file path * doc(external_velocity_limit_selector): fix default for numeric parameters Signed-off-by: Yuqi Huai --------- Signed-off-by: Yuqi Huai Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 12 +-- .../config/default.param.yaml | 4 - .../config/default_common.param.yaml | 15 ---- ...xternal_velocity_limit_selector.param.yaml | 18 ++++ ...xternal_velocity_limit_selector.launch.xml | 6 +- ...ternal_velocity_limit_selector.schema.json | 85 +++++++++++++++++++ 6 files changed, 106 insertions(+), 34 deletions(-) delete mode 100644 planning/external_velocity_limit_selector/config/default.param.yaml delete mode 100644 planning/external_velocity_limit_selector/config/default_common.param.yaml create mode 100644 planning/external_velocity_limit_selector/config/external_velocity_limit_selector.param.yaml create mode 100644 planning/external_velocity_limit_selector/schema/external_velocity_limit_selector.schema.json diff --git a/planning/external_velocity_limit_selector/README.md b/planning/external_velocity_limit_selector/README.md index 92579bfd0abce..2dc76dd3aec6e 100644 --- a/planning/external_velocity_limit_selector/README.md +++ b/planning/external_velocity_limit_selector/README.md @@ -51,17 +51,7 @@ Example: ## Parameters -| Parameter | Type | Description | -| ----------------- | ------ | ------------------------------------------ | -| `max_velocity` | double | default max velocity [m/s] | -| `normal.min_acc` | double | minimum acceleration [m/ss] | -| `normal.max_acc` | double | maximum acceleration [m/ss] | -| `normal.min_jerk` | double | minimum jerk [m/sss] | -| `normal.max_jerk` | double | maximum jerk [m/sss] | -| `limit.min_acc` | double | minimum acceleration to be observed [m/ss] | -| `limit.max_acc` | double | maximum acceleration to be observed [m/ss] | -| `limit.min_jerk` | double | minimum jerk to be observed [m/sss] | -| `limit.max_jerk` | double | maximum jerk to be observed [m/sss] | +{{ json_to_markdown("planning/external_velocity_limit_selector/schema/external_velocity_limit_selector.schema.json") }} ## Assumptions / Known limits diff --git a/planning/external_velocity_limit_selector/config/default.param.yaml b/planning/external_velocity_limit_selector/config/default.param.yaml deleted file mode 100644 index 8023776e191ba..0000000000000 --- a/planning/external_velocity_limit_selector/config/default.param.yaml +++ /dev/null @@ -1,4 +0,0 @@ -/**: - ros__parameters: - # motion state constraints - max_velocity: 20.0 # max velocity limit [m/s] diff --git a/planning/external_velocity_limit_selector/config/default_common.param.yaml b/planning/external_velocity_limit_selector/config/default_common.param.yaml deleted file mode 100644 index a23570a5fc791..0000000000000 --- a/planning/external_velocity_limit_selector/config/default_common.param.yaml +++ /dev/null @@ -1,15 +0,0 @@ -/**: - ros__parameters: - # constraints param for normal driving - normal: - min_acc: -0.5 # min deceleration [m/ss] - max_acc: 1.0 # max acceleration [m/ss] - min_jerk: -0.5 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] - - # constraints to be observed - limit: - min_acc: -2.5 # min deceleration limit [m/ss] - max_acc: 1.0 # max acceleration limit [m/ss] - min_jerk: -1.5 # min jerk limit [m/sss] - max_jerk: 1.5 # max jerk limit [m/sss] diff --git a/planning/external_velocity_limit_selector/config/external_velocity_limit_selector.param.yaml b/planning/external_velocity_limit_selector/config/external_velocity_limit_selector.param.yaml new file mode 100644 index 0000000000000..472b9370607b5 --- /dev/null +++ b/planning/external_velocity_limit_selector/config/external_velocity_limit_selector.param.yaml @@ -0,0 +1,18 @@ +/**: + ros__parameters: + # constraints param for normal driving + normal: + min_acc: -0.5 # min deceleration [m/ss] + max_acc: 1.0 # max acceleration [m/ss] + min_jerk: -0.5 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] + + # constraints to be observed + limit: + min_acc: -2.5 # min deceleration limit [m/ss] + max_acc: 1.0 # max acceleration limit [m/ss] + min_jerk: -1.5 # min jerk limit [m/sss] + max_jerk: 1.5 # max jerk limit [m/sss] + + # motion state constraints + max_velocity: 20.0 # max velocity limit [m/s] diff --git a/planning/external_velocity_limit_selector/launch/external_velocity_limit_selector.launch.xml b/planning/external_velocity_limit_selector/launch/external_velocity_limit_selector.launch.xml index 5ef089f3d3ee7..c499c0741f09f 100644 --- a/planning/external_velocity_limit_selector/launch/external_velocity_limit_selector.launch.xml +++ b/planning/external_velocity_limit_selector/launch/external_velocity_limit_selector.launch.xml @@ -1,7 +1,6 @@ - - + @@ -11,8 +10,7 @@ - - + diff --git a/planning/external_velocity_limit_selector/schema/external_velocity_limit_selector.schema.json b/planning/external_velocity_limit_selector/schema/external_velocity_limit_selector.schema.json new file mode 100644 index 0000000000000..36fdaf31cbc6f --- /dev/null +++ b/planning/external_velocity_limit_selector/schema/external_velocity_limit_selector.schema.json @@ -0,0 +1,85 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for external velocity limit selector node", + "type": "object", + "definitions": { + "external_velocity_limit_selector": { + "type": "object", + "properties": { + "max_velocity": { + "type": "number", + "description": "max velocity limit [m/s]", + "default": 20.0 + }, + "normal": { + "type": "object", + "properties": { + "min_acc": { + "type": "number", + "description": "min deceleration [m/ss]", + "default": -0.5 + }, + "max_acc": { + "type": "number", + "description": "max acceleration [m/ss]", + "default": 1.0 + }, + "min_jerk": { + "type": "number", + "description": "min jerk [m/sss]", + "default": -0.5 + }, + "max_jerk": { + "type": "number", + "description": "max jerk [m/sss]", + "default": 1.0 + } + }, + "required": ["min_acc", "max_acc", "min_jerk", "max_jerk"] + }, + "limit": { + "type": "object", + "properties": { + "min_acc": { + "type": "number", + "description": "min deceleration to be observed [m/ss]", + "default": -2.5 + }, + "max_acc": { + "type": "number", + "description": "max acceleration to be observed [m/ss]", + "default": 1.0 + }, + "min_jerk": { + "type": "number", + "description": "min jerk to be observed [m/sss]", + "default": -1.5 + }, + "max_jerk": { + "type": "number", + "description": "max jerk to be observed [m/sss]", + "default": 1.5 + } + }, + "required": ["min_acc", "max_acc", "min_jerk", "max_jerk"] + } + }, + "required": ["max_velocity", "normal", "limit"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/external_velocity_limit_selector" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 00dedb76428d9b3c323d61af39160dbaa56200d8 Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Fri, 24 Nov 2023 08:42:08 +0800 Subject: [PATCH 010/128] refactor(gnss_poser): rework parameters (#4693) * refactor(gnss_poser): rework parameters Signed-off-by: PhoebeWu21 * refactor(gnss_poser): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix * refactor(gnss_poser): rework parameters Signed-off-by: PhoebeWu21 * refactor(gnss_poser): rework parameters Signed-off-by: PhoebeWu21 * refactor(gnss_poser): 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> Co-authored-by: Yamato Ando --- sensing/gnss_poser/README.md | 8 +-- .../gnss_poser/launch/gnss_poser.launch.xml | 3 - .../gnss_poser/schema/gnss_poser.schema.json | 71 +++++++++++++++++++ 3 files changed, 72 insertions(+), 10 deletions(-) create mode 100644 sensing/gnss_poser/schema/gnss_poser.schema.json diff --git a/sensing/gnss_poser/README.md b/sensing/gnss_poser/README.md index b271f75eeeb6c..1ec7dc1f516ad 100644 --- a/sensing/gnss_poser/README.md +++ b/sensing/gnss_poser/README.md @@ -28,13 +28,7 @@ The `gnss_poser` is a node that subscribes gnss sensing messages and calculates ### Core Parameters -| Name | Type | Default Value | Description | -| ---------------------- | ------ | ---------------- | ------------------------------------------------------------------------------------------------------ | -| `base_frame` | string | "base_link" | frame id | -| `gnss_frame` | string | "gnss" | frame id | -| `gnss_base_frame` | string | "gnss_base_link" | frame id | -| `map_frame` | string | "map" | frame id | -| `gnss_pose_pub_method` | int | 0 | 0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect. | +{{ json_to_markdown("sensing/gnss_poser/schema/gnss_poser.schema.json") }} ## Assumptions / Known limits diff --git a/sensing/gnss_poser/launch/gnss_poser.launch.xml b/sensing/gnss_poser/launch/gnss_poser.launch.xml index d9b850e6995ae..90c3553312dc4 100755 --- a/sensing/gnss_poser/launch/gnss_poser.launch.xml +++ b/sensing/gnss_poser/launch/gnss_poser.launch.xml @@ -1,10 +1,8 @@ - - @@ -15,7 +13,6 @@ - diff --git a/sensing/gnss_poser/schema/gnss_poser.schema.json b/sensing/gnss_poser/schema/gnss_poser.schema.json new file mode 100644 index 0000000000000..1d63bb2f4850e --- /dev/null +++ b/sensing/gnss_poser/schema/gnss_poser.schema.json @@ -0,0 +1,71 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Gnss Poser Node", + "type": "object", + "definitions": { + "gnss_poser": { + "type": "object", + "properties": { + "base_frame": { + "type": "string", + "default": "base_link", + "description": "frame id for base_frame" + }, + "gnss_frame": { + "type": "string", + "default": "gnss", + "description": "frame id for gnss_frame" + }, + "gnss_base_frame": { + "type": "string", + "default": "gnss_base_link", + "description": "frame id for gnss_base_frame" + }, + "map_frame": { + "type": "string", + "default": "map", + "description": "frame id for map_frame" + }, + "use_gnss_ins_orientation": { + "type": "boolean", + "default": "true", + "description": "use Gnss-Ins orientation" + }, + "gnss_pose_pub_method": { + "type": "integer", + "default": "0", + "minimum": 0, + "maximum": 2, + "description": "0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect." + }, + "buff_epoch": { + "type": "integer", + "default": "1", + "minimum": 0, + "description": "Buffer epoch" + } + }, + "required": [ + "base_frame", + "gnss_frame", + "gnss_base_frame", + "map_frame", + "use_gnss_ins_orientation", + "gnss_pose_pub_method", + "buff_epoch" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/gnss_poser" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 041c536c746846b651590bdb7aab677cea126891 Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Fri, 24 Nov 2023 06:23:27 +0530 Subject: [PATCH 011/128] refactor(update_schema_vehicle_cmd_gate): rework parameters (#5652) update_schema_vehicle_cmd_gate Signed-off-by: karishma --- .../schema/vehicle_cmd_gate.json | 104 ++++++++++++++++++ 1 file changed, 104 insertions(+) create mode 100644 control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json diff --git a/control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json b/control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json new file mode 100644 index 0000000000000..983a001922053 --- /dev/null +++ b/control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json @@ -0,0 +1,104 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for vehicle cmd gate", + "type": "object", + "definitions": { + "vehicle_cmd_gate": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "default": 10.0, + "description": "To update period" + }, + "use_emergency_handling": { + "type": "boolean", + "default": "false", + "description": "true when emergency handler is used." + }, + "use_external_emergency_stop": { + "type": "boolean", + "default": "false", + "description": "true when external emergency stop information is used." + }, + "system_emergency_heartbeat_timeout": { + "type": "number", + "default": 0.5, + "description": "timeout for system emergency." + }, + "external_emergency_stop_heartbeat_timeout": { + "type": "number", + "default": 0.5, + "description": "timeout for external emergency." + }, + "stop_hold_acceleration": { + "type": "number", + "default": -1.5, + "description": "longitudinal acceleration cmd when vehicle should stop" + }, + "emergency_acceleration": { + "type": "number", + "default": -2.4, + "description": "longitudinal acceleration cmd when vehicle stop with emergency." + }, + "nominal.vel_lim": { + "type": "number", + "default": 25.0, + "description": "limit of longitudinal velocity (activated in AUTONOMOUS operation mode)." + }, + "nominal.lon_acc_lim": { + "type": "number", + "default": 5.0, + "description": "limit of longitudinal acceleration (activated in AUTONOMOUS operation mode)." + }, + "nominal.lon_jerk_lim": { + "type": "number", + "default": 5.0, + "description": "limit of longitudinal jerk (activated in AUTONOMOUS operation mode)." + }, + "nominal.lat_acc_lim": { + "type": "number", + "default": 5.0, + "description": "limit of lateral acceleration (activated in AUTONOMOUS operation mode)." + }, + "nominal.lat_jerk_lim": { + "type": "number", + "default": 5.0, + "description": "limit of lateral jerk (activated in AUTONOMOUS operation mode)." + }, + "nominal.actual_steer_diff_lim": { + "type": "number", + "default": 1.0, + "description": "limit of actual steer diff (activated in AUTONOMOUS operation mode)." + } + }, + "required": [ + "update_rate", + "use_emergency_handling", + "use_external_emergency_stop", + "system_emergency_heartbeat_timeout", + "external_emergency_stop_heartbeat_timeout", + "stop_hold_acceleration", + "emergency_acceleration", + "nominal.vel_lim", + "nominal.lon_acc_lim", + "nominal.lon_jerk_lim", + "nominal.lat_acc_lim", + "nominal.lat_jerk_lim", + "nominal.actual_steer_diff_lim" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/vehicle_cmd_gate" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From b9e98f1e43f350513cffd347a0f3c9d9a692e89e Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Fri, 24 Nov 2023 08:54:10 +0800 Subject: [PATCH 012/128] refactor(steer_offset_estimator): rework parameters (#5488) * refactor(steer_offset_estimator): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix * refactor(steer_offset_estimator): 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> --- vehicle/steer_offset_estimator/CMakeLists.txt | 1 + vehicle/steer_offset_estimator/Readme.md | 9 +-- .../config/steer_offset_estimator.param.yaml | 8 +++ ....xml => steer_offset_estimator.launch.xml} | 15 +---- .../schema/steer_offset_estimator.schema.json | 65 +++++++++++++++++++ .../src/steer_offset_estimator_node.cpp | 12 ++-- 6 files changed, 84 insertions(+), 26 deletions(-) create mode 100644 vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml rename vehicle/steer_offset_estimator/launch/{steer_offset_estimtor.launch.xml => steer_offset_estimator.launch.xml} (52%) create mode 100644 vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json diff --git a/vehicle/steer_offset_estimator/CMakeLists.txt b/vehicle/steer_offset_estimator/CMakeLists.txt index 641c696b50c96..eec8b2e24bec7 100644 --- a/vehicle/steer_offset_estimator/CMakeLists.txt +++ b/vehicle/steer_offset_estimator/CMakeLists.txt @@ -30,4 +30,5 @@ endif() ament_auto_package( INSTALL_TO_SHARE launch + config ) diff --git a/vehicle/steer_offset_estimator/Readme.md b/vehicle/steer_offset_estimator/Readme.md index 0c69382c374d5..3b455a97e4925 100644 --- a/vehicle/steer_offset_estimator/Readme.md +++ b/vehicle/steer_offset_estimator/Readme.md @@ -46,14 +46,7 @@ ros2 bag play --clock ## Parameters -| Params | Description | -| ----------------------- | ------------------------------------- | -| `steer_update_hz` | update hz | -| `initial_covariance` | steer offset is larger than tolerance | -| `forgetting_factor` | weight of using previous value | -| `valid_min_velocity` | velocity below this value is not used | -| `valid_max_steer` | steer above this value is not used | -| `warn_steer_offset_deg` | warn if offset is above this value | +{{ json_to_markdown("vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json") }} ## Diagnostics diff --git a/vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml b/vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml new file mode 100644 index 0000000000000..2f73449cd2969 --- /dev/null +++ b/vehicle/steer_offset_estimator/config/steer_offset_estimator.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + initial_covariance: 1000.0 + steer_update_hz: 10.0 + forgetting_factor: 0.999 + valid_min_velocity: 5.0 + valid_max_steer: 0.05 + warn_steer_offset_deg: 2.5 diff --git a/vehicle/steer_offset_estimator/launch/steer_offset_estimtor.launch.xml b/vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml similarity index 52% rename from vehicle/steer_offset_estimator/launch/steer_offset_estimtor.launch.xml rename to vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml index 4c636597bfbf2..8b98537c75500 100644 --- a/vehicle/steer_offset_estimator/launch/steer_offset_estimtor.launch.xml +++ b/vehicle/steer_offset_estimator/launch/steer_offset_estimator.launch.xml @@ -1,10 +1,6 @@ - - - - - - + + @@ -17,12 +13,7 @@ - - - - - - + diff --git a/vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json b/vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json new file mode 100644 index 0000000000000..cb2a03c97159b --- /dev/null +++ b/vehicle/steer_offset_estimator/schema/steer_offset_estimator.schema.json @@ -0,0 +1,65 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Steer Offset Estimator Node", + "type": "object", + "definitions": { + "steer_offset_estimator": { + "type": "object", + "properties": { + "initial_covariance": { + "type": "number", + "description": "steer offset is larger than tolerance", + "default": "1000.0" + }, + "steer_update_hz": { + "type": "number", + "description": "update hz of steer data", + "default": "10.0", + "minimum": 0.0 + }, + "forgetting_factor": { + "type": "number", + "description": "weight of using previous value", + "default": "0.999", + "minimum": 0.0 + }, + "valid_min_velocity": { + "type": "number", + "description": "velocity below this value is not used", + "default": "5.0", + "minimum": 0.0 + }, + "valid_max_steer": { + "type": "number", + "description": "steer above this value is not used", + "default": "0.05" + }, + "warn_steer_offset_deg": { + "type": "number", + "description": "Warn if offset is above this value. ex. if absolute estimated offset is larger than 2.5[deg] => warning", + "default": "2.5" + } + }, + "required": [ + "initial_covariance", + "steer_update_hz", + "forgetting_factor", + "valid_min_velocity", + "valid_max_steer", + "warn_steer_offset_deg" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/steer_offset_estimator" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp b/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp index 96a88cc7c1484..86c76dc6f2f26 100644 --- a/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp +++ b/vehicle/steer_offset_estimator/src/steer_offset_estimator_node.cpp @@ -28,13 +28,13 @@ SteerOffsetEstimatorNode::SteerOffsetEstimatorNode(const rclcpp::NodeOptions & n // get parameter const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); wheel_base_ = vehicle_info.wheel_base_m; - covariance_ = this->declare_parameter("initial_covariance", 1000.0); - forgetting_factor_ = this->declare_parameter("forgetting_factor", 0.999); - update_hz_ = this->declare_parameter("steer_update_hz", 10.0); - valid_min_velocity_ = this->declare_parameter("valid_min_velocity", 1.0); - valid_max_steer_ = this->declare_parameter("valid_max_steer", 0.1); + covariance_ = this->declare_parameter("initial_covariance"); + forgetting_factor_ = this->declare_parameter("forgetting_factor"); + update_hz_ = this->declare_parameter("steer_update_hz"); + valid_min_velocity_ = this->declare_parameter("valid_min_velocity"); + valid_max_steer_ = this->declare_parameter("valid_max_steer"); warn_steer_offset_abs_error_ = - this->declare_parameter("warn_steer_offset_deg", 2.5) * M_PI / 180.0; + this->declare_parameter("warn_steer_offset_deg") * M_PI / 180.0; // publisher pub_steer_offset_ = this->create_publisher("~/output/steering_offset", 1); From a7e5774da3a8f964ba8a7feaac95d9be1e03d16e Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 24 Nov 2023 14:24:20 +0900 Subject: [PATCH 013/128] feat(image_projection_based_fusion): fix iou geometry function (#5568) * enable to show debug iou value in roi_cluster_fusion Signed-off-by: yoshiri * refactor iou draw settings Signed-off-by: yoshiri * add backgroud color to iou Signed-off-by: yoshiri * prevent object copying when debugger is not enabled Signed-off-by: yoshiri * fix roi geometry functions Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../utils/geometry.hpp | 2 + .../src/roi_cluster_fusion/node.cpp | 13 +++--- .../src/utils/geometry.cpp | 41 ++++++++++++++++--- 3 files changed, 45 insertions(+), 11 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp index 199246715551c..de6a8c2987821 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/geometry.hpp @@ -64,6 +64,8 @@ bool is_inside( const sensor_msgs::msg::RegionOfInterest & outer, const sensor_msgs::msg::RegionOfInterest & inner, const double outer_offset_scale = 1.1); +void sanitizeROI(sensor_msgs::msg::RegionOfInterest & roi, const int width, const int height); + } // namespace image_projection_based_fusion #endif // IMAGE_PROJECTION_BASED_FUSION__UTILS__GEOMETRY_HPP_ 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 9da9df7eff6ca..492f832e30e8b 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 @@ -177,17 +177,18 @@ void RoiClusterFusionNode::fuseOnSingleImage( double iou(0.0); bool is_use_non_trust_object_iou_mode = is_far_enough( input_cluster_msg.feature_objects.at(cluster_map.first), trust_object_distance_); + auto image_roi = feature_obj.feature.roi; + auto cluster_roi = cluster_map.second; + sanitizeROI(image_roi, camera_info.width, camera_info.height); + sanitizeROI(cluster_roi, camera_info.width, camera_info.height); if (is_use_non_trust_object_iou_mode || is_roi_label_known) { - iou = - cal_iou_by_mode(cluster_map.second, feature_obj.feature.roi, non_trust_object_iou_mode_); + iou = cal_iou_by_mode(cluster_roi, image_roi, non_trust_object_iou_mode_); } else { - iou = cal_iou_by_mode(cluster_map.second, feature_obj.feature.roi, trust_object_iou_mode_); + iou = cal_iou_by_mode(cluster_roi, image_roi, trust_object_iou_mode_); } const bool passed_inside_cluster_gate = - only_allow_inside_cluster_ - ? is_inside(feature_obj.feature.roi, cluster_map.second, roi_scale_factor_) - : true; + only_allow_inside_cluster_ ? is_inside(image_roi, cluster_roi, roi_scale_factor_) : true; if (max_iou < iou && passed_inside_cluster_gate) { index = cluster_map.first; max_iou = iou; diff --git a/perception/image_projection_based_fusion/src/utils/geometry.cpp b/perception/image_projection_based_fusion/src/utils/geometry.cpp index 9ea49256650ee..29198280ec7b2 100644 --- a/perception/image_projection_based_fusion/src/utils/geometry.cpp +++ b/perception/image_projection_based_fusion/src/utils/geometry.cpp @@ -166,11 +166,42 @@ bool is_inside( const sensor_msgs::msg::RegionOfInterest & outer, const sensor_msgs::msg::RegionOfInterest & inner, const double outer_offset_scale) { - const double lower_scale = 1.0 - std::abs(outer_offset_scale - 1.0); - return outer.x_offset * lower_scale <= inner.x_offset && - outer.y_offset * lower_scale <= inner.y_offset && - inner.x_offset + inner.width <= (outer.x_offset + outer.width) * outer_offset_scale && - inner.y_offset + inner.height <= (outer.y_offset + outer.height) * outer_offset_scale; + const auto scaled_width = static_cast(outer.width) * outer_offset_scale; + const auto scaled_height = static_cast(outer.height) * outer_offset_scale; + const auto scaled_x_offset = + static_cast(outer.x_offset) - (scaled_width - outer.width) / 2.0; + const auto scaled_y_offset = + static_cast(outer.y_offset) - (scaled_height - outer.height) / 2.0; + + // 1. check left-top corner + if (scaled_x_offset > inner.x_offset || scaled_y_offset > inner.y_offset) { + return false; + } + // 2. check right-bottom corner + if ( + scaled_x_offset + scaled_width < inner.x_offset + inner.width || + scaled_y_offset + scaled_height < inner.y_offset + inner.height) { + return false; + } + return true; +} + +void sanitizeROI(sensor_msgs::msg::RegionOfInterest & roi, const int width_, const int height_) +{ + const unsigned int width = static_cast(width_); + const unsigned int height = static_cast(height_); + if (roi.x_offset >= width || roi.y_offset >= height) { + roi.width = 0; + roi.height = 0; + return; + } + + if (roi.x_offset + roi.width > width) { + roi.width = width - roi.x_offset; + } + if (roi.y_offset + roi.height > height) { + roi.height = height - roi.y_offset; + } } } // namespace image_projection_based_fusion From 5f9608d6aeee69b5110321c01f6710f38154eac7 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 24 Nov 2023 15:34:13 +0900 Subject: [PATCH 014/128] refactor(behavior_path_planner): move createObjectDebug to safety check (#5660) Signed-off-by: kosuke55 --- .../behavior_path_planner/marker_utils/utils.hpp | 2 -- .../utils/path_safety_checker/safety_check.hpp | 3 +++ .../behavior_path_planner/src/marker_utils/utils.cpp | 9 --------- .../src/scene_module/avoidance/avoidance_module.cpp | 2 +- .../scene_module/goal_planner/goal_planner_module.cpp | 2 +- .../src/scene_module/lane_change/normal.cpp | 2 +- .../start_planner/start_planner_module.cpp | 2 +- .../src/utils/lane_change/utils.cpp | 3 ++- .../src/utils/path_safety_checker/safety_check.cpp | 11 +++++++++++ 9 files changed, 20 insertions(+), 16 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp index 86f1a390261c6..72787f61d0fce 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp @@ -56,8 +56,6 @@ inline int64_t bitShift(int64_t original_id) return original_id << (sizeof(int32_t) * 8 / 2); } -CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj); - void updateCollisionCheckDebugMap( CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index b8bd1629d5f3f..7c00aec864246 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -132,6 +132,9 @@ std::vector getCollidedPolygons( bool checkPolygonsIntersects( const std::vector & polys_1, const std::vector & polys_2); +// debug +CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj); + } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index f1f681fed06a0..44978ec1124d6 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -42,15 +42,6 @@ using tier4_autoware_utils::createMarkerScale; using tier4_autoware_utils::createPoint; using visualization_msgs::msg::Marker; -CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) -{ - CollisionCheckDebug debug; - debug.current_obj_pose = obj.initial_pose.pose; - debug.extended_obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); - debug.current_twist = obj.initial_twist.twist; - return {tier4_autoware_utils::toHexString(obj.uuid), debug}; -} - void updateCollisionCheckDebugMap( CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe) { diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 1bd4fb3fef616..b3cff8bb26d8a 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1996,7 +1996,7 @@ bool AvoidanceModule::isSafePath( avoid_data_, planner_data_, parameters_, is_right_shift.value()); for (const auto & object : safety_check_target_objects) { - auto current_debug_data = marker_utils::createObjectDebug(object); + auto current_debug_data = utils::path_safety_checker::createObjectDebug(object); const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object.initial_pose.pose, object.shape); diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index ea8b5fd79c5d0..8c08464dd7c24 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1729,7 +1729,7 @@ bool GoalPlannerModule::checkSafetyWithRSS( { // Check for collisions with each predicted path of the object const bool is_safe = !std::any_of(objects.begin(), objects.end(), [&](const auto & object) { - auto current_debug_data = marker_utils::createObjectDebug(object); + auto current_debug_data = utils::path_safety_checker::createObjectDebug(object); const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( object, objects_filtering_params_->check_all_predicted_path); 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 d213eec21cdbf..27e1af6836a74 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 @@ -1718,7 +1718,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( lane_change_parameters_->lane_expansion_right_offset); for (const auto & obj : collision_check_objects) { - auto current_debug_data = marker_utils::createObjectDebug(obj); + auto current_debug_data = utils::path_safety_checker::createObjectDebug(obj); const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( obj, lane_change_parameters_->use_all_predicted_path); auto is_safe = true; 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 396e39eebba5f..e0a17ca247d8b 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 @@ -1092,7 +1092,7 @@ bool StartPlannerModule::isSafePath() const bool is_safe_dynamic_objects = true; // Check for collisions with each predicted path of the object for (const auto & object : target_objects_on_lane.on_current_lane) { - auto current_debug_data = marker_utils::createObjectDebug(object); + auto current_debug_data = utils::path_safety_checker::createObjectDebug(object); bool is_safe_dynamic_object = true; 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 fb2a96f1d5cbd..a8c7ce83fd98c 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -18,6 +18,7 @@ #include "behavior_path_planner/parameters.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/path_safety_checker/safety_check.hpp" #include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner/utils/path_utils.hpp" #include "behavior_path_planner/utils/utils.hpp" @@ -963,7 +964,7 @@ bool passParkedObject( } const auto & leading_obj = objects.at(*leading_obj_idx); - auto debug = marker_utils::createObjectDebug(leading_obj); + auto debug = utils::path_safety_checker::createObjectDebug(leading_obj); const auto leading_obj_poly = tier4_autoware_utils::toPolygon2d(leading_obj.initial_pose.pose, leading_obj.shape); if (leading_obj_poly.outer().empty()) { diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 40aa184105edb..ef36241adfa24 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -17,6 +17,7 @@ #include "interpolation/linear_interpolation.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" +#include "tier4_autoware_utils/ros/uuid_helper.hpp" #include #include @@ -392,4 +393,14 @@ bool checkPolygonsIntersects( } return false; } + +CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) +{ + CollisionCheckDebug debug; + debug.current_obj_pose = obj.initial_pose.pose; + debug.extended_obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); + debug.current_twist = obj.initial_twist.twist; + return {tier4_autoware_utils::toHexString(obj.uuid), debug}; +} + } // namespace behavior_path_planner::utils::path_safety_checker From 75487ba03e400b07618ac4bf866b11f68bd5a45c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 24 Nov 2023 17:06:10 +0900 Subject: [PATCH 015/128] feat(goal_planner): add time hysteresis to keep unsafe (#5662) feat(goal_planner): add tiem hysteresis to keep unsafe Signed-off-by: kosuke55 --- .../goal_planner/goal_planner.param.yaml | 1 + .../goal_planner/goal_planner_module.hpp | 17 ++++- .../path_safety_checker_parameters.hpp | 1 + .../goal_planner/goal_planner_module.cpp | 72 ++++++++++++++----- .../src/scene_module/goal_planner/manager.cpp | 2 + 5 files changed, 75 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml b/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml index 5ffac49847ce6..19550bac5c196 100644 --- a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml +++ b/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml @@ -160,6 +160,7 @@ safety_check_params: # safety check configuration enable_safety_check: true + keep_unsafe_time: 3.0 # collision check parameters check_all_predicted_path: true publish_debug_marker: false diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index b04a3fee41dcb..2e1c8d4010305 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -233,18 +233,26 @@ struct LastApprovalData struct PreviousPullOverData { + struct SafetyStatus + { + std::optional safe_start_time{}; + bool is_safe{false}; + }; + void reset() { stop_path = nullptr; stop_path_after_approval = nullptr; found_path = false; is_safe = false; + safety_status = SafetyStatus{}; } std::shared_ptr stop_path{nullptr}; std::shared_ptr stop_path_after_approval{nullptr}; bool found_path{false}; bool is_safe{false}; + SafetyStatus safety_status{}; }; class GoalPlannerModule : public SceneModuleInterface @@ -471,7 +479,14 @@ class GoalPlannerModule : public SceneModuleInterface void updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const; - bool isSafePath() const; + /** + * @brief Checks if the current path is safe. + * @return std::pair + * first: If the path is safe for a certain period of time, true. + * second: If the path is safe in the current state, true. + */ + std::pair isSafePath() const; + bool checkSafetyWithRSS( const PathWithLaneId & planned_path, const std::vector & ego_predicted_path, diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp index 3634586c40540..cfd242ab5b78b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -173,6 +173,7 @@ struct ObjectsFilteringParams struct SafetyCheckParams { bool enable_safety_check{false}; ///< Enable safety checks. + double keep_unsafe_time{0.0}; ///< Time to keep unsafe before changing to safe. double hysteresis_factor_expand_rate{ 0.0}; ///< Hysteresis factor to expand/shrink polygon with the value. double backward_path_length{0.0}; ///< Length of the backward lane for path generation. diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 8c08464dd7c24..04fd59676822b 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -400,7 +400,7 @@ bool GoalPlannerModule::isExecutionRequested() const bool GoalPlannerModule::isExecutionReady() const { if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) { - if (!isSafePath()) { + if (!isSafePath().first) { RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects"); return false; } @@ -724,7 +724,8 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const return; } - if (parameters_->safety_check_params.enable_safety_check && !isSafePath() && isActivated()) { + if ( + parameters_->safety_check_params.enable_safety_check && !isSafePath().first && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -864,7 +865,8 @@ bool GoalPlannerModule::hasDecidedPath() const // If it is dangerous before approval, do not determine the path. // This eliminates a unsafe path to be approved - if (parameters_->safety_check_params.enable_safety_check && !isSafePath() && !isActivated()) { + if ( + parameters_->safety_check_params.enable_safety_check && !isSafePath().first && !isActivated()) { return false; } @@ -1031,24 +1033,35 @@ void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. prev_data_.found_path = thread_safe_data_.foundPullOverPath(); - prev_data_.is_safe = parameters_->safety_check_params.enable_safety_check ? isSafePath() : true; - if (!isActivated()) { + // This is related to safety check, so if it is disabled, return here. + if (!parameters_->safety_check_params.enable_safety_check) { + prev_data_.safety_status.is_safe = true; return; } - if ( - !parameters_->safety_check_params.enable_safety_check || isSafePath() || - (!prev_data_.is_safe && prev_data_.stop_path_after_approval)) { + // Even if the current path is safe, it will not be safe unless it stands for a certain period of + // time. Record the time when the current path has become safe + const auto [is_safe, current_is_safe] = isSafePath(); + if (current_is_safe) { + if (!prev_data_.safety_status.safe_start_time) { + prev_data_.safety_status.safe_start_time = clock_->now(); + } + } else { + prev_data_.safety_status.safe_start_time = std::nullopt; + } + prev_data_.safety_status.is_safe = is_safe; + + // If safety check is enabled, save current path as stop_path_after_approval + // This path is set only once after approval. + if (!isActivated() || (!is_safe && prev_data_.stop_path_after_approval)) { return; } - prev_data_.is_safe = false; - const bool is_stop_path = std::any_of( - output.path->points.begin(), output.path->points.end(), - [](const auto & point) { return point.point.longitudinal_velocity_mps == 0.0; }); - if (is_stop_path) { - prev_data_.stop_path_after_approval = output.path; + auto stop_path = std::make_shared(*output.path); + for (auto & point : stop_path->points) { + point.point.longitudinal_velocity_mps = 0.0; } + prev_data_.stop_path_after_approval = stop_path; } BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() @@ -1750,7 +1763,7 @@ bool GoalPlannerModule::checkSafetyWithRSS( return is_safe; } -bool GoalPlannerModule::isSafePath() const +std::pair GoalPlannerModule::isSafePath() const { const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto & current_pose = planner_data_->self_odometry->pose.pose; @@ -1797,9 +1810,34 @@ bool GoalPlannerModule::isSafePath() const goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); const double hysteresis_factor = - prev_data_.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; - return checkSafetyWithRSS( + prev_data_.safety_status.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; + + const bool current_is_safe = checkSafetyWithRSS( pull_over_path, ego_predicted_path, target_objects_on_lane.on_current_lane, hysteresis_factor); + + /*   + *   ==== is_safe + *   ---- current_is_safe + *   is_safe + *   | + *   | time + *   1 +--+ +---+ +---========= +--+ + *   | | | | | | | | + *   | | | | | | | | + *   | | | | | | | | + *   | | | | | | | | + *   0 =========================-------==========-- t + */ + if (current_is_safe) { + if ( + prev_data_.safety_status.safe_start_time && + (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds() > + parameters_->safety_check_params.keep_unsafe_time) { + return {true /*is_safe*/, true /*current_is_safe*/}; + } + } + + return {false /*is_safe*/, current_is_safe}; } void GoalPlannerModule::setDebugData() diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp index 41d0299bca427..8baeb10ed1b85 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp @@ -334,6 +334,8 @@ GoalPlannerModuleManager::GoalPlannerModuleManager( { p.safety_check_params.enable_safety_check = node->declare_parameter(safety_check_ns + "enable_safety_check"); + p.safety_check_params.keep_unsafe_time = + node->declare_parameter(safety_check_ns + "keep_unsafe_time"); p.safety_check_params.hysteresis_factor_expand_rate = node->declare_parameter(safety_check_ns + "hysteresis_factor_expand_rate"); p.safety_check_params.backward_path_length = From 7ba74d6687d2cc59f1db72b24da25ad7b67ebb8b Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Fri, 24 Nov 2023 13:45:28 +0530 Subject: [PATCH 016/128] refactor(system-velodyne-monitor): rework parameters (#5667) system-velodyne-monitor Signed-off-by: karishma --- .../schema/velodyne_monitor.json | 73 +++++++++++++++++++ .../velodyne_monitor/src/velodyne_monitor.cpp | 16 ++-- 2 files changed, 81 insertions(+), 8 deletions(-) create mode 100644 system/velodyne_monitor/schema/velodyne_monitor.json diff --git a/system/velodyne_monitor/schema/velodyne_monitor.json b/system/velodyne_monitor/schema/velodyne_monitor.json new file mode 100644 index 0000000000000..eaf4a9cf36d1c --- /dev/null +++ b/system/velodyne_monitor/schema/velodyne_monitor.json @@ -0,0 +1,73 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for velodyne_monitor", + "type": "object", + "definitions": { + "velodyne_monitor": { + "type": "object", + "properties": { + "timeout": { + "type": "number", + "default": 0.5, + "description": " Timeout for HTTP request to get Velodyne LiDAR status." + }, + "ip_address": { + "type": "string", + "description": "IP address of target Velodyne LiDAR." + }, + "temp_cold_warn": { + "type": "boolean", + "default": "false", + "description": "true when external emergency stop information is used." + }, + "temp_cold_error": { + "type": "number", + "default": 0.5, + "description": "timeout for system emergency." + }, + "temp_hot_warn": { + "type": "number", + "default": 0.5, + "description": "timeout for external emergency." + }, + "temp_hot_error": { + "type": "number", + "default": -1.5, + "description": "longitudinal acceleration cmd when vehicle should stop" + }, + "rpm_ratio_warn": { + "type": "number", + "default": -2.4, + "description": "longitudinal acceleration cmd when vehicle stop with emergency." + }, + "rpm_ratio_error": { + "type": "number", + "default": 25.0, + "description": "limit of longitudinal velocity (activated in AUTONOMOUS operation mode)." + } + }, + "required": [ + "timeout", + "ip_address", + "temp_cold_warn", + "temp_cold_error", + "temp_hot_warn", + "temp_hot_error", + "rpm_ratio_warn", + "rpm_ratio_error" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/velodyne_monitor" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/system/velodyne_monitor/src/velodyne_monitor.cpp b/system/velodyne_monitor/src/velodyne_monitor.cpp index e8576a3a63066..99eebe7ec397e 100644 --- a/system/velodyne_monitor/src/velodyne_monitor.cpp +++ b/system/velodyne_monitor/src/velodyne_monitor.cpp @@ -32,14 +32,14 @@ VelodyneMonitor::VelodyneMonitor() : Node("velodyne_monitor"), updater_(this) { - timeout_ = declare_parameter("timeout", 0.5); - ip_address_ = declare_parameter("ip_address", "192.168.1.201"); - temp_cold_warn_ = declare_parameter("temp_cold_warn", -5.0); - temp_cold_error_ = declare_parameter("temp_cold_error", -10.0); - temp_hot_warn_ = declare_parameter("temp_hot_warn", 75.0); - temp_hot_error_ = declare_parameter("temp_hot_error", 80.0); - rpm_ratio_warn_ = declare_parameter("rpm_ratio_warn", 0.80); - rpm_ratio_error_ = declare_parameter("rpm_ratio_error", 0.70); + timeout_ = declare_parameter("timeout"); + ip_address_ = declare_parameter("ip_address"); + temp_cold_warn_ = declare_parameter("temp_cold_warn"); + temp_cold_error_ = declare_parameter("temp_cold_error"); + temp_hot_warn_ = declare_parameter("temp_hot_warn"); + temp_hot_error_ = declare_parameter("temp_hot_error"); + rpm_ratio_warn_ = declare_parameter("rpm_ratio_warn"); + rpm_ratio_error_ = declare_parameter("rpm_ratio_error"); updater_.add("velodyne_connection", this, &VelodyneMonitor::checkConnection); updater_.add("velodyne_temperature", this, &VelodyneMonitor::checkTemperature); From 64612e43d8a225092931aa7193790db2337f8178 Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Fri, 24 Nov 2023 15:13:43 +0530 Subject: [PATCH 017/128] refactor(vehicle_external_cmd_converter): rework parameters (#5659) * vehicle_external_cmd_converter Signed-off-by: karishma * Update vehicle/external_cmd_converter/src/node.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Signed-off-by: karishma * Update vehicle/external_cmd_converter/src/node.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Signed-off-by: karishma * vehicle_external_cmd_converter Signed-off-by: karishma --------- Signed-off-by: karishma Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../schema/external_cmd_converter.json | 55 +++++++++++++++++++ vehicle/external_cmd_converter/src/node.cpp | 10 ++-- 2 files changed, 60 insertions(+), 5 deletions(-) create mode 100644 vehicle/external_cmd_converter/schema/external_cmd_converter.json diff --git a/vehicle/external_cmd_converter/schema/external_cmd_converter.json b/vehicle/external_cmd_converter/schema/external_cmd_converter.json new file mode 100644 index 0000000000000..6a45e69adbb91 --- /dev/null +++ b/vehicle/external_cmd_converter/schema/external_cmd_converter.json @@ -0,0 +1,55 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for external_cmd_converter", + "type": "object", + "definitions": { + "velodyne_monitor": { + "type": "object", + "properties": { + "ref_vel_gain": { + "type": "number", + "default": 3.0 + }, + "timer_rate": { + "type": "number", + "default": 10.0, + "description": "timer's update rate." + }, + "wait_for_first_topic": { + "type": "boolean", + "default": "true", + "description": "if time out check is done after receiving first topic." + }, + "control_command_timeout": { + "type": "number", + "default": 1.0, + "description": "time out check for control command." + }, + "emergency_stop_timeout": { + "type": "number", + "default": 3.0, + "description": "time out check for emergency stop command." + } + }, + "required": [ + "ref_vel_gain", + "timer_rate", + "wait_for_first_topic", + "control_command_timeout", + "emergency_stop_timeout" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/external_cmd_converter" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/vehicle/external_cmd_converter/src/node.cpp b/vehicle/external_cmd_converter/src/node.cpp index 2a310b16c0841..32592c02c3347 100644 --- a/vehicle/external_cmd_converter/src/node.cpp +++ b/vehicle/external_cmd_converter/src/node.cpp @@ -42,13 +42,13 @@ ExternalCmdConverterNode::ExternalCmdConverterNode(const rclcpp::NodeOptions & n std::bind(&ExternalCmdConverterNode::onEmergencyStopHeartbeat, this, _1)); // Parameter - ref_vel_gain_ = declare_parameter("ref_vel_gain", 3.0); + ref_vel_gain_ = declare_parameter("ref_vel_gain"); // Parameter for Hz check - const double timer_rate = declare_parameter("timer_rate", 10.0); - wait_for_first_topic_ = declare_parameter("wait_for_first_topic", true); - control_command_timeout_ = declare_parameter("control_command_timeout", 1.0); - emergency_stop_timeout_ = declare_parameter("emergency_stop_timeout", 3.0); + const double timer_rate = declare_parameter("timer_rate"); + wait_for_first_topic_ = declare_parameter("wait_for_first_topic"); + control_command_timeout_ = declare_parameter("control_command_timeout"); + emergency_stop_timeout_ = declare_parameter("emergency_stop_timeout"); const auto period_ns = rclcpp::Rate(timer_rate).period(); rate_check_timer_ = rclcpp::create_timer( From 9a5e5c49e11303320e0a6a9b709e65855acbb9cd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 24 Nov 2023 19:12:02 +0900 Subject: [PATCH 018/128] feat(avoidance): suppress unnecessary avoidance path (#5387) * docs(avoidance): update flowchart Signed-off-by: satoshi-ota * feat(avoidance): suppress unnecessary avoidance path Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 4 + .../behavior_path_planner_avoidance_design.md | 143 ++++ .../utils/avoidance/avoidance_module_data.hpp | 5 +- .../utils/avoidance/utils.hpp | 21 +- .../avoidance/avoidance_module.cpp | 8 +- .../src/scene_module/avoidance/manager.cpp | 2 + .../src/utils/avoidance/utils.cpp | 736 ++++++++++-------- 7 files changed, 578 insertions(+), 341 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index ad06a1a9f6a10..d4394d1710e69 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -146,6 +146,10 @@ front_distance: 30.0 # [m] behind_distance: 30.0 # [m] + # params for filtering objects that are in intersection + intersection: + yaw_deviation: 0.175 # [rad] (default: 10.0deg) + # For safety check safety_check: # safety check configuration diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md index da96567ed542a..c4580bb1e82c3 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_avoidance_design.md @@ -209,6 +209,149 @@ The closer the object is to the shoulder, the larger the value of $ratio$ (theor In order to prevent chattering of recognition results, once an obstacle is targeted, it is hold for a while even if it disappears. This is effective when recognition is unstable. However, since it will result in over-detection (increase a number of false-positive), it is necessary to adjust parameters according to the recognition accuracy (if `object_last_seen_threshold = 0.0`, the recognition result is 100% trusted). +### Flowchart + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title object filtering flowchart +start + +if(object is satisfied with common target condition ?) then (yes) +if(vehicle can pass by the object without avoidance ?) then (yes) +:return false; +stop +else (\n no) +endif +else (\n no) +:return false; +stop +endif + +if(object is vehicle type ?) then (yes) +if(object is satisfied with vehicle type target condition ?) then (yes) +else (\n no) +:return false; +stop +endif +else (\n no) +if(object is satisfied with non-vehicle type target condition ?) then (yes) +else (\n no) +:return false; +stop +endif +endif + +#FF006C :return true; +stop +@enduml +``` + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title filtering flow for all types object +start + +partition isSatisfiedWithCommonCondition() { +if(object is avoidance target type ?) then (yes) +if(object is moving more than threshold time ?) then (yes) +:return false; +stop +else (\n no) +if(object is farther than forward distance threshold ?) then (yes) +:return false; +stop +else (\n no) +If(object is farther than backward distance threshold ?) then (yes) +:return false; +stop +else (\n no) +endif +endif +endif +else (\n no) +:return false; +stop +endif +#FF006C :return true; +stop +} + +@enduml +``` + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title filtering flow for vehicle type objects +start + +partition isSatisfiedWithVehicleCodition() { +if(object is force avoidance target ?) then (yes) +#FF006C :return true; +stop +else (\n no) +if(object is nearer lane centerline than threshold ?) then (yes) +:return false; +stop +else (\n no) +if(object is on same lane for ego ?) then (yes) +if(object is shifting right or left side road shoulder more than threshold ?) then (yes) +#FF006C :return true; +stop +else (\n no) +:return false; +stop +endif +else (\n no) +if(object is in intersection ?) then (no) +#FF006C :return true; +stop +else (\n yes) +if(object pose is paralell to ego lane ?) then (no) +#FF006C :return true; +stop +else (\n yes) +:return false; +stop +endif +endif +endif +endif +endif +} + +@enduml +``` + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam noteTextAlignment left + +title filtering flow for non-vehicle type objects +start + +partition isSatisfiedWithNonVehicleCodition() { +if(object is nearer crosswalk than threshold ?) then (yes) +:return false; +stop +else (\n no) +endif +#FF006C :return true; +stop +} + +@enduml +``` + ## Overview of algorithm for avoidance path generation ### How to prevent shift line chattering that is caused by perception noise diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 60cf9b1244236..c90321ea649a6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -159,6 +159,7 @@ struct AvoidanceParameters double object_check_min_forward_distance{0.0}; double object_check_max_forward_distance{0.0}; 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. @@ -394,8 +395,7 @@ struct ObjectData // avoidance target std::string reason{""}; // lateral avoid margin - // NOTE: If margin is less than the minimum margin threshold, boost::none will be set. - boost::optional avoid_margin{boost::none}; + std::optional avoid_margin{std::nullopt}; }; using ObjectDataArray = std::vector; @@ -482,6 +482,7 @@ struct AvoidancePlanningData // current driving lanelet lanelet::ConstLanelets current_lanelets; + lanelet::ConstLanelets extend_lanelets; // output path ShiftedPath candidate_path; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 2e04935e37336..7ed455ea5350e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -33,18 +33,6 @@ using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygo bool isOnRight(const ObjectData & obj); -bool isVehicleTypeObject(const ObjectData & object); - -bool isWithinCrosswalk( - const ObjectData & object, - const std::shared_ptr & overall_graphs); - -bool isWithinIntersection( - const ObjectData & object, const std::shared_ptr & route_handler); - -bool isTargetObjectType( - const PredictedObject & object, const std::shared_ptr & parameters); - double calcShiftLength( const bool & is_object_on_right, const double & overhang_dist, const double & avoid_margin); @@ -106,6 +94,10 @@ lanelet::ConstLanelets getTargetLanelets( lanelet::ConstLanelets getCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data); +lanelet::ConstLanelets getExtendLanes( + const lanelet::ConstLanelets & lanelets, const Pose & ego_pose, + const std::shared_ptr & planner_data); + void insertDecelPoint( const Point & p_src, const double offset, const double velocity, PathWithLaneId & path, boost::optional & p_out); @@ -139,6 +131,11 @@ void filterTargetObjects( const std::shared_ptr & planner_data, const std::shared_ptr & parameters); +double getRoadShoulderDistance( + ObjectData & object, const AvoidancePlanningData & data, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters); + double extendToRoadShoulderDistanceWithPolygon( const std::shared_ptr & rh, const lanelet::ConstLineString3d & target_line, const double to_road_shoulder_distance, diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index b3cff8bb26d8a..3124f00932375 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -265,6 +265,9 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( *getPreviousModuleOutput().reference_path, planner_data_); + data.extend_lanelets = + utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_); + // expand drivable lanes std::for_each( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { @@ -1058,7 +1061,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( AvoidOutlines outlines; for (auto & o : data.target_objects) { - if (!o.avoid_margin) { + if (!o.avoid_margin.has_value()) { o.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; if (o.avoid_required && is_forward_object(o)) { break; @@ -1069,7 +1072,7 @@ AvoidOutlines AvoidanceModule::generateAvoidOutline( const auto is_object_on_right = utils::avoidance::isOnRight(o); const auto desire_shift_length = - helper_.getShiftLength(o, is_object_on_right, o.avoid_margin.get()); + helper_.getShiftLength(o, is_object_on_right, o.avoid_margin.value()); if (utils::avoidance::isSameDirectionShift(is_object_on_right, desire_shift_length)) { o.reason = AvoidanceDebugFactor::SAME_DIRECTION_SHIFT; if (o.avoid_required && is_forward_object(o)) { @@ -2813,6 +2816,7 @@ void AvoidanceModule::updateDebugMarker( addObjects(data.other_objects, std::string("NotNeedAvoidance")); addObjects(data.other_objects, std::string("LessThanExecutionThreshold")); addObjects(data.other_objects, std::string("TooNearToGoal")); + addObjects(data.other_objects, std::string("ParallelToEgoLane")); } // shift line pre-process diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index f71024dcc5034..f4807223503fa 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -114,6 +114,8 @@ AvoidanceModuleManager::AvoidanceModuleManager( 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"); } diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index ce4c9ad7ac72d..d6427a1fe8c36 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include @@ -232,11 +233,8 @@ void pushUniqueVector(T & base_vector, const T & additional_vector) } // namespace -bool isOnRight(const ObjectData & obj) +namespace filtering_utils { - return obj.lateral < 0.0; -} - bool isTargetObjectType( const PredictedObject & object, const std::shared_ptr & parameters) { @@ -313,8 +311,132 @@ bool isWithinIntersection( object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon()))); } +bool isParallelToEgoLane(const ObjectData & object, const double threshold) +{ + const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; + const auto closest_pose = + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); + const auto yaw_deviation = std::abs(calcYawDeviation(closest_pose, object_pose)); + + return yaw_deviation < threshold || yaw_deviation > M_PI - threshold; +} + +bool isObjectOnRoadShoulder( + ObjectData & object, const std::shared_ptr & route_handler, + const std::shared_ptr & parameters) +{ + using boost::geometry::return_centroid; + using boost::geometry::within; + using lanelet::geometry::distance2d; + using lanelet::geometry::toArcCoordinates; + using lanelet::utils::to2D; + + // assume that there are no parked vehicles in intersection. + std::string turn_direction = object.overhang_lanelet.attributeOr("turn_direction", "else"); + if (turn_direction == "right" || turn_direction == "left" || turn_direction == "straight") { + return false; + } + + // ============================================ <- most_left_lanelet.leftBound() + // y road shoulder + // ^ ------------------------------------------ + // | x + + // +---> --- object closest lanelet --- o ----- <- object_closest_lanelet.centerline() + // + // -------------------------------------------- + // +: object position + // o: nearest point on centerline + + lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y()); + + const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; + const auto centerline_pose = + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); + lanelet::BasicPoint3d centerline_point( + centerline_pose.position.x, centerline_pose.position.y, centerline_pose.position.z); + + bool is_left_side_parked_vehicle = false; + if (!isOnRight(object)) { + auto [object_shiftable_distance, sub_type] = [&]() { + const auto most_left_road_lanelet = + route_handler->getMostLeftLanelet(object.overhang_lanelet); + const auto most_left_lanelet_candidates = + route_handler->getLaneletMapPtr()->laneletLayer.findUsages( + most_left_road_lanelet.leftBound()); + + lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet; + const lanelet::Attribute sub_type = + most_left_lanelet.attribute(lanelet::AttributeName::Subtype); + + for (const auto & ll : most_left_lanelet_candidates) { + const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); + if (sub_type.value() == "road_shoulder") { + most_left_lanelet = ll; + } + } + + const auto center_to_left_boundary = + distance2d(to2D(most_left_lanelet.leftBound().basicLineString()), to2D(centerline_point)); + + return std::make_pair( + center_to_left_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); + }(); + + if (sub_type.value() != "road_shoulder") { + object_shiftable_distance += parameters->object_check_min_road_shoulder_width; + } + + const auto arc_coordinates = toArcCoordinates( + to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid); + object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance; + + is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio; + } + + bool is_right_side_parked_vehicle = false; + if (isOnRight(object)) { + auto [object_shiftable_distance, sub_type] = [&]() { + const auto most_right_road_lanelet = + route_handler->getMostRightLanelet(object.overhang_lanelet); + const auto most_right_lanelet_candidates = + route_handler->getLaneletMapPtr()->laneletLayer.findUsages( + most_right_road_lanelet.rightBound()); + + lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet; + const lanelet::Attribute sub_type = + most_right_lanelet.attribute(lanelet::AttributeName::Subtype); + + for (const auto & ll : most_right_lanelet_candidates) { + const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); + if (sub_type.value() == "road_shoulder") { + most_right_lanelet = ll; + } + } + + const auto center_to_right_boundary = + distance2d(to2D(most_right_lanelet.rightBound().basicLineString()), to2D(centerline_point)); + + return std::make_pair( + center_to_right_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); + }(); + + if (sub_type.value() != "road_shoulder") { + object_shiftable_distance += parameters->object_check_min_road_shoulder_width; + } + + const auto arc_coordinates = toArcCoordinates( + to2D(object.overhang_lanelet.centerline().basicLineString()), object_centroid); + object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance; + + is_right_side_parked_vehicle = + object.shiftable_ratio > parameters->object_check_shiftable_ratio; + } + + return is_left_side_parked_vehicle || is_right_side_parked_vehicle; +} + bool isForceAvoidanceTarget( - ObjectData & object, const lanelet::ConstLanelets & extend_lanelets, + ObjectData & object, const AvoidancePlanningData & data, const std::shared_ptr & planner_data, const std::shared_ptr & parameters) { @@ -350,7 +472,7 @@ bool isForceAvoidanceTarget( bool not_parked_object = true; // check traffic light - const auto to_traffic_light = getDistanceToNextTrafficLight(object_pose, extend_lanelets); + const auto to_traffic_light = getDistanceToNextTrafficLight(object_pose, data.extend_lanelets); { not_parked_object = to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance; @@ -358,7 +480,7 @@ bool isForceAvoidanceTarget( // check crosswalk const auto to_crosswalk = - utils::getDistanceToCrosswalk(ego_pose, extend_lanelets, *rh->getOverallGraphPtr()) - + utils::getDistanceToCrosswalk(ego_pose, data.extend_lanelets, *rh->getOverallGraphPtr()) - object.longitudinal; { const auto stop_for_crosswalk = @@ -372,6 +494,181 @@ bool isForceAvoidanceTarget( return !not_parked_object; } +bool isSatisfiedWithCommonCondition( + ObjectData & object, const AvoidancePlanningData & data, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + // Step1. filtered by target object type. + if (!isTargetObjectType(object.object, parameters)) { + object.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE; + return false; + } + + // Step2. filtered stopped objects. + const auto object_type = utils::getHighestProbLabel(object.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); + if (object.move_time > object_parameter.moving_time_threshold) { + object.reason = AvoidanceDebugFactor::MOVING_OBJECT; + return false; + } + + // Step3. filtered by longitudinal distance. + const auto & ego_pos = planner_data->self_odometry->pose.pose.position; + fillLongitudinalAndLengthByClosestEnvelopeFootprint(data.reference_path_rough, ego_pos, object); + + if (object.longitudinal < -parameters->object_check_backward_distance) { + object.reason = AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD; + return false; + } + + if (object.longitudinal > parameters->object_check_max_forward_distance) { + object.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD; + return false; + } + + // Step4. filtered by distance between object and goal position. + // TODO(Satoshi OTA): remove following two conditions after it can execute avoidance and goal + // planner module simultaneously. + const auto & rh = planner_data->route_handler; + const auto ego_idx = planner_data->findEgoIndex(data.reference_path_rough.points); + const auto to_goal_distance = + rh->isInGoalRouteSection(data.current_lanelets.back()) + ? calcSignedArcLength( + data.reference_path_rough.points, ego_idx, data.reference_path_rough.points.size() - 1) + : std::numeric_limits::max(); + + if (object.longitudinal > to_goal_distance) { + object.reason = AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL; + return false; + } + + if ( + object.longitudinal + object.length / 2 + parameters->object_check_goal_distance > + to_goal_distance) { + object.reason = "TooNearToGoal"; + return false; + } + + return true; +} + +bool isSatisfiedWithNonVehicleCondition( + ObjectData & object, [[maybe_unused]] const AvoidancePlanningData & data, + const std::shared_ptr & planner_data, + [[maybe_unused]] const std::shared_ptr & parameters) +{ + // avoidance module ignore pedestrian and bicycle around crosswalk + if (isWithinCrosswalk(object, planner_data->route_handler->getOverallGraphPtr())) { + object.reason = "CrosswalkUser"; + return false; + } + + return true; +} + +bool isSatisfiedWithVehicleCondition( + ObjectData & object, const AvoidancePlanningData & data, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + using boost::geometry::within; + + object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler); + + // from here condition check for vehicle type objects. + if (isForceAvoidanceTarget(object, data, planner_data, parameters)) { + return true; + } + + // Object is on center line -> ignore. + if (std::abs(object.lateral) < parameters->threshold_distance_object_is_on_center) { + object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; + return false; + } + + lanelet::BasicPoint2d object_centroid(object.centroid.x(), object.centroid.y()); + const auto on_ego_driving_lane = + within(object_centroid, object.overhang_lanelet.polygon2d().basicPolygon()); + if (on_ego_driving_lane) { + if (isObjectOnRoadShoulder(object, planner_data->route_handler, parameters)) { + return true; + } else { + object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + return false; + } + } + + if (!object.is_within_intersection) { + return true; + } + + if (isParallelToEgoLane(object, parameters->object_check_yaw_deviation)) { + object.reason = "ParallelToEgoLane"; + return false; + } + + return true; +} + +bool isNoNeedAvoidanceBehavior( + ObjectData & object, const std::shared_ptr & parameters) +{ + if (!object.avoid_margin.has_value()) { + return false; + } + + const auto shift_length = + calcShiftLength(isOnRight(object), object.overhang_dist, object.avoid_margin.value()); + if (!isShiftNecessary(isOnRight(object), shift_length)) { + object.reason = "NotNeedAvoidance"; + return true; + } + + if (std::abs(shift_length) < parameters->lateral_execution_threshold) { + object.reason = "LessThanExecutionThreshold"; + return true; + } + + return false; +} + +std::optional getAvoidMargin( + const ObjectData & object, const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + const auto & vehicle_width = planner_data->parameters.vehicle_width; + const auto object_type = utils::getHighestProbLabel(object.object.classification); + const auto object_parameter = parameters->object_parameters.at(object_type); + + const auto max_avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor + + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; + const auto min_avoid_margin = object_parameter.safety_buffer_lateral + 0.5 * vehicle_width; + const auto soft_lateral_distance_limit = + object.to_road_shoulder_distance - parameters->soft_road_shoulder_margin - 0.5 * vehicle_width; + const auto hard_lateral_distance_limit = + object.to_road_shoulder_distance - parameters->hard_road_shoulder_margin - 0.5 * vehicle_width; + + // Step1. check avoidable or not. + if (hard_lateral_distance_limit < min_avoid_margin) { + return std::nullopt; + } + + // Step2. check if it should expand road shoulder margin. + if (soft_lateral_distance_limit < min_avoid_margin) { + return min_avoid_margin; + } + + // Step3. nominal case. avoid margin is limited by soft constraint. + return std::min(soft_lateral_distance_limit, max_avoid_margin); +} +} // namespace filtering_utils + +bool isOnRight(const ObjectData & obj) +{ + return obj.lateral < 0.0; +} + double calcShiftLength( const bool & is_object_on_right, const double & overhang_dist, const double & avoid_margin) { @@ -627,7 +924,7 @@ std::vector generateObstaclePolygonsForDrivableArea( } // check if avoid marin is calculated - if (!object.avoid_margin) { + if (!object.avoid_margin.has_value()) { continue; } @@ -636,7 +933,7 @@ std::vector generateObstaclePolygonsForDrivableArea( // generate obstacle polygon const double diff_poly_buffer = - object.avoid_margin.get() - object_parameter.envelope_buffer_margin - vehicle_width / 2.0; + object.avoid_margin.value() - object_parameter.envelope_buffer_margin - vehicle_width / 2.0; const auto obj_poly = tier4_autoware_utils::expandPolygon(object.envelope_poly, diff_poly_buffer); const bool is_left = 0 < object.lateral; @@ -707,6 +1004,33 @@ lanelet::ConstLanelets getCurrentLanesFromPath( start_lane, p.backward_path_length, p.forward_path_length); } +lanelet::ConstLanelets getExtendLanes( + const lanelet::ConstLanelets & lanelets, const Pose & ego_pose, + const std::shared_ptr & planner_data) +{ + lanelet::ConstLanelets extend_lanelets = lanelets; + + while (rclcpp::ok()) { + const double lane_length = lanelet::utils::getLaneletLength2d(extend_lanelets); + const auto arc_coordinates = lanelet::utils::getArcCoordinates(extend_lanelets, ego_pose); + const auto forward_length = lane_length - arc_coordinates.length; + + if (forward_length > planner_data->parameters.forward_path_length) { + break; + } + + const auto next_lanelets = planner_data->route_handler->getNextLanelets(extend_lanelets.back()); + + if (next_lanelets.empty()) { + break; + } + + extend_lanelets.push_back(next_lanelets.front()); + } + + return extend_lanelets; +} + void insertDecelPoint( const Point & p_src, const double offset, const double velocity, PathWithLaneId & path, boost::optional & p_out) @@ -1007,361 +1331,123 @@ void compensateDetectionLost( } } -void filterTargetObjects( - ObjectDataArray & objects, AvoidancePlanningData & data, DebugData & debug, +double getRoadShoulderDistance( + ObjectData & object, const AvoidancePlanningData & data, const std::shared_ptr & planner_data, const std::shared_ptr & parameters) { - using boost::geometry::return_centroid; - using boost::geometry::within; - using lanelet::geometry::distance2d; - using lanelet::geometry::toArcCoordinates; using lanelet::utils::to2D; - if (data.current_lanelets.empty()) { - return; - } - - const auto & rh = planner_data->route_handler; - const auto & path_points = data.reference_path_rough.points; - const auto & ego_pos = planner_data->self_odometry->pose.pose.position; - const auto & vehicle_width = planner_data->parameters.vehicle_width; - const rclcpp::Time now = rclcpp::Clock(RCL_ROS_TIME).now(); - - // for goal - const auto ego_idx = planner_data->findEgoIndex(path_points); - const auto dist_to_goal = rh->isInGoalRouteSection(data.current_lanelets.back()) - ? calcSignedArcLength(path_points, ego_idx, path_points.size() - 1) - : std::numeric_limits::max(); - - // extend lanelets if the reference path is cut for lane change. - const auto & ego_pose = planner_data->self_odometry->pose.pose; - lanelet::ConstLanelets extend_lanelets = data.current_lanelets; - while (rclcpp::ok()) { - const double lane_length = lanelet::utils::getLaneletLength2d(extend_lanelets); - const auto arclength = lanelet::utils::getArcCoordinates(extend_lanelets, ego_pose); - const auto next_lanelets = rh->getNextLanelets(extend_lanelets.back()); - - if (next_lanelets.empty()) { - break; - } + const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; + const auto object_closest_index = + findNearestIndex(data.reference_path_rough.points, object_pose.position); + const auto object_closest_pose = + data.reference_path_rough.points.at(object_closest_index).point.pose; - if (lane_length - arclength.length < planner_data->parameters.forward_path_length) { - extend_lanelets.push_back(next_lanelets.front()); - } else { - break; - } + const auto rh = planner_data->route_handler; + if (!rh->getClosestLaneletWithinRoute(object_closest_pose, &object.overhang_lanelet)) { + return 0.0; } - for (auto & o : objects) { - const auto & object_pose = o.object.kinematics.initial_pose_with_covariance.pose; - const auto object_closest_index = findNearestIndex(path_points, object_pose.position); - const auto object_closest_pose = path_points.at(object_closest_index).point.pose; + double road_shoulder_distance = std::numeric_limits::max(); - const auto object_type = utils::getHighestProbLabel(o.object.classification); - const auto object_parameter = parameters->object_parameters.at(object_type); + const bool get_left = isOnRight(object) && parameters->use_adjacent_lane; + const bool get_right = !isOnRight(object) && parameters->use_adjacent_lane; + const bool get_opposite = parameters->use_opposite_lane; - if (!isTargetObjectType(o.object, parameters)) { - o.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE; - data.other_objects.push_back(o); - continue; - } - - // if following condition are satisfied, ignored the objects as moving objects. - // 1. speed is higher than threshold. - // 2. keep that speed longer than the time threshold. - if (o.move_time > object_parameter.moving_time_threshold) { - o.reason = AvoidanceDebugFactor::MOVING_OBJECT; - data.other_objects.push_back(o); - continue; - } - - // calc longitudinal distance from ego to closest target object footprint point. - fillLongitudinalAndLengthByClosestEnvelopeFootprint(data.reference_path_rough, ego_pos, o); - - // object is behind ego or too far. - if (o.longitudinal < -parameters->object_check_backward_distance) { - o.reason = AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD; - data.other_objects.push_back(o); - continue; - } - if (o.longitudinal > parameters->object_check_max_forward_distance) { - o.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD; - data.other_objects.push_back(o); - continue; - } - - // Target object is behind the path goal -> ignore. - if (o.longitudinal > dist_to_goal) { - o.reason = AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL; - data.other_objects.push_back(o); - continue; - } + lanelet::BasicPoint3d p_overhang( + object.overhang_pose.position.x, object.overhang_pose.position.y, + object.overhang_pose.position.z); - if (o.longitudinal + o.length / 2 + parameters->object_check_goal_distance > dist_to_goal) { - o.reason = "TooNearToGoal"; - data.other_objects.push_back(o); - continue; - } + lanelet::ConstLineString3d target_line{}; - lanelet::ConstLanelet overhang_lanelet; - if (!rh->getClosestLaneletWithinRoute(object_closest_pose, &overhang_lanelet)) { - continue; + const auto update_road_to_shoulder_distance = [&](const auto & target_lanelet) { + const auto lines = + rh->getFurthestLinestring(target_lanelet, get_right, get_left, get_opposite, true); + const auto & line = isOnRight(object) ? lines.back() : lines.front(); + const auto d = boost::geometry::distance(object.envelope_poly, to2D(line.basicLineString())); + if (d < road_shoulder_distance) { + road_shoulder_distance = d; + target_line = line; } + }; - if (overhang_lanelet.id()) { - o.overhang_lanelet = overhang_lanelet; - lanelet::BasicPoint3d overhang_basic_pose( - o.overhang_pose.position.x, o.overhang_pose.position.y, o.overhang_pose.position.z); - - const bool get_left = isOnRight(o) && parameters->use_adjacent_lane; - const bool get_right = !isOnRight(o) && parameters->use_adjacent_lane; - const bool get_opposite = parameters->use_opposite_lane; - - lanelet::ConstLineString3d target_line{}; - o.to_road_shoulder_distance = std::numeric_limits::max(); - const auto update_road_to_shoulder_distance = [&](const auto & target_lanelet) { - const auto lines = - rh->getFurthestLinestring(target_lanelet, get_right, get_left, get_opposite, true); - const auto & line = isOnRight(o) ? lines.back() : lines.front(); - const auto d = boost::geometry::distance(o.envelope_poly, to2D(line.basicLineString())); - if (d < o.to_road_shoulder_distance) { - o.to_road_shoulder_distance = d; - target_line = line; - } - }; - - // current lanelet - { - update_road_to_shoulder_distance(overhang_lanelet); - - o.to_road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( - rh, target_line, o.to_road_shoulder_distance, overhang_lanelet, o.overhang_pose.position, - overhang_basic_pose, parameters->use_hatched_road_markings, - parameters->use_intersection_areas); - } - - // previous lanelet - lanelet::ConstLanelets previous_lanelet{}; - if (rh->getPreviousLaneletsWithinRoute(overhang_lanelet, &previous_lanelet)) { - update_road_to_shoulder_distance(previous_lanelet.front()); - - o.to_road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( - rh, target_line, o.to_road_shoulder_distance, previous_lanelet.front(), - o.overhang_pose.position, overhang_basic_pose, parameters->use_hatched_road_markings, - parameters->use_intersection_areas); - } + // current lanelet + { + update_road_to_shoulder_distance(object.overhang_lanelet); - // next lanelet - lanelet::ConstLanelet next_lanelet{}; - if (rh->getNextLaneletWithinRoute(overhang_lanelet, &next_lanelet)) { - update_road_to_shoulder_distance(next_lanelet); + road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( + rh, target_line, road_shoulder_distance, object.overhang_lanelet, + object.overhang_pose.position, p_overhang, parameters->use_hatched_road_markings, + parameters->use_intersection_areas); + } - o.to_road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( - rh, target_line, o.to_road_shoulder_distance, next_lanelet, o.overhang_pose.position, - overhang_basic_pose, parameters->use_hatched_road_markings, - parameters->use_intersection_areas); - } + // previous lanelet + lanelet::ConstLanelets previous_lanelet{}; + if (rh->getPreviousLaneletsWithinRoute(object.overhang_lanelet, &previous_lanelet)) { + update_road_to_shoulder_distance(previous_lanelet.front()); - debug.bounds.push_back(target_line); - } + road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( + rh, target_line, road_shoulder_distance, previous_lanelet.front(), + object.overhang_pose.position, p_overhang, parameters->use_hatched_road_markings, + parameters->use_intersection_areas); + } - // calculate avoid_margin dynamically - // NOTE: This calculation must be after calculating to_road_shoulder_distance. - const auto max_avoid_margin = object_parameter.safety_buffer_lateral * o.distance_factor + - object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; - const auto min_avoid_margin = object_parameter.safety_buffer_lateral + 0.5 * vehicle_width; - const auto soft_lateral_distance_limit = - o.to_road_shoulder_distance - parameters->soft_road_shoulder_margin - 0.5 * vehicle_width; - const auto hard_lateral_distance_limit = - o.to_road_shoulder_distance - parameters->hard_road_shoulder_margin - 0.5 * vehicle_width; - - const auto avoid_margin = [&]() -> boost::optional { - // Step1. check avoidable or not. - if (hard_lateral_distance_limit < min_avoid_margin) { - return boost::none; - } + // next lanelet + lanelet::ConstLanelet next_lanelet{}; + if (rh->getNextLaneletWithinRoute(object.overhang_lanelet, &next_lanelet)) { + update_road_to_shoulder_distance(next_lanelet); - // Step2. check if it should expand road shoulder margin. - if (soft_lateral_distance_limit < min_avoid_margin) { - return min_avoid_margin; - } + road_shoulder_distance = extendToRoadShoulderDistanceWithPolygon( + rh, target_line, road_shoulder_distance, next_lanelet, object.overhang_pose.position, + p_overhang, parameters->use_hatched_road_markings, parameters->use_intersection_areas); + } - // Step3. nominal case. avoid margin is limited by soft constraint. - return std::min(soft_lateral_distance_limit, max_avoid_margin); - }(); + return road_shoulder_distance; +} - if (!!avoid_margin) { - const auto shift_length = calcShiftLength(isOnRight(o), o.overhang_dist, avoid_margin.get()); - if (!isShiftNecessary(isOnRight(o), shift_length)) { - o.reason = "NotNeedAvoidance"; - data.other_objects.push_back(o); - continue; - } +void filterTargetObjects( + ObjectDataArray & objects, AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters) +{ + if (data.current_lanelets.empty()) { + return; + } - if (std::abs(shift_length) < parameters->lateral_execution_threshold) { - o.reason = "LessThanExecutionThreshold"; - data.other_objects.push_back(o); - continue; - } - } + const rclcpp::Time now = rclcpp::Clock(RCL_ROS_TIME).now(); + const auto push_target_object = [&data, &now](auto & object) { + object.last_seen = now; + data.target_objects.push_back(object); + }; - // for non vehicle type object - if (!isVehicleTypeObject(o)) { - if (isWithinCrosswalk(o, rh->getOverallGraphPtr())) { - // avoidance module ignore pedestrian and bicycle around crosswalk - o.reason = "CrosswalkUser"; - data.other_objects.push_back(o); - } else { - // if there is no crosswalk near the object, avoidance module avoids pedestrian and bicycle - // no matter how it is shifted. - o.last_seen = now; - o.avoid_margin = avoid_margin; - data.target_objects.push_back(o); - } + for (auto & o : objects) { + if (!filtering_utils::isSatisfiedWithCommonCondition(o, data, planner_data, parameters)) { + data.other_objects.push_back(o); continue; } - o.is_within_intersection = isWithinIntersection(o, rh); + o.to_road_shoulder_distance = getRoadShoulderDistance(o, data, planner_data, parameters); + o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters); - // from here condition check for vehicle type objects. - if (isForceAvoidanceTarget(o, extend_lanelets, planner_data, parameters)) { - o.last_seen = now; - o.avoid_margin = avoid_margin; - data.target_objects.push_back(o); - continue; - } - - // Object is on center line -> ignore. - if (std::abs(o.lateral) < parameters->threshold_distance_object_is_on_center) { - o.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; + if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) { data.other_objects.push_back(o); continue; } - lanelet::BasicPoint2d object_centroid(o.centroid.x(), o.centroid.y()); - - /** - * Is not object in adjacent lane? - * - Yes -> Is parking object? - * - Yes -> the object is avoidance target. - * - No -> ignore this object. - * - No -> the object is avoidance target no matter whether it is parking object or not. - */ - const auto is_in_ego_lane = - within(object_centroid, overhang_lanelet.polygon2d().basicPolygon()); - if (is_in_ego_lane) { - /** - * TODO(Satoshi Ota) use intersection area - * under the assumption that there is no parking vehicle inside intersection, - * ignore all objects that is in the ego lane as not parking objects. - */ - std::string turn_direction = overhang_lanelet.attributeOr("turn_direction", "else"); - if (turn_direction == "right" || turn_direction == "left" || turn_direction == "straight") { - o.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + if (filtering_utils::isVehicleTypeObject(o)) { + if (!filtering_utils::isSatisfiedWithVehicleCondition(o, data, planner_data, parameters)) { data.other_objects.push_back(o); continue; } - - const auto centerline_pose = - lanelet::utils::getClosestCenterPose(overhang_lanelet, object_pose.position); - lanelet::BasicPoint3d centerline_point( - centerline_pose.position.x, centerline_pose.position.y, centerline_pose.position.z); - - // ============================================ <- most_left_lanelet.leftBound() - // y road shoulder - // ^ ------------------------------------------ - // | x + - // +---> --- object closest lanelet --- o ----- <- object_closest_lanelet.centerline() - // - // -------------------------------------------- - // +: object position - // o: nearest point on centerline - - bool is_left_side_parked_vehicle = false; - if (!isOnRight(o)) { - auto [object_shiftable_distance, sub_type] = [&]() { - const auto most_left_road_lanelet = rh->getMostLeftLanelet(overhang_lanelet); - const auto most_left_lanelet_candidates = - rh->getLaneletMapPtr()->laneletLayer.findUsages(most_left_road_lanelet.leftBound()); - - lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet; - const lanelet::Attribute sub_type = - most_left_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_left_lanelet_candidates) { - const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_left_lanelet = ll; - } - } - - const auto center_to_left_boundary = distance2d( - to2D(most_left_lanelet.leftBound().basicLineString()), to2D(centerline_point)); - - return std::make_pair( - center_to_left_boundary - 0.5 * o.object.shape.dimensions.y, sub_type); - }(); - - if (sub_type.value() != "road_shoulder") { - object_shiftable_distance += parameters->object_check_min_road_shoulder_width; - } - - const auto arc_coordinates = - toArcCoordinates(to2D(overhang_lanelet.centerline().basicLineString()), object_centroid); - o.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance; - - is_left_side_parked_vehicle = o.shiftable_ratio > parameters->object_check_shiftable_ratio; - } - - bool is_right_side_parked_vehicle = false; - if (isOnRight(o)) { - auto [object_shiftable_distance, sub_type] = [&]() { - const auto most_right_road_lanelet = rh->getMostRightLanelet(overhang_lanelet); - const auto most_right_lanelet_candidates = - rh->getLaneletMapPtr()->laneletLayer.findUsages(most_right_road_lanelet.rightBound()); - - lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet; - const lanelet::Attribute sub_type = - most_right_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_right_lanelet_candidates) { - const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_right_lanelet = ll; - } - } - - const auto center_to_right_boundary = distance2d( - to2D(most_right_lanelet.rightBound().basicLineString()), to2D(centerline_point)); - - return std::make_pair( - center_to_right_boundary - 0.5 * o.object.shape.dimensions.y, sub_type); - }(); - - if (sub_type.value() != "road_shoulder") { - object_shiftable_distance += parameters->object_check_min_road_shoulder_width; - } - - const auto arc_coordinates = - toArcCoordinates(to2D(overhang_lanelet.centerline().basicLineString()), object_centroid); - o.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance; - - is_right_side_parked_vehicle = o.shiftable_ratio > parameters->object_check_shiftable_ratio; - } - - if (!is_left_side_parked_vehicle && !is_right_side_parked_vehicle) { - o.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + } else { + if (!filtering_utils::isSatisfiedWithNonVehicleCondition(o, data, planner_data, parameters)) { data.other_objects.push_back(o); continue; } } - o.last_seen = now; - o.avoid_margin = avoid_margin; - - // set data - data.target_objects.push_back(o); + push_target_object(o); } } From c1c90988874e45f218df2223a6b1b524595f9e12 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 24 Nov 2023 22:22:09 +0900 Subject: [PATCH 019/128] feat(objects_of_interest_marker_interface): add objects of interest marker interface (#5564) * feat(interest_objects_marker_interface): add interest objects marker interface Signed-off-by: Fumiya Watanabe * feat(interest_objects_marker_interface): change marker type Signed-off-by: Fumiya Watanabe * feat(interest_objects_marker_interface): change markers Signed-off-by: Fumiya Watanabe * feat(interest_objects_marker_interface): fix lane change interface Signed-off-by: Fumiya Watanabe * feat(interest_objects_marker_interface): fix interface Signed-off-by: Fumiya Watanabe * refactor(interest_objects_marker_interface): fix interface Signed-off-by: Fumiya Watanabe * refactor(interest_objects_marker_interface): refactor and add descriptions Signed-off-by: Fumiya Watanabe * refactor(lane_change): refactor Signed-off-by: Fumiya Watanabe * docs(interest_objects_visualization): add contents (under construction) Signed-off-by: Fumiya Watanabe * chore(interest_objects_visualization): fix includes and package.xml Signed-off-by: Fumiya Watanabe * fix(interest_objects_marker_interface): fix Signed-off-by: Fumiya Watanabe * refactor(objects_of_interest_marker_interface): rename interface Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../scene_module/lane_change/interface.hpp | 11 +++ .../path_safety_checker_parameters.hpp | 1 + planning/behavior_path_planner/package.xml | 1 + .../scene_module/lane_change/interface.cpp | 20 +++- .../path_safety_checker/safety_check.cpp | 3 + .../CMakeLists.txt | 27 ++++++ .../README.md | 15 +++ .../coloring.hpp | 31 ++++++ .../marker_data.hpp | 34 +++++++ .../marker_utils.hpp | 73 ++++++++++++++ .../objects_of_interest_marker_interface.hpp | 93 ++++++++++++++++++ .../package.xml | 28 ++++++ .../src/coloring.cpp | 54 +++++++++++ .../src/marker_utils.cpp | 96 +++++++++++++++++++ .../objects_of_interest_marker_interface.cpp | 90 +++++++++++++++++ 15 files changed, 576 insertions(+), 1 deletion(-) create mode 100644 planning/objects_of_interest_marker_interface/CMakeLists.txt create mode 100644 planning/objects_of_interest_marker_interface/README.md create mode 100644 planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/coloring.hpp create mode 100644 planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_data.hpp create mode 100644 planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp create mode 100644 planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp create mode 100644 planning/objects_of_interest_marker_interface/package.xml create mode 100644 planning/objects_of_interest_marker_interface/src/coloring.cpp create mode 100644 planning/objects_of_interest_marker_interface/src/marker_utils.cpp create mode 100644 planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.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 b7f84987e0499..f2427f185fbaa 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 @@ -25,6 +25,7 @@ #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/path_shifter/path_shifter.hpp" +#include "objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp" #include @@ -48,6 +49,8 @@ namespace behavior_path_planner using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; +using objects_of_interest_marker_interface::ColorName; +using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using tier4_planning_msgs::msg::LaneChangeDebugMsg; using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; @@ -133,6 +136,13 @@ class LaneChangeInterface : public SceneModuleInterface void setObjectDebugVisualization() const; + void setObjectsOfInterestData(const bool is_approved); + + void publishObjectsOfInterestData() + { + objects_of_interest_marker_interface_.publishMarkerArray(); + } + void updateSteeringFactorPtr(const BehaviorModuleOutput & output); void updateSteeringFactorPtr( @@ -142,6 +152,7 @@ class LaneChangeInterface : public SceneModuleInterface mutable LaneChangeDebugMsgArray lane_change_debug_msg_array_; std::unique_ptr prev_approved_path_; + ObjectsOfInterestMarkerInterface objects_of_interest_marker_interface_; void clearAbortApproval() { is_abort_path_approved_ = false; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp index cfd242ab5b78b..29fc44b439bbc 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -201,6 +201,7 @@ struct CollisionCheckDebug std::vector obj_predicted_path; ///< object's predicted path. Polygon2d extended_ego_polygon{}; ///< Ego vehicle's extended collision polygon. Polygon2d extended_obj_polygon{}; ///< Detected object's extended collision polygon. + autoware_auto_perception_msgs::msg::Shape obj_shape; ///< object's shape. }; using CollisionCheckDebugPair = std::pair; using CollisionCheckDebugMap = diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 1f1eed3f95ec2..c7265528d69ca 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -61,6 +61,7 @@ magic_enum motion_utils object_recognition_utils + objects_of_interest_marker_interface planning_test_utils rclcpp rclcpp_components 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 05b7c5d7dec92..57acfa5002296 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 @@ -40,7 +40,8 @@ LaneChangeInterface::LaneChangeInterface( : SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, - prev_approved_path_{std::make_unique()} + prev_approved_path_{std::make_unique()}, + objects_of_interest_marker_interface_{&node, name} { steering_factor_interface_ptr_ = std::make_unique(&node, name); } @@ -198,6 +199,9 @@ BehaviorModuleOutput LaneChangeInterface::plan() stop_pose_ = module_type_->getStopPose(); + setObjectsOfInterestData(true); + publishObjectsOfInterestData(); + updateSteeringFactorPtr(output); clearWaitingApproval(); @@ -220,6 +224,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); module_type_->updateLaneChangeStatus(); setObjectDebugVisualization(); + setObjectsOfInterestData(false); + publishObjectsOfInterestData(); // 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); @@ -308,6 +314,18 @@ void LaneChangeInterface::setObjectDebugVisualization() const } } +void LaneChangeInterface::setObjectsOfInterestData(const bool is_approved) +{ + const auto debug_data = + is_approved ? module_type_->getAfterApprovalDebugData() : module_type_->getDebugData(); + for (const auto & [uuid, data] : debug_data) { + const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; + objects_of_interest_marker_interface_.insertObjectData( + data.current_obj_pose, data.obj_shape, color); + } + return; +} + std::shared_ptr LaneChangeInterface::get_debug_msg_array() const { const auto debug_data = module_type_->getDebugData(); diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index ef36241adfa24..71a51901b3af6 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -319,6 +319,8 @@ std::vector getCollidedPolygons( const auto interpolated_data = getInterpolatedPoseWithVelocityAndPolygonStamped( predicted_ego_path, current_time, ego_vehicle_info); if (!interpolated_data) { + debug.expected_obj_pose = obj_pose; + debug.extended_obj_polygon = obj_polygon; continue; } const auto & ego_pose = interpolated_data->pose; @@ -399,6 +401,7 @@ CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) CollisionCheckDebug debug; debug.current_obj_pose = obj.initial_pose.pose; debug.extended_obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); + debug.obj_shape = obj.shape; debug.current_twist = obj.initial_twist.twist; return {tier4_autoware_utils::toHexString(obj.uuid), debug}; } diff --git a/planning/objects_of_interest_marker_interface/CMakeLists.txt b/planning/objects_of_interest_marker_interface/CMakeLists.txt new file mode 100644 index 0000000000000..eec17f8d9218b --- /dev/null +++ b/planning/objects_of_interest_marker_interface/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.5) +project(objects_of_interest_marker_interface) + +### Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Werror) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +ament_auto_add_library(objects_of_interest_marker_interface SHARED + src/coloring.cpp + src/objects_of_interest_marker_interface.cpp + src/marker_utils.cpp +) + +# Test +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package() diff --git a/planning/objects_of_interest_marker_interface/README.md b/planning/objects_of_interest_marker_interface/README.md new file mode 100644 index 0000000000000..636e4fde32ca2 --- /dev/null +++ b/planning/objects_of_interest_marker_interface/README.md @@ -0,0 +1,15 @@ +# Objects Of Interest Marker Interface + +!!! warning + + Under Construction + +## Purpose + +## Inner-workings / Algorithms + +## Inputs / Outputs + +## Assumptions / Known limits + +## Future extensions / Unimplemented parts diff --git a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/coloring.hpp b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/coloring.hpp new file mode 100644 index 0000000000000..041a6a454d0dd --- /dev/null +++ b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/coloring.hpp @@ -0,0 +1,31 @@ +// 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 OBJECTS_OF_INTEREST_MARKER_INTERFACE__COLORING_HPP_ +#define OBJECTS_OF_INTEREST_MARKER_INTERFACE__COLORING_HPP_ +#include "objects_of_interest_marker_interface/marker_data.hpp" + +#include + +#include + +namespace objects_of_interest_marker_interface::coloring +{ +std_msgs::msg::ColorRGBA getGreen(const float alpha); +std_msgs::msg::ColorRGBA getAmber(const float alpha); +std_msgs::msg::ColorRGBA getRed(const float alpha); +std_msgs::msg::ColorRGBA getGray(const float alpha); +} // namespace objects_of_interest_marker_interface::coloring + +#endif // OBJECTS_OF_INTEREST_MARKER_INTERFACE__COLORING_HPP_ diff --git a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_data.hpp b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_data.hpp new file mode 100644 index 0000000000000..32262ab7eec35 --- /dev/null +++ b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_data.hpp @@ -0,0 +1,34 @@ +// 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 OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_DATA_HPP_ +#define OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_DATA_HPP_ + +#include +#include +#include + +namespace objects_of_interest_marker_interface +{ +struct ObjectMarkerData +{ + geometry_msgs::msg::Pose pose{}; + autoware_auto_perception_msgs::msg::Shape shape{}; + std_msgs::msg::ColorRGBA color; +}; + +enum class ColorName { GRAY, GREEN, AMBER, RED }; +} // namespace objects_of_interest_marker_interface + +#endif // OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_DATA_HPP_ diff --git a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp new file mode 100644 index 0000000000000..cff45e5c1a9eb --- /dev/null +++ b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp @@ -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. + +#ifndef OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_UTILS_HPP_ +#define OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_UTILS_HPP_ +#include "objects_of_interest_marker_interface/marker_data.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace objects_of_interest_marker_interface::marker_utils +{ +/** + * @brief Create arrow marker from object marker data + * @param id Marker id + * @param data Object marker data + * @param name Module name + * @param height_offset Height offset of arrow marker + * @param arrow_length Length of arrow marker + */ +visualization_msgs::msg::Marker createArrowMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, + const double height_offset, const double arrow_length = 1.0); + +/** + * @brief Create circle marker from object marker data + * @param id Marker id + * @param data Object marker data + * @param name Module name + * @param radius Radius of circle marker + * @param height_offset Height offset of circle marker + * @param line_width Line width of circle marker + */ +visualization_msgs::msg::Marker createCircleMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, const double radius, + const double height_offset, const double line_width = 0.1); + +/** + * @brief Create target marker from object marker data + * @param id Marker id + * @param data Object marker data + * @param name Module name + * @param height_offset Height offset of target marker + * @param arrow_length Length of arrow marker + * @param line_width Line width of circle marker + */ +visualization_msgs::msg::MarkerArray createTargetMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, + const double height_offset, const double arrow_length = 1.0, const double line_width = 0.1); +} // namespace objects_of_interest_marker_interface::marker_utils + +#endif // OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_UTILS_HPP_ diff --git a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp new file mode 100644 index 0000000000000..79bab6d5faf69 --- /dev/null +++ b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp @@ -0,0 +1,93 @@ +// 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 OBJECTS_OF_INTEREST_MARKER_INTERFACE__OBJECTS_OF_INTEREST_MARKER_INTERFACE_HPP_ +#define OBJECTS_OF_INTEREST_MARKER_INTERFACE__OBJECTS_OF_INTEREST_MARKER_INTERFACE_HPP_ +#include "objects_of_interest_marker_interface/coloring.hpp" +#include "objects_of_interest_marker_interface/marker_data.hpp" +#include "objects_of_interest_marker_interface/marker_utils.hpp" + +#include + +#include +#include +#include +#include + +#include +#include + +namespace objects_of_interest_marker_interface +{ +class ObjectsOfInterestMarkerInterface +{ +public: + /** + * @brief Constructor + * @param node Node that publishes marker + * @param name Module name + */ + ObjectsOfInterestMarkerInterface(rclcpp::Node * node, const std::string & name); + + /** + * @brief Insert object data to visualize + * @param pose Object pose + * @param shape Object shape + * @param color_name Color name + */ + void insertObjectData( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape, + const ColorName & color_name); + + /** + * @brief Insert object data to visualize with custom color data + * @param pose Object pose + * @param shape Object shape + * @param color Color data with alpha + */ + void insertObjectDataWithCustomColor( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape, + const std_msgs::msg::ColorRGBA & color); + + /** + * @brief Publish interest objects marker + */ + void publishMarkerArray(); + + /** + * @brief Set height offset of markers + * @param offset Height offset of markers + */ + void setHeightOffset(const double offset); + + /** + * @brief Get color data from color name + * @param color_name Color name + * @param alpha Alpha + */ + static std_msgs::msg::ColorRGBA getColor(const ColorName & color_name, const float alpha = 0.99f); + +private: + rclcpp::Publisher::SharedPtr pub_marker_; + + double height_offset_{0.5}; + std::vector obj_marker_data_array_; + + std::string name_; + std::string topic_namespace_ = "/planning/debug/objects_of_interest"; +}; + +} // namespace objects_of_interest_marker_interface + +#endif // OBJECTS_OF_INTEREST_MARKER_INTERFACE__OBJECTS_OF_INTEREST_MARKER_INTERFACE_HPP_ diff --git a/planning/objects_of_interest_marker_interface/package.xml b/planning/objects_of_interest_marker_interface/package.xml new file mode 100644 index 0000000000000..0aebdd3b099b1 --- /dev/null +++ b/planning/objects_of_interest_marker_interface/package.xml @@ -0,0 +1,28 @@ + + + objects_of_interest_marker_interface + 0.1.0 + The objects_of_interest_marker_interface package + + Fumiya Watanabe + + Apache License 2.0 + + Fumiya Watanabe + + ament_cmake_auto + + autoware_auto_perception_msgs + geometry_msgs + rclcpp + std_msgs + tier4_autoware_utils + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/objects_of_interest_marker_interface/src/coloring.cpp b/planning/objects_of_interest_marker_interface/src/coloring.cpp new file mode 100644 index 0000000000000..6c566474e4c9e --- /dev/null +++ b/planning/objects_of_interest_marker_interface/src/coloring.cpp @@ -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. + +#include "objects_of_interest_marker_interface/coloring.hpp" + +namespace +{ +std_msgs::msg::ColorRGBA convertFromColorCode(const uint64_t code, const float alpha) +{ + const float r = static_cast(code >> 16) / 255.0; + const float g = static_cast((code << 48) >> 56) / 255.0; + const float b = static_cast((code << 56) >> 56) / 255.0; + + return tier4_autoware_utils::createMarkerColor(r, g, b, alpha); +} +} // namespace + +namespace objects_of_interest_marker_interface::coloring +{ +std_msgs::msg::ColorRGBA getGreen(const float alpha) +{ + constexpr uint64_t code = 0x00e676; + return convertFromColorCode(code, alpha); +} + +std_msgs::msg::ColorRGBA getAmber(const float alpha) +{ + constexpr uint64_t code = 0xffea00; + return convertFromColorCode(code, alpha); +} + +std_msgs::msg::ColorRGBA getRed(const float alpha) +{ + constexpr uint64_t code = 0xff3d00; + return convertFromColorCode(code, alpha); +} + +std_msgs::msg::ColorRGBA getGray(const float alpha) +{ + constexpr uint64_t code = 0xbdbdbd; + return convertFromColorCode(code, alpha); +} +} // namespace objects_of_interest_marker_interface::coloring diff --git a/planning/objects_of_interest_marker_interface/src/marker_utils.cpp b/planning/objects_of_interest_marker_interface/src/marker_utils.cpp new file mode 100644 index 0000000000000..71414eae4dbe7 --- /dev/null +++ b/planning/objects_of_interest_marker_interface/src/marker_utils.cpp @@ -0,0 +1,96 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "objects_of_interest_marker_interface/marker_utils.hpp" + +namespace objects_of_interest_marker_interface::marker_utils +{ +using geometry_msgs::msg::Point; + +using std_msgs::msg::ColorRGBA; + +using tier4_autoware_utils::createDefaultMarker; +using tier4_autoware_utils::createMarkerScale; + +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + +Marker createArrowMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, + const double height_offset, const double arrow_length) +{ + const double line_width = 0.25 * arrow_length; + const double head_width = 0.5 * arrow_length; + const double head_height = 0.5 * arrow_length; + + Marker marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name, id, Marker::ARROW, + createMarkerScale(line_width, head_width, head_height), data.color); + + const double height = 0.5 * data.shape.dimensions.z; + + Point src, dst; + src = data.pose.position; + src.z += height + height_offset + arrow_length; + dst = data.pose.position; + dst.z += height + height_offset; + + marker.points.push_back(src); + marker.points.push_back(dst); + + return marker; +} + +Marker createCircleMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, const double radius, + const double height_offset, const double line_width) +{ + Marker marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name, id, Marker::LINE_STRIP, + createMarkerScale(line_width, 0.0, 0.0), data.color); + + const double height = 0.5 * data.shape.dimensions.z; + + constexpr size_t num_points = 20; + for (size_t i = 0; i < num_points; ++i) { + Point point; + const double ratio = static_cast(i) / static_cast(num_points); + const double theta = 2 * tier4_autoware_utils::pi * ratio; + point.x = data.pose.position.x + radius * tier4_autoware_utils::cos(theta); + point.y = data.pose.position.y + radius * tier4_autoware_utils::sin(theta); + point.z = data.pose.position.z + height + height_offset; + marker.points.push_back(point); + } + marker.points.push_back(marker.points.front()); + + return marker; +} + +MarkerArray createTargetMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, + const double height_offset, const double arrow_length, const double line_width) +{ + MarkerArray marker_array; + marker_array.markers.push_back( + createArrowMarker(id, data, name + "_arrow", height_offset, arrow_length)); + marker_array.markers.push_back(createCircleMarker( + id, data, name + "_circle1", 0.5 * arrow_length, height_offset + 0.75 * arrow_length, + line_width)); + marker_array.markers.push_back(createCircleMarker( + id, data, name + "_circle2", 0.75 * arrow_length, height_offset + 0.75 * arrow_length, + line_width)); + + return marker_array; +} +} // namespace objects_of_interest_marker_interface::marker_utils diff --git a/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp b/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp new file mode 100644 index 0000000000000..6261b4791be48 --- /dev/null +++ b/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp @@ -0,0 +1,90 @@ +// 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 "objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp" + +#include +#include +#include + +namespace objects_of_interest_marker_interface +{ +using autoware_auto_perception_msgs::msg::Shape; +using geometry_msgs::msg::Pose; +using std_msgs::msg::ColorRGBA; +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + +ObjectsOfInterestMarkerInterface::ObjectsOfInterestMarkerInterface( + rclcpp::Node * node, const std::string & name) +: name_{name} +{ + // Publisher + pub_marker_ = node->create_publisher(topic_namespace_ + "/" + name, 1); +} + +void ObjectsOfInterestMarkerInterface::insertObjectData( + const Pose & pose, const Shape & shape, const ColorName & color_name) +{ + insertObjectDataWithCustomColor(pose, shape, getColor(color_name)); +} + +void ObjectsOfInterestMarkerInterface::insertObjectDataWithCustomColor( + const Pose & pose, const Shape & shape, const ColorRGBA & color) +{ + ObjectMarkerData data; + data.pose = pose; + data.shape = shape; + data.color = color; + + obj_marker_data_array_.push_back(data); +} + +void ObjectsOfInterestMarkerInterface::publishMarkerArray() +{ + MarkerArray marker_array; + for (size_t i = 0; i < obj_marker_data_array_.size(); ++i) { + const auto data = obj_marker_data_array_.at(i); + const MarkerArray target_marker = + marker_utils::createTargetMarker(i, data, name_, height_offset_); + marker_array.markers.insert( + marker_array.markers.end(), target_marker.markers.begin(), target_marker.markers.end()); + } + pub_marker_->publish(marker_array); + obj_marker_data_array_.clear(); +} + +void ObjectsOfInterestMarkerInterface::setHeightOffset(const double offset) +{ + height_offset_ = offset; +} + +ColorRGBA ObjectsOfInterestMarkerInterface::getColor( + const ColorName & color_name, const float alpha) +{ + switch (color_name) { + case ColorName::GREEN: + return coloring::getGreen(alpha); + case ColorName::AMBER: + return coloring::getAmber(alpha); + case ColorName::RED: + return coloring::getRed(alpha); + case ColorName::GRAY: + return coloring::getGray(alpha); + default: + return coloring::getGray(alpha); + } +} + +} // namespace objects_of_interest_marker_interface From a353f5ff36e4af545ad32599bb0b42b18c45bac4 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 24 Nov 2023 23:47:06 +0900 Subject: [PATCH 020/128] feat(logging_level_configure_rviz_plugin): add autoware_util logger button (#5666) * feat(logging_level_configure_rviz_plugin): add autoware_util logger button Signed-off-by: Takamasa Horibe * add for control Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../config/logger_config.yaml | 21 +++++++++++++++++++ 1 file changed, 21 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 23a5123d8d8e2..11dd050658aeb 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 @@ -85,3 +85,24 @@ Control: logger_name: control.vehicle_cmd_gate - node_name: /control/vehicle_cmd_gate logger_name: tier4_autoware_utils + +# ============================================================ +# common +# ============================================================ + +Common: + tier4_autoware_utils: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner + logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/lane_driving/motion_planning/path_smoother + logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/motion_velocity_smoother + logger_name: tier4_autoware_utils + - node_name: /control/trajectory_follower/controller_node_exe + logger_name: tier4_autoware_utils + - node_name: /control/vehicle_cmd_gate + logger_name: tier4_autoware_utils From 957331e842733d42f9c765ea833929398a53cb2a Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 24 Nov 2023 15:27:10 +0000 Subject: [PATCH 021/128] chore: update CODEOWNERS (#5499) Signed-off-by: GitHub Co-authored-by: github-actions Co-authored-by: Tomohito ANDO --- .github/CODEOWNERS | 46 +++++++++++++++++++++++++--------------------- 1 file changed, 25 insertions(+), 21 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index e298dccefd827..a51cffba864f6 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -19,9 +19,9 @@ common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/glog_component/** takamasa.horibe@tier4.jp common/goal_distance_calculator/** taiki.tanaka@tier4.jp common/grid_map_utils/** maxime.clement@tier4.jp -common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp -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 yutaka.shimizu@tier4.jp +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 @@ -34,8 +34,9 @@ common/tensorrt_common/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato. 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_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 yutaka.shimizu@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_debug_rviz_plugin/** takayuki.murooka@tier4.jp @@ -43,7 +44,7 @@ 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_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 yutaka.shimizu@tier4.jp +common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp common/tier4_screen_capture_rviz_plugin/** taiki.tanaka@tier4.jp common/tier4_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp @@ -56,7 +57,7 @@ common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.j common/traffic_light_utils/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp yusuke.muramatsu@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 yutaka.shimizu@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 control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -81,20 +82,22 @@ launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.j launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp launch/tier4_map_launch/** 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 yutaka.shimizu@tier4.jp zulfaqar.azmi@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 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/** akihiro.sakurai@tier4.jp fumihito.ito@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_parser/** 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 @@ -113,20 +116,20 @@ perception/cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihir perception/compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yukihiro.saito@tier4.jp perception/crosswalk_traffic_light_estimator/** satoshi.ota@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/detected_object_feature_remover/** tomoya.kimura@tier4.jp -perception/detected_object_validation/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/detected_object_validation/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp perception/detection_by_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/elevation_map_loader/** kosuke.takeuchi@tier4.jp taichi.higashide@tier4.jp perception/euclidean_cluster/** yukihiro.saito@tier4.jp perception/front_vehicle_velocity_estimator/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp perception/ground_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp perception/heatmap_visualizer/** kotaro.uetake@tier4.jp -perception/image_projection_based_fusion/** yukihiro.saito@tier4.jp yusuke.muramatsu@tier4.jp +perception/image_projection_based_fusion/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp yusuke.muramatsu@tier4.jp perception/lidar_apollo_instance_segmentation/** yukihiro.saito@tier4.jp perception/lidar_apollo_segmentation_tvm/** ambroise.vincent@arm.com xinyu.wang@tier4.jp perception/lidar_apollo_segmentation_tvm_nodes/** ambroise.vincent@arm.com xinyu.wang@tier4.jp perception/lidar_centerpoint/** kenzo.lobos@tier4.jp yusuke.muramatsu@tier4.jp perception/lidar_centerpoint_tvm/** carl.liu@autocore.ai xinyu.wang@tier4.jp -perception/map_based_prediction/** kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp yutaka.shimizu@tier4.jp +perception/map_based_prediction/** kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp perception/multi_object_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/object_merger/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/object_range_splitter/** yukihiro.saito@tier4.jp @@ -152,7 +155,7 @@ 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_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@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 yutaka.shimizu@tier4.jp zulfaqar.azmi@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_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 @@ -161,30 +164,31 @@ planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp +planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner_common/** isamu.takagi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_run_out_module/** makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_run_out_module/** makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_stop_line_module/** shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yutaka.shimizu@tier4.jp +planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_template_module/** daniel.sanchez@tier4.jp planning/behavior_velocity_traffic_light_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp -planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp -planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp -planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp -planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp yutaka.shimizu@tier4.jp +planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp +planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp planning/obstacle_stop_planner/** berkay@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp +planning/planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp -planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp zulfaqar.azmi@tier4.jp +planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp planning/rtc_interface/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/rtc_replayer/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/sampling_based_planner/bezier_sampler/** maxime.clement@tier4.jp From 9a88fc63f9bbf9a20492230d0cdeae0910725618 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 25 Nov 2023 01:59:13 +0900 Subject: [PATCH 022/128] refactor(behavior_path_planner): move updateCollisionCheckDebugMap to safety checker (#5670) refactor(goal_planner): move updateCollisionCheckDebugMap to safety checker Signed-off-by: kosuke55 --- .../behavior_path_planner/marker_utils/utils.hpp | 3 --- .../utils/path_safety_checker/safety_check.hpp | 2 ++ .../src/marker_utils/utils.cpp | 13 ------------- .../src/scene_module/avoidance/avoidance_module.cpp | 5 +++-- .../goal_planner/goal_planner_module.cpp | 2 +- .../src/scene_module/lane_change/normal.cpp | 12 ++++++++---- .../start_planner/start_planner_module.cpp | 4 ++-- .../src/utils/lane_change/utils.cpp | 2 +- .../src/utils/path_safety_checker/safety_check.cpp | 13 +++++++++++++ 9 files changed, 30 insertions(+), 26 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp index 72787f61d0fce..ed38bfcd805aa 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/utils.hpp @@ -56,9 +56,6 @@ inline int64_t bitShift(int64_t original_id) return original_id << (sizeof(int32_t) * 8 / 2); } -void updateCollisionCheckDebugMap( - CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe); - 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/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index 7c00aec864246..7a9bc3c9b3b17 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -134,6 +134,8 @@ bool checkPolygonsIntersects( // debug CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj); +void updateCollisionCheckDebugMap( + CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe); } // namespace behavior_path_planner::utils::path_safety_checker diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index 44978ec1124d6..648b4c6cc1fe6 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -42,19 +42,6 @@ using tier4_autoware_utils::createMarkerScale; using tier4_autoware_utils::createPoint; using visualization_msgs::msg::Marker; -void updateCollisionCheckDebugMap( - CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe) -{ - auto & [key, element] = object_debug; - element.is_safe = is_safe; - if (debug_map.find(key) != debug_map.end()) { - debug_map[key] = element; - return; - } - - debug_map.insert(object_debug); -} - 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/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 3124f00932375..a3cb4dd6dc8e2 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -2028,14 +2028,15 @@ bool AvoidanceModule::isSafePath( if (!utils::path_safety_checker::checkCollision( shifted_path.path, ego_predicted_path, object, obj_path, p, parameters_->rss_params, hysteresis_factor, current_debug_data.second)) { - marker_utils::updateCollisionCheckDebugMap( + utils::path_safety_checker::updateCollisionCheckDebugMap( debug.collision_check, current_debug_data, false); safe_count_ = 0; return false; } } - marker_utils::updateCollisionCheckDebugMap(debug.collision_check, current_debug_data, true); + utils::path_safety_checker::updateCollisionCheckDebugMap( + debug.collision_check, current_debug_data, true); } safe_count_++; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 04fd59676822b..1fcee94717932 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -1753,7 +1753,7 @@ bool GoalPlannerModule::checkSafetyWithRSS( planned_path, ego_predicted_path, object, obj_path, planner_data_->parameters, safety_check_params_->rss_params, hysteresis_factor, current_debug_data.second); - marker_utils::updateCollisionCheckDebugMap( + utils::path_safety_checker::updateCollisionCheckDebugMap( goal_planner_data_.collision_check, current_debug_data, !has_collision); return has_collision; 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 27e1af6836a74..f35c2d6083836 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 @@ -1728,7 +1728,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( current_debug_data.second); if (collided_polygons.empty()) { - marker_utils::updateCollisionCheckDebugMap(debug_data, current_debug_data, is_safe); + utils::path_safety_checker::updateCollisionCheckDebugMap( + debug_data, current_debug_data, is_safe); continue; } @@ -1738,20 +1739,23 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( utils::lane_change::isCollidedPolygonsInLanelet(collided_polygons, expanded_target_lanes); if (!collision_in_current_lanes && !collision_in_target_lanes) { - marker_utils::updateCollisionCheckDebugMap(debug_data, current_debug_data, is_safe); + utils::path_safety_checker::updateCollisionCheckDebugMap( + debug_data, current_debug_data, is_safe); continue; } is_safe = false; path_safety_status.is_safe = false; - marker_utils::updateCollisionCheckDebugMap(debug_data, current_debug_data, is_safe); + utils::path_safety_checker::updateCollisionCheckDebugMap( + debug_data, current_debug_data, is_safe); const auto & obj_pose = obj.initial_pose.pose; const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, obj.shape); path_safety_status.is_object_coming_from_rear |= !utils::path_safety_checker::isTargetObjectFront( path, current_pose, common_parameters.vehicle_info, obj_polygon); } - marker_utils::updateCollisionCheckDebugMap(debug_data, current_debug_data, is_safe); + utils::path_safety_checker::updateCollisionCheckDebugMap( + debug_data, current_debug_data, is_safe); } return path_safety_status; 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 e0a17ca247d8b..06b195ea29b50 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 @@ -1104,7 +1104,7 @@ bool StartPlannerModule::isSafePath() const if (!utils::path_safety_checker::checkCollision( pull_out_path, ego_predicted_path, object, obj_path, planner_data_->parameters, safety_check_params_->rss_params, hysteresis_factor, current_debug_data.second)) { - marker_utils::updateCollisionCheckDebugMap( + utils::path_safety_checker::updateCollisionCheckDebugMap( start_planner_data_.collision_check, current_debug_data, false); is_safe_dynamic_objects = false; is_safe_dynamic_object = false; @@ -1112,7 +1112,7 @@ bool StartPlannerModule::isSafePath() const } } if (is_safe_dynamic_object) { - marker_utils::updateCollisionCheckDebugMap( + utils::path_safety_checker::updateCollisionCheckDebugMap( start_planner_data_.collision_check, current_debug_data, is_safe_dynamic_object); } } 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 a8c7ce83fd98c..1b68b8387d7d2 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -989,7 +989,7 @@ bool passParkedObject( // If there are still enough length after the target object, we delay the lane change if (min_dist_to_end_of_current_lane > minimum_lane_change_length) { debug.second.unsafe_reason = "delay lane change"; - marker_utils::updateCollisionCheckDebugMap(object_debug, debug, false); + utils::path_safety_checker::updateCollisionCheckDebugMap(object_debug, debug, false); return true; } diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 71a51901b3af6..a29eeb070ce88 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -406,4 +406,17 @@ CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) return {tier4_autoware_utils::toHexString(obj.uuid), debug}; } +void updateCollisionCheckDebugMap( + CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe) +{ + auto & [key, element] = object_debug; + element.is_safe = is_safe; + if (debug_map.find(key) != debug_map.end()) { + debug_map[key] = element; + return; + } + + debug_map.insert(object_debug); +} + } // namespace behavior_path_planner::utils::path_safety_checker From dd8d8a0db3aa61578d2f10bbb29c996b29dc5407 Mon Sep 17 00:00:00 2001 From: Mehmet Dogru <48479081+mehmetdogru@users.noreply.github.com> Date: Sat, 25 Nov 2023 16:01:34 +0900 Subject: [PATCH 023/128] feat(map_based_prediction): consider only routable neighbours for lane change (#5669) Signed-off-by: Mehmet Dogru --- .../config/map_based_prediction.param.yaml | 1 + .../map_based_prediction_node.hpp | 1 + .../src/map_based_prediction_node.cpp | 30 +++++++++++-------- 3 files changed, 20 insertions(+), 12 deletions(-) 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 260ae45da2e05..69ff96a263f4b 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -29,5 +29,6 @@ diff_dist_threshold_to_left_bound: 0.29 #[m] diff_dist_threshold_to_right_bound: -0.29 #[m] num_continuous_state_transition: 3 + consider_only_routable_neighbours: false reference_path_resolution: 0.5 #[m] 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 01f39057aef36..bdd9ad89bc025 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 @@ -157,6 +157,7 @@ class MapBasedPredictionNode : public rclcpp::Node double diff_dist_threshold_to_left_bound_; double diff_dist_threshold_to_right_bound_; int num_continuous_state_transition_; + bool consider_only_routable_neighbours_; double reference_path_resolution_; // Stop watch 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 2ceb22fd6e7b9..b2f1296cc85b9 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -760,6 +760,9 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ num_continuous_state_transition_ = declare_parameter("lane_change_detection.num_continuous_state_transition"); + + consider_only_routable_neighbours_ = + declare_parameter("lane_change_detection.consider_only_routable_neighbours"); } reference_path_resolution_ = declare_parameter("reference_path_resolution"); /* prediction path will disabled when the estimated path length exceeds lanelet length. This @@ -1514,19 +1517,22 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( if (!!opt) { return *opt; } - const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft(lanelet) - : routing_graph_ptr_->adjacentRight(lanelet); - if (!!adjacent) { - return *adjacent; - } - // search for unconnected lanelet - const auto unconnected_lanelets = get_left - ? getLeftLineSharingLanelets(lanelet, lanelet_map_ptr_) - : getRightLineSharingLanelets(lanelet, lanelet_map_ptr_); - // just return first candidate of unconnected lanelet for now - if (!unconnected_lanelets.empty()) { - return unconnected_lanelets.front(); + if (!consider_only_routable_neighbours_) { + const auto adjacent = get_left ? routing_graph_ptr_->adjacentLeft(lanelet) + : routing_graph_ptr_->adjacentRight(lanelet); + if (!!adjacent) { + return *adjacent; + } + // search for unconnected lanelet + const auto unconnected_lanelets = + get_left ? getLeftLineSharingLanelets(lanelet, lanelet_map_ptr_) + : getRightLineSharingLanelets(lanelet, lanelet_map_ptr_); + // just return first candidate of unconnected lanelet for now + if (!unconnected_lanelets.empty()) { + return unconnected_lanelets.front(); + } } + // if no candidate lanelet found, return empty return std::nullopt; }; From a58157195ebc141ec17118571c780b7412534d41 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 25 Nov 2023 09:35:03 +0000 Subject: [PATCH 024/128] chore: update CODEOWNERS (#5674) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index a51cffba864f6..b1bec4eb372eb 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -179,6 +179,7 @@ planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp takamasa.horibe@tier4.jp +planning/objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp planning/obstacle_stop_planner/** berkay@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp From e76d0324106af0198ab24fe2bf0ba10ef0c327db Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sun, 26 Nov 2023 14:23:12 +0900 Subject: [PATCH 025/128] fix(behavior_velocity_planner): fix json schema (#5676) Signed-off-by: satoshi-ota --- .../schema/behavior_velocity_planner.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json b/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json index 7291b4ea42015..a119139a13a20 100644 --- a/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json +++ b/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json @@ -42,7 +42,7 @@ "description": "max jerk of the vehicle" }, "is_publish_debug_path": { - "type": "number", + "type": "boolean", "default": "false", "description": "is publish debug path?" } From 627c5f4601887dc7805eac7472800cdfd9410728 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Sun, 26 Nov 2023 17:30:42 +0900 Subject: [PATCH 026/128] fix(goal_planner): adjust the goal search range to regenerate the feasible refined_path (#5571) * adjust the goal search range to regenerate the feasible refined_path Signed-off-by: Zhe Shen --------- Signed-off-by: Zhe Shen Co-authored-by: kyoichi-sugahara --- .../default_fixed_goal_planner.hpp | 6 ++ .../default_fixed_goal_planner.cpp | 57 +++++++++++++++++-- 2 files changed, 57 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp index 9cede67fff6e5..1595503a225f8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp @@ -33,6 +33,12 @@ class DefaultFixedGoalPlanner : public FixedGoalPlannerBase protected: PathWithLaneId modifyPathForSmoothGoalConnection( const PathWithLaneId & path, const std::shared_ptr & planner_data) const; + bool isPathValid( + const PathWithLaneId & refined_path, + const std::shared_ptr & planner_data) const; + lanelet::ConstLanelets extractLaneletsFromPath( + const PathWithLaneId & refined_path, + const std::shared_ptr & planner_data) const; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp b/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp index 4c9832c374c63..22bce5bbff0c0 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp @@ -16,6 +16,7 @@ #include "behavior_path_planner/utils/goal_planner/util.hpp" #include "behavior_path_planner/utils/path_utils.hpp" +#include "behavior_path_planner/utils/utils.hpp" #include #include @@ -24,7 +25,8 @@ namespace behavior_path_planner { - +using Point2d = tier4_autoware_utils::Point2d; +using autoware_auto_planning_msgs::msg::PathWithLaneId; BehaviorModuleOutput DefaultFixedGoalPlanner::plan( const std::shared_ptr & planner_data) const { @@ -38,6 +40,40 @@ BehaviorModuleOutput DefaultFixedGoalPlanner::plan( return output; } +lanelet::ConstLanelets DefaultFixedGoalPlanner::extractLaneletsFromPath( + const PathWithLaneId & refined_path, + const std::shared_ptr & planner_data) const +{ + const auto & rh = planner_data->route_handler; + lanelet::ConstLanelets refined_path_lanelets; + for (size_t i = 0; i < refined_path.points.size(); ++i) { + const auto & path_point = refined_path.points.at(i); + int64_t lane_id = path_point.lane_ids.at(0); + lanelet::ConstLanelet lanelet = rh->getLaneletsFromId(lane_id); + bool is_unique = + std::find(refined_path_lanelets.begin(), refined_path_lanelets.end(), lanelet) == + refined_path_lanelets.end(); + if (is_unique) { + refined_path_lanelets.push_back(lanelet); + } + } + return refined_path_lanelets; +} + +bool DefaultFixedGoalPlanner::isPathValid( + const PathWithLaneId & refined_path, + const std::shared_ptr & planner_data) const +{ + const auto lanelets = extractLaneletsFromPath(refined_path, planner_data); + // std::any_of detects whether any point lies outside lanelets + bool has_points_outside_lanelet = std::any_of( + refined_path.points.begin(), refined_path.points.end(), + [&lanelets](const auto & refined_path_point) { + return !utils::isInLanelets(refined_path_point.point.pose, lanelets); + }); + return !has_points_outside_lanelet; +} + PathWithLaneId DefaultFixedGoalPlanner::modifyPathForSmoothGoalConnection( const PathWithLaneId & path, const std::shared_ptr & planner_data) const { @@ -53,11 +89,20 @@ PathWithLaneId DefaultFixedGoalPlanner::modifyPathForSmoothGoalConnection( refined_goal = goal; } } - - auto refined_path = utils::refinePathForGoal( - planner_data->parameters.refine_goal_search_radius_range, M_PI * 0.5, path, refined_goal, - goal_lane_id); - + double goal_search_radius{planner_data->parameters.refine_goal_search_radius_range}; + // TODO(shen): define in the parameter + constexpr double range_reduce_by{1.0}; // set a reasonable value, 10% - 20% of the + // refine_goal_search_radius_range is recommended + bool is_valid_path{false}; + autoware_auto_planning_msgs::msg::PathWithLaneId refined_path; + while (goal_search_radius >= 0 && !is_valid_path) { + refined_path = + utils::refinePathForGoal(goal_search_radius, M_PI * 0.5, path, refined_goal, goal_lane_id); + if (isPathValid(refined_path, planner_data)) { + is_valid_path = true; + } + goal_search_radius -= range_reduce_by; + } return refined_path; } From b856fd0b5e0d65bb82bcf3f9fc5d9252e8bc7816 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 26 Nov 2023 21:04:41 +0900 Subject: [PATCH 027/128] feat(goal_planner): keep decided path (#5663) Signed-off-by: kosuke55 --- .../scene_module/goal_planner/goal_planner_module.hpp | 2 ++ .../scene_module/goal_planner/goal_planner_module.cpp | 9 +++++++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 2e1c8d4010305..bce41a46cc963 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -246,6 +246,7 @@ struct PreviousPullOverData found_path = false; is_safe = false; safety_status = SafetyStatus{}; + has_decided_path = false; } std::shared_ptr stop_path{nullptr}; @@ -253,6 +254,7 @@ struct PreviousPullOverData bool found_path{false}; bool is_safe{false}; SafetyStatus safety_status{}; + bool has_decided_path{false}; }; class GoalPlannerModule : public SceneModuleInterface diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 1fcee94717932..63ecb289a4db9 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -854,10 +854,13 @@ void GoalPlannerModule::updateSteeringFactor( pose, distance, SteeringFactor::GOAL_PLANNER, steering_factor_direction, type, ""); } -// NOTE: Once this function returns true, it will continue to return true thereafter. Because -// selectPullOverPath() will not select new path. bool GoalPlannerModule::hasDecidedPath() const { + // Once this function returns true, it will continue to return true thereafter + if (prev_data_.has_decided_path) { + return true; + } + // if path is not safe, not decided if (!thread_safe_data_.foundPullOverPath()) { return false; @@ -1034,6 +1037,8 @@ void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) // this is used to determine whether to generate a new stop path or keep the current stop path. prev_data_.found_path = thread_safe_data_.foundPullOverPath(); + prev_data_.has_decided_path = hasDecidedPath(); + // This is related to safety check, so if it is disabled, return here. if (!parameters_->safety_check_params.enable_safety_check) { prev_data_.safety_status.is_safe = true; From c9b932d97024c5d5dc2896852654822172aee6cd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 26 Nov 2023 22:45:47 +0900 Subject: [PATCH 028/128] feat(dyanmic_avoidance): deal with oncoming forked predicted path (#5678) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 5 ++ .../dynamic_avoidance_module.cpp | 65 ++++++++++++++++++- 2 files changed, 68 insertions(+), 2 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 077e0ecec0f29..34769a98b0545 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 @@ -320,9 +320,14 @@ 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( + const std::vector & path_points_for_object_polygon, + const size_t obj_seg_idx, const PredictedPath & obj_path, + const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( const std::vector & path_points_for_object_polygon, 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; MinMaxValue calcMinMaxLateralOffsetToAvoid( const std::vector & path_points_for_object_polygon, 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 f917f1e2f3c65..066684629aa45 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 @@ -222,6 +222,27 @@ std::optional getObstacleFromUuid( } return *itr; } + +double calcDistanceToSegment( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2_first, + const geometry_msgs::msg::Point & p2_second) +{ + const Eigen::Vector2d first_to_target(p1.x - p2_first.x, p1.y - p2_first.y); + const Eigen::Vector2d second_to_target(p1.x - p2_second.x, p1.y - p2_second.y); + const Eigen::Vector2d first_to_second(p2_second.x - p2_first.x, p2_second.y - p2_first.y); + + if (first_to_target.dot(first_to_second) < 0) { + return first_to_target.norm(); + } + if (second_to_target.dot(-first_to_second) < 0) { + return second_to_target.norm(); + } + + const Eigen::Vector2d p2_nearest = + Eigen::Vector2d{p2_first.x, p2_first.y} + + 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(); +} } // namespace DynamicAvoidanceModule::DynamicAvoidanceModule( @@ -564,10 +585,11 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 2.h. calculate longitudinal and lateral offset to avoid to generate object polygon by - // "object_path_base" + // "ego_path_base" const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( - path_points_for_object_polygon, object.pose, obj_points, object.vel, time_to_collision); + path_points_for_object_polygon, object.pose, obj_points, object.vel, obj_path, object.shape, + time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( path_points_for_object_polygon, obj_points, is_collision_left, object.lat_vel, prev_object); @@ -805,6 +827,7 @@ DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudi MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( const std::vector & path_points_for_object_polygon, 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 = @@ -844,11 +867,49 @@ 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(path_points_for_object_polygon, obj_seg_idx, obj_path, obj_shape); + return MinMaxValue{ + std::max(obj_lon_offset.min_value - start_length_to_avoid, valid_start_length_to_avoid), + obj_lon_offset.max_value + end_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( + const std::vector & path_points_for_object_polygon, const size_t obj_seg_idx, + const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const +{ + const size_t valid_obj_path_end_idx = [&]() { + int ego_path_idx = obj_seg_idx + 1; + for (size_t obj_path_idx = 0; obj_path_idx < obj_path.path.size(); ++obj_path_idx) { + bool are_paths_close{false}; + for (; 0 < ego_path_idx; --ego_path_idx) { + const double dist_to_segment = calcDistanceToSegment( + obj_path.path.at(obj_path_idx).position, + path_points_for_object_polygon.at(ego_path_idx).point.pose.position, + path_points_for_object_polygon.at(ego_path_idx - 1).point.pose.position); + if ( + dist_to_segment < planner_data_->parameters.vehicle_width / 2.0 + + parameters_->lat_offset_from_obstacle + + calcObstacleMaxLength(obj_shape)) { + are_paths_close = true; + break; + } + } + + if (!are_paths_close) { + return obj_path_idx; + } + } + return obj_path.path.size() - 1; + }(); + return -motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); +} + MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( const std::vector & path_points_for_object_polygon, const Polygon2d & obj_points, const bool is_collision_left, const double obj_normal_vel, From bc43dec130e1cc95e5d75c921dbb52fb628be482 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 26 Nov 2023 23:20:08 +0900 Subject: [PATCH 029/128] feat(goal_planner): safer safety check (#5677) typo Signed-off-by: kosuke55 --- .../goal_planner/goal_planner.param.yaml | 8 +- .../goal_planner/goal_planner_module.hpp | 2 - .../path_safety_checker_parameters.hpp | 13 +- .../path_safety_checker/safety_check.hpp | 19 +- .../goal_planner/goal_planner_module.cpp | 46 ++++- .../src/scene_module/goal_planner/manager.cpp | 14 ++ .../path_safety_checker/safety_check.cpp | 165 ++++++++++++++++++ 7 files changed, 258 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml b/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml index 19550bac5c196..cf5bf683f7b73 100644 --- a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml +++ b/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml @@ -160,6 +160,7 @@ safety_check_params: # safety check configuration enable_safety_check: true + method: "integral_predicted_polygon" keep_unsafe_time: 3.0 # collision check parameters check_all_predicted_path: true @@ -170,10 +171,15 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 longitudinal_velocity_delta_time: 0.8 + integral_predicted_polygon_params: + forward_margin: 1.0 + backward_margin: 1.0 + lat_margin: 1.0 + time_horizon: 10.0 # hysteresis factor to expand/shrink polygon with the value hysteresis_factor_expand_rate: 1.0 # temporary - backward_path_length: 30.0 + backward_path_length: 100.0 forward_path_length: 100.0 # debug diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index bce41a46cc963..97a5fdd966b8f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -244,7 +244,6 @@ struct PreviousPullOverData stop_path = nullptr; stop_path_after_approval = nullptr; found_path = false; - is_safe = false; safety_status = SafetyStatus{}; has_decided_path = false; } @@ -252,7 +251,6 @@ struct PreviousPullOverData std::shared_ptr stop_path{nullptr}; std::shared_ptr stop_path_after_approval{nullptr}; bool found_path{false}; - bool is_safe{false}; SafetyStatus safety_status{}; bool has_decided_path{false}; }; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp index 29fc44b439bbc..c4a60332fe4ff 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -134,6 +134,14 @@ struct RSSparams double rear_vehicle_deceleration{0.0}; ///< brake parameter }; +struct IntegralPredictedPolygonParams +{ + double forward_margin{0.0}; ///< Forward margin for extended ego polygon for collision check. + double backward_margin{0.0}; ///< Backward margin for extended ego polygon for collision check. + double lat_margin{0.0}; ///< Lateral margin for extended ego polygon for collision check. + double time_horizon{0.0}; ///< Time horizon for object's prediction. +}; + /** * @brief Parameters for generating the ego vehicle's predicted path. */ @@ -173,12 +181,15 @@ struct ObjectsFilteringParams struct SafetyCheckParams { bool enable_safety_check{false}; ///< Enable safety checks. - double keep_unsafe_time{0.0}; ///< Time to keep unsafe before changing to safe. + std::string method{"RSS"}; /// Method to use for safety checks. + /// possible values: ["RSS", "integral_predicted_polygon"] + double keep_unsafe_time{0.0}; ///< Time to keep unsafe before changing to safe. double hysteresis_factor_expand_rate{ 0.0}; ///< Hysteresis factor to expand/shrink polygon with the value. double backward_path_length{0.0}; ///< Length of the backward lane for path generation. double forward_path_length{0.0}; ///< Length of the forward path lane for path generation. RSSparams rss_params{}; ///< Parameters related to the RSS model. + IntegralPredictedPolygonParams integral_predicted_polygon_params{}; ///< Parameters for polygon. bool publish_debug_marker{false}; ///< Option to publish debug markers. }; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index 7a9bc3c9b3b17..a4851e97d5008 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -85,6 +85,20 @@ boost::optional calcInterpolatedPoseWithVelocity( boost::optional getInterpolatedPoseWithVelocityAndPolygonStamped( const std::vector & pred_path, const double current_time, const VehicleInfo & ego_info); +boost::optional getInterpolatedPoseWithVelocityAndPolygonStamped( + const std::vector & pred_path, const double current_time, + const Shape & shape); +template +std::vector filterPredictedPathByTimeHorizon( + const std::vector & path, const double time_horizon, const F & interpolateFunc); +std::vector filterPredictedPathByTimeHorizon( + const std::vector & path, const double time_horizon); +ExtendedPredictedObject filterObjectPredictedPathByTimeHorizon( + const ExtendedPredictedObject & object, const double time_horizon, + const bool check_all_predicted_path); +ExtendedPredictedObjects filterObjectPredictedPathByTimeHorizon( + const ExtendedPredictedObjects & objects, const double time_horizon, + const bool check_all_predicted_path); /** * @brief Iterate the points in the ego and target's predicted path and * perform safety check for each of the iterated points. @@ -131,12 +145,15 @@ std::vector getCollidedPolygons( bool checkPolygonsIntersects( const std::vector & polys_1, const std::vector & polys_2); +bool checkSafetyWithIntegralPredictedPolygon( + const std::vector & ego_predicted_path, const VehicleInfo & vehicle_info, + const ExtendedPredictedObjects & objects, const bool check_all_predicted_path, + const IntegralPredictedPolygonParams & params, CollisionCheckDebugMap & debug_map); // debug CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj); void updateCollisionCheckDebugMap( CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe); - } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 63ecb289a4db9..b2692200557ed 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -769,7 +769,7 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output) const { // safe or not safe(no feasible stop_path found) -> not_safe: try to find new feasible stop_path - if (prev_data_.is_safe || !prev_data_.stop_path_after_approval) { + 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( @@ -1817,8 +1817,23 @@ std::pair GoalPlannerModule::isSafePath() const const double hysteresis_factor = prev_data_.safety_status.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; - const bool current_is_safe = checkSafetyWithRSS( - pull_over_path, ego_predicted_path, target_objects_on_lane.on_current_lane, hysteresis_factor); + const bool current_is_safe = std::invoke([&]() { + if (parameters_->safety_check_params.method == "RSS") { + return checkSafetyWithRSS( + pull_over_path, ego_predicted_path, target_objects_on_lane.on_current_lane, + hysteresis_factor); + } else if (parameters_->safety_check_params.method == "integral_predicted_polygon") { + return utils::path_safety_checker::checkSafetyWithIntegralPredictedPolygon( + ego_predicted_path, vehicle_info_, target_objects_on_lane.on_current_lane, + objects_filtering_params_->check_all_predicted_path, + parameters_->safety_check_params.integral_predicted_polygon_params, + goal_planner_data_.collision_check); + } + RCLCPP_ERROR( + getLogger(), " [pull_over] invalid safety check method: %s", + parameters_->safety_check_params.method.c_str()); + throw std::domain_error("[pull_over] invalid safety check method"); + }); /*   *   ==== is_safe @@ -1940,11 +1955,34 @@ void GoalPlannerModule::setDebugData() goal_planner_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9)); } - add(showSafetyCheckInfo(goal_planner_data_.collision_check, "object_debug_info")); + if (parameters_->safety_check_params.method == "RSS") { + add(showSafetyCheckInfo(goal_planner_data_.collision_check, "object_debug_info")); + } 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); + + // visualize safety status maker + { + visualization_msgs::msg::MarkerArray marker_array{}; + const auto color = prev_data_.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); + auto marker = createDefaultMarker( + header.frame_id, header.stamp, "safety_status", 0, + visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); + + marker.pose = planner_data_->self_odometry->pose.pose; + marker.text += "is_safe: " + std::to_string(prev_data_.safety_status.is_safe) + "\n"; + if (prev_data_.safety_status.safe_start_time) { + const double elapsed_time_from_safe_start = + (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds(); + marker.text += + "elapsed_time_from_safe_start: " + std::to_string(elapsed_time_from_safe_start) + "\n"; + } + marker_array.markers.push_back(marker); + add(marker_array); + } } // Visualize planner type text diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp index 8baeb10ed1b85..83c0d7002936c 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp @@ -336,6 +336,7 @@ GoalPlannerModuleManager::GoalPlannerModuleManager( node->declare_parameter(safety_check_ns + "enable_safety_check"); p.safety_check_params.keep_unsafe_time = node->declare_parameter(safety_check_ns + "keep_unsafe_time"); + p.safety_check_params.method = node->declare_parameter(safety_check_ns + "method"); p.safety_check_params.hysteresis_factor_expand_rate = node->declare_parameter(safety_check_ns + "hysteresis_factor_expand_rate"); p.safety_check_params.backward_path_length = @@ -361,6 +362,19 @@ GoalPlannerModuleManager::GoalPlannerModuleManager( node->declare_parameter(rss_ns + "longitudinal_velocity_delta_time"); } + // IntegralPredictedPolygonParams + std::string integral_ns = safety_check_ns + "integral_predicted_polygon_params."; + { + p.safety_check_params.integral_predicted_polygon_params.forward_margin = + node->declare_parameter(integral_ns + "forward_margin"); + p.safety_check_params.integral_predicted_polygon_params.backward_margin = + node->declare_parameter(integral_ns + "backward_margin"); + p.safety_check_params.integral_predicted_polygon_params.lat_margin = + node->declare_parameter(integral_ns + "lat_margin"); + p.safety_check_params.integral_predicted_polygon_params.time_horizon = + node->declare_parameter(integral_ns + "time_horizon"); + } + // debug { const std::string ns = base_ns + "debug."; diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index a29eeb070ce88..473a0489a14a9 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -14,13 +14,16 @@ #include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp" +#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp" #include "interpolation/linear_interpolation.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include "tier4_autoware_utils/ros/uuid_helper.hpp" +#include #include #include +#include #include namespace behavior_path_planner::utils::path_safety_checker @@ -181,6 +184,27 @@ Polygon2d createExtendedPolygon( : tier4_autoware_utils::inverseClockwise(polygon); } +std::vector createExtendedPolygonsFromPoseWithVelocityStamped( + const std::vector & predicted_path, const VehicleInfo & vehicle_info, + const double forward_margin, const double backward_margin, const double lat_margin) +{ + std::vector polygons{}; + polygons.reserve(predicted_path.size()); + + for (const auto & elem : predicted_path) { + const auto & pose = elem.pose; + const double base_to_front = vehicle_info.max_longitudinal_offset_m + forward_margin; + const double base_to_rear = vehicle_info.rear_overhang_m + backward_margin; + const double width = vehicle_info.vehicle_width_m + lat_margin * 2; + + const auto polygon = + tier4_autoware_utils::toFootprint(pose, base_to_front, base_to_rear, width); + polygons.push_back(polygon); + } + + return polygons; +} + PredictedPath convertToPredictedPath( const std::vector & path, const double time_resolution) { @@ -274,6 +298,147 @@ boost::optional getInterpolatedPoseWithVeloci return PoseWithVelocityAndPolygonStamped{current_time, pose, velocity, ego_polygon}; } +boost::optional getInterpolatedPoseWithVelocityAndPolygonStamped( + const std::vector & pred_path, const double current_time, + const Shape & shape) +{ + auto toPoseWithVelocityStampedVector = [](const auto & pred_path) { + std::vector path; + path.reserve(pred_path.size()); + for (const auto & elem : pred_path) { + path.push_back(PoseWithVelocityStamped{elem.time, elem.pose, elem.velocity}); + } + return path; + }; + + const auto interpolation_result = + calcInterpolatedPoseWithVelocity(toPoseWithVelocityStampedVector(pred_path), current_time); + + if (!interpolation_result) { + return {}; + } + + const auto & pose = interpolation_result->pose; + const auto & velocity = interpolation_result->velocity; + + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(pose, shape); + + return PoseWithVelocityAndPolygonStamped{current_time, pose, velocity, obj_polygon}; +} + +template +std::vector filterPredictedPathByTimeHorizon( + const std::vector & path, const double time_horizon, const F & interpolateFunc) +{ + std::vector filtered_path; + + for (const auto & elem : path) { + if (elem.time < time_horizon) { + filtered_path.push_back(elem); + } else { + break; + } + } + + const auto interpolated_opt = interpolateFunc(path, time_horizon); + if (interpolated_opt) { + filtered_path.push_back(*interpolated_opt); + } + + return filtered_path; +}; + +std::vector filterPredictedPathByTimeHorizon( + const std::vector & path, const double time_horizon) +{ + return filterPredictedPathByTimeHorizon( + path, time_horizon, [](const auto & path, const auto & time) { + return calcInterpolatedPoseWithVelocity(path, time); + }); +} + +ExtendedPredictedObject filterObjectPredictedPathByTimeHorizon( + const ExtendedPredictedObject & object, const double time_horizon, + const bool check_all_predicted_path) +{ + auto filtered_object = object; + auto filtered_predicted_paths = getPredictedPathFromObj(object, check_all_predicted_path); + + for (auto & predicted_path : filtered_predicted_paths) { + // path is vector of polygon + const auto filtered_path = filterPredictedPathByTimeHorizon( + predicted_path.path, time_horizon, [&object](const auto & poses, double t) { + return getInterpolatedPoseWithVelocityAndPolygonStamped(poses, t, object.shape); + }); + predicted_path.path = filtered_path; + } + + filtered_object.predicted_paths = filtered_predicted_paths; + return filtered_object; +} + +ExtendedPredictedObjects filterObjectPredictedPathByTimeHorizon( + const ExtendedPredictedObjects & objects, const double time_horizon, + const bool check_all_predicted_path) +{ + ExtendedPredictedObjects filtered_objects; + filtered_objects.reserve(objects.size()); + + for (const auto & object : objects) { + filtered_objects.push_back( + filterObjectPredictedPathByTimeHorizon(object, time_horizon, check_all_predicted_path)); + } + + return filtered_objects; +} + +bool checkSafetyWithIntegralPredictedPolygon( + const std::vector & ego_predicted_path, const VehicleInfo & vehicle_info, + const ExtendedPredictedObjects & objects, const bool check_all_predicted_path, + const IntegralPredictedPolygonParams & params, CollisionCheckDebugMap & debug_map) +{ + const std::vector filtered_ego_path = filterPredictedPathByTimeHorizon( + ego_predicted_path, params.time_horizon); // path is vector of pose + const std::vector extended_ego_polygons = + createExtendedPolygonsFromPoseWithVelocityStamped( + filtered_ego_path, vehicle_info, params.forward_margin, params.backward_margin, + params.lat_margin); + + const ExtendedPredictedObjects filtered_path_objects = filterObjectPredictedPathByTimeHorizon( + objects, params.time_horizon, check_all_predicted_path); // path is vector of polygon + + Polygon2d ego_integral_polygon{}; + for (const auto & ego_polygon : extended_ego_polygons) { + std::vector unions{}; + boost::geometry::union_(ego_integral_polygon, ego_polygon, unions); + if (!unions.empty()) { + ego_integral_polygon = unions.front(); + boost::geometry::correct(ego_integral_polygon); + } + } + + // check collision + for (const auto & object : filtered_path_objects) { + CollisionCheckDebugPair debug_pair = createObjectDebug(object); + 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); + } + return false; + } + } + } + } + return true; +} + bool checkCollision( const PathWithLaneId & planned_path, const std::vector & predicted_ego_path, From 49112d9a67b790f363562569ae75fb2e3e68e63d Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Sun, 26 Nov 2023 23:25:45 +0900 Subject: [PATCH 030/128] feat(run_out): use the predicted object's velocity and covariance for the collision detection (#5672) * feat(run_out): use the predicted object's velocity and covariance for the collision detection Signed-off-by: Tomohito Ando * chore: update readme Signed-off-by: Tomohito Ando * fix calculation Signed-off-by: Tomohito Ando --------- Signed-off-by: Tomohito Ando --- .../README.md | 20 ++++++----- .../config/run_out.param.yaml | 19 +++++----- .../src/dynamic_obstacle.cpp | 36 +++++++++++++++++-- .../src/manager.cpp | 9 +++-- .../src/utils.hpp | 2 ++ 5 files changed, 64 insertions(+), 22 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/README.md b/planning/behavior_velocity_run_out_module/README.md index a36cfdf6485c6..c48f2a951cd55 100644 --- a/planning/behavior_velocity_run_out_module/README.md +++ b/planning/behavior_velocity_run_out_module/README.md @@ -188,15 +188,17 @@ You can choose whether to use this feature by parameter of `slow_down_limit.enab | `margin_ahead` | double | [m] ahead margin for detection area polygon | | `margin_behind` | double | [m] behind margin for detection area polygon | -| Parameter /dynamic_obstacle | Type | Description | -| --------------------------- | ------ | ----------------------------------------------------------------------------------------------------------------------------- | -| `min_vel_kmph` | double | [km/h] minimum velocity for dynamic obstacles | -| `max_vel_kmph` | double | [km/h] maximum velocity for dynamic obstacles | -| `diameter` | double | [m] diameter of obstacles. used for creating dynamic obstacles from points | -| `height` | double | [m] height of obstacles. used for creating dynamic obstacles from points | -| `max_prediction_time` | double | [sec] create predicted path until this time | -| `time_step` | double | [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path | -| `points_interval` | double | [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method | +| Parameter /dynamic_obstacle | Type | Description | +| ------------------------------------ | ------ | ----------------------------------------------------------------------------------------------------------------------------- | +| `use_mandatory_area` | double | [-] whether to use mandatory detection area | +| `assume_fixed_velocity.enable` | double | [-] If enabled, the obstacle's velocity is assumed to be within the minimum and maximum velocity values specified below | +| `assume_fixed_velocity.min_vel_kmph` | double | [km/h] minimum velocity for dynamic obstacles | +| `assume_fixed_velocity.max_vel_kmph` | double | [km/h] maximum velocity for dynamic obstacles | +| `diameter` | double | [m] diameter of obstacles. used for creating dynamic obstacles from points | +| `height` | double | [m] height of obstacles. used for creating dynamic obstacles from points | +| `max_prediction_time` | double | [sec] create predicted path until this time | +| `time_step` | double | [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path | +| `points_interval` | double | [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method | | Parameter /approaching | Type | Description | | ---------------------- | ------ | ----------------------------------------------------- | 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 2641214ac5ad4..ea63462b32d84 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 @@ -21,14 +21,17 @@ # parameter to create abstracted dynamic obstacles dynamic_obstacle: - use_mandatory_area: false # [-] whether to use mandatory detection area - min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles - max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles - diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points - height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points - max_prediction_time: 10.0 # [sec] create predicted path until this time - time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path - points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method + use_mandatory_area: false # [-] whether to use mandatory detection area + assume_fixed_velocity: + enable: false # [-] If enabled, the obstacle's velocity is assumed to be within the minimum and maximum velocity values specified below + min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles + max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles + std_dev_multiplier: 1.96 # [-] min and max velocity of the obstacles are calculated from this value and covariance + diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points + height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points + max_prediction_time: 10.0 # [sec] create predicted path until this time + time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path + points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method # approach if ego has stopped in the front of the obstacle for a certain amount of time approaching: diff --git a/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index 16013efc5fd97..e4c4d3cc8a012 100644 --- a/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -287,6 +287,31 @@ PointCloud2 concatPointCloud( return concat_points; } +void calculateMinAndMaxVelFromCovariance( + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double std_dev_multiplier, run_out_utils::DynamicObstacle & dynamic_obstacle) +{ + const double x_velocity = std::abs(twist_with_covariance.twist.linear.x); + const double y_velocity = std::abs(twist_with_covariance.twist.linear.y); + const double x_variance = twist_with_covariance.covariance.at(0); + const double y_variance = twist_with_covariance.covariance.at(7); + const double x_std_dev = std::sqrt(x_variance); + const double y_std_dev = std::sqrt(y_variance); + + // calculate the min and max velocity using the standard deviation of twist + // note that this assumes the covariance of x and y is zero + const double min_x = std::max(0.0, x_velocity - std_dev_multiplier * x_std_dev); + const double min_y = std::max(0.0, y_velocity - std_dev_multiplier * y_std_dev); + const double min_velocity = std::hypot(min_x, min_y); + + const double max_x = x_velocity + std_dev_multiplier * x_std_dev; + const double max_y = y_velocity + std_dev_multiplier * y_std_dev; + const double max_velocity = std::hypot(max_x, max_y); + + dynamic_obstacle.min_velocity_mps = min_velocity; + dynamic_obstacle.max_velocity_mps = max_velocity; +} + } // namespace DynamicObstacleCreatorForObject::DynamicObstacleCreatorForObject( @@ -303,9 +328,14 @@ std::vector DynamicObstacleCreatorForObject::createDynamicObsta DynamicObstacle dynamic_obstacle; dynamic_obstacle.pose = predicted_object.kinematics.initial_pose_with_covariance.pose; - // TODO(Tomohito Ando): calculate velocity from covariance of predicted_object - dynamic_obstacle.min_velocity_mps = tier4_autoware_utils::kmph2mps(param_.min_vel_kmph); - dynamic_obstacle.max_velocity_mps = tier4_autoware_utils::kmph2mps(param_.max_vel_kmph); + if (param_.assume_fixed_velocity) { + dynamic_obstacle.min_velocity_mps = tier4_autoware_utils::kmph2mps(param_.min_vel_kmph); + dynamic_obstacle.max_velocity_mps = tier4_autoware_utils::kmph2mps(param_.max_vel_kmph); + } else { + calculateMinAndMaxVelFromCovariance( + predicted_object.kinematics.initial_twist_with_covariance, param_.std_dev_multiplier, + dynamic_obstacle); + } dynamic_obstacle.classifications = predicted_object.classification; dynamic_obstacle.shape = predicted_object.shape; diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index a5253f59b60f9..09c87ed81cf38 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -84,8 +84,13 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) auto & p = planner_param_.dynamic_obstacle; const std::string ns_do = ns + ".dynamic_obstacle"; p.use_mandatory_area = getOrDeclareParameter(node, ns_do + ".use_mandatory_area"); - p.min_vel_kmph = getOrDeclareParameter(node, ns_do + ".min_vel_kmph"); - p.max_vel_kmph = getOrDeclareParameter(node, ns_do + ".max_vel_kmph"); + p.assume_fixed_velocity = + getOrDeclareParameter(node, ns_do + ".assume_fixed_velocity.enable"); + p.min_vel_kmph = + getOrDeclareParameter(node, ns_do + ".assume_fixed_velocity.min_vel_kmph"); + p.max_vel_kmph = + getOrDeclareParameter(node, ns_do + ".assume_fixed_velocity.max_vel_kmph"); + p.std_dev_multiplier = getOrDeclareParameter(node, ns_do + ".std_dev_multiplier"); p.diameter = getOrDeclareParameter(node, ns_do + ".diameter"); p.height = getOrDeclareParameter(node, ns_do + ".height"); p.max_prediction_time = getOrDeclareParameter(node, ns_do + ".max_prediction_time"); diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index b25a8fc94bff3..519a05756a4a4 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -114,11 +114,13 @@ struct Smoother struct DynamicObstacleParam { bool use_mandatory_area; + bool assume_fixed_velocity; float min_vel_kmph; float max_vel_kmph; // parameter to convert points to dynamic obstacle + float std_dev_multiplier; float diameter; // [m] float height; // [m] float max_prediction_time; // [sec] From 14ecdb073687e0f1c50f809ebeb12ccd03f74613 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Mon, 27 Nov 2023 08:30:14 +0900 Subject: [PATCH 031/128] chore(tier4_perception_launcher): remove launch parameter default of detection_by_tracker (#5664) * chore(tier4_perception_launcher): remove launch parameter default Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 5 +++-- .../camera_lidar_radar_fusion_based_detection.launch.xml | 5 +++-- .../launch/object_recognition/detection/detection.launch.xml | 3 --- .../detection/lidar_based_detection.launch.xml | 5 +++-- launch/tier4_perception_launch/launch/perception.launch.xml | 1 - 5 files changed, 9 insertions(+), 10 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 b3e9e9148ee60..660e6fa7778c8 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 @@ -194,8 +194,9 @@ - - + + + 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 1b4c3f38e038d..65caad54876ff 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 @@ -218,8 +218,9 @@ - - + + + 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 b69f1c0ee8b14..6b87d655d39e8 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 @@ -74,7 +74,6 @@ - @@ -106,7 +105,6 @@ - @@ -136,7 +134,6 @@ - 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 ac521934265d7..2c8b7d6581c53 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 @@ -60,8 +60,9 @@ - - + + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 6582dfd32d91d..96ad80131e4e7 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -177,7 +177,6 @@ - From 0496b197e9bdf9503885fbe5b3196c974823fdb8 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 27 Nov 2023 09:08:04 +0900 Subject: [PATCH 032/128] feat(pid_longitudinal_controller): use Integrated error when vehicle is stopped (#5549) * Add time threshold to activate error integration Signed-off-by: Daniel Sanchez * add pre-commit changes Signed-off-by: Daniel Sanchez * add param to enable or disable low speed error integration Signed-off-by: Daniel Sanchez * eliminate unused include Signed-off-by: Daniel Sanchez * Update control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp Co-authored-by: Takamasa Horibe Signed-off-by: Daniel Sanchez * Update README and formatting Signed-off-by: Daniel Sanchez * delete extra NOTE comment Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez Signed-off-by: Daniel Sanchez Co-authored-by: Takamasa Horibe --- control/pid_longitudinal_controller/README.md | 13 +++++++--- .../pid_longitudinal_controller.hpp | 7 +++++ ...ongitudinal_controller_defaults.param.yaml | 2 ++ .../src/pid_longitudinal_controller.cpp | 26 ++++++++++++++++++- .../param/longitudinal/pid.param.yaml | 2 ++ 5 files changed, 46 insertions(+), 4 deletions(-) diff --git a/control/pid_longitudinal_controller/README.md b/control/pid_longitudinal_controller/README.md index 9d25322c793e0..a110cb94d1d91 100644 --- a/control/pid_longitudinal_controller/README.md +++ b/control/pid_longitudinal_controller/README.md @@ -90,8 +90,13 @@ This PID logic has a maximum value for the output of each term. This is to preve - Large integral terms may cause unintended behavior by users. - Unintended noise may cause the output of the derivative term to be very large. -Also, the integral term is not accumulated when the vehicle is stopped. This is to prevent unintended accumulation of the integral term in cases such as Autoware assumes that the vehicle is engaged, but an external system has locked the vehicle to start. -On the other hand, if the vehicle gets stuck in a depression in the road surface when starting, the vehicle will not start forever, which is currently being addressed by developers. +Note: by default, the integral term in the control system is not accumulated when the vehicle is stationary. This precautionary measure aims to prevent unintended accumulation of the integral term in scenarios where Autoware assumes the vehicle is engaged, but an external system has immobilized the vehicle to initiate startup procedures. + +However, certain situations may arise, such as when the vehicle encounters a depression in the road surface during startup or if the slope compensation is inaccurately estimated (lower than necessary), leading to a failure to initiate motion. To address these scenarios, it is possible to activate error integration even when the vehicle is at rest by setting the `enable_integration_at_low_speed` parameter to true. + +When `enable_integration_at_low_speed` is set to true, the PID controller will initiate integration of the acceleration error after a specified duration defined by the `time_threshold_before_pid_integration` parameter has elapsed without the vehicle surpassing a minimum velocity set by the `current_vel_threshold_pid_integration` parameter. + +The presence of the `time_threshold_before_pid_integration` parameter is important for practical PID tuning. Integrating the error when the vehicle is stationary or at low speed can complicate PID tuning. This parameter effectively introduces a delay before the integral part becomes active, preventing it from kicking in immediately. This delay allows for more controlled and effective tuning of the PID controller. At present, PID control is implemented from the viewpoint of trade-off between development/maintenance cost and performance. This may be replaced by a higher performance controller (adaptive control or robust control) in future development. @@ -207,7 +212,9 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving. | max_d_effort | double | max value of acceleration with d gain | 0.0 | | min_d_effort | double | min value of acceleration with d gain | 0.0 | | lpf_vel_error_gain | double | gain of low-pass filter for velocity error | 0.9 | -| current_vel_threshold_pid_integration | double | Velocity error is integrated for I-term only when the absolute value of current velocity is larger than this parameter. [m/s] | 0.5 | +| enable_integration_at_low_speed | bool | Whether to enable integration of acceleration errors when the vehicle speed is lower than `current_vel_threshold_pid_integration` or not. | +| current_vel_threshold_pid_integration | double | Velocity error is integrated for I-term only when the absolute value of current velocity is larger than this parameter. [m/s] | +| time_threshold_before_pid_integration | double | How much time without the vehicle moving must past to enable PID error integration. [s] | 5.0 | | brake_keeping_acc | double | If `enable_brake_keeping_before_stop` is true, a certain acceleration is kept during DRIVE state before the ego stops [m/s^2] See [Brake keeping](#brake-keeping). | 0.2 | ### STOPPING Parameter (smooth stop) diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 921cd3995f6a9..b4ac9e1506eb7 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -97,6 +98,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro // vehicle info double m_wheel_base; + bool m_prev_vehicle_is_under_control{false}; + std::shared_ptr m_under_control_starting_time{nullptr}; // control state enum class ControlState { DRIVE = 0, STOPPING, STOPPED, EMERGENCY }; @@ -145,7 +148,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro // drive PIDController m_pid_vel; std::shared_ptr m_lpf_vel_error{nullptr}; + bool m_enable_integration_at_low_speed; double m_current_vel_threshold_pid_integrate; + double m_time_threshold_before_pid_integrate; bool m_enable_brake_keeping_before_stop; double m_brake_keeping_acc; @@ -384,6 +389,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro void updateDebugVelAcc( const Motion & ctrl_cmd, const geometry_msgs::msg::Pose & current_pose, const ControlData & control_data); + + double getTimeUnderControl(); }; } // namespace autoware::motion::control::pid_longitudinal_controller diff --git a/control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml b/control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml index eb2ef443c4576..f1ddea7ebad88 100644 --- a/control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml +++ b/control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml @@ -32,7 +32,9 @@ max_d_effort: 0.0 min_d_effort: 0.0 lpf_vel_error_gain: 0.9 + enable_integration_at_low_speed: false current_vel_threshold_pid_integration: 0.5 + time_threshold_before_pid_integration: 2.0 enable_brake_keeping_before_stop: false brake_keeping_acc: -0.2 diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index d13e628f2e1d4..12f0eece1e477 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -100,9 +100,14 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node) const double lpf_vel_error_gain{node.declare_parameter("lpf_vel_error_gain")}; m_lpf_vel_error = std::make_shared(0.0, lpf_vel_error_gain); + m_enable_integration_at_low_speed = + node.declare_parameter("enable_integration_at_low_speed"); m_current_vel_threshold_pid_integrate = node.declare_parameter("current_vel_threshold_pid_integration"); // [m/s] + m_time_threshold_before_pid_integrate = + node.declare_parameter("time_threshold_before_pid_integration"); // [s] + m_enable_brake_keeping_before_stop = node.declare_parameter("enable_brake_keeping_before_stop"); // [-] m_brake_keeping_acc = node.declare_parameter("brake_keeping_acc"); // [m/s^2] @@ -284,6 +289,7 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac m_pid_vel.setLimits(max_pid, min_pid, max_p, min_p, max_i, min_i, max_d, min_d); update_param("current_vel_threshold_pid_integration", m_current_vel_threshold_pid_integrate); + update_param("time_threshold_before_pid_integration", m_time_threshold_before_pid_integrate); } // stopping state @@ -556,6 +562,11 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled && m_current_operation_mode.mode == OperationModeState::AUTONOMOUS; + if (is_under_control != m_prev_vehicle_is_under_control) { + m_prev_vehicle_is_under_control = is_under_control; + m_under_control_starting_time = + is_under_control ? std::make_shared(clock_->now()) : nullptr; + } // transit state // in DRIVE state if (m_control_state == ControlState::DRIVE) { @@ -959,8 +970,15 @@ double PidLongitudinalController::applyVelocityFeedback( const double diff_vel = (target_motion.vel - current_vel) * vel_sign; const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled && m_current_operation_mode.mode == OperationModeState::AUTONOMOUS; + + const bool vehicle_is_moving = std::abs(current_vel) > m_current_vel_threshold_pid_integrate; + const double time_under_control = getTimeUnderControl(); + const bool vehicle_is_stuck = + !vehicle_is_moving && time_under_control > m_time_threshold_before_pid_integrate; + const bool enable_integration = - (std::abs(current_vel) > m_current_vel_threshold_pid_integrate) && is_under_control; + (vehicle_is_moving || (m_enable_integration_at_low_speed && vehicle_is_stuck)) && + is_under_control; const double error_vel_filtered = m_lpf_vel_error->filter(diff_vel); std::vector pid_contributions(3); @@ -1059,4 +1077,10 @@ void PidLongitudinalController::checkControlState( stat.summary(level, msg); } +double PidLongitudinalController::getTimeUnderControl() +{ + if (!m_under_control_starting_time) return 0.0; + return (clock_->now() - *m_under_control_starting_time).seconds(); +} + } // namespace autoware::motion::control::pid_longitudinal_controller diff --git a/control/trajectory_follower_node/param/longitudinal/pid.param.yaml b/control/trajectory_follower_node/param/longitudinal/pid.param.yaml index bc3213081d86e..c39088753fe64 100644 --- a/control/trajectory_follower_node/param/longitudinal/pid.param.yaml +++ b/control/trajectory_follower_node/param/longitudinal/pid.param.yaml @@ -32,7 +32,9 @@ max_d_effort: 0.0 min_d_effort: 0.0 lpf_vel_error_gain: 0.9 + enable_integration_at_low_speed: false current_vel_threshold_pid_integration: 0.5 + time_threshold_before_pid_integration: 2.0 enable_brake_keeping_before_stop: false brake_keeping_acc: -0.2 From bd4d9733ce7f1a263d1d2e2156d080f78ab07c8c Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Mon, 27 Nov 2023 08:30:48 +0800 Subject: [PATCH 033/128] refactor(goal_distance_calculator): rework parameters (#4830) * refactor(goal_distance_calculator): rework parameters Signed-off-by: PhoebeWu21 * refactor(goal_distance_calculator): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix * refactor(goal_distance_calculator): rework parameters Signed-off-by: PhoebeWu21 * refactor(goal_distance_calculator): 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> --- .../goal_distance_calculator.param.yaml | 1 + .../goal_distance_calculator.launch.xml | 2 -- .../goal_distance_calculator.schema.json | 36 +++++++++++++++++++ .../src/goal_distance_calculator_node.cpp | 4 +-- 4 files changed, 39 insertions(+), 4 deletions(-) create mode 100644 common/goal_distance_calculator/schema/goal_distance_calculator.schema.json diff --git a/common/goal_distance_calculator/config/goal_distance_calculator.param.yaml b/common/goal_distance_calculator/config/goal_distance_calculator.param.yaml index 5b8c019de5a20..46738a33ae0bd 100644 --- a/common/goal_distance_calculator/config/goal_distance_calculator.param.yaml +++ b/common/goal_distance_calculator/config/goal_distance_calculator.param.yaml @@ -1,3 +1,4 @@ /**: ros__parameters: update_rate: 10.0 + oneshot: false diff --git a/common/goal_distance_calculator/launch/goal_distance_calculator.launch.xml b/common/goal_distance_calculator/launch/goal_distance_calculator.launch.xml index 7a796049384bc..7ba2eb45c9233 100644 --- a/common/goal_distance_calculator/launch/goal_distance_calculator.launch.xml +++ b/common/goal_distance_calculator/launch/goal_distance_calculator.launch.xml @@ -1,8 +1,6 @@ - - diff --git a/common/goal_distance_calculator/schema/goal_distance_calculator.schema.json b/common/goal_distance_calculator/schema/goal_distance_calculator.schema.json new file mode 100644 index 0000000000000..bc8d7d808619f --- /dev/null +++ b/common/goal_distance_calculator/schema/goal_distance_calculator.schema.json @@ -0,0 +1,36 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Goal Distance Calculator Node", + "type": "object", + "definitions": { + "goal_distance_calculator": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "default": "10.0", + "exclusiveMinimum": 0, + "description": "Timer callback period. [Hz]" + }, + "oneshot": { + "type": "boolean", + "default": "false", + "description": "Publish deviations just once or repeatedly." + } + }, + "required": ["update_rate", "oneshot"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/goal_distance_calculator" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp b/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp index 6b147ed66d690..c6062d2a156ee 100644 --- a/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp +++ b/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp @@ -40,8 +40,8 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions durable_qos.transient_local(); // Node Parameter - node_param_.update_rate = declare_parameter("update_rate", 10.0); - node_param_.oneshot = declare_parameter("oneshot", true); + node_param_.update_rate = declare_parameter("update_rate"); + node_param_.oneshot = declare_parameter("oneshot"); // Core goal_distance_calculator_ = std::make_unique(); From 577892b72722975eaef27e203912aace751f11ec Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 27 Nov 2023 11:27:09 +0900 Subject: [PATCH 034/128] feat(bytetracker): modify kalman filter model to get better tracking performance (#5639) * wip: try to replace kalman filter statements in bytetrack Signed-off-by: yoshiri * add config file for kalman filter Signed-off-by: yoshiri * add actual kalman filter code Signed-off-by: yoshiri * update readme Signed-off-by: yoshiri * Update perception/bytetrack/config/bytetracker.param.yaml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> * docs(bytetrack): Update demo video on README.md Signed-off-by: Manato HIRABAYASHI --------- Signed-off-by: yoshiri Signed-off-by: Manato HIRABAYASHI Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> --- perception/bytetrack/CMakeLists.txt | 6 +- perception/bytetrack/README.md | 12 +- .../bytetrack/config/bytetracker.param.yaml | 14 + .../bytetrack/lib/include/byte_tracker.h | 2 +- .../bytetrack/lib/include/kalman_filter.h | 67 ----- perception/bytetrack/lib/include/strack.h | 51 +++- perception/bytetrack/lib/src/byte_tracker.cpp | 7 +- .../bytetrack/lib/src/kalman_filter.cpp | 175 ------------- perception/bytetrack/lib/src/strack.cpp | 241 +++++++++++++----- perception/bytetrack/package.xml | 2 + 10 files changed, 256 insertions(+), 321 deletions(-) create mode 100644 perception/bytetrack/config/bytetracker.param.yaml delete mode 100644 perception/bytetrack/lib/include/kalman_filter.h delete mode 100644 perception/bytetrack/lib/src/kalman_filter.cpp diff --git a/perception/bytetrack/CMakeLists.txt b/perception/bytetrack/CMakeLists.txt index e481464455a55..c020843af56b5 100644 --- a/perception/bytetrack/CMakeLists.txt +++ b/perception/bytetrack/CMakeLists.txt @@ -29,7 +29,10 @@ target_include_directories(bytetrack_lib $ $ ) -target_link_libraries(bytetrack_lib Eigen3::Eigen) +target_link_libraries(bytetrack_lib + Eigen3::Eigen + yaml-cpp +) # # ROS node @@ -91,4 +94,5 @@ rclcpp_components_register_node(${PROJECT_NAME}_visualizer ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/perception/bytetrack/README.md b/perception/bytetrack/README.md index e58f4bb5892aa..cabbdd2f05836 100644 --- a/perception/bytetrack/README.md +++ b/perception/bytetrack/README.md @@ -6,7 +6,7 @@ The core algorithm, named `ByteTrack`, mainly aims to perform multi-object track Because the algorithm associates almost every detection box including ones with low detection scores, the number of false negatives is expected to decrease by using it. -[demo video](https://user-images.githubusercontent.com/3022416/225920856-745a3bb7-6b35-403d-87b0-6e5085952d70.mp4) +[demo video](https://github.com/YoshiRi/autoware.universe/assets/3022416/40f4c158-657e-48e1-81c2-8ac39152892d) ## Inner-workings / Algorithms @@ -20,6 +20,16 @@ the number of false negatives is expected to decrease by using it. - This package is ported version toward Autoware from [this repository](https://github.com/ifzhang/ByteTrack/tree/main/deploy/TensorRT/cpp) (The C++ implementation by the ByteTrack's authors) +### 2d tracking modification from original codes + +The paper just says that the 2d tracking algorithm is a simple Kalman filter. +Original codes use the `top-left-corner` and `aspect ratio` and `size` as the state vector. + +This is sometimes unstable because the aspectratio can be changed by the occlusion. +So, we use the `top-left` and `size` as the state vector. + +Kalman filter settings can be controlled by the parameters in `config/bytetrack_node.param.yaml`. + ## Inputs / Outputs ### bytetrack_node diff --git a/perception/bytetrack/config/bytetracker.param.yaml b/perception/bytetrack/config/bytetracker.param.yaml new file mode 100644 index 0000000000000..7078f190c87e6 --- /dev/null +++ b/perception/bytetrack/config/bytetracker.param.yaml @@ -0,0 +1,14 @@ +# Kalman filter parameters for 2d tracking +dt: 0.1 # time step[s] +dim_x: 8 # tlbr + velocity +dim_z: 4 # tlbr +q_cov_x: 0.1 +q_cov_y: 0.1 +q_cov_vx: 0.1 +q_cov_vy: 0.1 +r_cov_x: 0.1 +r_cov_y: 0.1 +p0_cov_x: 100.0 +p0_cov_y: 100.0 +p0_cov_vx: 100.0 +p0_cov_vy: 100.0 diff --git a/perception/bytetrack/lib/include/byte_tracker.h b/perception/bytetrack/lib/include/byte_tracker.h index 08394e6b0ccdf..60328c5acfd62 100644 --- a/perception/bytetrack/lib/include/byte_tracker.h +++ b/perception/bytetrack/lib/include/byte_tracker.h @@ -96,5 +96,5 @@ class ByteTracker std::vector tracked_stracks; std::vector lost_stracks; std::vector removed_stracks; - byte_kalman::KalmanFilter kalman_filter; + KalmanFilter kalman_filter; }; diff --git a/perception/bytetrack/lib/include/kalman_filter.h b/perception/bytetrack/lib/include/kalman_filter.h deleted file mode 100644 index f2b1e1c7817dd..0000000000000 --- a/perception/bytetrack/lib/include/kalman_filter.h +++ /dev/null @@ -1,67 +0,0 @@ -/* - * MIT License - * - * Copyright (c) 2021 Yifu Zhang - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - */ - -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#pragma once - -#include "data_type.h" - -#include -namespace byte_kalman -{ -class KalmanFilter -{ -public: - static const double chi2inv95[10]; - KalmanFilter(); - KAL_DATA initiate(const DETECTBOX & measurement); - void predict(KAL_MEAN & mean, KAL_COVA & covariance); - KAL_HDATA project(const KAL_MEAN & mean, const KAL_COVA & covariance); - KAL_DATA update( - const KAL_MEAN & mean, const KAL_COVA & covariance, const DETECTBOX & measurement); - - Eigen::Matrix gating_distance( - const KAL_MEAN & mean, const KAL_COVA & covariance, const std::vector & measurements, - bool only_position = false); - -private: - Eigen::Matrix _motion_mat; - Eigen::Matrix _update_mat; - float _std_weight_position; - float _std_weight_velocity; -}; -} // namespace byte_kalman diff --git a/perception/bytetrack/lib/include/strack.h b/perception/bytetrack/lib/include/strack.h index 2110723e86c58..260f38ea93770 100644 --- a/perception/bytetrack/lib/include/strack.h +++ b/perception/bytetrack/lib/include/strack.h @@ -38,16 +38,18 @@ #pragma once -#include "kalman_filter.h" - +// #include "kalman_filter.h" +#include #include #include +#include #include enum TrackState { New = 0, Tracked, Lost, Removed }; +/** manage one tracklet*/ class STrack { public: @@ -55,8 +57,7 @@ class STrack ~STrack(); std::vector static tlbr_to_tlwh(std::vector & tlbr); - static void multi_predict( - std::vector & stracks, byte_kalman::KalmanFilter & kalman_filter); + static void multi_predict(std::vector & stracks); void static_tlwh(); void static_tlbr(); std::vector tlwh_to_xyah(std::vector tlwh_tmp); @@ -65,10 +66,16 @@ class STrack void mark_removed(); int next_id(); int end_frame(); + void init_kalman_filter(); + void update_kalman_filter(const Eigen::MatrixXd & measurement); + void reflect_state(); - void activate(byte_kalman::KalmanFilter & kalman_filter, int frame_id); + void activate(int frame_id); void re_activate(STrack & new_track, int frame_id, bool new_id = false); void update(STrack & new_track, int frame_id); + void predict(const int frame_id); + + void load_parameters(const std::string & filename); public: bool is_activated; @@ -76,19 +83,41 @@ class STrack boost::uuids::uuid unique_id; int state; - std::vector _tlwh; - std::vector tlwh; - std::vector tlbr; + std::vector original_tlwh; // top left width height + std::vector tlwh; // top left width height + std::vector tlbr; // top left bottom right int frame_id; int tracklet_len; int start_frame; - KAL_MEAN mean; - KAL_COVA covariance; float score; int label; private: - byte_kalman::KalmanFilter kalman_filter; + KalmanFilter kalman_filter_; + struct KfParams + { + // dimension + char dim_x = 8; + char dim_z = 4; + // system noise + float q_cov_x; + float q_cov_y; + float q_cov_vx; + float q_cov_vy; + // measurement noise + float r_cov_x; + float r_cov_y; + // initial state covariance + float p0_cov_x; + float p0_cov_y; + float p0_cov_vx; + float p0_cov_vy; + // other parameters + float dt; // sampling time + }; + static KfParams _kf_parameters; + static bool _parameters_loaded; + enum IDX { X1 = 0, Y1 = 1, X2 = 2, Y2 = 3, VX1 = 4, VY1 = 5, VX2 = 6, VY2 = 7 }; }; diff --git a/perception/bytetrack/lib/src/byte_tracker.cpp b/perception/bytetrack/lib/src/byte_tracker.cpp index 94aae0a5c94cc..a3477e78ad6dd 100644 --- a/perception/bytetrack/lib/src/byte_tracker.cpp +++ b/perception/bytetrack/lib/src/byte_tracker.cpp @@ -106,7 +106,10 @@ std::vector ByteTracker::update(const std::vector & obj ////////////////// Step 2: First association, with IoU ////////////////// strack_pool = joint_stracks(tracked_stracks, this->lost_stracks); - STrack::multi_predict(strack_pool, this->kalman_filter); + // do prediction for each stracks + for (size_t i = 0; i < strack_pool.size(); i++) { + strack_pool[i]->predict(this->frame_id); + } std::vector > dists; int dist_size = 0, dist_size_size = 0; @@ -196,7 +199,7 @@ std::vector ByteTracker::update(const std::vector & obj for (size_t i = 0; i < u_detection.size(); i++) { STrack * track = &detections[u_detection[i]]; if (track->score < this->high_thresh) continue; - track->activate(this->kalman_filter, this->frame_id); + track->activate(this->frame_id); activated_stracks.push_back(*track); } diff --git a/perception/bytetrack/lib/src/kalman_filter.cpp b/perception/bytetrack/lib/src/kalman_filter.cpp deleted file mode 100644 index e515450858d80..0000000000000 --- a/perception/bytetrack/lib/src/kalman_filter.cpp +++ /dev/null @@ -1,175 +0,0 @@ -/* - * MIT License - * - * Copyright (c) 2021 Yifu Zhang - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - */ - -// 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 "kalman_filter.h" - -#include - -namespace byte_kalman -{ -const double KalmanFilter::chi2inv95[10] = {0, 3.8415, 5.9915, 7.8147, 9.4877, - 11.070, 12.592, 14.067, 15.507, 16.919}; -KalmanFilter::KalmanFilter() -{ - int ndim = 4; - double dt = 1.; - - _motion_mat = Eigen::MatrixXf::Identity(8, 8); - for (int i = 0; i < ndim; i++) { - _motion_mat(i, ndim + i) = dt; - } - _update_mat = Eigen::MatrixXf::Identity(4, 8); - - this->_std_weight_position = 1. / 20; - this->_std_weight_velocity = 1. / 160; -} - -KAL_DATA KalmanFilter::initiate(const DETECTBOX & measurement) -{ - DETECTBOX mean_pos = measurement; - DETECTBOX mean_vel; - for (int i = 0; i < 4; i++) mean_vel(i) = 0; - - KAL_MEAN mean; - for (int i = 0; i < 8; i++) { - if (i < 4) - mean(i) = mean_pos(i); - else - mean(i) = mean_vel(i - 4); - } - - KAL_MEAN std; - std(0) = 2 * _std_weight_position * measurement[3]; - std(1) = 2 * _std_weight_position * measurement[3]; - std(2) = 1e-2; - std(3) = 2 * _std_weight_position * measurement[3]; - std(4) = 10 * _std_weight_velocity * measurement[3]; - std(5) = 10 * _std_weight_velocity * measurement[3]; - std(6) = 1e-5; - std(7) = 10 * _std_weight_velocity * measurement[3]; - - KAL_MEAN tmp = std.array().square(); - KAL_COVA var = tmp.asDiagonal(); - return std::make_pair(mean, var); -} - -void KalmanFilter::predict(KAL_MEAN & mean, KAL_COVA & covariance) -{ - // revise the data; - DETECTBOX std_pos; - std_pos << _std_weight_position * mean(3), _std_weight_position * mean(3), 1e-2, - _std_weight_position * mean(3); - DETECTBOX std_vel; - std_vel << _std_weight_velocity * mean(3), _std_weight_velocity * mean(3), 1e-5, - _std_weight_velocity * mean(3); - KAL_MEAN tmp; - tmp.block<1, 4>(0, 0) = std_pos; - tmp.block<1, 4>(0, 4) = std_vel; - tmp = tmp.array().square(); - KAL_COVA motion_cov = tmp.asDiagonal(); - KAL_MEAN mean1 = this->_motion_mat * mean.transpose(); - KAL_COVA covariance1 = this->_motion_mat * covariance * (_motion_mat.transpose()); - covariance1 += motion_cov; - - mean = mean1; - covariance = covariance1; -} - -KAL_HDATA KalmanFilter::project(const KAL_MEAN & mean, const KAL_COVA & covariance) -{ - DETECTBOX std; - std << _std_weight_position * mean(3), _std_weight_position * mean(3), 1e-1, - _std_weight_position * mean(3); - KAL_HMEAN mean1 = _update_mat * mean.transpose(); - KAL_HCOVA covariance1 = _update_mat * covariance * (_update_mat.transpose()); - Eigen::Matrix diag = std.asDiagonal(); - diag = diag.array().square().matrix(); - covariance1 += diag; - // covariance1.diagonal() << diag; - return std::make_pair(mean1, covariance1); -} - -KAL_DATA -KalmanFilter::update( - const KAL_MEAN & mean, const KAL_COVA & covariance, const DETECTBOX & measurement) -{ - KAL_HDATA pa = project(mean, covariance); - KAL_HMEAN projected_mean = pa.first; - KAL_HCOVA projected_cov = pa.second; - - // chol_factor, lower = - // scipy.linalg.cho_factor(projected_cov, lower=True, check_finite=False) - // kalmain_gain = - // scipy.linalg.cho_solve((cho_factor, lower), - // np.dot(covariance, self._upadte_mat.T).T, - // check_finite=False).T - Eigen::Matrix B = (covariance * (_update_mat.transpose())).transpose(); - Eigen::Matrix kalman_gain = (projected_cov.llt().solve(B)).transpose(); // eg.8x4 - Eigen::Matrix innovation = measurement - projected_mean; // eg.1x4 - auto tmp = innovation * (kalman_gain.transpose()); - KAL_MEAN new_mean = (mean.array() + tmp.array()).matrix(); - KAL_COVA new_covariance = covariance - kalman_gain * projected_cov * (kalman_gain.transpose()); - return std::make_pair(new_mean, new_covariance); -} - -Eigen::Matrix KalmanFilter::gating_distance( - const KAL_MEAN & mean, const KAL_COVA & covariance, const std::vector & measurements, - bool only_position) -{ - KAL_HDATA pa = this->project(mean, covariance); - if (only_position) { - printf("not implement!"); - exit(0); - } - KAL_HMEAN mean1 = pa.first; - KAL_HCOVA covariance1 = pa.second; - - // Eigen::Matrix d(size, 4); - DETECTBOXSS d(measurements.size(), 4); - int pos = 0; - for (DETECTBOX box : measurements) { - d.row(pos++) = box - mean1; - } - Eigen::Matrix factor = covariance1.llt().matrixL(); - Eigen::Matrix z = - factor.triangularView().solve(d).transpose(); - auto zz = ((z.array()) * (z.array())).matrix(); - auto square_maha = zz.colwise().sum(); - return square_maha; -} -} // namespace byte_kalman diff --git a/perception/bytetrack/lib/src/strack.cpp b/perception/bytetrack/lib/src/strack.cpp index b06456098cc38..eda11509d2403 100644 --- a/perception/bytetrack/lib/src/strack.cpp +++ b/perception/bytetrack/lib/src/strack.cpp @@ -38,12 +38,20 @@ #include "strack.h" +#include + #include -STrack::STrack(std::vector tlwh_, float score, int label) +#include + +// init static variable +bool STrack::_parameters_loaded = false; +STrack::KfParams STrack::_kf_parameters; + +STrack::STrack(std::vector input_tlwh, float score, int label) { - _tlwh.resize(4); - _tlwh.assign(tlwh_.begin(), tlwh_.end()); + original_tlwh.resize(4); + original_tlwh.assign(input_tlwh.begin(), input_tlwh.end()); is_activated = false; track_id = 0; @@ -52,49 +60,71 @@ STrack::STrack(std::vector tlwh_, float score, int label) tlwh.resize(4); tlbr.resize(4); - static_tlwh(); - static_tlbr(); + static_tlwh(); // update object size + static_tlbr(); // update object size frame_id = 0; tracklet_len = 0; this->score = score; start_frame = 0; this->label = label; + + // load static kf parameters: initialized once in program + const std::string package_share_directory = + ament_index_cpp::get_package_share_directory("bytetrack"); + const std::string default_config_path = + package_share_directory + "/config/bytetracker.param.yaml"; + if (!_parameters_loaded) { + load_parameters(default_config_path); + _parameters_loaded = true; + } } STrack::~STrack() { } -void STrack::activate(byte_kalman::KalmanFilter & kalman_filter, int frame_id) +void STrack::init_kalman_filter() +{ + // assert parameter is loaded + assert(_parameters_loaded); + + // init kalman filter state + Eigen::MatrixXd X0 = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, 1); + Eigen::MatrixXd P0 = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, _kf_parameters.dim_x); + X0(IDX::X1) = this->original_tlwh[0]; + X0(IDX::Y1) = this->original_tlwh[1]; + X0(IDX::X2) = this->original_tlwh[2]; + X0(IDX::Y2) = this->original_tlwh[3]; + P0(IDX::X1, IDX::X1) = _kf_parameters.p0_cov_x; + P0(IDX::Y1, IDX::Y1) = _kf_parameters.p0_cov_y; + P0(IDX::X2, IDX::X2) = _kf_parameters.p0_cov_x; + P0(IDX::Y2, IDX::Y2) = _kf_parameters.p0_cov_y; + P0(IDX::VX1, IDX::VX1) = _kf_parameters.p0_cov_vx; + P0(IDX::VY1, IDX::VY1) = _kf_parameters.p0_cov_vy; + P0(IDX::VX2, IDX::VX2) = _kf_parameters.p0_cov_vx; + P0(IDX::VY2, IDX::VY2) = _kf_parameters.p0_cov_vy; + this->kalman_filter_.init(X0, P0); +} + +/** init a tracklet */ +void STrack::activate(int frame_id) { - this->kalman_filter = kalman_filter; this->track_id = this->next_id(); this->unique_id = boost::uuids::random_generator()(); std::vector _tlwh_tmp(4); - _tlwh_tmp[0] = this->_tlwh[0]; - _tlwh_tmp[1] = this->_tlwh[1]; - _tlwh_tmp[2] = this->_tlwh[2]; - _tlwh_tmp[3] = this->_tlwh[3]; + _tlwh_tmp[0] = this->original_tlwh[0]; + _tlwh_tmp[1] = this->original_tlwh[1]; + _tlwh_tmp[2] = this->original_tlwh[2]; + _tlwh_tmp[3] = this->original_tlwh[3]; std::vector xyah = tlwh_to_xyah(_tlwh_tmp); - DETECTBOX xyah_box; - xyah_box[0] = xyah[0]; - xyah_box[1] = xyah[1]; - xyah_box[2] = xyah[2]; - xyah_box[3] = xyah[3]; - auto mc = this->kalman_filter.initiate(xyah_box); - this->mean = mc.first; - this->covariance = mc.second; - - static_tlwh(); - static_tlbr(); + // init kf + init_kalman_filter(); + // reflect state + reflect_state(); this->tracklet_len = 0; this->state = TrackState::Tracked; - // if (frame_id == 1) - // { - // this->is_activated = true; - // } this->is_activated = true; this->frame_id = frame_id; this->start_frame = frame_id; @@ -103,17 +133,12 @@ void STrack::activate(byte_kalman::KalmanFilter & kalman_filter, int frame_id) void STrack::re_activate(STrack & new_track, int frame_id, bool new_id) { std::vector xyah = tlwh_to_xyah(new_track.tlwh); - DETECTBOX xyah_box; - xyah_box[0] = xyah[0]; - xyah_box[1] = xyah[1]; - xyah_box[2] = xyah[2]; - xyah_box[3] = xyah[3]; - auto mc = this->kalman_filter.update(this->mean, this->covariance, xyah_box); - this->mean = mc.first; - this->covariance = mc.second; + // TODO(me): write kf update + Eigen::MatrixXd measurement = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, 1); + measurement << new_track.tlwh[0], new_track.tlwh[1], new_track.tlwh[2], new_track.tlwh[3]; + update_kalman_filter(measurement); - static_tlwh(); - static_tlbr(); + reflect_state(); this->tracklet_len = 0; this->state = TrackState::Tracked; @@ -132,18 +157,14 @@ void STrack::update(STrack & new_track, int frame_id) this->tracklet_len++; std::vector xyah = tlwh_to_xyah(new_track.tlwh); - DETECTBOX xyah_box; - xyah_box[0] = xyah[0]; - xyah_box[1] = xyah[1]; - xyah_box[2] = xyah[2]; - xyah_box[3] = xyah[3]; - auto mc = this->kalman_filter.update(this->mean, this->covariance, xyah_box); - this->mean = mc.first; - this->covariance = mc.second; + // update + // TODO(me): write update + Eigen::MatrixXd measurement = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, 1); + measurement << new_track.tlwh[0], new_track.tlwh[1], new_track.tlwh[2], new_track.tlwh[3]; + update_kalman_filter(measurement); - static_tlwh(); - static_tlbr(); + reflect_state(); this->state = TrackState::Tracked; this->is_activated = true; @@ -151,24 +172,31 @@ void STrack::update(STrack & new_track, int frame_id) this->score = new_track.score; } +/** reflect kalman filter state to current object variables*/ +void STrack::reflect_state() +{ + // update tlwh + static_tlwh(); + // update tlbr + static_tlbr(); +} + void STrack::static_tlwh() { if (this->state == TrackState::New) { - tlwh[0] = _tlwh[0]; - tlwh[1] = _tlwh[1]; - tlwh[2] = _tlwh[2]; - tlwh[3] = _tlwh[3]; + tlwh[0] = original_tlwh[0]; + tlwh[1] = original_tlwh[1]; + tlwh[2] = original_tlwh[2]; + tlwh[3] = original_tlwh[3]; return; } - - tlwh[0] = mean[0]; - tlwh[1] = mean[1]; - tlwh[2] = mean[2]; - tlwh[3] = mean[3]; - - tlwh[2] *= tlwh[3]; - tlwh[0] -= tlwh[2] / 2; - tlwh[1] -= tlwh[3] / 2; + // put kf state to tlwh + Eigen::MatrixXd X = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, 1); + this->kalman_filter_.getX(X); + tlwh[0] = X(IDX::X1); + tlwh[1] = X(IDX::Y1); + tlwh[2] = X(IDX::X2); + tlwh[3] = X(IDX::Y2); } void STrack::static_tlbr() @@ -222,15 +250,102 @@ int STrack::end_frame() return this->frame_id; } -void STrack::multi_predict( - std::vector & stracks, byte_kalman::KalmanFilter & kalman_filter) +void STrack::multi_predict(std::vector & stracks) { for (size_t i = 0; i < stracks.size(); i++) { if (stracks[i]->state != TrackState::Tracked) { - stracks[i]->mean[7] = 0; + // not tracked } - kalman_filter.predict(stracks[i]->mean, stracks[i]->covariance); + // prediction + stracks[i]->predict(stracks[i]->frame_id + 1); + // TODO(me): write prediction stracks[i]->static_tlwh(); stracks[i]->static_tlbr(); } } + +void STrack::update_kalman_filter(const Eigen::MatrixXd & measurement) +{ + // assert parameter is loaded + assert(_parameters_loaded); + + // get C matrix + Eigen::MatrixXd C = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, _kf_parameters.dim_x); + C(IDX::X1, IDX::X1) = 1; + C(IDX::Y1, IDX::Y1) = 1; + C(IDX::X2, IDX::X2) = 1; + C(IDX::Y2, IDX::Y2) = 1; + + // get R matrix + Eigen::MatrixXd R = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, _kf_parameters.dim_z); + R(IDX::X1, IDX::X1) = _kf_parameters.r_cov_x; + R(IDX::Y1, IDX::Y1) = _kf_parameters.r_cov_y; + R(IDX::X2, IDX::X2) = _kf_parameters.r_cov_x; + R(IDX::Y2, IDX::Y2) = _kf_parameters.r_cov_y; + + // update + if (!this->kalman_filter_.update(measurement, C, R)) { + std::cerr << "Cannot update" << std::endl; + } +} + +void STrack::predict(const int frame_id) +{ + // check state is Tracked + if (this->state != TrackState::Tracked) { + // not tracked + return; + } + + // else do prediction + float time_elapsed = _kf_parameters.dt * (frame_id - this->frame_id); + // A matrix + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(_kf_parameters.dim_x, _kf_parameters.dim_x); + A(IDX::X1, IDX::VX1) = time_elapsed; + A(IDX::Y1, IDX::VY1) = time_elapsed; + A(IDX::X2, IDX::VX2) = time_elapsed; + A(IDX::Y2, IDX::VY2) = time_elapsed; + + // u and B matrix + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, 1); + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, _kf_parameters.dim_x); + + // get P_t + Eigen::MatrixXd P_t = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, _kf_parameters.dim_x); + this->kalman_filter_.getP(P_t); + + // Q matrix + Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(_kf_parameters.dim_x, _kf_parameters.dim_x); + Q(IDX::X1, IDX::X1) = _kf_parameters.q_cov_x; + Q(IDX::Y1, IDX::Y1) = _kf_parameters.q_cov_y; + Q(IDX::VX1, IDX::VX1) = _kf_parameters.q_cov_vx; + Q(IDX::VY1, IDX::VY1) = _kf_parameters.q_cov_vy; + Q(IDX::X2, IDX::X2) = _kf_parameters.q_cov_x; + Q(IDX::Y2, IDX::Y2) = _kf_parameters.q_cov_y; + Q(IDX::VX2, IDX::VX2) = _kf_parameters.q_cov_vx; + Q(IDX::VY2, IDX::VY2) = _kf_parameters.q_cov_vy; + + // prediction + if (!this->kalman_filter_.predict(u, A, B, Q)) { + std::cerr << "Cannot predict" << std::endl; + } +} + +void STrack::load_parameters(const std::string & path) +{ + YAML::Node config = YAML::LoadFile(path); + // initialize ekf params + _kf_parameters.dim_x = config["dim_x"].as(); + _kf_parameters.dim_z = config["dim_z"].as(); + _kf_parameters.q_cov_x = config["q_cov_x"].as(); + _kf_parameters.q_cov_y = config["q_cov_y"].as(); + _kf_parameters.q_cov_vx = config["q_cov_vx"].as(); + _kf_parameters.q_cov_vy = config["q_cov_vy"].as(); + _kf_parameters.r_cov_x = config["r_cov_x"].as(); + _kf_parameters.r_cov_y = config["r_cov_y"].as(); + _kf_parameters.p0_cov_x = config["p0_cov_x"].as(); + _kf_parameters.p0_cov_y = config["p0_cov_y"].as(); + _kf_parameters.p0_cov_vx = config["p0_cov_vx"].as(); + _kf_parameters.p0_cov_vy = config["p0_cov_vy"].as(); + _kf_parameters.dt = config["dt"].as(); +} diff --git a/perception/bytetrack/package.xml b/perception/bytetrack/package.xml index 6b3891438c179..da1768e1bf7ea 100644 --- a/perception/bytetrack/package.xml +++ b/perception/bytetrack/package.xml @@ -19,6 +19,7 @@ cv_bridge eigen image_transport + kalman_filter libboost-system-dev libopencv-dev rclcpp @@ -26,6 +27,7 @@ sensor_msgs tensorrt_common tier4_perception_msgs + yaml-cpp ament_lint_auto autoware_lint_common From b50be764537574a35d878fe833e7a5cd7dbdc767 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 27 Nov 2023 11:43:00 +0900 Subject: [PATCH 035/128] docs(behavior_path_planner): update main documentation (#5519) * docs(behavior_path_planner): update main documentation Signed-off-by: Zulfaqar Azmi * place image in note Signed-off-by: Zulfaqar Azmi * Add path shifter explanation Signed-off-by: Zulfaqar Azmi * Update input output and debug Signed-off-by: Zulfaqar Azmi * fix introduction Signed-off-by: Zulfaqar Azmi * enchance drivable area expansion explanation Signed-off-by: Zulfaqar Azmi * fix type in the debug subsection * include safety check Signed-off-by: Zulfaqar Azmi * add parameter folder structure Signed-off-by: Zulfaqar Azmi * Enabling and disabling module Signed-off-by: Zulfaqar Azmi * fix limitation Signed-off-by: Zulfaqar Azmi * Update based on feedback Signed-off-by: Zulfaqar Azmi * Rerouting subsection Signed-off-by: Zulfaqar Azmi * minor fixes Signed-off-by: Zulfaqar Azmi * fix some minor point Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- planning/behavior_path_planner/README.md | 346 +++++++++++------- .../image/behavior_modules.png | Bin 134367 -> 0 bytes .../image/behavior_path_planner_bt_config.png | Bin 179116 -> 0 bytes .../image/checking_module_transition.png | Bin 0 -> 46021 bytes .../static_drivable_area_after_expansion.png | Bin 0 -> 151054 bytes .../static_drivable_area_before_expansion.png | Bin 0 -> 146681 bytes .../image/supported_module_avoidance.svg | 58 +++ ...ported_module_avoidance_by_lane_change.svg | 58 +++ .../image/supported_module_goal_planner.svg | 57 +++ .../image/supported_module_lane_change.svg | 48 +++ .../image/supported_module_lane_following.svg | 48 +++ .../image/supported_module_start_planner.svg | 48 +++ 12 files changed, 537 insertions(+), 126 deletions(-) delete mode 100644 planning/behavior_path_planner/image/behavior_modules.png delete mode 100644 planning/behavior_path_planner/image/behavior_path_planner_bt_config.png create mode 100644 planning/behavior_path_planner/image/checking_module_transition.png create mode 100644 planning/behavior_path_planner/image/static_drivable_area_after_expansion.png create mode 100644 planning/behavior_path_planner/image/static_drivable_area_before_expansion.png create mode 100644 planning/behavior_path_planner/image/supported_module_avoidance.svg create mode 100644 planning/behavior_path_planner/image/supported_module_avoidance_by_lane_change.svg create mode 100644 planning/behavior_path_planner/image/supported_module_goal_planner.svg create mode 100644 planning/behavior_path_planner/image/supported_module_lane_change.svg create mode 100644 planning/behavior_path_planner/image/supported_module_lane_following.svg create mode 100644 planning/behavior_path_planner/image/supported_module_start_planner.svg diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 0c0c7c806c119..884767315ac12 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -1,190 +1,284 @@ # Behavior Path Planner -## Purpose / Use cases +The Behavior Path Planner's main objective is to significantly enhance the safety of autonomous vehicles by minimizing the risk of accidents. It improves driving efficiency through time conservation and underpins reliability with its rule-based approach. Additionally, it allows users to integrate their own custom behavior modules or use it with different types of vehicles, such as cars, buses, and delivery robots, as well as in various environments, from busy urban streets to open highways. -The `behavior_path_planner` module is responsible to generate +The module begins by thoroughly analyzing the ego vehicle's current situation, including its position, speed, and surrounding environment. This analysis leads to essential driving decisions about lane changes or stopping and subsequently generates a path that is both safe and efficient. It considers road geometry, traffic rules, and dynamic conditions while also incorporating obstacle avoidance to respond to static and dynamic obstacles such as other vehicles, pedestrians, or unexpected roadblocks, ensuring safe navigation. -1. **path** based on the traffic situation, -2. **drivable area** that the vehicle can move (defined in the path msg), -3. **turn signal** command to be sent to the vehicle interface. +Moreover, the planner actively interacts with other traffic participants, predicting their actions and accordingly adjusting the vehicle's path. This ensures not only the safety of the autonomous vehicle but also contributes to smooth traffic flow. Its adherence to traffic laws, including speed limits and traffic signals, further guarantees lawful and predictable driving behavior. The planner is also designed to minimize sudden or abrupt maneuvers, aiming for a comfortable and natural driving experience. -## Design +!!! note -### Scene modules design + The [Planning Component Design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/) Document outlines the foundational philosophy guiding the design and future development of the Behavior Path Planner module. We strongly encourage readers to consult this document to understand the rationale behind its current configuration and the direction of its ongoing development. -#### Support modules +## Purpose / Use Cases -Behavior path planner has following scene modules. +Essentially, the module has three primary responsibilities: -| 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) | -| Avoidance By LC | 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 | -| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](./docs/behavior_path_planner_goal_planner_design.md) | -| Pull Out | 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) | +1. Creating a **path based** on the traffic situation. +2. Generating **drivable area**, i.e. the area within which the vehicle can maneuver. +3. Generating **turn signal** commands to be relayed to the vehicle interface. -![behavior_modules](./image/behavior_modules.png) +## Features -All scene modules are implemented by inheriting base class `scene_module_interface.hpp`. +### Supported Scene Modules -#### How to implement new module? +Behavior Path Planner has following scene modules -WIP +| 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) | ---- +!!! Note -### Manager design + click on the following images to view the video of their execution -The role of manager is to launch the appropriate scene module according to the situation. (e.g. if there is parked-vehicle in ego's driving lane, the manager launches the avoidance module.) +
+ + + + + + + + + + + +
Lane Following ModuleAvoidance ModuleAvoidance by Lane Change Module
Lane Change ModuleStart Planner ModuleGoal Planner Module
+
-Now, it is able to select two managers with different architecture. +!!! Note -| Name | Description | Details | -| :------------------------------------ | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :----------------------------------------------------- | -| Behavior Tree based manager (default) | this manager launches scene modules based on Behavior Tree. all scene modules run exclusively. | LINK(WIP) | -| BT-free manager (unstable) | this manager is developed in order to achieve complex scenario, and launches scene modules without Behavior Tree. multiple modules can run simultaneously on this manager. | [LINK](./docs/behavior_path_planner_manager_design.md) | + Users can refer to [Planning component design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/#supported-functions) for some additional behavior. -The manager is switched by flag `COMPILE_WITH_OLD_ARCHITECTURE` in CmakeLists.txt of `behavior_path_planner` package. Please set the flag **FALSE** if you try to use BT-free manager. +#### How to add or implement new module? -```cmake -cmake_minimum_required(VERSION 3.14) -project(behavior_path_planner) +All scene modules are implemented by inheriting base class `scene_module_interface.hpp`. -find_package(autoware_cmake REQUIRED) -autoware_package() +!!! Warning -find_package(OpenCV REQUIRED) -find_package(magic_enum CONFIG REQUIRED) + The remainder of this subsection is work in progress (WIP). -set(COMPILE_WITH_OLD_ARCHITECTURE TRUE) # <- HERE +### Planner Manager -... -``` +The Planner Manager's responsibilities include: -**What is the Behavior Tree?**: In the behavior path planner, the behavior tree mechanism is used to manage which modules are activated in which situations. In general, this "behavior manager" like function is expected to become bigger as more and more modules are added in the future. To improve maintainability, we adopted the behavior tree. The behavior tree has the following advantages: easy visualization, easy configuration management (behaviors can be changed by replacing configuration files), and high scalability compared to the state machine. +1. Activating the relevant scene module in response to the specific situation faced by the autonomous vehicle. For example, when a parked vehicle blocks the ego vehicle's driving lane, the manager would engage the avoidance module. +2. Managing the execution order when multiple modules are running simultaneously. For instance, if both the lane-changing and avoidance modules are operational, the manager decides which should take precedence. +3. Merging paths from multiple modules when they are activated simultaneously and each generates its own path, thereby creating a single functional path. -The current behavior tree structure is shown below. Each modules (LaneChange, Avoidance, etc) have _Request_, _Ready_, and _Plan_ nodes as a common function. +!!! note -- **Request**: Check if there is a request from the module (e.g. LaneChange has a request when there are multi-lanes and the vehicle is not on the preferred lane), -- **Ready**: Check if it is safe to execute the plan (e.g. LaneChange is ready when the lane_change path does not have any conflicts with other dynamic objects on S-T space). -- **Plan**: Calculates path and set it to the output of the BehaviorTree. Until the internal status returns SUCCESS, it will be in running state and will not transit to another module. -- **ForceApproval**: A lane change-specific node that overrides the result of _Ready_ when a forced lane change command is given externally. + To check the scene module's transition, i.e.: registered, approved and candidate modules, set `verbose: true` in the [behavior path planner configuration file](https://github.com/autowarefoundation/autoware_launch/blob/0cd5d891a36ac34a32a417205905c109f2bafe7b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml#L3). -![behavior_path_planner_bt_config](./image/behavior_path_planner_bt_config.png) + ![Scene module's transition table](./image/checking_module_transition.png) + +!!! note + + For more in-depth information, refer to [Manager design](./docs/behavior_path_planner_manager_design.md) document. ## Inputs / Outputs / API -### output +### Input -| Name | Type | Description | -| :-------------------------- | :------------------------------------------------------- | :--------------------------------------------------------------------------------------------- | -| ~/input/path | `autoware_auto_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | -| ~/input/path_candidate | `autoware_auto_planning_msgs::msg::Path` | the path the module is about to take. to be executed as soon as external approval is obtained. | -| ~/input/turn_indicators_cmd | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | -| ~/input/hazard_lights_cmd | `tier4_planning_msgs::msg::PathChangeModuleArray` | hazard lights command. | -| ~/input/ready_module | `tier4_planning_msgs::msg::PathChangeModule` | (for remote control) modules that are ready to be executed. | -| ~/input/running_modules | `tier4_planning_msgs::msg::PathChangeModuleArray` | (for remote control) current running module. | +| Name | Required? | Type | Description | +| :---------------------------- | :-------: | :----------------------------------------------------- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| ~/input/odometry | ○ | `nav_msgs::msg::Odometry` | for ego velocity. | +| ~/input/accel | ○ | `geometry_msgs::msg::AccelWithCovarianceStamped` | for ego acceleration. | +| ~/input/objects | ○ | `autoware_auto_perception_msgs::msg::PredictedObjects` | dynamic objects from perception module. | +| ~/input/occupancy_grid_map | ○ | `nav_msgs::msg::OccupancyGrid` | occupancy grid map from perception module. This is used for only Goal Planner module. | +| ~/input/traffic_signals | ○ | `autoware_perception_msgs::msg::TrafficSignalArray` | traffic signals information from the perception module | +| ~/input/vector_map | ○ | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map information. | +| ~/input/route | ○ | `autoware_auto_mapping_msgs::msg::LaneletRoute` | current route from start to goal. | +| ~/input/scenario | ○ | `tier4_planning_msgs::msg::Scenario` | Launches behavior path planner if current scenario == `Scenario:LaneDriving`. | +| ~/input/lateral_offset | △ | `tier4_planning_msgs::msg::LateralOffset` | lateral offset to trigger side shift | +| ~/system/operation_mode/state | ○ | `autoware_adapi_v1_msgs::msg::OperationModeState` | Allows planning module to know if vehicle is in autonomous mode or can be controlled[ref](https://github.com/autowarefoundation/autoware.universe/blob/main/system/default_ad_api/document/operation-mode.md) | -### input +- ○ Mandatory: Planning Module would not work if anyone of this is not present. +- △ Optional: Some module would not work, but Planning Module can still be operated. -| Name | Type | Description | -| :----------------------------- | :----------------------------------------------------- | :------------------------------------------------------------------------------------ | -| ~/input/route | `autoware_auto_mapping_msgs::msg::LaneletRoute` | current route from start to goal. | -| ~/input/vector_map | `autoware_auto_mapping_msgs::msg::HADMapBin` | map information. | -| ~/input/objects | `autoware_auto_perception_msgs::msg::PredictedObjects` | dynamic objects from perception module. | -| ~/input/occupancy_grid_map/map | `nav_msgs::msg::OccupancyGrid` | occupancy grid map from perception module. This is used for only Goal Planner module. | -| ~/input/kinematic_state | `nav_msgs::msg::Odometry` | for ego velocity. | +### Output -## General features of behavior path planner +| Name | Type | Description | QoS Durability | +| :---------------------------- | :------------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | +| ~/output/path | `autoware_auto_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | +| ~/output/turn_indicators_cmd | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | +| ~/output/hazard_lights_cmd | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | +| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | +| ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | +| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | -### Drivable area generation logic +### Debug -The behavior path planner generates drivable area that is defined in `autoware_auto_planning_msgs::msg::PathWithLaneId` and `autoware_auto_planning_msgs::msg::Path` messages as: +| Name | Type | Description | QoS Durability | +| :-------------------------------------- | :-------------------------------------------------- | :---------------------------------------------------------------------------------------- | -------------- | +| ~/debug/avoidance_debug_message_array | `tier4_planning_msgs::msg::AvoidanceDebugMsgArray` | debug message for avoidance. notify users reasons for avoidance path cannot be generated. | `volatile` | +| ~/debug/lane_change_debug_message_array | `tier4_planning_msgs::msg::LaneChangeDebugMsgArray` | debug message for lane change. notify users unsafe reason during lane changing process | `volatile` | +| ~/debug/maximum_drivable_area | `visualization_msgs::msg::MarkerArray` | shows maximum static drivable area. | `volatile` | +| ~/debug/turn_signal_info | `visualization_msgs::msg::MarkerArray` | TBA | `volatile` | +| ~/debug/bound | `visualization_msgs::msg::MarkerArray` | debug for static drivable area | `volatile` | +| ~/planning/path_candidate/\* | `autoware_auto_planning_msgs::msg::Path` | the path before approval. | `volatile` | +| ~/planning/path_reference/\* | `autoware_auto_planning_msgs::msg::Path` | reference path generated by each modules. | `volatile` | -```c++ -std::vector left_bound; -std::vector right_bound; -``` +!!! note -Optionally, the drivable area can be expanded by a static distance. -Expansion parameters are defined for each module of the `behavior_path_planner` and should be prefixed accordingly (see `config/drivable_area_expansion.yaml` for an example). + For specific information of which topics are being subscribed and published, refer to [behavior_path_planner.xml](https://github.com/autowarefoundation/autoware.universe/blob/9000f430c937764c14e43109539302f1f878ed70/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml#L36-L49). -| Name | Unit | Type | Description | Default value | -| :------------------------------- | :--- | :-------------- | :----------------------------------------- | :------------ | -| drivable_area_right_bound_offset | [m] | double | expansion distance of the right bound | 0.0 | -| drivable_area_right_bound_offset | [m] | double | expansion distance of the left bound | 0.0 | -| drivable_area_types_to_skip | | list of strings | types of linestrings that are not expanded | [road_border] | +## How to enable or disable the modules -Click [here](./docs/behavior_path_planner_drivable_area_design.md) for details. +Enabling and disabling the modules in the behavior path planner is primarily managed through two key files: `default_preset.yaml` and `behavior_path_planner.launch.xml`. -### Turn signal decision logic +The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the behavior path planner's modules or features. For example: -The behavior path planner outputs turn signal information as `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand`. It uses rule-based algorithm to determine blinkers. +- `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. -```c++ -module autoware_auto_vehicle_msgs { - module msg { - module TurnIndicatorsCommand_Constants { - const uint8 NO_COMMAND = 0; - const uint8 DISABLE = 1; - const uint8 ENABLE_LEFT = 2; - const uint8 ENABLE_RIGHT = 3; - }; +!!! note - @verbatim (language="comment", text= - " Command for controlling turn indicators.") + Click [here](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/preset/default_preset.yaml) to view the `default_preset.yaml`. - struct TurnIndicatorsCommand { - builtin_interfaces::msg::Time stamp; +The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the behavior path planner's node is running. For instance, the parameter `avoidance.enable_module` in - @default (value=0) - uint8 command; - }; - }; -}; +```xml + ``` -Click [here](./docs/behavior_path_planner_turn_signal_design.md) for details. +corresponds to launch_avoidance_module from `default_preset.yaml`. -### Shifted path generation logic +Therefore, to enable or disable a module, simply set the corresponding module in `default_preset.yaml` to `true` or `false`. These changes will be applied upon the next launch of Autoware. -Some modules have to generate shifted path from reference path, then shift path generation logic is implemented as library **path shifter**. **path shifter** takes a reference path and shift lines and output a shifted path. +## Generating Path -```c++ -struct ShiftLine -{ - Pose start{}; // shift start point in absolute coordinate - Pose end{}; // shift start point in absolute coordinate +A sophisticated methodology is used for path generation, particularly focusing on maneuvers like lane changes and avoidance. At the core of this design is the smooth lateral shifting of the reference path, achieved through a constant-jerk profile. This approach ensures a consistent rate of change in acceleration, facilitating smooth transitions and minimizing abrupt changes in lateral dynamics, crucial for passenger comfort and safety. - // relative shift length at the start point related to the reference path - double start_shift_length{}; +The design involves complex mathematical formulations for calculating the lateral shift of the vehicle's path over time. These calculations include determining lateral displacement, velocity, and acceleration, while considering the vehicle's lateral acceleration and velocity limits. This is essential for ensuring that the vehicle's movements remain safe and manageable. - // relative shift length at the end point related to the reference path - double end_shift_length{}; +The `ShiftLine` struct (as seen [here](https://github.com/autowarefoundation/autoware.universe/blob/9000f430c937764c14e43109539302f1f878ed70/planning/behavior_path_planner/include/behavior_path_planner/utils/path_shifter/path_shifter.hpp#L35-L48)) is utilized to represent points along the path where the lateral shift starts and ends. It includes details like the start and end points in absolute coordinates, the relative shift lengths at these points compared to the reference path, and the associated indexes on the reference path. This struct is integral to managing the path shifts, as it allows the path planner to dynamically adjust the trajectory based on the vehicle's current position and planned maneuver. - size_t start_idx{}; // associated start-point index for the reference path - size_t end_idx{}; // associated end-point index for the reference path -}; -``` +Furthermore, the design and its implementation incorporate various equations and mathematical models to calculate essential parameters for the path shift. These include the total distance of the lateral shift, the maximum allowable lateral acceleration and jerk, and the total time required for the shift. Practical considerations are also noted, such as simplifying assumptions in the absence of a specific time interval for most lane change and avoidance cases. + +The shifted path generation logic enables the behavior path planner to dynamically generate safe and efficient paths, precisely controlling the vehicle’s lateral movements to ensure the smooth execution of lane changes and avoidance maneuvers. This careful planning and execution adhere to the vehicle's dynamic capabilities and safety constraints, maximizing efficiency and safety in autonomous vehicle navigation. + +!!! note + + If you're a math lover, refer to [Path Generation Design](./docs/behavior_path_planner_path_generation_design.md) for the nitty-gritty. + +## Collision Assessment / Safety check + +The purpose of the collision assessment function in the Behavior Path Planner is to evaluate the potential for collisions with target objects across all modules. It is utilized in two scenarios: + +1. During candidate path generation, to ensure that the generated candidate path is collision-free. +2. When the path is approved by the manager, and the ego vehicle is executing the current module. If the current situation is deemed unsafe, depending on each module's requirements, the planner will either cancel the execution or opt to execute another module. + +The safety check process involves several steps. Initially, it obtains the pose of the target object at a specific time, typically through interpolation of the predicted path. It then checks for any overlap between the ego vehicle and the target object at this time. If an overlap is detected, the path is deemed unsafe. The function also identifies which vehicle is in front by using the arc length along the given path. The function operates under the assumption that accurate data on the position, velocity, and shape of both the ego vehicle (the autonomous vehicle) and any target objects are available. It also relies on the yaw angle of each point in the predicted paths of these objects, which is expected to point towards the next path point. + +A critical part of the safety check is the calculation of the RSS (Responsibility-Sensitive Safety) distance-inspired algorithm. This algorithm considers factors such as reaction time, safety time margin, and the velocities and decelerations of both vehicles. Extended object polygons are created for both the ego and target vehicles. Notably, the rear object’s polygon is extended by the RSS distance longitudinally and by a lateral margin. The function finally checks for overlap between this extended rear object polygon and the front object polygon. Any overlap indicates a potential unsafe situation. + +However, the module does have a limitation concerning the yaw angle of each point in the predicted paths of target objects, which may not always accurately point to the next point, leading to potential inaccuracies in some edge cases. + +!!! note + + For further reading on the collision assessment method, please refer to [Safety check utils](./docs/behavior_path_planner_safety_check.md) + +## Generating Drivable Area + +### Static Drivable Area logic + +The drivable area is used to determine the area in which the ego vehicle can travel. The primary goal of static drivable area expansion is to ensure safe travel by generating an area that encompasses only the necessary spaces for the vehicle's current behavior, while excluding non-essential areas. For example, while `avoidance` module is running, the drivable area includes additional space needed for maneuvers around obstacles, and it limits the behavior by not extending the avoidance path outside of lanelet areas. -Click [here](./docs/behavior_path_planner_path_generation_design.md) for details. +
+ + + + + + + +
Before expansion
After expansion
+
-## References / External links +Static drivable area expansion operates under assumptions about the correct arrangement of lanes and the coverage of both the front and rear of the vehicle within the left and right boundaries. Key parameters for drivable area generation include extra footprint offsets for the ego vehicle, the handling of dynamic objects, maximum expansion distance, and specific methods for expansion. Additionally, since each module generates its own drivable area, before passing it as the input to generate the next running module's drivable area, or before generating a unified drivable area, the system sorts drivable lanes based on the vehicle's passage order. This ensures the correct definition of the lanes used in drivable area generation. -This module depends on the external [BehaviorTreeCpp](https://github.com/BehaviorTree/BehaviorTree.CPP) library. +!!! note - + Further details can is provided in [Drivable Area Design](./docs/behavior_path_planner_drivable_area_design.md). -[[1]](https://www.sciencedirect.com/science/article/pii/S1474667015347431) H. Vorobieva, S. Glaser, N. Minoiu-Enache, and S. Mammar, “Geometric path planning for automatic parallel parking in tiny spots”, IFAC Proceedings Volumes, vol. 45, no. 24, pp. 36–42, 2012. +### Dynamic Drivable Area Logic -## Future extensions / Unimplemented parts +Large vehicles require much more space, which sometimes causes them to veer out of their current lane. A typical example being a bus making a turn at a corner. In such cases, relying on a static drivable area is insufficient, since the static method depends on lane information provided by high-definition maps. To overcome the limitations of the static approach, the dynamic drivable area expansion algorithm adjusts the navigable space for an autonomous vehicle in real-time. It conserves computational power by reusing previously calculated path data, updating only when there is a significant change in the vehicle's position. The system evaluates the minimum lane width necessary to accommodate the vehicle's turning radius and other dynamic factors. It then calculates the optimal expansion of the drivable area's boundaries to ensure there is adequate space for safe maneuvering, taking into account the vehicle's path curvature. The rate at which these boundaries can expand or contract is moderated to maintain stability in the vehicle's navigation. The algorithm aims to maximize the drivable space while avoiding fixed obstacles and adhering to legal driving limits. Finally, it applies these boundary adjustments and smooths out the path curvature calculations to ensure a safe and legally compliant navigable path is maintained throughout the vehicle's operation. -- +!!! note + + The feature can be enabled in the [drivable_area_expansion.param.yaml](https://github.com/autowarefoundation/autoware_launch/blob/0cd5d891a36ac34a32a417205905c109f2bafe7b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/drivable_area_expansion.param.yaml#L10). + +## Generating Turn Signal + +The Behavior Path Planner module uses the `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` to output turn signal commands (see [TurnIndicatorsCommand.idl](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand.idl)). The system evaluates the driving context and determines when to activate turn signals based on its maneuver planning—like turning, lane changing, or obstacle avoidance. + +Within this framework, the system differentiates between **desired** and **required** blinker activations. **Desired** activations are those recommended by traffic laws for typical driving scenarios, such as signaling before a lane change or turn. **Required** activations are those that are deemed mandatory for safety reasons, like signaling an abrupt lane change to avoid an obstacle. + +The `TurnIndicatorsCommand` message structure has a command field that can take one of several constants: `NO_COMMAND` indicates no signal is necessary, `DISABLE` to deactivate signals, `ENABLE_LEFT` to signal a left turn, and `ENABLE_RIGHT` to signal a right turn. The Behavior Path Planner sends these commands at the appropriate times, based on its rules-based system that considers both the **desired** and **required** scenarios for blinker activation. + +!!! note + + For more in-depth information, refer to [Turn Signal Design](./docs/behavior_path_planner_turn_signal_design.md) document. + +## Rerouting + +!!! warning + + Rerouting is a feature that was still under progress. Further information will be included on a later date. + +## Parameters and Configuration + +The [configuration files](https://github.com/autowarefoundation/autoware_launch/tree/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner) are organized in a hierarchical directory structure for ease of navigation and management. Each subdirectory contains specific configuration files relevant to its module. The root directory holds general configuration files that apply to the overall behavior of the planner. The following is an overview of the directory structure with the respective configuration files. + +```text +behavior_path_planner +├── behavior_path_planner.param.yaml +├── drivable_area_expansion.param.yaml +├── scene_module_manager.param.yaml +├── avoidance +│ └── avoidance.param.yaml +├── avoidance_by_lc +│ └── avoidance_by_lc.param.yaml +├── dynamic_avoidance +│ └── dynamic_avoidance.param.yaml +├── goal_planner +│ └── goal_planner.param.yaml +├── lane_change +│ └── lane_change.param.yaml +├── side_shift +│ └── side_shift.param.yaml +└── start_planner + └── start_planner.param.yaml +``` + +Similarly, the [common](https://github.com/autowarefoundation/autoware_launch/tree/main/autoware_launch/config/planning/scenario_planning/common) directory contains configuration files that are used across various modules, providing shared parameters and settings essential for the functioning of the Behavior Path Planner: + +```text +common +├── common.param.yaml +├── costmap_generator.param.yaml +└── nearest_search.param.yaml +``` + +The [preset](https://github.com/autowarefoundation/autoware_launch/tree/main/autoware_launch/config/planning/preset) directory contains the configurations for managing the operational state of various modules. It includes the default_preset.yaml file, which specifically caters to enabling and disabling modules within the system. + +```text +preset +└── default_preset.yaml +``` -## Related issues +## Limitations & Future Work -- +1. Goal Planner module cannot be simultaneously executed together with other modules. +2. Module is not designed as plugin. Integrating custom module is not straightforward and user have to modify some part of the behavior path planner main code. diff --git a/planning/behavior_path_planner/image/behavior_modules.png b/planning/behavior_path_planner/image/behavior_modules.png deleted file mode 100644 index 0f21b959ed32ccb6964868f48bbe1e80701f4e4f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 134367 zcmeFZhd-C^-#<*GvNf!dk&tYX$QCMXC8L5nhRUtbo z`+gqZ?{(de$Nl>k?w`l!`d*(;@phi)@j70w=Q_?P-Q!vew4AgQ6ch}HwKeo8C^lwO zP^=H!NP|B~jE#`S|D$$OJFLGEUw#{{Bk|uH?uQKBPhGTi_p)%cp|HDf(b-1S&C1or z=7O93MfVA+N+k*k9*V;ns`}pdM!$QR>f2Q)Pqxte50xKg8Rik<>9n$x;d~u+^3py5 zql_ij!p0xpUw4gu|K3r)-^aNm`Fm`X(UvVo@0MGN2nnaj43~RZm}gN*SG`|e?cF~p z|M4{c-IgWgYtnA_-Q<4l=^0##l;Mn}(fB{V2DA^ht>@wU|9(9XH9I?-o|(D6yu6%(qQH<| zT3R|WDe0I?V`Sve$)WLaO%s#t_)vJFWdz_>tC4(|EcP};ILoa9K?+X5L=3;gCH zjtkuEYYAADrlq9~b^cmZ(YnR{)>zOosR(`gu z&^Gv}W{+U$h3_>D+yOD;;}<9buU%u3b?y$GoSclP$SWz4y?4-Ov*7W2%q1U^_cP&Q zA~G|7srPW>Vpg)Uv#T!#ESVG)7gG-9sUOnPvTD4s`+slp_J&s6n}eQ&ie z%9Ju^`n}BORA-6zl;!=se7=?rGMq&vB@bS_FzmE7H>Wsr=8T-2oQ`>;{R6VX6%{+{ z>guwdJW+FVla`m4Z~gj}4y(Oo%NDG5bypY1`1ttb++28W?pWgdt~*Va#=7_Y{Pl~H z!pYg0g_(IWpD7|TQZpS(7aJQZBqpZm;j!5Iwq9Zbib{{C&t&(F`ZXU`^z-qF#R*4EZd zVxKeGIyxd0yvEa>Jv(mqy101Xx9{H@b{~B^aAb+z{^G?A6dIbEmQ($81JA`X^`gqk z4&GC|Y|v?Y{yc4_-T|?tU3?EVJT}N7)pO&A&70o8e{b&SxMXNOGBPw& zm3j0|YiH-iv`WT(UgO_3td4rOe+ejZj(YS+AYGJqbCkKI<+@X+PRSiOQ2pTp!;c?7 zT-@F7#XsNNHY9nYpAyfbFXNh$nvG3nzVl#nieZTp2dZ5#-&*FJm{~=PRYRPrz|GjE ziKWHG{;|@Y@VvZ<7t2a0h>VZ8w{PD}%ch$ZYGk)>-(L3j-Co0T-&yK}7=d8T3{@;j ze}6wSH}|#veoL8s`_hYxx4FLDaU^rI@NHVY>lh-d^+f zsmk1ib}heq=~&vV)H2%A($h(iXlrY$T)HIrP%nFO^o-C}wM7?ye}8rkj_UXC=?x4F za7Ur3socMtQ=(Dj-_PXpwcSKn&@RnSG~C{M#=T_2h7DFXJ(s(4Q$WoMI`o*r&|Z{4?-ZWb06lGR%38X*?(@2KJ%t+kIHZ8xg0 zn*H;6Xk;Y0O0UiP$+KsgdU~5VIXUZp%}<=IOhE6rl!+Do_ATb$KW~fVjEr6F!K)M= z?(V%cVRUj=mgSxo7M?URii(SiI~ibh;sjI2v$M5cJ^m3{Swc@uN*UdLzvpP!yoIGL zS61;zAA~Jmce~ zuguVjYxuVZ1O%Y^nMc0lhNPr?R~H&)I&t(Uou#EExrCp;e?NHgR`}J`pHQ=R|1f=)!Ec!ud8w(a@Ve(HGXv)I&+}iixw=l?OkJj~uCCs4 zwyZ(Z%#8cUkt6wbEjvxiyjgbd-d%IqPbg$|*Z1!U7!z8Wnlv9jew^%f%&V@gwK~WY z6j>jrDy+d|Umd*O#nshUsPfnFa3hEA2_bCmgY)0qc;R+l*g)7{3@FKG~qW z%7RTDqA&b;Apm`mnudl?MrNy$l2ZQj=fO!y92$Hq@(Kzk&zy-{O6YIPGJ{>LR$WMAET|(RS(|&J4JqzAo{bjk*Q~;qTw;UCu#8f0CF5Ym*>`K(! zoagfDd}YM7Yb_Z9kY@!r z5V%TTfzlD$vq#m|RsbWm_4{`Q3IZpvR@i;IW@gt)fB4d=s;X{rjnQ}*O_pm&OL>vS z_QTy--78IahnBQNSWmdK0L#^!fk$P+uLJ z*_%(vHJ5V+r`r}JT{gA zkC2{$fpSK92@A!8wKFk^9vyYMcfgHi)22=FO~24d?CtHVrUn|)^|H;atwS;4qU67A z`rO(Y`26|vC@~sEOWLq?Mn*<2{Fh_{S69RG^Ce!qeA(Aq9YTTckiv8{AO4srAt{;k zw*QKFqz2#6@bEErNwh#oOIzD;%rVQA#o1j~O0Xsv5_r^EPoKW|oO9+9dK^}UjDy@< z22#)E<%;BiiS3i72L=odURSm>{`!UY)Pv&!nr?1x2WLN>GAus7ZQZ(cm@CvKCMM+Z zId8&@1?nNAsHBAT<;$0Hm-?wMe0ve}Oo$(P78`e=#3BF<{EVqXaSnuCxVT()un@uSc+sN=+{@Y|&c||ceIN03QR(5DU zHYUdW;zg#*moNWYSm5R3TZifJZ+W_f+>E^pXO_P3t=qTz3R{%aU0f#B>DUE;6;ENq zglu5yUtXA&rxd<_|9)g#Ts@t583i{tcVcof)1tqXl@)HK7A+HlJW7F^cjF3aZ7gOwqk~^-Af+z)}SUP;H8WSLn2=@{ZfLZ@=)F7BDt8 zrkD{wTWDUrPUo)7CP_(2`wJH|?d$}xn(;SphHyyR>bOKjMMmyaM!$D)abb7+y#-G& zN!pH&pPxEl>1&V6U^5qm3cz%8s`9nnM-$8mlsWlRP|e?8QR!bV6&?+`E>PQOX8~1H zf@nx;YEQiC3jqNER6!7`&d<+}nS~{2xc%|K`y}aqKX0CJUl-AQUy+VHQ7ozY+))4x z0-?#5FR?{KE1xU!{%MG$Vh z3g8h`qw}?wxUjG=1;w#r$K>38(=V^AOrasKq)F|zxBGLx{Z2bm2)6H)D@y$X17Xfs zu*3sy0y@WzNqYRze^XaC>?g*@7ku<9?op8sU1D;6J^~;R0CV!kS}ALDpzOo2zCePjai&WuLd%cbo;G?ZB<=Uv+lL$ znA)jRTLM=XXK=R|nnA~sWn-HpS=xpqw0}uHGRPswp{7Pn-@xF(%a5EK-|#}7Z`&&kSCL7#iq)WmzU5zu2r%!Jq(+QxTqNbdnTofm6Hih!_o>Pyis;e!k z6kR9m>MSL(C*9xi-f6lHzz2-|siPwUMS!9v7m|~+7k|&p%q;O}Y4w7$vomh!kb}b> zFwR%6UYXn5Z^RS9++_5AB(r~i#`EW!@fay6FysFH`zOJf6e*y8@uK* zytS4>nWCK}CMH&W{J0q$MD6ThvjF$g0~HlYn0*gkz2dA|`%si5WplN;qN%9~2t=%` z2YeKTW8vsXr>v|T8XCGWh;5#*%66qNAhh?CPop@}#7s%+Jq% zF|iU8rY~G)m+JpWy7ue0Z#(v$dG=-`uac3C?atET*+x>zCXJ;ojapA&+jkL6C=H|Wr z9nz^k9rGVQ-T=gc3k%X01{2(%!FN4=JujeztgLL!;O!&3@q5BNGO?O{zkka<$`r#N z0g%KeCr9HMxx2fky?$*Xcjx%=;~NtZ(h0$0ylc}G_4BVK9X*xzH|?FLY5Zo z06Ugt>sD$<$C0JQ74X|zw{E39c(4xFg^@NiHWqgO{!WZOkk#J4K1#IN&aYpY78InC z=mGV}Xvb&Kao3MU{Kv`%?K|w*2fByoF4DZ_0uFJW7`}G?)f&p|WRwn$-%*=FB zmAF8z&qqis}-@SYF?p;niHio6wUS=lUJszH(6%#Y_gzt)qZd=rkiHVVL`1p{e zXBJmakd3M;B{o%|Ov2JS}@?=R@EpIyyS&4;xX$Ku@(_zIcB6#c>$-i`CcF*AE5$BcnW9UyXmWD&KVi z{?Rr`V1a&>b9jav(W=}wT-@pBm&R0|6W1m2@>|Bqq;amvuhh;VZ-0|+tf9s#G(QO-L$o;-DmDs9c!&BZ0~ z&K+b?HoMW_m2gC3&9zk7Ed#{b)Q?`kmaTR(mb ze)ddkW@bhOvj)osQ3LHF5bz1mDBr0|3Vb_2pW&)w$Fsi4zFIZ+zK@wl$%w12t6Ptf zC6DvjxpHCZYxW^l^z`(k%K}XS8d(C$5wf4pB^J`y*jSx?>T!HRLO2*38lbzE7hSA0 zR3B~r%~+UPeAx703n5btpR_NV&d$y8?cTlq@rhK;c z*ul)oN~j_M8o1^y{u?Rk2jztK?wz_8uuO`LV$p0dV6i zJC%UPL$4<)qR|)Pgx?MV8AZm%Zj<-^^6YFhWUbmaZ>XW(be3P<4{jaSvepo=yaBL5 zKF#7An9en&#f<>56pMRbkojtD&5xZ59fLr5dD$GrKN$6%GG^- z{{C9UW_%AKvU76i_Fwo`g^LdD4FOB(^Lf-}AL-+UP^Zi%8|Q{Yyd+}<-3ZN%e1hYb zryT8puk^AtFx-#dlM4bv!$ce@Q=grg0j}q#f9~V$-J4{0zxwL7z4fMo+v%`0kOJvK z_*DWj_Ve&iC@*!jj4P-dY63MwtLc2@v3GScLYW8c|N8aokyo#Be(p`e(*GEQ+(WRI z=V;<_t(SBDkIQ9EO-&^nzldmPY1Ov0T>NC?eD#6z0#hMrg2PeH zbW}pA>l+vdA=vWslhY97w4f>xX!*Z7-qhkqo)r|0UE`<3?(7m1W3+3&r+Vp9fs4{M z+Vv25LQAeeIK{5-8ykzYX-cr@s|lOu%0H@+0YUKky?ZfOJrE0uAtp8a+fJe)R8=!{ z%k)6jP>19c$E84%R;lQ-H0Nyk(seyAFK!e&#v0m=?&;HESo3r%j-k{|zJGrn{zha{S*Vgu-(PJ558t7y z1ij?yRoXXi-tZ_X?fm@tbB&bb|4MDzavQoUQXb#;r9GM;@-nYCEIgcshz@te&Z-$1 zabS#u&4fh8p+loMM4LQ_HYT_`o_jh?T?N@65;}+A+(&0jqTIt&zq8d-?({Gi(U_vUK>QU zA^ygVb!nAM)}Rdk7Fq(7eh1|?Hy^*J9I*59{5U34QCD0zt)2rYClR$4{@OstQA4X; z+1_0lR&v}C6@B8wiT5cAY`7tH^Nqqsou1IDI}&Afd2^l9F`d+E^2p)l1#64Bfz zfvz$I5xf8G^I>|7HQQB|6>n09PMAe!L4>rh?~a70Q}W#9Ozvf+EtUTG5{8^ZkTt zhd`b0HF55qyvGqc*>}2VT|Aqk;&0sw#dns?d_3BT$C=-vQ)~>NCVcR5v9vIB4nnWy zdjhyS^31fXtOnvMPo6s$7ZXE|TTX-CauGL?_1wOwsHnF|yz)(H&y{Ep!;~a}kUcm%YL}s3~Zc>l`FF7MzW(y_h%gQ%gebM zu5mY1uB}|OwzFgMaY7Beefw4g-#-Fx%G4K?EFOfa5 zjneb;UEVAn0!YXHAP^kl{qoFXWv)x{agpO@7{d5-kA#J($;m2|{RVFC)QIOy1%@$I zRVoM9mZwn;RhV-WGo_c&6i)*1dU?&W1ZZtfyOEd}8L%>9_QG?F^P%2wnzJy){|Jtt zA>@IInv~Fg6&oEMt_GGVz#?H3YynAB^X%?}%Cig2ABIV1k;9e*QIkjQkAZ>t%A&_J z^@UGDU4jm0VWOoKA<;K<0czdU)D)4iLVNF}cV`$A-4)s$)`38|GiLtV3L!pBB?hkA zc>^pcEsaW>R`_wC#MLX@CceGgHM$pw3tyejZJH9-X=r6YJ&s`Hs_81UJ85bvV*Q)r zs%$5Dig1;>Ufgov2X%h?{ymV#qx=sI4IA+B#CI9L78$wG;_#b~ANBYJ1PHRMoeQ(y zFgP)O83s|!jonA`H(xgaL1W9LGt2#a~4 zzDGnv12XaE&70%#Eb)*Ah99Ty^n7p^Och&DcmL^Z{n{^zsB$SOsmZAZ?g2P0!0H@D zc~39|uvy6^Led4?EU<5TASs^r&>)8tcZ>4c4mR;~5NGQmXYc*}>uPOl%ZDehXU`sj zfiO*!oLaRp((#jFm4!grw$1mVFt<$s3SWCoXdXH8E`Ct+a)7P1HJR*SnE>8gmu~cC z_|hDVo8QNx*cB5SyMcNRU$h*#<6pji&z-(sT2i8EXxN!GpV?*)ll958SO<;25+jDo zr9Yqcq{x$B1QS>0_b;`G2WTRookWd91>MchgDrVa$)7V>);TyTYSSA_Nw8gFaJ~-% zu7*jCLTS&E?pep2;IoLT50x}Hdh}>$SQtZh2MAQi)2AZK1KevW*q(U2T2CL_+1PCI z=O*$3kobT_VJIJve_l;hHAv#9#_RW2F^m-^%0eEe zURjJv-nZxWk*U52?tVzxuopM4ZcT&n2Hr@tR6oCibv?Jy8TqFu)jt#H0nPZ)C%bbG)du6wvp$wu8K>!Io_O zs{yOisdDZ^%mmoIivU%8{8;ed!Gq=&7L+edWFJ zkMkmGk~?5oa&G*4G^o18Yw!pBWbgR6*r!9#ONpg}0b|j1hu~)6+iGTJ0i8yBz3hHc zEN)K)^uqFaPn6FyZ`l$8Ro&3Uq!#-edL6M3@L-LMl3I<@QeF}X7X*N*>5e$}+`pni ziMfd$acY-!Dn_A&#rTD=Z>A*hl zup*J?a+^SfC@^UL-^q zhL?@adM__8Vglm7N4(-H+ zD2-s)eX#vc|BHdtLhLb+s*V1Ec$yG7Ib=KEzz}YKd?EsmM#9Cw*!U`zP;x^yF_(1~ z3yO;m+1n2Vs+=4v{x@H_#swy!7MP4w0lYR){IL1g;M*`oh_Kq(DP$TA!3d2LPmoN; z#1QpxJzd>ENEp39rt%$6=QxufwPVRbl{#R|!p|qx9?SUc0%%7K1cboz**Lo+ZEfe& z%uHx>G#&rusQl$XPX{8jS_?WjI)(%VRp)!iq54w>FG2c23BaV7B3Fk5P%xwc{M123 zMGIJO*s0iCbR72rS1De+d7}aD{^IrPUBbfW-});(v8x*JHQUm5^Oy)LQ-m!xoDm=vK zG?)m0YS06N@kG((pP5yPmF4xI5_lUj-dGkK4~!|{&Mqt4ad~c(gE>uYMu=D;uCsqm z`^|nn16K{+H{nC@%_xCcVWz3`Zzh$9#^>PRKzIj{t|L|nG$iT{9jget)W>t+nvbt{ zpa55v=6A`;vZ7_61J=X8qr<*QynC1End!Q{%_$0Ue*f}Yb=UETFm2`FIN)Tx2yg+ej#9EGnoAhXF-}n!^4#%Lw@2n znfcFdW88T#^4+^576J{J*pnZRit~zy&@(bJVuqu)qLM(Xu=5g{_np$y3nnVoO~Dg8 zFKK=l@ZJF(gm{Ip*uym44GdUe{b|1c=>|=MSGx{I5;SLM;fFLe>mv(4QEnVLay~3H zw5qXjxI*4`qI`{l2WlNeKI{Y*y{G4;%h)+NAHbTxvI6Zi45kK%eVfK)df~SqMMO4) zA{Z9-E2HT`UrOJS*8l5Q7$O#yU!EEfJsBF2#H0^d5hy-te;md}$NJ)eBJB@)czF%f z$8P@*BGpVo)`|FSe{%BpgoHLC<)ap&ldk(efgrL@#3t~1&t~QqgwPMX2lrNgBmzA`}po1Eo7Wp$Yc!AHF$FpN~XMKhE9T0sAROMfKWeuO22_==Nmxu{np=~ z0)0S}tS2j<-e+%a9*CZR$-N%petuzL$o1ad4}7bK7Bj?10+WLP@hsjgCVX0-VKeEpQ+Hs2Z?#xPqp*N!@R+W20Br&X}U`(P~~>4~nEeqsQ7jqqwn zF|gm#bcG0Osf}RTg>D3&gkte)!rD^h8XX`Hrs?R{QYL^CibX2QbAD5YL`+I_grY$v z%gW0=-km{1&#PSJgaXTazs}Rs)9|_VCh(_llydc_Ph0Uo)V@9kyAeEb{|#73*x)Fx z5qXtO7cWj&2wIag26Sd1h0>iyW!{peXU~R}IKUf2({}+-w>X>(jJQM5cPl>M zd-}tEZtnwe*zbNTvmK;mFw-MA5Dxv4a6d1PQ}HsE}B6g!FWT+1i2Ub!-o&Uk{`-yVWZ&PxQLKw&AvU?wI%GDcM#DB zVF%({pe2B|p?Huf{m(B%XaGPZ96Jb%50N#(uL0&6UgcdLF-1pu+uW=Pn;7yDQIYpK zeu1*E88VK9j7+F;E-`iRFkSvlTJQ@Bs$(Bz>+>PNNjRRj_rLhUcieT-y_d@KqJ|nD zgOGULOSpgkhyO8K{~I129=w8rT7n~_gs`PoTJQLOqDd1mF4EqpN4eOuh8es0d558~ zaX&hLJ>1GLkvU+@7rwK95`*<&E+dU6RAf}N<>5HP3O97T->oG58U zMT3irXVU`KNQUw6&qk8jItc(?Hlqah4stsm z4^MBDLL7;2KsZXIMA(1<*~VB+Y3qg(YlKqY9E~_ z-@oOkwe?Sb@f;b$1J`ycUd3J&G0dkRf$TD$X&OZ{JXQ&5>Dtt_WxMo{EC@)bb7-wU z(o*W68OZtk<%eM#O0f+{VHxQ64U}7StE|G**AwMnBfJm_uxaGC9WgkE6#C6Z>wmB= z!Uij~`D;K%CVSRadWht{VNAv#TOUbP5^}n-w$y_F8_5AcUqOdS6LI<#8x6$kXuttT0r=&^mog42FM=TOK^b@=)hrT+j zF7>SKl*SHoPx%3evI|}te(oRWKK3W0J1QJ@ikaWk`X4@nDJSoBwVf2&3i#Qv$q)&u zLr^3V^&Z4M#X!# z(Hm{LZ)8Nl{85ftdKCtxg^f*^dIV!Sf((ZDK_h5TAXLF?(O0j!AZO02QU{iV?eGQ; zQZF(PL$9&v*bo#&f?9lTv?~Nj6a+7%V#f4ca5+MhuCmR14FsReg(kw#U zi)_}$Ur(T};1i3SeYKUaUr>q-ie6~w#1|%Q)W#Yeg(TVF9MLD;J_hX)PxO4ipqw*#_1iC&1)<^d=FeS#2&ASm2VIApLI6i3@;p3? z$*C!y-ou6@>gT^$6n|2ae>3Ea9cv4zYf*OheQaBOzu}h1Y#@Lcb{J>7MhYZyAjFMF z-Jq{Zhmv$1VR ztNh@GAS(iQR{AR@AZeIX^3@XEy>~7zjiX42ISln~Gd*A)xI8X} zq?RQ<(Xh~#0gf@{%zphiv~YAjLCbQPSj`Zyl@rN|zC-2gs-2z1~cib8UybF*!3sT0lN@KHio)NdF>fs z9`$G9egpLkBqF_M!y!Hvau^3Fpth^ar|JsGA5&#>knrZib0j zCrN5O!dFP$hvc7Cun(Ab>e!H}E99QQvu<&XCS?6VovmYk*JJzr`*86}2r<)MxnG-m z1=^B%{K*pZaOmc=N0+{j9j>IYk>Y^QC-$ii&lP8K0?DYyZl{tLE!wlhCTbjtc{}Lh z=B9r3Y>I^Uz8lc9cgVYIzqPgk7Qtg&{&S{M4PY&8jCrg8x`G83xTZH7;10>HisipY zQ+R~=d|ePGmf!O_UV(%(8t_)&`C01;8sMynn6t7 zy*2YP5~@`t00a};z6Ik@hM$6)8gXg z)o@h2{6EV`;AjQR8O5Soleh$um0ZUaxGKU1I-`O#U3|4702^$O8e}a$O6{)IGc=3@6&w-Sd(eMzMm6L( zNoQEq)2FvQ1meIR2H52E?GlAs*MJ&EadbDbXqz9O;OnRbWUw{G38Cnl~94cVv6tN|r}u`ve=j^BZNgG5)eD-|N~ zh82Db@j>+}YaR*#t9~RKfjnyZ;CCvmDG341s=t2=#=qAMej2t%2ib^>8>R+f!G!5^c!CBMdV0=-Ai> z2J_v%iR=&mCbo8TG=R4ef1aEv@?IQ%>>*DZZiT6W={-cB$hK|Uu(cw46!Z@l7YU*e z?B8F?Qpk^qsWoW9G_(Ki_%Sz{na7)Bqodn>?8VQOv9}zYejgtq=2ciyva^-N4E`b# zk``2SJK4HD{3nzWFeGV^xZHkP_#|?}PM!IbJ9qA^k;P1U@j}ib{B6c$R-AhBIpd{d z;oIjsDHv3|vbnLdsMoI_exJ47p)nQWy^O3ZEteJ`6`Tw2v|E4YE0z(5K^xrf6cLsH zlnW-{(LAC%-(#-oh;RE33jS6*|Gc=k4&TMX&i?lO9u1jv^gMV>`4+V_PCv>xh#>Ib zP;|a^;|o*2CxE&0VTZJ6pPX0Yi4+`M25-#2jiM zQH9NhNAR&mTfmE#K5F{f@4dN4u;2nGTv=6YFC54Sb%wY@1`V)<^yn3|5lH~;Wt;|C z7kF}g{QS%e(f^6uP-0|aVujg-9mX-W)ZO*fq{NBkk05XuwC9>pS3X}kNKPB5Bai_7 z=B3%#1|rP-!_MoDy28yX{D35Y-NX4uS*X@ZZ;gVpg?Z&-{e661=4+NGpbf(8J~%Jgj<|+ z&OSt_eV^z7FiLVDSly=2-$Gpp$|KV&@mq6!QyZf2SMqWxM zHMPUY)?K(!xI~vs(O4s3q@AE5R4+p%_QEnmwDI{j>&8Fj^UqFlI4r)OU`knfki&7< zOJCGYdC-ON)%~xwGU_T)OIbiriyE{_hEmhsUdSNt zobzcz{;jmAfMcV7f-V(QVG!rmuM_ec@ zdjz6wL9}2e!*Q0g(g|w%#Rn3Gh2$MzE9{CvD6(6v*NNo4P#t4jFgzPjM0O${c&=;b z!(w;(_Tu`~f{wrzuovzA79fxUoZ!K6tYdrLWcE&Zqc+lCj^Qw@yQk;J{wLC^v27L8 zDHHF#uVFXB_eqa>jZGJo=>4}`)O~yYy&gwa)`ZvGPkxTR@oa)|fy`f$r0k@#`s4Pt ze(fEM8#YH-S3lWhsGziMFi9xf-Ni-4*qAfPO}F_KiY}&E8p;m*kN7L`!ePgvB=&?y zM8N+(R{t44ii-1Io@(Im$A?hE`Iec2nehh4=A1pwx<9x7Y%OKsfIkD*gG&# zJG5$O`1__p?d4<}%`9U}^z{E8FuQW)O3X;-dTQ!c{hwg2>|9)7jng?&|INz?8YT9-$ieBpc`U`l(2ziJ-E-%TODSNZqN!?a@fYEb_TeTH6j;2G zhOn3z{O5amxu%AO+QB){s}U9lLJGZka|^JN?bhtAtgIhb6(JQN9ya}i95+9N>rh@t5@Kvv`bwfofz9jQ?;$P*PO^%fQ8Y*zBp@Qk+kvGv$-a-)f+K4 zvHZ|fIL5?TqX9Y8zCLOnhJGV$C2_l^x|$LP{91}U|7}@jF{ow; zTu>g~%G%l4!39e$$X$5TU5XearGye|nfvf&I0tWs*rhFGI7J1j{gl??I3rGS{6osl z=2HU%bGrQ$<>#0(^&AQ)F7HYNa>Vr?k( zR_K11DqgugDq6x`s>I?t;3mm_5QbDXE}@Iw%J45vo3z~vA358G~b?%5jYeu#`04* z+WJ7yhMj>hNfDq%VL>HjZwV2Uh8PGf2#(}+XQ=juaE@<1ar=zDQSriaj zs+8j!QjSMJ(+06Jyv2G~2c9Mh{IJfocY%-Ioj!?>1EK?01sLv1C<>j zA|hVmwuR)hkoWv|uc_({-0@egHw=*DCiw53&1QWm5pDJlXLq9(A!XC)$=b$kG z_4@%Itye*uS-82C#|$q@f%FmS4LNSQjJA#C=dJ7=ly+ z6BF6H=TDiLkxg?`*Fj9=xBpY)Vp^mh&))9+Y6*G0|+f#_k=PqVq_%I`+%14j+7ISofYuCbOfy5-vE`jYOIuESn^XNyN&yk9hA zPpusHnwHj9+`AR+9_SoupsoAPClA}eQP`vOfhZums;sg`X+V=Hbr5^=%at6iLf8uD zQYm<9tg!7DYRx4KH}-|8^#$8TT}6|*{^(quo&Iqhp{$6tF0l7 zsQ?qQX#J&ku3tZYzAf_J;PmM}SXMX!X2UQ0bIO~}V8XwD-LzAp2>pZL1>@W=eA+!w zw2@Ki{?=Yw8&c4#C&Ef#F^NIIc*j4wLic7Z$&nN=J97zkikNvOv}g43qG36>z{sid zMR#GC<18l}RN1;`iIx)V*t(i-8zJph1C2jQ$x%3PfF!o@e;V#2Dv788n%#*#fvy;u zaGuaZBHfH(?PD)L-j=P+oCfP2&jp7mh_#tN~nm&qi{`<3z$P|+S|AE_4WNM zZ5^2<8yo4)+^vbCGxPH|y>_s(c`ht2O6_d;yWof8WjqoR@z=G(Hq%L8+Ex<2ui*ai z$A#G<38kf_$0mX__|gw#56$}K44Po$zN{b{w<#jK`$d%QKzd)F1-4n*!-v!m8OS;A zV;Y0w<8fNt{_dJ=l^1uRX66*9y$|N>P8!_eIGDEMkU-q+U#kNlj65sO*iA{_t zfV;%M|8V{Y#)a@<``@lF(QU{i{oKOJ#&)xkYsZfK^Ph#2I}U{e2V>f+?=TX&F16+Q zRkT+hL zKUyat)_(~BKO@8biHQ>?p$I>z!{9-+59o}(%uk%}gCmxf#)HNT%QOvQESLh(BfNKW34DK+SSGR{@g;wn0SmZbgIilc)= zfgwfVtSRaR5J6^;AMR{|0@uw(jrzm#DRI;X_Pn<(tScGL|NTmmYX@V5?37IM2aQN6 zmSW>$g+7DR3s5!+4`dkfU2lE5cuZgmXa-c(H-=6UTfBTzj3HCt8Pr=biQRFOoJ;xR zb(f*(7ssdb#TrADG11}MXv2Rj%yjKP~FJ;VY zP2$W!QR*!7k%oC6g1EU23x#a*hlc?VG_r11x;`b_Da(TqwKx)( zQo7)dGfcTM*ERTpUcY|*fsV)Z1E(Dj=@r1irapVCiHb>Jo zoRQ@d6^)J5hc1I-iUpBUn2EfrI*w|-JkA&q zg45y z{HA6G3ukOS-=?UmRMKIuv>r`*A2c4l`6{7NM00z->3@*)uWEn^WKt9n6>j-w^yJv1 z#p?);-3>&m+D7sNR7?k}vgE5vuQyIF*BP4Rd&V{TSKt5yLcn0Jk=Xu;A8fJ1cS%dT z8DFP8{U-v^Io#-n8p>GVBt^;LGa{_gtRBb9E+D)IjQDYXTx@Lmt5?r|F# zveK5=m_9;#A*a{ju%UL*J&2zQ$Wdf0%94h^Bfn*C?&H>bC49G!;E;;b-89KDbBLq% zSAmhDu(5j~b;_QFWFU$kTe$4*z7^IyI?=QMUqQX!t76#2-SgHmoOo}IRuk>?-@kWn zXKAGCwgz9)7gfwPc-_l)yRL#MT{jZL3+hzTEp}m1(K_%*k!Es4=EiXU@899rWPIy!5k+tQ+=qYE3SLid0k$cko3oPCRP$ljxc^2E$Q|hCljveUgx^hmQ<<0iwuwGF3YDd zB1ur>j63>=gCI8Tvq?Gv{SvZMok$5z^XXyGv3BhgxJiyvPWOM3;>J=ZH!*#%nVP-e zL&HErCF;V*ywT|yizsWf17G%V>-l1tXz!5fK!7&lUdpDN`p1QQcc)Mj#dUF8wS63Mi5?P|%297pjkU0u~n1TP&Dk|<9 zR-`KVa}t80qCx@Qha`U#L^4DvYQBEGe3(@viw8#-{&T_^@3MgN4Nab?k(X#cpFrsT zZpIgPp z=HCAPV62{|me!9N=FcGLPT+$_=9Pl+s8jX?KqSFu?-9{tQF@F~| z;FE?trLL}oU>onX26bIs=KFqs4}Zf8aG)S0Hta3CoVY^^r6BvVv6;p(uJ}v85l|^O zDhczet5XGDqCDm4DSO}NH%E@6pl|t3Na#W$BK%(wBJdpTv?wsh0L}XR`Or}vy`0a` zXESFn>5!aR?#c7T#`TWXeAgo{y;NmQ2n*bnEh0VRtBBL3Q;sR-E z{emQK_Z;S#kN7N=$TtNrwj-C3893eA#39x#=nEn z?j$SKM7^EM17<&2)-wH)8692E$}Q`QAOxYbWVV}<4%F>I)pPLXQ*A8X6=vEn*25G) zYv+ga7u0e-8%LTyy-o2v+)$+C<;rt|inn)l>p^aT^doSn$mC-Ap&dl#gN=9+@EXAV zr71~=!zV=;nw)Dx3JsvstX1l8mG|Xyc;N~x3UUCC9G?mZP{#a3y`+CW-)Q;IsqK7m zQPrB-od8Q$#Vx5?xdzb?%0KRSohW6L_^{2M)tc7^o+}zn5q&3`F60);%~tUI{^tnY z9dR=n3bY^6GGR6?-Rif1Df{-VHattbcj(&aoz&Eeryt@?nkP+6j+#Vn!U6dsN3MRJ zdi&E3nZgf8-a3u>cMQ81UhvAA_vv?2P998fP>@N2WK0Zm;4(`n)o8H75g!Q4jCJF2S45NO;jgNRCnEtFn8sB zoUt;c0p`nIg}-}$VQZ6bT$%5QIF}c3{4rb;E@Yz!5sGeMVqidKC1Qse4>L{|zI{^r z?WZBPgc8j%PJlRh!cvMYn%yHjUQMl(syy;HL_}no668vgWZc1eYk|6;n#6%2A6U=i zWRdRV_xXJBq4;x|dPdZ@?3!>WKR8Tos&<0Z~IZUsOW?+o(uS5pS6(5;^c><^&J{-gJOtE5S&jO6fvSfHp2b z=Z80j;b4objij_q`j6^HK1s(O@hvzS%ZnW+!}9^ONQw)z6(isuf(>yfcf572`O(xH z)1wKZ`U;9hJSw7PEe(baN`?AQUpngASdQQ7ZlX)6^Dk8j0Uj>laT0B^7Z74;*O}K| zpDCa~H#a}u(&Z2?zv}lv8tQ9(7{^Vj2}o7QTpQ(=1h~>DdT{Byv0E2Z^*b$ZUnzU} zxf5I3PkQ6@?B$-Nosg$U=n0#(?OQ8~n%oqQ^D{=MyG`og{14J=I4bvNJ&T9#x_4-3 zY&aQ?8D|_%9n!dNr(;i#<%5n92Y>c$Z%PvaE%(y>;?zgIgMV}vG}PC-z@2MeOaLn+RDtk0Rs*43yai7eG$w!d66#J%F|+It^Tta84+A{||2}WEI6gn;SJ^8U}bls1d{_ zZ#hB!8*nTse`>*RBlS8&w|i018K2jepSpw)ZcfffS=R2soVY1>68FS`rfFA^KVBK; zdfXSqL^NY7vzrTB=kXR4ayA!+1_`nwF-+(~f#v$f3wuOGGjIQix^}HpSdX$^@Cnpm z@+zQ$p^>2>6&&6%Ppz;9n-RYvX z(P%&Q^?V2z!wA7^zHmG$Tvv$SYBvxrxNaGa8y@xE@Fhv)V6W>-{QX@vugxz_l`hg* z@Lhjf!+IIgD;zV(DkEk0296J2@TbXkW!jPy`}(UBS06Mr_{mNs-%CjbMFH(4Ned^V zMHe#=00*wLK=6>xwHdDw(7VX>?~!S?jzIDyGqF1gdsUU%Jws~ysu0A4zp4&dj2sYo z@PH4;u*oC@cYmn357Hkv7p5+#*GX85aMR6O?kjo^rAPFRj5tnv91nwBiTv>@k`Z_t zMykl$Q?kFYsmVJ)fd1fUg9PF#7cL@|N}{+357-@KI~`~Jwm@#%`+VX0ix%wjk>4X60tX1kJ4i^z9b_3>=7!;0 z4Ujq)oG1OOvv(`)Q=IEIuI}`Ev-9_MNK%r`NwJe1-G$0rm<+@xztmT=-dLa*cn6_e zsDaQdh*JxW6+L}dM}VB|!t1qyj&;0X7cqeN{)33`zrye)Kj`=oP?4Jd86A<^vpFi# z`|=*Hp9$Mx&mx{$KrWh$hU$}D3DNkXQ5oR56=-fRD} z*V=2pYwz{Gt>5~6`aV6weP8!=ox^b+=W)hmlx|G#PkSisji`kSmgWNJ`P`^LTmC|e z(z$N;Zdcl&;1PXmYEqvpYLvk#I*oWEi&Z?_E_T0y%!c^~z2y*-2-?J#va(2a5gIsb zte)D<+!%A@<)`zXUqn~zac@7i*6-re$Bj(G4y=d(bo9``2_whX2c;J6mO(b==1F|; z;UMUhO$jzNHN|;UgY+IOB8c{A2)U@0@aPfu$jFH0tLvemkAD1UToKMu*3p+XW2yN0 zgB&;`MMelRudQ>LL!C)>Uk2Tj5lZ(AGzJPHC7j>X+&hR^#qzGDYy>fJ))_3#X?C)+ z;6;{#c2z3QA60$=FzD&2j!+GyK6lne_eqaWI6l=q)&0lji23DQAa$Vuk<;J4w7exV zCA{eI!%>$bM{=g73!i;bJ5h6gxE)mV&VteM^{^mn`WWRL+CXH8E8fY1q19ia{lPOhj)h5+DwSN zm}QwPS-6l0Q1BEoYuEasO)gk}iWC=MY}(#9Y8?IC_yz2F3-FI1E8z_&8<96h;ue1q zunb~iW6uO>S*7kp9b{Ko@WYS?1t|WY5#lB8MY`2OC&9qaJ1nCN*dvbSu5>n7u#$?$ z=pI|Z#>R#aDk4>id)j0KSewwgHu!we!i8WCs&Wy^1e*yo>D-~2vu9Hb652iDwtf+E zsVQeq&tDLEPi*Gn?xsJlD_vE%G~s1{ZAXMi0-n7dFVF~uUgfgC z!boc%v9&cL5LFrQO8KZyacRN;jy3>-GoUF4l_J<*wr*XN{})^Y_^BMcymo!*#*$w) zzHb5;wr`|;XK#a68xYbj1>bgc&Dj<7Ru*KYZv#DzcseUWq(M*vxiC8iN|NYPRE~R} zV=E_l@{jLom?@BR>^G3I32I1V#~sZoClATj{$ zD1@^zP#(BxBudorxDQ(DD;T)N*?^b#v`WmKMpPg0p^=1x5EN88=~&QA2GB;SXKO=3 ziiT|EB6p8S!oKP(bOQ}!@c2gvu(B%;cs+W9oChXl;5GlK7pOw-zUP?9M=gl|Jmi+s z*kk+d$T*JM+tMJv5AJW^?_Y?PM*n^Ws0)mEn9-=?WrxKOJE8v)vCRfOz4uv5TqLVY zO6!~Ir*97~n2*YaNZ^`}8Mx`mtSr1cQ9B@IBgaxDoX&K=E0CfY9v;?%UX7X3Lt{jV zV9%n4T-q@RXABdjzIWQ6o}LKVfprlTp_65JX3ZaxmROYA+Dq-92v495h=nJo3Qt0m zcc41NTivy58hXq_-kkf_RSMgW&X1gHXNz#{q@+_^EYz8d4RE}((wj*HWoM60;l8kX z)4e3*9*>mO?vzW~X@7n5<#l6E*LUTFe@U=M!M7tm();E0B$wf~k>ddJ1BEgF(HSuB z^w5>G6zvq)-5}uq6Fky>+lKNjnD}i~!kp7lbd;DMxm`$&(5S3>;=}MI=1+J-= zua>k}Eeb)Jya|{x^lyA7RsZ}cOJs^Ws*p|rBughk*JKbd;$oE!QzrN=4UW@&^pF9)@vqBbl#q>t} z1Q$RU@TnbFJo@g<&>IJQ*I#^P_a`>Xw{vz1aRvp8gdA-3i2Bw$2+0zxsnA?>L9M^D z=NWLp`9p7-e`%zo7$*;*o^l4e01-X1FWCOg^8@kdp?tdK#$zgUe7=b~3+Qy3hytEXZx)G=N;B#AvW4B;s3U^W^w4AElz@Ru#1<6b zbD>|^x;jTRM3fbYmcARm zt{PP%*1cS}_x8t{pdMvlKj#odO~NUWU}aq-e~9v%#*4-fKq=w6n@6V*ZFuVOWnaIh zA6oa>8%3MB21%jf#wfrPw-2GIFviN6}wY42596;*sPOwTnO6w^hv#A5wheIuqyI-!>GD1Cbl{Wb#h zB&i%|z?99AS5Rn#SfS>rQ-8CjZ^!v2pVrpdo-=KLspI)QuL=9Bi>7^NH#$Cr5?lv{|hgt*r6F5{$o_ww+7 zwET(N0~`vde|*hZ30Q;JJ9qqim_<=U9Z;|UjI_Jv0l9NYvO;!I9sfC%1I1T?H(}d*;O&UN z2plG&&Y6yOex%cLyt|en4S~-@VgL5}LeP~f@`vyD!QYVxtL>W&BpZ}saY5tFw>N9n ztT97jl}NZis{nFSdIyFB4jkVQZLZ%ExJ;aU;}0}LyP%8P)Ll?A_eo#vG<2il*8 z0>6&Deh;xKcv2QqXQ3E@qgM7dv>GDC>hG6xV8ehtx->TIFo}O7u@&$%+&FXZ3x3e2 zz&hPyeL6c^1(ib&4<`UvS4CW?n{^Ok|s1FZ6}a zz#Dz2tJ9sLi%sNGZN7{PL5lbkbI>jQS2Z(s-HTv4-(7mAOD`g#k9wN}xB(4``(H@e zo1){BWT^+M4#`^_IdXaOK(`PWf@sRL`y7ve0a+$>gz#F0Z@W-&hz3ePNj{rY*YS_2 zH=q^wbL=IXyN*v)&WrF^o+iu8iJr zJW#o1vG6>=u9e4zk46=p-EDzl4LTHFp=Ut*&^c^FfCP~BFgJd+1EEtwLf);fg_ft! zV~sInz{X^cr7WUCP^r5~{F-4#k>AZ7SEwpx&*$d8 zY!AjF?L&=SpKk`l=&dY#0{$dYYpY7}PSBtc#&Ug7N39T15!FtBf&#J%xq6yeM;Lx2 ze9o(P%$^QA8pN;px zz4MH{!*Ze*-KEKxvFjR2;aSYRzXb@%qo%!aA8bSR&KFiSxepZsl0I6#{5vDnRiQHgU_M+hCNz zbH@uOK>-|vAMZGN#^m4`p(YT-WxX* zZF^HxWFfv5WrrN}ucE zNFW?}()Jf25rU4NBq0E9_)G!QmLqGxM0?d3s6xGisqR3ZT1%q~(66<&WAqGXViqQy z41liuW{oa9-s;u!Aa`>;-1Vvi_$9Uw%7pZmidQzjo`iiUa)3?d`shF{*sN zMRNA4CCJi9!k)TNNHvJx{Wk}`+Gb={MtVAQK(4j88A6>3-219e1t|R>h#`y}xX8Dx z@I7`84*6&iw`)Y;BaJOvs_i2-o*csDrrrZJAL;tX%tjbyh|fia8pc<+kTWKzsi^LKI#j@aVWW|R#_v-B!;W9CX2_`Os(Bh*mF1Ii8p>_q465eNF zzyV6zGH`1AJzK%HBE5w9R@^HJ0>XVMRViYoDz7H<1#a?-M*RvDJn71C(G)jyhUGSadI8&e}Hhu|c5 zUjMUiko2PcTAB&MKFuDH@c13aPpWU(7CMV7HX>?(l9cUZ_fkllgJfzT<+2vXn}jn_ z)|cJQ<(G$2qt}HC1!qk9Ew8jI!}xN{pRf6DFGKtq2$W0GCUX6;aeH&Q^+eUcT=v5oqe0N zXch7+WU8~Xdh!>|w?K*22N?Is=btN7%Tv*&C{_W%mGfw{7euM2#}Tm($+>gwH#XW&$}DZsE7$#nuJrL* zaWk9OHKVh@4u_TbkopipBin8$DK_rf@Zbwd58MR3$Mx_@OO9R&2+%~rQy~u;vEZhF z%bco2J|*SIaMM%M(Yz_^0fC~%jMf`b&dZfygnpw^{teZwJj9=NtZ6WJS$`@Il8%tI zumQ5+T$HGp4YH8oSvvC?2(YBLg&4;E=wKxt3NYA@X(+YqJQ>%1;P+!Rp6$9H*f?DpT(9(ASm!J@l4kfCyFxupkiFD#eG1PT6cVy3?%_r}FlYv$S;$i86)3rn(s^>S zxGNA#L3-a0e*RU%$j6R8|H{YS)|7$$WM*K}8bX{Of`bwNA+hJp;{spkNK;{ul}XoB z9{#GsbuX4c;%s>pGIZFYpW)fVY-m;ebNAdi*mcqo9>xAD`#Tj>RJYc3buVGLd7@a5 z7cG;K3G&(Vc#j0umXJHd9kP5b;P*mPi6>(|zykQ^v$-KSb@*Y@hLP#|2*ef5Z@%cX z;g!nz$x8M8Vd(f4EZMvLER<*NYFY8l1&Mm5D6#@FWJr;&Iq?HXLRqk0*YhtI=qaSE zzsHQ1XWyZ0F4j8K#xO2u6Bq_<-1tq>m2Cu-e3g75e*Q%3b(bTMU4@K2sd!`M&Y3=l zK04B{js^K8av;cgL~pqYS&W|;<;8^n|Kp5HxL`uw(R5$NY6^K!kaVvp_?a&kFLwtS z6=jED%f81?o(Qa36|(q3a<5W|miNM4fLh@U2+5ty221r=TxUe@Q01eG))IFx{OC{B zVcnroz_z5;jNF|abuU(Ad>ZaI0FUfi349JXg6&3<)P?Hk)@Lh~0VLyZXzL%C1dRIf zjT_sd)B)ThITio@coo>EY`Ef{O)dphhH#Ow)ZFONxd*(k2;bmh!xa_Pv9eFHe84RY%>c_Ed)iO{Sr-7ure6 z$x5%N^@I2d+3b7MtD;HG0@}j(@?iVW^p+BZx@%6#F(2DVSeKqGA`)~y>~E4pfKm^F zIR9|{R7>#(uz$dRXxh{&$p)TFnyBeCgzYqaiSGddc^2KR^l5jm!buWg!#*%{O3Z`Ixi8v`=VhvFw5}9VKk_Pc`!i$ZyjwV*H+DWQNoO?4^pK!6c^fJP8q0&4I!*Vw?9vHiBZ z1DX0dcDCr!+kFa%3}`d{GDXm4SBHWVsNKzvgui09AQEQ=R}h;ML56E<&Ss|c9V}N1 z=P^VUv` zH{gX~$?L)3*F*%1D})g^i_V9WehMVSjWXO5o_SyxK!SOu%!#wKEt?>E4DsYGH)g|k(fwnnn1DrA60x?> zjqwu>C@5DL)eErx(crgg?U)e;KTt5fBNgh&vq@*bp*Bmg*#qG{9s$YML4}v+(oxcG z2C;MqjlB{$^K0#+KEb|{&?wC_U{I^;qp}h#Yp;R8A!Q`L_1ioj?8a%hYK{;SW3qld zMQn#$S$VK2#O{j@;(6uapK7#rb1$kF$)3D&2FVn%XaIt8C8y6t>gc`MK@qv2%lfw> z9SYflv#DMQl{GK_B`73(ez1?}M&*Uq=})&rv6%5f8iiZrz785zdg zJT@KBZ-o#H1rNx--w2>C&d%rhLk2y8GEW9fy8f$%C@4U3h5AN?7)Yy0v&~06R;0hb zr-!PTB2j(K;rn8$2<3+;XzF_ z%pB_t+e^tDc`^iOG7k@?x@zjS1OpLj z{)Sy<%P@VrXOz_8fnVc3bYz!JMQbYb@JMC|O`{YQ;J9J4ksOk8G&`;t`Sf^+ZZZmi zj~w~Ji!{v4mU;|T)tN)jL5FY4sJzlyG*!?|QCswQhe8}me{_ma#(an*$$(EEp#dZo z!F|dnVJ(myprh9S5to6HZqL&1Zonq`Yh9&iGGJpt;3OXYAx{iwgG9zF*t)Zf^}pu= z$EQ|{`8q&{=&&M}+aq3FWGPED6-dwI!Xhvj$dJ{29=i5BL_UNV$s(HX35>|Gr$M8P z9jzCTZJdJB5^eZq5mtmgiL`=>3$x(6!S!&%GvGmtjVVba-5sgck*nN{h#T-j9#CMf zo>p7vxj$k{$WXl~l2jKBV<{^e9JE!53y%avn}_%ia$y#p1#i*w3JBZsZ7&1_ajnz@ z2~$p_5C;cIJj0U@aNqzn=C8T+eVnQmT(^j4!9GgsDf`C(p-|PY8JG%*TSL$>2edQr zGuh1CvNG^P)t+M`N9Xr~xqEk43M(n_fnYg1tzs6~eKf>^hNhimSN0)=wW6Y#K){gb zqb-dFVxaWn*xRxdwG7frlae}INeUmtEEgB|50z*KEP|3dE0p&RRXw?s)d;%=RsyMO zW0}c;(dwdYj#R=?${P(7|BMaz4M`LlB0dKDIW35ro&J#+6DcaV7Y@35*0A0ek>4u25 z5z`+50CR1PBP%u-tF&@UZ(m;?bo{#_o%PXcx+7k;)HvH?3BKqkr#tO3w3%5xgqEE@ zC@|O+=XRMLcXs{;l{C@^#mFU^%!XJ2egwcn9NJB=kJ0v?2em%ZyFggX1u9eg{&#o) z6q$1B6cG#w{^8LvPHVKkyi{Xfe-0m~-Gh^gN-Q-e!j#b|lKmDpUy6`^WKLi&&thi} z@%95I`|aY28>*_RIkA4y^Jf6qQTp@M0yXcKAL6J(4s>O7=}TVriiSGgZl3Sm-J7r; zh|Au8_^{#J5_H?1XivKR5Ve#&1;?M(ZGzwsN*)&r6XN2|&iVw30UDuhyYB!!02N}2 zv*_-C0F10xQo^%)Ayn7uwhSV|Uo8S@1RcyQ%8RE>9~9t*sU-|%1*#ytFphxhu^v=q z1H~T(=w~jMZaoC>aEp}&b%fk43D|QlA3m#a@&Wm2-WXJ3IX7s=&#e*_Kpo(3;GFRc z8$8GQJ<+>68{QSU7Ia$TFlgi-{RD(r(0Y2%e#(i5MN)d0GUesidY+))A2up#T3XW( zeK{gJc!^;h@9JJ3LJj!Dz_$w^G6s-=M5zbxNjjQLk-YsRO3koy55@t{C4-s^_F zxry~FKycDxgz8wDok?yBdT79wok0!?&DE2l-T(0No^9_tMJX;E5XwtHIWK^;huj>L z4S-az{_g?ipZOFLI8?l<)C}JS0M_`S>qGBnBfQ)Y@CTP2qSO|{NJLKWxZ@3ff+U0l zZ*V_IT0qKuX(_t_1!V*gSOOF@UW0XK7cx(!IkXofSaZ;U(f=HO=o5AWba>8y%Y$MD zjxt<0N(1P=CgEA6UzXM1F}P_ezuR0g({ZzGkZM#|Kz9mu2gSXdnwllh-xn6(IuMhA zgadvT9uVwEq1`9}ZM?UGJOgaYeBna?iE zQJh{2{PK2TtRlfi^ec6AMzN5PCGtW6AMOB_4oM~fk(kR3k_d?|5+De*IwUJEufUc#+X zMwYw7{mBvZ1f4rqkH`dvl%}@MM*jkYpU6M~Ax6zzzV1mOAM{VYG%rFKV_6=7>*8u!WHud7!2=0&)*+55!qteWPCCY{Y${LV8>>l_5fv? zjZ5dgR~H3g`STQ(#!?G7BTW17&CFa2Ocv+?MehmWrW69ukOYw6pj!$tw-{`CI70eH zutPzjVZrmEaVvPSX%D6@oJTAG?L->l2JVPAYA;!CDo-Br*ymgyW&%LeYqJR^f%Yq= zH!R9gNN}K;SPdBGAk=7$9^IEOF@*dW4SPUW70{r3svRK^{1~tv0(&qk425T- zZK(Z&*-fc8hGAjO4r+UdXQ6Z`(ZY$7fvRj=Mu;Q8hRnBE(uK;BE02~(h<%zCkf(4291Oh8$3lI~a z%nshMDjGMn2f(((nDBhSLWV%wtK1HYi|ep0N{F%nj@)9raT6Hs#{>{UZGx}GL`Kh` zyQi@UU=7fTth$mr`0gIjG{PA$oQWG+ZOW*AQr-dUzI?Ung$oy`a*_HFDuOM-TuF?^ zkQRg)oHXAK3WguPe$~1rhfH_r+-Zdk-Y8!0xRc+ELZm)GcesQ6oT;qIY2ck%l zPXzVUM^|}}dQZ@w1fQ*jx;(Pd-8=}hQ24$rVhxMj18+g99{%@sbzd2}*{-+`t{J!d zsCD_WWv4?~BT2pmT|;xHUcERZ#_cQYA{Z$KAaVeAM;*>64VTRUHnqoD39$;b|J^v% zE`mrh-+XB?paJvQ$@bAjyR?Nkckc?Rs;X+F)&wA(ggK;o)q=YZ!WQBkRD%J)kubv{ zdGtsj-JgPTh|-h8b#u_lg3Syl`b7?iDvl!r5rU^cO`5QL;t^VCg;)mRUkd9Qdy&VVl&u)hqh8g*WSvE3ozYB&Vfr`RiVuDl(<-3S&smdCWgOrPA z-6cyDkM~mmv$Fs<8BQ-fF8@^Bc^f^EhJSLSdyd3h^!~0CT z;SJBxlQ>*};jRdk0A7!U}Y!E+g9hi_yOa8B4b*qY7wP8;J3~$Q{vT>czu-I!r#PH8Zc5HrsrNg1rSI?M8_pW1OI%(qaXCk(I{nE^ zvHRJ(obK(qa*s=-j8j5?g)g^=Z__)MWk(NIh;4qd=2>-5@3i@I&3T>+I=Wcfc=Wz- z&WLz3?dlkkfLH{AFM2K=R!8Z17()U55h*NHKmDf-@He70fJfjDyY;v{u^qni_ zn}dZQgFP3}L%;>TQ!8&k=7?|$3rx(zIG!Zka|2(V^`x7IJ8yl2@6R9B$*CG&H~#!`qUqcs7kssdiU0?TV=lvA=2+TJoe{s z51ed%eZ85TU2|YN@^SE2a_RK~i@^2siMr`r40Ox~28SL=qsmyXibZ$r^912=8$Qv$ z>3D1)Wv2jLIq@TVkylD$Fv7uoKReZC)KIHWbOZmF!X87@x9f~ zUreH>Ndw6J9T6UIZTeOS6m!tFq;%R3W-E{M-JP6%CEKoOczg15L!KXnP7)?VRe+GL z?HlUA^FeedJ73ClF^pj#Vcaz9BlO)qXabzGC&~)tC>DjjvRMPx`ic*i` zHs>LS;aUE;2_yT$Oy#(;HQK9H6!v$=@HU0v(e zTY~sLs&B19?pTdZCN>UX)Q$+#3!o&>V!3>nf@35>jqB**-@3FhYJsLcA=Z5v>V`9^)7Xx`x`5-3oq5h~_9zJ|l zS4_KAEkZ92%ngpi&--@Rjl9iBg(x&e+3l^EDUCqs5+U1o8qe39_-Te7zdX>BxMz6p zdSt7Q;RS0^_u&WM&KFEW-D}0sYn??gvxpxqLwsupR3T}&K_CFCM@C=y6`h3UEMB8` zs`sFSLjZb+OdkK~>7z~(AK-7{%EidANp02PyP341@4GE_70BaJClYxsq98Ay4^_hk z+U&@7bD^?pj-DpqEjQXOJanl&xdM2`vGS?caQFt2S8o%efxQWBB7ut)Il(BzxWz$m zsLXNM(Eq-KDrG*BJ+jFNBzc}zI~C1de{mJ~tJzqd`@V`@nH~3GN;+5ES~MzGwd0hE zvIBBmm>SpeR2KB<_n^d_FM-e1u*YF`Z3@7Kvb-!_IHW)nV@&(ou7iA1wncJP7iL7j zoDJsoZ^J|o0-g5t<@PLbspi1J$@=Ce-CP^(@Y}{2-;U6_5gQJ{b3~cb9;Ej)Y4g&-98gQ^M2*$KOfD5}wb@CIB&fIKQD3}9I-F#i^PM9GL7BZ}CPiUJ~XARY*jN zVh+#yKGR)cYIFf4rj&bsk@Pi2D6tRMFU(g z{tZRVop2<}$ikI9KEJ4@4vo%bvP;1d^FU9d61ePKjg5^mz+J#9APcg(#=`LjHUeoo=+S1)@v^Wy}2-?U48=8cF%H_8}NZG^IQ^W&#}V=CN9o zyXK<|PDKaOb+o{Njb8H^EU5e#wF~A*!yRE^(L(J+d*F)rZccoQA1LABOS+3wdVq*S zZDj!vY)4Er06udGzJ*RNb~c(c-P^M9wBDU6R>25p;A!~PgY@VSJ1;^>5P!w!9to49 zf4|GXG@^;`BBmUN1&9DW#v@&STVFl$)&~siK*`Bkor z^{TSIz8xc<*C2Vn4iHPq-QIeNFD|d{=gES{`NuHA4z*mZw#quh5O{br|HR_u8B&1e z07T{wLy!-#c?&cTD`Z(V7iW}h@p%kYRt$yIK@d~&*BzEaMq2vk#r_KsUn+`AJ8+Uo z@igIJ0&Por&Z8bM$)9Pe=xUp&2ux+By$UnVg>7hxYMuDIXcc}#LqqWP7n7Z(-=vkM zsOM^4KeirVyOa|h_nw-g>WR@BJOF7y!{T+Rc4UTm6c3;PSBqnc^j@#c)fM3#u$mX& zdgB4Q(?q}q=+$%dw3!~=oi#Od6~E~hRr`n=Hv)jWe0}cf(spo_!svt5cTBFpDm+*_ zO6egI-L_M&Xy3ybC-m1vG**B!JB+ANw{3kUMt>n?GX296jjecMusK|(|EYCVoo<@_ z4(ls_BQkc%^zLq;T9w}dseC+Q0qtPgXKijzV6LIrLspvv&RbXcfvhNrN^-Mq?oTqO zZC2B4to0P(rR*ZU2YNUhKtB9M#?3T!_}Fo^9Hn4kUf|+Wu>_7(ncQZoOXm zvSe=3r$nI56mFq_FM~VMF;sRwc1-=?!47A&OA)Ec0-Fu1-sN#8?*wL;m)d%C zH_{fAN6?k@2OBNv??;yMV+hsA5ZE24C7q!|hx}0l1hSSGF|+q%MPL>lrug$N;9IdM z-29kc%0KdfKM!Q2*9HkAQ$2r9?dd%1`Al@hZ-!kYEy8AnbC`o0r?=AB`Mz9K#O-a? z%0FN#Za$iouik|J$SIGQjByO+%UxmeuwvXFM$^q+%De>w)0MrOeY zgP0#QRM&_bf~3;-8mDA0#IJ|a8Y(Hs?}pjqgfHRePE&WBA>Xow8B&o`=aKM z*U3Zp1Pri_V?%MsWkgkU`A}|07}9zyDWsyfc#kw!Rf$`doxT0@w$hkYx;^{Sk1WeC zD6qf>L6B@q>ne8qoA$z{#NWLo<_to8da~3H^!I&XagR%jyIjLt=NMYX!-uoGly$dl zyJBq+vHQSJO+JH*=}w03sN5a<5q)wR`cCeNMh~fYY>BwYyVy|l@PPxObY%+rt>0az zJOutz;n=;S_viWL-KpibHnmyR&3@Eb&8DR^LNR*mdo%_Oo9+qj*aJ^!4q6Wi_asu7 zg8T$a7a87qDeMIM&&(+YYKjlth073==rq7XM&^$VGnireE}_~v-bXCvFb-eawf!$@ zJBH=(fGnW6p6q^o_r^!}?n$8HR=p~&<)RTIU4*d5z1e+x34hA^o%;XSA z@L`*#GK{KlM3jbpr1jkP{Chj$L5;^yC%w7aK#74rKNSrlHW@OmJ_Ta6*|5bOyfO+D z1_0=uDsfIy=>kd2AO7(sccQvFWS|EPAMmm>ighv5x(5(R0k|@tcgP}xUj#?ngI<=} z_x*t|T4E2f4F1-^_5&Y&i=lhFcc@LFA8Zi`nvv654MW|4l5V#JtTlSC7otxJeAT(x z7$D_Y^Z14o25(UNCLdy~ga>HBhUzeiI4Xe@fr4VeB^5|17=L(-t@8O-R@Fg|II_~ z7$8P{+KQP7d6)CZx8r27c)jzB~*MsCk-8A})ab7`1hb*k+k=!!joV*`ObD3Ylo z5~%2ofs8E1E@h> zd{qig-Ae9bml>C*(pid%Y6Mv-5LQ<+H*8lQxj(okfaL+0a6u6rPB-qs5w)FxoAJm2V}!PTd{lXsaWj(w4azl_jQxEuwh+77 z&u7fFECcO&brI9t@DKs@JV;N{~loj+$!xLkRk(ctjVbZjg&{9C74Rt$Cz)~H~4mE!{O1E z!!*dNym|>;=FQFOq6{n}JkFxA-@0Sm5FI~+?y3CSic0u(;n61DQ6Z037mpRNqIf#9 zHqBrd?TNgF5os9%9|AqNkqEgo+(!~WhjQ-vLo+~ zMm#=HfX#_C-9sTYg58Qv%%qCLI?|p--AWzK_Vp}L`o*7$D-2lbMd9KT+6GZiZ$$Gv zGYdJ^W&k$wCQK6+H_ci@F&?OZzGQ$gEE7L`my)#ZFsa`h~dx|fp`CMJ;@S@AY$5GF&r#L zw7+2nOVV_0O=u#1O3l`wP|*_n!IpR zghj-4CTqkSs1eG9pTFiDg)(4Bc}rKI$nzjeg}4H=E7G0o%Q2tx(I;d`As>Txo1az>{)^tBa!9nMBe0qBwH zY?_nwmXPqYvxPTFc3cs98$n=W=7M(i#cSpQIKA`UCovS@yrzy$(cLOE)U83a(3n=M z_EOdYjFl4tXhQcp9RP|AD%8c9B>;_y);Mn=M_4Kb%F!6!yHy|$2%sTpC*CTNrdz}^ zaq^F<#yy#Zr@ZZs^d)DZ8##D#?P06?IeztlB*Vb~r8SqT4kz_s1=4@3k3Ah*# zbk!m9?jJpe%^wG!_z2y@;Yv(3=eCHo7g}DGe`kGYl!5K8x%w+LKOH|fiNVn8RTp)$ z=DKGgW0Kf8vzvostDuCwN@oJTcCohd@Pqt>WqK_2zVY|}upip_C+1H-K6CSP#;Q`A z;|?P!SB;%wDqpAD6^+(iN#yS{`1ka@#LKt4PCQCRQ}q9f#@#rkauUP(DZr)!>@19> zM`1#G&=axKm50HY*9UlhhwC)@8+`V5*J-L@5!(N|FZy4OhWU*C?>HJ*eTLa_6ml*i zlHC227adiAsb*Z7#xUzD$M77K9gfy?VjKbw^2i4{J`6^x3k=Jq80jJ5N)(auz?p%G zV|X2^aV%H@#?9Ied5jPA$3JbiRaZ^8Xk>N+l5Rd2Ac}A2c8QZV!h>fuh=JjT7<#;jC-iqJ3>`gp ze~7_2`HNCcw5#5&0;syvR!()b4{ed|?gxM7G8nQhad@bzHxO?;LMXsUOvG-40Z5cB z8ku<3|HJO_|F2tZ{Mmpgk0E%M(j1N=XTvDRW8RvR8PYVejYe~Rse!1NG(||KIanB$ zhw;+*Lqd>`0SXieFf0!OKSym5~rh51&8FcgW-63e02Nyaj!T zJj(B%)%^VV5N@IH67WV%HMQ4wtB^eS;#gOsK@O)H#~LcaSGCxjik(y@9_jxiQNjPy z*hlrGw)&nG1v#Kh|2uU8k0M_)Os z6OvxR$$Moi`}Yo=Uum_0p8@II{5$a$p&-A_8pv!J(o#OmB+l!go(sNB+GYG5s=Mvt zGj^?5q3tBSXcjJE&cAo1{^D|JvZCjCAZk1)SSfZ%j^BM#q-L<+5?n>1z4rlj#?=~3 zbwIBq8XB%HdCTC9nk~NW^3?I)xOrEu%xyAXk{(51%5%rPj+L;s@+|{x zfx#pD@STav$G=l=hm0?W{?Mw+LP1UY74Q!SZcMC!R9axXhBw7>Zc8Uty-exuA1>_% z*_HHa{YPGWfN^AYTUdhA0h5J;U*YP!76Krkm)~wy8Q$JoCdBTF|49)Yy{LLpF~Uvg zqL4rsU6j$k^}ebxry)R2K-4hAne^+t;-k(Kbi8}4Y zv;flV|DNKnb^)gk$GIOA-@>b^&J*i;Upz#x3twvHF!8j5g?`C|ZH`p8wa3fJ|F(5# z*m65{K5K(FFD3D6)9LXwNIx%EwwRkwo6q_z?xB$7-*uT9{JnQ8A>JZ&p$Hc8^ ztMe^iru{3Gp4saEzF0Hz!bPL|S_eHV1h6`LCRRu1*N5XmcBY%@SyoQ$`^|zSC8CNa zedy8-m@uQreh5tT% zJ4sK5y$x^Ok_XaoG3f7Gx%nN zrKf(?HT{Fjzj@`~COlYJ@LSL>QuF`(YU=&mC5o3rYUuOM6F(-TtJ5@XJ6`(VH>StH zozJNBJ*X#Rr#Z2&ow$yF^01*ZKXc-2BF;fvUkN<MSqw^ECKNL49q(V7D#I z{qS-80n#^3c-YWz(}=AJpA!bJveQ~n1pcp$F4}Uqd7D)vtlg3 zq@RWHtBE=t0a8w+0A2^?Cgmu7sjJ)9xeV9Vr70K|c{x8TYx)#Mw6@Hp>Mg3W>@H1c zg)HY|WvFV*o;Ayea=hk7{b_W$ODAa?i%1_dHZdks&q&@pvHETUcm5>oyfTbixtYwo z`J*c(Ms{>KrEoE-@5%|V8(xkNY7u&Ze^0cZc;-SSZ=6)LBQG#L;lzR*)DkG!5XY&l zu6!J>_U04jI<@FI@Re;7*tBj^j?EQK$t!QPL*&?dU*Zz}I~1l1gRrRuvhbm+E5@%t z^kU)5v`THsE-lt0X~B;q1@4VlY>easH@CaVVF$w0>x5{1tPGSA)Q-D)fnwc6 z$B7G!-!+tm(oMW}WT2HF{^bA@R5hC;92B_DEaSuhKCh@Nxbv2b8Q4_PQUfQLRhrQ7 zxMq)E?`PEU*U$dU3bMa z7jC3eaNu8%VI`a=v><5nr`=ss|8t1NF^_)ly`)oJG-;`T6K4{4h}~3qeB|WB!Py@E zc~fxH&920v4R&)a%omzh+k#soRW{l-yo_ENjsL7I^*`*j)Vyl;+~sLRBD4s^(S zg>Oy)PRU>lR5S0RI7V)(pte%-Y*l5UAa#SgrFn-$?F{6iuyCqj|DG`(I-m7Y?N^tS z7%`nq&(h3bBUv0l(G{PAbWZUw?l0@xo-6G< z?~8)m*~hTLX67ZI*cdy9%EDiO9n|o)R0)DU@OJyE4Kx^x#yiQPwJ0+#@aTdl0VK@) z_9jm2j+pc_CE0at*NRf5q~MOxidCNs!+%wyn{>%`=RVhS?0iZ-sASd97bt*NQ0v?5 zbh6ooZ~ZB5{8M^@uUFObc-E<1^e<^?X<{n9$OUJ@;G|)48A(q`4Oc_?V~$FEuwgu> z>Bnsu=Wa91CMP}c+f{Y`*1Gf;WmG1LwXYIWNvrGjMowYwh70xwMr1M=0UqMaB-NL5 z4(-MEmp(c;xUc2#XnzpH|7QCgfh$j9@WI{6wE9;~!dVq<&>`}^1K_QQxpm6EYHGO^jbp4pE+ z)4_iy8NOOqsc0iI4|^@Py~AgJyXgJHyN=1It2k3&=n{Du@6P!?!zbyh1nbW&?d<}Y z=lVKp)A{k)i;8q;cnkvsB!3-4MaiP?#U&nt(7CS`S1PC8q|aH7Uy0F1Rbc^v?MdgJ zX)*FI3mWXxnBJBb(+ljSV-&$k{TTc_S<51^*~iT<}YX;U803u5rwOw{jcvMyHo}+R%B@n(;lB zlSB7eBDeIDXO4lV7yIwEqo2y?kM31Cp3-fpxi5N`(7Qo8K;?-j`wA|pnHJ|>; z|B5+vad^Er`6prxVWRM#!Q6qU&fKfWE0-& zMwxk%8=05O$^2Ohv2V3v>xZT@O68tuU?0L{i2uPu!Ck5UyQ_2SoI*LCu$am9J&`c4 z)>Y4aSlvN6gY;?H<6(HCf6?I;34y=d!s47m$L}z2dh)-Wws8RrD)xd1`=lJ6 zvdghum0E0zMdlQlG|6o-!RgJpzG`djQ=XtKYqDpqw6-~J!-OJ;YET105zPwGe<`wghi4=QoqHUpiL(^!+ zv=gC0k6FwtOB^`#Ri9Yw`r*vnn_kR4p7@q0B;@FPBbIs>qbS+6N$TpebZW>FIPB$R zUdN;$1JRhk&7nQq4F7wzQUcAQo3&*B6q%fJ5XHNmCP!p4>JL!qUfLPIsBpg{bD#q} z`=lZsjp-&v0yn(vgK?^(L(g-U-@h1or_iqUpsCBFOEC*$15TwbM0tPIAys7&b`Mp{ z<(#MIZt9M_=`8boNc;-2_ z=cL8pG4z#ZrO!~t*gv`8x>fV0ehq(}aI^5tCkubf%qhDoGZ zHg$>OJekMSyn4!`u`@~xh4@-=f%Ah8Tt+@@ zqwQQjf7~#LXmGRzaBt^;eJZh4C`vp($S?7yfVq*XZw+<}k#*79rs%{yx2upt*x!*+ zZ~ZCCDxP(t=uq==r*hr#jVm*DT?iMqOk01Wx^Qx$Ko}X3Mf#hygxeRtjtyL#N$05g zJnQjb{CBF526s^Bk)2a>=0%nW#7gad>GwVG35WA^4nr*a>lNb*aXZdqM*5>7eN7!6 zhJ(6$hL7kM{a5B6B%TJr1!8x3k6YNXxx&U@DzT`_jz50XD7P?r#EC0IwiV=ndin7cU3q)4-Dtmakbnk23m<_gqfI`>ITnl~MdNyem*%m6CjdTLs*I*Z3}J@0pDp!LQIzSfNM9?jxQQt zwp#{klV))wc_DOCxKk@B&^-8HK~1}?(|V?bQSBM`jG=}BoV6AH@utoC*tElsU^$HwGL(FiANUon?%L78)9%qOi}l6WW3sr(viT$G@f&YU z@`^&haVpK*EIH*b21^d-LxL(Snpsx{OXq{ccEG_eZrL?} z!SrXQN1O@rMvEO@yIE$X6`i4X$%Jq*OS~;F}}tn*)z3WQZMG^iN-!S z+*~?D^dI{w)4>R80_dvC_7v;G-hOo0t#OefnqkCLj)ECRii8eH0`*VYn3sEtTO;fA z^`qEnKMf-L^yBx=aIStd(q=V_?HmC%bHbRL*~dv#s3J(vd^BVcBb}|Y*)cxG-y*-} zjYgC8Rpyp44@+_Vw`CFrZ?7v$<7fO7=*yE$e&Nfx=ZLdSxQyKR$>nC60gh%Hl@`h7 z-^ZHR8Cj~&564wLf!hpRICPx<^#{q=)M;4B>T`qLi|LSW4iG3?g7A@1?_KG)U45tK z)cZAUYyT!kF@ITLd>1D9`moZ%+o-VA=T-VOYN@Sv=8gMWx3ST7f(vlnME%j3NZgdd zcrak(?LTx9h^48ftK;JB`||Z0M~^KzyNztWLahIFL6{8|5rN7eL!SOgIYkGgb_8Xv z-MnjEW}N-3qWhQGz=^7VIB`Oa^AmOitZdxCNS~ebAhtqM@VsomA{UzlK~euUhhhGG z4tzirYJ;s~oF}JCy_$5SX!F9sv~|yXY6~fP{1BFMkd|<+NP?EI+|oB3R`K?XbcxP9 z(d3vLng04ewlSSs`t2o~&@}&Cm#~qD{&u(3XHh!94VTm*|qSfFS_Y!YqhD=3wFPO(LRSU3{+7{bB zlXvjwaSnGYJR(NU)qlrRP$1#tR3(G>l`X4JFdViIHLXdGiC|t_sh~p5Co8NSw+1sP z*@95+;(LVSUq0M;AmD7ZSn>FZD4zM(g|Q4~>Q+B^=+SEU79Q>182s@gJnm25%HHyi zjw;^bfnqS8XUP z^?0}U?fDVLk@bEn?j&ZeHCQ(DZP#xBrOV1|(wypf?@VHmUlbT%y>eH_qQ52y0URe?s*7aLy;*?d0S%f2KKQe7bTRf+t zhUC(NlX4!-*WDJ^9))lyZ}hjU(>isI{qTQY)BpQf4P(=0pZM?@j4zMY?9-^+snMh$ zsPRKrNcbTd6kA-l~t}@erD?W=RPsx=6BBcB8Qe~3pb0V zo>XD@oAorw8SKpGuylD6VBF7q6w(K+e$1sUwc)MRxpn8c_aiVDwB?UhFCX6m2bQRP z+$6b_teNyY<`}eZ2-$n>fk5XS&RgF!9L|3aPzY*I62sSBmHPLD zL;X%XTieVnEO(B@>{Q=zj=tlAcXhrDcW#q1m;OaN=JEJ#Tl&QKh$xEe)K~pH#cNWE zo72K1u|^&z&&=_AIWK$s0`7e3(()u9$0P94dZ5T#P)Ataf$u`){%l35`#&old5@7DQUzwf%fzrORwIe(nj zyWi(|*0a{V?sY%wY1pS+WR~mn>S<@}m2lG!&z>C%-2nKnt0LmA=+GuL!+x`}SAAeQ zNmI_CVmrSKgkbuHgi7_XUIs*{0qtMoH9Pnog3sa@#2q>`NjcC9-2rxh?zE+f$bHee zLnS0R7)fNX^KV}3jYFFrWW^`l(? zIdYbo+Mg0;!%TavTde|IAbrg9a-Dx2-?)j!0z5S*EBmvs!?xQ__th2mWiVMP?nCas z@^d}h8soxTqD-vQqwejpa0!n*yN79r>9W`)n_h<&4Pkkn|$Y*?lkI9vejIRj7 z1i&Lj+Eh1iyhLP(EHc6@7dv|#;SOGR<><%>J6zi^VjF}4TN89?&2~bYhAU^VSC;&U z2)2cC7(@CPiLLqR%aW0mCThuC8s$E0yA$BLcHHEpm?T)kJ9 znVm(;3?&|;ZgQJ#G(QO2;Ar$>MGmMh49gmrt22Lbf346}t>?aDunIfSLsKsC-tOZn z!O`|?H0*>@GhBxhpvkUmX>m!vy%DhAowJ_F!+%1L6BYu_D*m()Wbt%FLQn4(?hZ*x z5A+!~P@8)fueC!@gcvdTpRVP!N_pKhk19ARNBnA z)jJ3naf-9Lrw>PoC_hSWIGgNblLj$I3^Z|&;@?m0Kb6>B5XmU}c=B;6d$%8l9i%u_ zr=L(9p{6)^p2?7}ge3DZ%T)aZ1(4`VG-~^C)IBQgkpItx*+=Jbp)nCDiPjPE+k23v z>eaQ^gqnMJa+@~OjuE|+@VJZG#!JrNvE)aA%=C)85r%Oa!5E)$3AH?h5(q)?V=Oyy z)RQdAYH+w)oyY=v>A4eK!n>`yW%)EK0keQz(t|5Gz|&`nrhYO!-)RzDf3t z^o{g1(Ot-icM1v-3zVe<@l(rUTQi$>o0Pc^Vsy7!{QDo-4ybMn58K4ClDK|Q{sOyE zdpM!EAqw>mn{@sbWrzfS+lhwrySroTZh4X)^e)neZlW06dk3i0cj#4*;2Qz{IWGXW zP_8KY^Yn=6e#nuNZtv6ebmeIMM3IBHIbPdAt z1AU`C@EslIM|l;!4n^>uBU}9oM*8FbpM;f8K5WQwdi#ob%Q_0uvtAaPfT$cu`suQ$F1pzNs3Q z^1@-TzMMPH43i^FH8cde zL};Bux+7FX=q2aJb)>0zjOqIZG(XtmdRDc1Q$@tkJa(2H`J{pR3X~VSBGT6?9at!a zb%u@Ld}IeapK15QD7*$T;BCAV;z)qy%Set?E})W4l;^bJdawmjW!i}}PTHdyDl9hJ z2WhK5y_+yht_WR9Qvd+SxntT#caX->PL<)fjeqgM?F2L)O>{4~%4bX(*-;sBr5zGN zYRjj+rECDv^G2_N{blx`C;)ggAW7=}A7d#ziUvfM$xJ z4yTeDh6kSprk+fU(i*pgBqi=LWLX`0Y8ojDU8<7Qcl`I1DfP^LPGV4+W-1;H#!H$0zC+TDp-lSJ31#CtT=g+E*~Z^!1D;_%>NtdTuI2wzDp+ zx7l{OlvWPu+~qW|TA8LG|7|<{%HEnU9vJ#iI`9qbQPkX4YN@#*^r4oyIy&fAkW6Rp zSPUVS8eleeat6D`kcyx_!#*^%c=t3UNkfGu#8z>C2Gb6Ta1yyuhwi6W7V;Tx+V?Vc z0ZcEK4R4Qex!ILqzeAa?-jnb^iI^jttVB#{md}7{Bg%y5cf5{x5xyb(GOyF$okQgh zc)#GXjs{*HVG9_F_=-%*?PTJS`~W7z>hy?6cT1(rX&J66Vwb_s8mucc)k?wW{o>`4+Q-{rB$NqQ&W@$=2GlvzV z$44dE)OYxiL=&P~&M4&^JbL|<&QbVJ&MWh2{&7Wjj!vT~lO%scc2CGsX57O@_~4Sa zRp^$X@|J^~!M~H=c0$tk@rx-hZai~M_iISd)|?uZ2pSmNg)&~8#km{4y3Wy8HE#3+I_+4 zhxrUE^`)?sK^39y8DNw-qkPuztL!Qq3g_UpdzswXN*>B2O*n9A!uKCgz2nVoNKj{f zBk5j8wM@PvXy)vt-KWn1Xb(G{jSeZiouJ#9N=qBPaRZDVJku}gprw|Y98}Ly9%^-T zMh1#lY)8whDUHr>;XrvslS1Y>4R;bRo(cn91Gz}|1iGq;}gAtGRAHl2<_KTZQ065Ur{ZUdWN1OMI(05WJOU!zYjfI_HTH3~I;5BgK`6MQa((0Z9WkN!hm73CGXa#1E3sf?L+ce0GyW^3S7PTHQFep= z9)6t2F~p1rT`E-)feoyxTG_3ZvmTVLJhwra7o$jMUjQ>+gNFRFD68H0eFP@r@=N7z z)>d+5e_`ZXP!ZfuA@Zq9N$P)4ByY`GV))SjpVK6K9F})NLk@lh!=|(32pCe65n(2qcO|?^Q^R6zKN<~ z{Rkg2lF`|u;m0Bn+R(*EWS#4S(GAK!Q-!Ti7P!@VA`o&K6+%2t)v5g;az6w3&Z(?= z`kM;t9XUZW!0jTPR91bKbA8BR*e8x0YG)_ill$Ktnu!UT#5*r36e1@S}a>udM%>orP&j=*M z*1J zRc3v5=D2m+8Z8X|a^#;_2Ne z<7^x3<7*5=SP-+=Hq<{5-k1|v+fpeI@zyG14xC?m+LVNq&q$62Ul2T256*K|e&<^+ z0Gn!hF@Br5)%5Y4kvuYT(x!PlqL3N~JRk2&>zGk|(BbYyPvP+?tVJBfrFxgMsuUT_yxe`*^EWG_ZY#&^Zn@N)%WN0LurSDIvZI zMr^uBBMs*C~F+Jy(~f za^n8)harw)I~SZ<5^jfk+~#gg%eX{CiZya#)gM{oyOkQ9s0@`f1eu1?%Q(6rRD!?r znb+zyQ!Zxo7wJzu)c}3Q`7Z_SQZ`cMhr4a=R4rDH2!o#If}#@MzmN z=nV)szY?LJ76(bCS^cN@mlkG{CAg=OB50{E&aI-pm}NPuslNG;I3-j|63urZX-5XH zbx%ncyrAS+RerCbX63!&3j@tye7!IGe&d(~Lf7G{!x|CPtgLdNc*w|3>=avW9q}7J z{D}I|Hh;dR{W;kG@#L>SS4g4g&Z)x+1En*xx}*L22539bx{YHPbz`U13)fA%@u(P{ z*AN)B?ySR=c^|0i`(_`jzuz$WOvsFcD79iV&72kmf0U4@++F)-49n%H345@hxhiVk%pCv`e&Lf36RNANGf+UN!PnAFxMH2LOG z-9Q?Zpzsae>XHw<2=1arWE@C2l0-X{{ArHGxIe3V7)Zsq#ZuHzkYEu&4u2&gkempA zK9cU~fd9A|AuaQpS|lIT`SY8*nH>1~T#x9FWL)C75WH-`l2Jsz>m?KLm%?mcHEYm< z`rrYVi>Nsae1HC;?n`v5e`SR||I|d#;dyD~kZ#>pvLYp^+5MS%><-WBZ1<}&3Uxv> zK+>xoI~G&3rin*~^U$_ObrD_TVI>b6E|usxw3I)HqdHdqOX1w`IFmca)Jo3+ikNX3 zo*_ZUaC;p-d|P`E38`Dv^PPZb;(E4v+KZ<|bSV25tg(U92E%!|%nE3*W zv>(anwwIaw{7t;wPxS@)(Zr>a;N_pPnP%X{8n4W-!ZbRyMm)-F@oBnNB6FYS;E1X9^WAF)7_m~_2 z*%~BUw-7LWn_|<*U>m*%cZ@&ao46{+zy;U_IaI!J_S1A&NWD7;o9dDkW~tCmdN&Qy zh@W{HMEi~GU|Rc-TDNMHq41#Urai91-z!}(CBj4hSkDa~N6SY{NU?rL#e?X5K;U(X zCreb^g;$$W8G@tOL|%(ha?mRffHV&oCVzemt82I+ok+5;JCS>%-qM!=mbEze$R$|2 zpzq~*;a8b3-s4)ec~Ef}2dM`5BtuWj(88WtOD3v?MLTUP$il-I`<55XZMc;F!dClO z$Z{i;5mHt%kw?GEr|5w@lfb)s@M13-DiaX&9jw6|cw6z{~z?A3&I=;C2c~C@$OoGJ#VUqzMkz zjj`~;$hJ?=x!DTV+F;amAE`8{TL!K5%54PZ#w7(r_(*$ zf!+l=f%$6}NKyvdJ_W3x@b0OrRP}P0AV!9iPc0_PH4)$=Rv4$03_MTfcr$)5k~ zJMw|H9gE$l7x=U%D5z#AD%}Sx0ALD1ooV4<#;_GI>IfqA0u33?w;To(BYKxnvtSnP z78FDi%2B)@3U^IcFbj~ZBczj5vc~gDW1ioT3zNHyyFd~|i}rXNCe{s^6#)tZf1aF_ zE05aQORpVw(JtoM3Sf)?vtg{HBsI=JQV?EpA2z7nI*#U)q_;co{JPvMC@x8zva5=6 zVPq$i9&#jhbYkdl>QKdg)3oSo2R}DNCIsRcIhLZJw$Y%edMgCrQ4}M`%2~;~=s@%o z1>?|3jhZ;-kp?AeiEHDX0H)zC9glo^c#GJ^kmCl(txYHwemzz z{8S^FWaN4I&bzhKAh{#T+e6Af(Pno))0DSt?2CHp*OosXDD4w9Aj{jYLYExH7mD7l zBez&XaHnFMu4Ws}p=}sH9X@Cj%-pIz%suxHW$!`r=lllYhd`)_Faj$CfnQusRC(dd zdTR7Tt?-ekHjO)B5;SHt(0}D8+68n7PS%H^4O5)lVd z7AA?ZQeP5Y{GS%!pk{|mq{Vh0J`nV?^SAmVz_w;HcKn|}k;>%sb9Kjc2%5M?!*@{U z*$+!w_8RTF6k53!U-_WVQN~?ZCKCi<&|Hw(01G{sGKV&Ua&dE$bT^hs9M23ohPA5T z{*@X4Njlg}G}UI(?5EF#`{yN)Lt6px=sR%Tph3(&_>_mwz>R`vx69$mtx@>)t}bJI zhi~bX?9Peeva-$R0~DAhR#ef8PH?!)fbZ>p8Xb+sCp03lEoJnYj;_P(*yeK%5OimS zcgAtN?pJ;Uw#d>=|3T1IMWqLso{{vkSd`&LJDO5ki6*RW0l}@Hv{KSi6Yo^Pk=0?F zI9^-OGxZbBjLxC=^P$~qHn!TFe|eOKp`C;xl-Ht^AGG*Q-#$W+%W3bx?UKGv4oSx* zKFftrha~LaHI5PB16tQhMuzg!*lr`fnSG9IXcHJEj2^V~dZ4`dQTf!{ zta^*QAh>aGVGgdcSEBZjrS{f$Maqwi{|ucpd!`rc}VqKyzzS9X$iI6NZYkmU|~G@QR^vD9bg`?Z#%PTl$y~FXrq;8*+vOtSXTlM zA0OK7Zeeo6c{DS^^dhMB5Rxtx12CT^ z$VpQc{u(ZPCMvQtf*l9p)BDE<21U?Loi8ZY1Y^t<;Lgd+^(9VMxK8FTDJV=Dex}M# z|B-8jR4ceJU`UY+)D8Y~O3OUqmj22VXkWO?2AIsL(<^sMIK{fhJeR+;&k<%KG7zt- zA&_~@mHA5-#G}D0WBd0rOs_zT(HjNVKq`-3?g;n!eKes4WOrg+XT@>>Nd4hPfH^@m znKF%V?pVsuUrY|3&*u+Z`kd#xsFwWP^8hkfay z$AmW`2#HeH-#2CbC}rtYfRSohg0Z3T6Jz53k7`E`c5}5z-nmqG@7^gs?5PCTeZ9yd zU0?oQ`n0QWM~*Zx)PKE7+j4o|tiAPjrgnmrrC-?q#*Xi%d)qlT0>Qof$y{yYKyHeW zAwfdX#o(kxHpS<~)*9M4%X7Ndd!j|rXHiHA`lE4W?kTppDB?UA9uYAFCrzEUo-{Qz zab@mC27QvFe?liDlYr@_qKbir^pK7QOE+z~V==Z0!E;$j>16VZ0Wx?UPb5M#ZBH)t z^cBdF( zB8OxCqM6b(vdfOqL)n zAf1_^xv2e{f6?j8D_Mb(^fIxrzkNbK)Qksb>(@wAMQ{Vj`Ez_?$fae~sK-7=$I&a(trAomMVETeVHfSTNoYw*rostT4_P=@%LS1}^zrM|MT z!R600xPq(=QF`QnPGd*>!^SsJBII=BjH$q)p_?_wkv+o~fYAf^An zRt_esL|+-1mA3gF62Ru*_7Cb0-cLHh7g=h`u^v?7Te=e7RkM{|s6AkbRK3?C2KVmY z7|$m$B6p=Gp9vu{8YtWsYILj!ZZ0Q8PPiWM&QaTf`aWX@QYF(UoGCdu^;xvL-uwFn zF2ph8S<{}(=vgL&!STB}DiAb(#9udYza^0?wgZ=9taD@0#}*jRGF;^7G*C@M!nsfU>y(?>3r}+k?_<@z!eYVT3`K`c1X- zlirgj;x#g!ovas5i&H!oZfl3WTzeX;Wv%j6jjL-f2cmMN-qTAfBkmTBES~BNF|Lhy zzRnnjE8o%+T0^`;joLK2PH@0q?H%&Z8FmhXQ*=Ux!sd>Ecup6cyH>qCjZG9C(-Xvf zdhvWLkrtUbI>MYm(h)J{V?lOXubw>fr&!5e!JN0cYV0;d9Eh1T>^2gI`i?DXOamuC z#`ZD7)2-z87lx|ApsTdAIaDYA-cG&es&a8?j_}E3iPB=eC9Bs%%1GJWUYshYe;L2} zt=|mSowfF64BJogR=HD2(A`c;t+;p1s1=`7zns9U-rep;phfOJ#5S_8L^aBd(G4yO z{k1=Q&l)p{iyCX0uH}%gD#}K9;Egm=%pz`V&g%}|e1?#ubkrJm=&S%rMNZgAssWlSl0s_Ti=h%^65rJKJ>_t81 z!QIr9=x#xLj)mW*ge%cV!xGA;upBZ_6s}SbKHj6>4iuo{emgc~hDyt`zaFV$YYp?% zuZ?Wy61G?eabdP72m_V0O5XS3Mp|273 zN!{X_3tj;*ua}q{md*K1bka$YfPGa{4+1(lix|aPhbKd5vBH6_lts?!3;8o4%SplEHWT2ICFF&t7lIJ1K8QB`Q zqYdVp`$%@wjGIZT$Nq-5D+jR+oRXPg{E5`j6|BQV1yHsZ8s%bdpEs%pMNJP=0L@8( z{~62$<8x&}j^y8^q2=-C&OPwS4q-%m2^pljc|ln~>Yb4-3DuV?IhlTvsp@a)(ShCk z1mY>)XX*+fcI~?32A^I$Q!D3M0=UK0JA1H>JA~#8T;~9Sd7&R1$bn}lygkF7`)f4s zd2VozBxhwYSF;6YE6ehA#5pQ3LH9wBOoV=wwj1IYYe0^O{`zG9;6rLyzxyyLWVDXL z-dFq@6_w=I3FzUZBTS3X zm0$AVZW~=mv<3bB;N4-<>eJI%ck_NgUB4*An&Cg=x<@J6(wuzi9_?X$_Kxr27_h82 z3>goH@+4l+B7s6U;pbh*fmrnI&a;Ji4=S4iSW11`P*YEhQ&tG`Q5Y{hjIdXj);=%@ z&(fzu&MRw;ecJuUQ0}f2^_kZ;`Rbc)4F0ZhX>Zb0Eu`6v@a2TYxAZe2?8(gkp0dCx z?y9=bc7^jm@5qQHWJX2XpFni-$`*JO_0MvjTUsiYTgcW!Vrc=aA?xn?cW}Z6pAw#_ z6)YR?MmF>svquTJ<~23bST%2M3?{21b2Jzk>`4j2en>Q}gt%(mvz)Cw)Vr_IN{0DB zFWe$GRDovk9u7UVlvO^;kR8ST_KdsY#(N4|-{uq-yGq-sRB?Y7!OWcLQmFM^6y|qT z+K6xY*`Qnzp1Bl`R5>%hWl~S(mUGqgym{a=TrJfGFZ8iOQ$XipgX*6{X|3TheuTH4 z3+lJ@oz(oGyiijg8SK0iKLw6syasXf(O3+{E<~zsdSmd_~ju($)|KaUZFW_O4}GQn{9X_0%YH#=Wyjh-3W4Z#h_6 z_!H`}6j|Alaf`WG<9A7KFN(;G#wja3umzKViPNQ_f#Xy4HP04koI{fF^%qTH^Kna1 zQ}03haPzw5&sbN(Zy4=-j=IHp*{`3|*pbPej^@!H38zZl??<-YveKD~DI`Hay3in8 z`8)CLRB80NCh#upuR2BM|J#S|iU%oN_(-H5` z_vg=EE^os7ks@{SwGf&?6Kb?zc$L+2)z^)8Dt*TlsHf>Wff$Z75uGU^A)-b{dp^Q| z1Kp=jsQdKLw-xhh#|rW|#`NL4>>KNovYABKv54L~S4XEbY^?y|TskZoo9`d<(1%|3 zIu#zwKokRa+ud3S194nl^p~8_WWMbPqQR_(aasptifP!N;Tt1w1n-$RQ&k{xvj#v; zpuOk2&?OWdQAh7C{7bhbu^VV4q%$Y@;(?gn{@vH(wDuVPdUm=7>7-iN7@=`)J@$o~ zjA(91<7&-w_VO3F@kwWzD)%P+`d0>`$3ZriZSdhRH-`QklsT#X)~7>9CQsg*m+IC1 zM}pRd+R~-92V#(_DgCPV2EhPJ&`B<_J#SD&`?zsz58WT{(?484w+=fdb;MmigD@1Q zsJw$rWUw(VvX5Owe##-mmW++=$8GdUc2q)T@kB)T)fYrnh3+L{qkjtgRDSw5S`ozg z%6xo4py=q~7qq0F)VS;FZyD)KWzeO3DbvKj*82IIUu>RdM`3tZepI?=5*lz!_zf-J zjp`C^?_LM~ssGZnYxEgUG4*H=L@`kJ=ok(Vijrc4qv=&RXBejhp+`CAayL;Vlx&fz&hUrzopIiEZ-1zV`zRR3?mS8ZZ&k|6jPcd&){m=IaKmi`9} zAE^tZq}W|c4zJ|{MI%)?mVBR>FaHy+WKQDB zwo`6_>myVOYvgm+E&ep4BCg(drj5`3=GO04IE)m5&a{fr3$(JgM!^}+&AGI@Z+%NJ z&NhN8MI6(iKik1J9qBx!asY>~L$re9lzk2@S+#qD#VVv=u_7+ME3#G{b8HNLAvIW| zEW;KH_7 zOY(f!1bn9Ku^W^l)F9t$dCybLP zkL*Kyq5=b6<8g-7>3}E`7JntYiejNJ_V)ly9f>Qif+8WkP!n(RnZ7~zSHx%3qr4cY zznc(!r7MU2`j@2wOz>IeApEH+XcA`Y!CAhGt62psP4!pKb|cUD4aHaU^U$M} zDpIpjtG9(y>Qg?6(#q;labH0X@97(UGnQ0CDsPmlYfWO%cdGM?rA3NNj+H(GLh8&- zftw1hZdTj>{m_yYCdAx_v+pL?-I@24eNUTZQ(MB5y4T;)lFU+mL;w}8kr9jq!F5j> ziKL|}4(R>MBpOmXZDq{r#up{X`Y2|^ed0^N6>$Fh@i;O@(6QtePO*okMJk51jE@cA z=#q0Y70TL0@z?zvxFpLaaw8B&0JdUSARqaAjSBOiutguR7e0+nc84p1H61?t!Xod?W3zVdlZ^wJbQT zRLtuhKJsy4tQLIO6SMxX)+X=d&rlxYzIXBQa5T`_*I&BI4f%iCpeZ){*S7+G=DwA? zFGu_u*7exbN~QhsRjA6qne|3Y$LzuA%$udGq`yUew<*UioU zf{z<(vsEvotyQsxmc3p%iJ}uHz&eoaS0;j$h;zvR+K@e!j2+~12(A;~szlvs|2GZ=wj-Nvd-@`gl2c3~+ zvAlXbb1EH36q5NvezrsU-squ>Kq2+y!{m%q5XBEZrGoD}Z5BDg5MCrZq^u*v{QzjBkrh#E?al)8ZyeX5jGu5QZjT4Bq9u*?Pq6^BJ zk?@PBGTqVeTh*zF5lB|ZkK><1>Fy+xL*EKAin@nMi8i_NeP;m&J&K ziCv*6WwLsL9%Z@HU5T})A;EYKCs*0t1f_77+#5x9;(pcrOPG*|1e^jIkF6CRbggY^ zm?Y>T&grh>Shhp>j7M<(nhCF?U(NX#dt8ksCzc2-=-}O{)QPJJWkHIz052;IswZ2G z@mVK=zuVK1F0!1R7R*c!Wk-NnVitcZYJN@wC>Cbw7*~(Vxt`)x3h^ito_?!ekbPqt zU}+z9If^vpw7f7G)a4%u-H6nuDR!*z0ZTi0cHClV5ZkTqo#bz&tD9(c8EdJ42Y!T+ zed!2BAGc*?N(&BAlt1Y(*vrogf3lU?3y*KH<;6R$i{6+qh^MZCHgy$>>J3FLB+OYr z<#8A(_A}7Iz5Yus=1ctk!8g>UA23GaGNgp2W^6GHBjqSWX;g}bgS~KqBjZ^p&6&&p zzBZR53;p^FIS}24PKQEI?;V~Vg^>D;iPGq;MsTJ&Xh{CM-jJ+s${%M^4bp0ZXkep{fZk>p{{gu` z`e@Y&2*=B*FFkCeYhg^SwBk}%F0*)mFKdS_vw(dLO_f7rmPB~eIC`Gu??%hl*E1OZ z1}H_1No7SNcNeTjskwx$N!?__7DyQfQV?Y3SXxeyuMG=|x$nYRV7Tv!v)O5zW^kSA zA!Y4Y8^=#$*YuS$J zoXB8d6Yv^C;B3*6md=f!@Kk;L<{Hg)=S)!p&h7Hi%FRWwq0!s~HQ$V^9*exOJS^g+ zu3~;qnSe`{+0nv<^+#56VGRok`UOri*BKD*R8x0c=tjodscT4}Ncr#c60=LPF&JNZFgSE8 zd43HCBn{xo2Da@?IPbY2pR?1YOklwEk-4C<+SEH$AUywukA~Ef6UOfQAt@O9PcCww zirl>fo9>V1#oMF%DYIFK8j?8x>fepV=Fp0KRAL70hUDxm@WGep;aVTq3A;!?_XiY! z=guJ#W-R6g73Wck?9St%u?Cy=iH0v?=5$q4hOy$~f(0=v7-aY9ksrC14GqFo1q%dF zy3S@B9TZJ^o*N>ItiOGibz^dHp!^6qr1M~cnu#f3>)$oy){onQ6eqPMk>ZX_(cJ+K3Rr_!thXS|^(rmn zI#7QXn{7V@zPI1@_Ke}=^eO&W>DZDG$Qna-_>Dn2H$#pge~VbH`fkKIzCgeF+P4&= z+h<93RM6&|AAN(G13Lf*+UMoMJjA9Rc`X5loUwKXMc)O3n2GulQq(!bFK(LLwl?cS;P3*E2V8QWFPNj;+ZGq`9+ylQY8(U&}}~0=3lN6OHUd z!Y82%BsyxA9KKmS5%v|G?41&F`3+vfdLPr$;_#ceB3n53E7h| ze6#)FpKVt0Z5&9yHf@*Fj#pqu|JF=K*F*209MR#z+XP&rWw|GfbCa8J@L2V=5sCiO z;2zO@bhc%f9MBmWRD9(Fyv0Vp#%E4IS=YlL1vNBxB(_j> ze-DG5SsJP+vXk~Gh1g03fBhf>Y-Nn=LwrGjjtIhZZ9G%xI_-erE#pfPRRz?Om(cl3 zJ$$5Yv{kzhXD{MsT;O1_JbZkdn(kMuuT>) zdsUR6_hs!XE)x}rYElrt_6aM0UkTAm%n|)jcsu-iN|53rSv?8Ihp{Y!M0pWu4Z%Y37BCKzD?46lRVLQZAhuzaYgridnV^B>tDh3?%}V@dvx?c zvY^WB{Dz?_+pvJ%-GIXvVI6edzq*eZLB8LA_6La}n`~W0v{$i23% zhAeHr-=QyeY?M{iDwV$o9V2$<*iL{jd-#9NU6FC{)$Om|!*im6{&Z_>9X3ygru1dveXW#D+ifM?#>XLpEe=cVoL-6z=Z7 zuwdS49&lWSfX4&Bvi>i7bBZyRnw*4$FDx`av>(4S9vH&m%m&PG{r+ER8& zE2Xq-!~a(bfj?N%V?oLi+M$~Svr6TzC^)`-e$TSr)*yp&kb>uQ*%I2HZ865v=;f*Z zXXR9=dH#pDTbsjxndIX%AY9@JZ#2LxbZ>$i^e$T!5Cp07ORE^HN{gUxoDIqi*XH&E~X zMeir_pW8^-n!Gi45c)KoGir|@m<_4*TP*W-<-CLS`7V)b8Pq-WzXBr zrw7rULja*+?5+`H@9`6lN0qyCHtb0?7QZpAUZJKjHS$*TjX6;RaG@KoKvV=P!Q(~^U0a~I6^Le zDs;v zO75&UZvNog{tNm5&W2Eyivl)^=1}_!gLeLlSG$(3onoCE*zO4kLDf8z#sJFmfwkwd z=gv)KWNwX*6EO@LLvgAx<7gq}pizv(bXq@)xWS>pL%#z+8VAhTPA#v^Q{aw_&$)=X znm!GM`-+Hf2Pls=>nN*yLlN6!5kGUc$8)h*3sB4iP-ZCSU`Dxlcxs+2cv>hWsB3*Z zchy)lc5Z!X!fR{Y9i$Jrn_XUt;Q=tgMe|mtj5x_@ThB;krp{yy_Mffi!c`Z*G z4+s!Lpe@gxfekb2WzXDvd@IDy1!GUqm|iRX01yg^w!QR3;>n}Q65Vh>&{=!3pBAdi zkJPF4eGfF~fFB9);cWIfEWUYL1aYhau5Jhwfb9HhRGH$v*_E(myxBaksr|ZhqJHfc zTNLWv2IQ?kj;THeH#7qI26NkR^YFr&B3ur*V*K+$BWxHN28}35D4V?8(~%>5Oqr9I ze=^YoDk*5fKr*@M?Sm=plGnQAig!4&Aeg4_;QJGq-3Bi;11FwWzdfvXUoRinD0hMj zqARyMDZ!N>@~V6ly!+_L*i&gNIf#8eY>GRHU7d6BEK(I?+sQ2cA%`obHGBWyq5T0d z0DAj1b4suJ`||b`zk~8!8=OIAi^BdgqeEs=vwG_99!ytF#^a6*VGk@KFZ&-u&P*T< ze-K?mxM|ImVBcMWgg&^hRl;?A9WCJGKmsfIbgCF7F1VuW;LzNr${Ux;}|K z&x;%AM0RHe>7>DF9@B&7AUSv5_pZ(1^>pQ*|0y@|%=tenMh30r}W2H+p&BPVkD4jodK z1lh44VeUt*co-mgUc@)2Ka8Kz`ux|hrajfP+??o?>Ajh1#Y(T3spl|$=UIQ${tXCo z9)uq(?sa50$h5c}tK{^Rr0TpVHl;yv81D&0; zw-!FxrU$?(L)W~ z4KtNq_ONlXH3Kl1b5j9`zuK3GwG3GXJVSA6mhr5lf8Yc{-la%}7y1v1#|?T|W!Z+5`6tp=m8?U}j^TC907B3rU))@}#bYOv5wJs#^JE$Gc^xMu+V+V*U4 zea4K0(p8y$)poFx4SZD^Xzph%r`&krH^h>%niw-e+fId>`*U~HUO0gCdJvBd`KQ|O zy3ae(o%bGZ7BZ08yit#$*gG=5u!7D*D)&Y9u53xxQPFW2bkBUn{ zD^_rnSEh@l)hB>+K?7<}dM~XMM6t<_CPe4cPdg+^oX-ucl!rH9Fs-}}7PmJ=$eFM8 zl|8?@_=;`$gx=^z@jeZZ#wJeu!R#xynF}EGqt}`^VGy5qPbYWEi>rjwUzT-HkGj#1 zvGSb@@pu>ZHfLpcwO}z`Tz6$1+HJ@l>buECC<*^jxo~+wF%xp@^WK?-;qS7r^Rt~3 z9%bV54AmX8qIYEh;?6$+w5akaUIlv|hIf(2H^c$A$UdMT6^mu!qLw5AclmkZw* z)`ertY?fh0yT{sQ37|AQN|lO93z!OR2b*V9@~!-A-+u!c+&AS0vtK#lU(So3EO`fE zkbV1+AIrmn(==~nD*k~JErU=d^_ksKrDUcLb+%Dh+9YRC#*PF_JPa!h(~j3ELxirD z^P)-KJ<_SFSM1x3Fmpw{j^yCxxva5FD3zymd|XXmkFmC(CQ39mg7HDNs|>gftDT9< zlGaWJKM^@~^GFHF^B_s3b&-h7dH|P{*XIb;ENF!sm2Fb<3yXZu^*I;bzCR#0k;my@{PNiR zyhL}Q-$aY-%0Hl?uljof)Xlx1_N$_4(&j=H0r79i>G+8gFSgf0yynJRuz>-)>5<9S zj^czLe9R!T@!!l(P%ZC}Iso<_?}8cfckRRRx)VI_PU`!;Q&cYt1ey4f1+ww^_~aujk4`ib;Ahw_RgG`z+QZd z+^-@)gkdrazN)n9+pa4IhXj5{ZRk5l`R_t1Y-LPvv2dfLzYx@m67$dPJ71DXJd%-} zbZ@SDDmhfg@xMQBcYGV(Jl9mO&A}j*z@=PyBx&SzP)P?;<5&S} zVCE$s)9MvJu$@~!c7NZ8CcEtE9e07p@Dy-s-U?oeYD)*27pYKF=u^di3|Px3O44u$ zKJ56IuBt~e9^O;iGj#%v#s2daVYt4U1!;coMNmt)`*8H3h5Tk$PHMSjoVxk+;3YZt z`3y3?C1D+7=&FiJ#*-yBhw2^4VW#KxSO*U=1%T5fnOH;3y{}coRWsY_O7$knhv=iB znISXUMHz6Ee%0SFb@2vpR_^ANYK1*j$Jn^!M3?>R40}g@7P2xkK+FY z9DX;dDD*9#vgc@JQhs?D)B5@ZE>sC2IbF$Bk0g_W&V}}&h9B;T_$>%Pc&5t-Zp0C9 z#1;dU%}_I5Tt^35qT@~nokxkt;Iiws@8aLt#z6X914WfA6GO)%bjZMQoPAnWkk6_ZQ->|S+QAj^A~gG$LIJ5EHK^*; z`2p0qT|Y{mlm6yuuFA{u?$}q{WuU-qZvfz$Z6>FNDfUB`xeobj+9Ac-2auV}Ycb-} zXL6VV5ZTE2-v;3wzb#RnrPeYCKY0_V%aqmU#-gu!XN$Yp7CJqw5ceRx zaaQNT(e|#{@qP9V!w0JvsHmF8x~}JYuOAPw1EucqJ@Wr+!g?JmMA4onndzODp^897 z8^YP>9ue%pfUTZpLTifavK6vURc_L~0fyS~T?qcm;7~*UP?pNmALdZq&FOL^izF8K zmp^4bI}Pw!J^!g%%>ByU(^e+|;wXKYC4hGkGS!hY5)@11ngY}u0MK>w`1o_s0aq1i zI9;1yJ7i#E6osAucHSqIrKzg086pFb&Q})Q+Op15H+gzWbNSgM$J30pZ!B8yX1Hqr z00i!Hvt0r4{x<3%I*|%?&xIaJ&Hs*)y7Nwa)gT}wr!coT{ zom8<8swvkM#L}|;%bzieL-g$@l%Kja+~-ko>Q~>cmj^9hLnzWqZ&BZR=PsAzZ$PM9 z?dnVS03sF{aFj8}-mTF9pWc+1O3H|1^MpwGjPsV zF7824oMI){(9)?#CeD1MK)qXVkl+^Tg>9(@Nqoh6~_HGP3zu&VIlk{lrG$@s8t(Jlpcc3fFLi z0zl+vu2Qqcmk4YJy?Mx`&z zie*pMPK>EJs7ALfu@0VC6M?-+R}i0V;dzUtMC4Z64e%|03R&mhMQOXabI8P~H`%D# zDX@}yvV<*9U&i!wNswvf%V`$hFX3dJfrHWSbkb$bHOjhrid6=hQ#oJxmS*X$4`o-> zPc2UEL2t&&fG-zD=lBoyIO5qK>qv{ z8B~*O(!>*41gdp&`}MnnJXW9o<=749))Q^|{Z*$xO9&+{hUq9>r3a;+GZjm>w&9SK z{Ps_=?Vo`#D94KrlKjUa%NQZ=ipfoJIbSOxQbT=we0un3I zNO!lCbO=a;f*{@9wf7AAyZ5<1{vkMX;?2(+=M4Ph)>1~|Z)K?l1-7IN&^QojBB0%} zZ>l+%nK(8;2rj4bJ}8dOOJ@5LA*(J`oAAWGN$exGH-Sn)TbLsNF6F}fcA#ygj_pDh z9;F2z2XGi{14R9>n-U8Yo#@*3chrutN7&oKezNvASOsG@_>t$Ot1SH4z$+ban6;q@ zyY_4x8h>!{{sW;ojfwgXl43_sFK$|@P6$p%x6uljTg?i&L^n+cD=7`6d z#Xvxxg!|LYDP!Wz0B~f%$Sh-JbVBoKB=7RVDSf}=p+Fks9a{p+-Xjnr`S;n9WR-vn zGUy_P+feSf6^Uwn;sWo#KjMZZssyfZjqU5U{!Zm+nFYOdK;fZ{7XTpe8ohG_b*@O8 zySNaILFs37p9}-&rGgLX`e=E_Uet1M!Ns5}5dbY7yYPY1V*n_BK%3O%J4W_dAKoS! z3+(}%dW%a-F~#yJXel85b;KJW3_S6E=Mtoul4B8hSv8qtozB z>E{sW1_gJHXh8lPQni$%TsQ^s7AX`~bO<3gK}g`mAsg`1M5&c3;;#ciAPDLP)S!Tw zX$#u2+lMwKS;2m9;o3ljoGBwE&ssj5_9y{c$fyJIU)d-`dn!)d2^Ps#LUqzlX?2{ z2bM^JEL3!QGB!ch27vf;%UGjf&5s9jV$th-uWuJuz41 zirq{3Ht1PGhI0Tf0CH2xKHSBt)pxpIZe-N0EoomWJskyUf2P*P#`odX!!juC1 zWvC(J3o=U`CSiw8lYw(ph`f!^BJ^dC`(? zpI@?`xCpOI;O5!T&dU3gHhjw&{L8q|VF=)wJ?J5FS$<78WV{L%Q1{J7EJy`3niz8O z@2L0jHF0!t4BL%dw2zjD@tWHx#fXtWUPwpiFhk>~L*6cBCXz_*Vh6 zsj$8f3NEMwCuM8FWxowyx6uGQiT(r?IDv^L98-50X=xqQQ#|`GujC%${I) z`99R(R2a{hoYUznKz`p?#o^6Yumocprg_lrO?K`&7E)0}VHJ2~9QxbbxhNAt2`G`m z#+=G6T5kedg80`9IqkmhE_x=doWwnd6gUiNUbva43`)^^uS~ODg&@~{(84IHMPhdo z)bRnr2S*K|x)Oldlka%Oo|fh$YlhMZk7Qv@z3%C6C@wUQ^SUOCw^<3)M|t3mdkyTjyl<596Id<L>Ml&Yfl%2*)igU}=X9?^d6ju94)x+UCfYM$cnwIhX9#*c278RV6XfB>k0 zI`ZQXbvNowFjrx|GoBt*2Lpv$Di+kR?l6-kyNJoAk;x{dJCfhwfFRPWA=6~H>^L9y zH=Kbp=s=U0YfzjYBcKrUoS?eH*6wSozd09DXHS3zJ&eFbRb*M>SH%v)vUGg+&guZOf-1ou3%MeD#*d$sBoXyHV(I; z9G@rf>`~i~XmSv>8-^BAaU96(^EMt(_&0@*EJOQAUj@|h`5ChWh4A#KJDy4d>Gpng zP19vCnk-bG^C@E6HW}P&;N9gsC5BidmpRiv8BruLIZ8P9A_ai~FEEY}^zf4;LO?Ty zx$zl7gYVkT7oGV%uo4|50ZrBu`a7npne&orz;9V!J{Xt8;|;ev!<PYl5{DL>dA|o66453R-xa2FS#U`NAg7%=f46W100NV|DQ!O*v zWvzQ*&6my3MWR4nc1pUsLxO=`GgB6|b1w(n5m5QQD4qOkR!vyHQ5*+KWB?=!JuF0) z08_ma7DGro(ZTe-U5al9=&GLF1K?aoUqCPWKMH~1m6m6LXI9{QY|m-LtP`_81*65+ z?DG+0{#MZQUzOWe#%;iHdrbPx9?sKTwH&H=@b38Fv1$J5OkHRZ@sK-xefC^u_jN8V z=`&E2+VM?%C@NaJH3=B7{>iciiO(P7Tp%n13c_>xv*SlagW&wjQW3BOzJBY3L*}Jw zm{-&jyL+jXu9Huz?9R_7F}f%R&w!X}(&rQktPNC7wzkC^bYK(rJ5b0tb^!si8#?KC z>V(5Xf5j$mpC0Yxov{O}Odus?Q;gU;)Aw5pRIMfNnCl`a@Z6eixu0+a^7cGx@XBW8 z`$?~GEE=5~%Z^43>4Iyj?m{w89wW0A(G)T5Sg!|i)C=}K{)60FtAUS!ofJTn)hG+l@xf*Q zj3}IWb%K};678FaWmD%5C(Pf;Hj!l6J23{wzeWpq_1I2Q>n1;aN_7?cB=;+p8;ta2 zYuj~7Obum`+rAW{S8$32)dc)C2w){gnzzz1F=NJofjr8}K$lJif)y#CSGP) zJRb_BAKD2cGMl;#O)*~ZKa3IGA(1A_x_aq9?}{IA?=iI6aBP}RnJhocAgf|0{3rbZ zkhUVrVkG|qoJrygb0J!>OW@k7kUbw9%Sza&m zG{yq5fqs#=LB$1D9LuY6Kjl?k41osU$}d2~vWf#_?DpbVfX-TU;hw9a)YQ%?@27RP znoB~XB!Bfs`_oFMpkB5!g-pQw(39zlEqno6*azYXG{B$}B+a$AlxcFx`%}4fKWn_c z0{v?KJ8Rd^lrc?-#0rkM;fg<<6Z$}Gi0{u~_8FGK({vXuvNyI)ejxTH1Yg~&m zFA`U!We@WeYAF9p!0}?o;*YEp9aq5ibHa4yQDFPy@&cOK8lO|c(_CfX0m><>PROgW zYD)SbbH;fr@B4qcfx`u-IDlMpasMoH;X|)D2ZP@TM1ZYm#A^6y9paF8Zt0SN*>+s3f!GF(y zKI#}F3g(fcb}!k^zzj!JMR&K+J~(^s5k~|H7$gD0 z(ADN=dlvLcgq(ov4wD|4kMFDj+ZpDeCZH9qVF!r+2$pHE`01Bfw>x1=)14EblL~>w zTeg#4I8?7Mt;89|e4n~fHL;-4^d#AXGrw)=bhLx2+Bvw4uSOL1XBC-LoDA5P$(9@< zuE9mTDdXuvl$phc8iFqA{GIUNgqOfhMG}l>WDor{-cg-k?hb;w*!bklu_}gP7Hy5Esu~<$lx{2`hLmVnF!Xp3P$St z=!mJ)Mx`QSGW;LI{nv6Jj+ej5=q- zHp@v_Kr36Ll3^7Xr{oKQ=f<=1t0IplQ-IfuT=@+0n+>mH$_Zvmf;;jjUVcH`fnUc9 zGXkywvV0pc{W5L(B+=cvk1dzH>iY^9voc!2rnMDsdfA@7Hyc=2%c0b-oFgupi`Ky@ zXxpKVMkjE{=WZ9cJqH?pgLIHp$e2D(bbcNPL}2ujqbt8mi?^{@SWxpb@c-#ADA`KO z;(Wr5x1=Us8ZnYw@?KfS5K@76E8kAPWVs_FjNG|b@eVlZ?xSQu-R%G9B9J8V0NqTL z3%LxH1Q1Qsg%%S}yu4SmjoaXpa$zAWF9R*(M|fwE(p}JtVg-k7P8ep>pRcknP;z6^ z-)?|A?{X7@iEYbZ6DOj@>PB%y3srJ(cY~Q5?k~1VhvO?|M;Q)Z0F{;W>kk!bGU#0B zT7VL+R~z$x`k<3w)^;7unv;oH`GPf7?HqAwy%O$ZArEa^@SH!W$JA1bd)A~7f)e+2 zA(jwz);i3Lw(jnBkXHVPJlW;+2M+fE^4 zz)pN;wu2BfA(=j9x>WcIXn+$qz*Gc272k6PzJJ#dq6nDCL8mTLq#65JTZ8lIw$S+T zbhlk_6aR~|Qi@ebOw?{vL8HOsgtG5sgqh!Cdy5Dav?Z*O1 z_kNwGD4U|z^5{hea5!S)GIYRjjAok5$_74I6nc6mYX4pZqtlab>Kmd^ao4A+;5N^>!PJ!%`s;G*t$0LXp0~Au@;&F zdRb(Zw`PjfHSlM-3qZ%slyUV^<9Cgd<48t5fM@U92RBxKy77*%h1h}cVbLu}hj`2w zy!kxVU4=Xs<&LpxLI&N#172)uUP2`&yTSQO@4x0-?`WwZsr&#D(w)=rU7O zPW=aseEUTN1}Ky&64Krqz)%wdD0mt6?S>Q1S#Sr&k)(PDCk43+u#azz`NKZsj<1A# z0^AkU;7^zZZ#Gcfddi=k`3zA@*})_|1{(^qj2#8S0<0m6@35lorzV8h1EJvh11CDd4i`w$y~ZnQ^$RD8&F^ zMMFa6^zYB<{azFHUm81UAY6X|Kpp6LP`~NxX%hJ|^7cD2$KbWIC7`X5pY4 zgw9@v>2-qWl{Vfcp6HW^1~3ZO|1Xx(jw8a&3t&XMiiIoHfKbRgb}8L4kaN$LK9N;( zu>uQ9D!7n}y5v|6bk56^Xi_M@p;h%ls<06gEF(6PZKHvOWbH;20uiuHwtp&z&c@)? zgb#jS%>}Lzyx;Qdp4x>ctX3s2wMD+dq9mhsgQ@)~wNI;Mtdd11565;4_&f0Q0zmO& zzx+eZVVE-da1wQ`t5v?|4O$$+zx6i=`PBSJiyKjKrOPMMg5DjB;yEj9IZcP1bCV&% zoIjj)3B0)fx@5ae`cir<2l9=t##M+TwBmwLa?^lN>4iahsF8MJJ+Qily|RHSSv37# z{nk(co38_%`Y~)F7QY@3_Sly=7AxcPt3AbTFbZ>kZFxC8{%|-a*h+8_h^iqANvBd| zmc{rDOJl<$(-bls=+PwKPKRcMEXMAES*eud;C*nD2djZ0%;jR?cllRJXyq}4 z^e==y8o~i{r4Imm`4;jjHhno-H)au-84(D|%`~C&)q#OWAJzTu@`>2qU3Yh2CuH%M z-0=clXJu;P&2nGhWe*$kj8Q~y+jfWaE$|Fm%-EAa{?0hyH?ksp-N3OT7XF0aFqacr zzG;Dt^X7Evz0ifl7_v-_UV;a6XXew5P#-&qA`|4=$A04oBp$-1}H{9PFQD%W}}2YjZ=ZWQ2TTE!^i z^dDFaQh!~4`CS5SqY=!@M&luZ0)SVhj<@f!;t3P))%%PPX8^gEb5c8UQ<2Ne>&Oavo)-}is3cI}L_`5j6UR`kj+M{ZRvTS7s0+-=>D*I=0(=j(Pi zFb|jIDrUU}aY*dn0lTjJG96@4t7db78ttE6=b2ev0oJu0?=@I#mI+-|PwU2#pavUX zd|-;oWp9tab5Y2a1+%b*BlB<(^B0gjAvxKy8V2P^a>-X93sBhVG&EnVP^7ZHnl8t4 z!~h9~250bt`3j$!{m9mMMk~mYOCbb{QiB6Z)21|>6}u=b6{v+=DmVvPnFE-_@$*o3 zLSf!Gy$`Fw#X_VE-lM4O+u>$GwWv6E?dU2WFppya1t%(-{?4MxmTsCk-*aMGfP*w% zn=We#=w>6&dN~1kott30Wyy>u+;LEUdq!Oz)W;!#0Y#GcYG?A_iE6>3vd@i|H8DHf zKvH$20tRnDGymWivp{^{21X&uT=ZiXkpZlSEp!hByjR9XzXJmXMl)={z)o_mbsdSE%ZAUg!m zzbPF0<>#0fcC_!7bT2nwL|l2rTg|W{?WZ0lkJA&TXf$QNxKN|=b<-~fv-4H}QMBE? zo&%;R%on4Ij!88za-fCWY5wXyMLR%nB{y`))HDQaqv4vdwWy=o*(j?cNHgg2(Xc$B zU_0(FL|G;W@_aPC4S7)#ZfyG6!OhiTf(S=<+|Mt{bbxaFj7)P35(wD zo8HGSxE}COl~Zxj(*@Uqn_~EXUc+hvz$rJ~41krcC{8DPFxF=NU@4>8Stb9ov5qyf zRF57__@Xb4({Y2M(Qjse0VwpxA^a%TFBqFJI0DwGKC4^|;;j34urNtSzkv-kv@9QK ztnA8mIGu=f2DdCB#+WXTS$sa*?&93rT>^;74kRX02B1;g7^L^Z^@{qlwYpHShn_GT zkUe|nSfAs`@e5Y|^>jhKtUSevrQ4 z`>3sMizAy@6(WmGal{BY(@uGQTaQ?^OPCzu;!=@Oyb!G)-Klt(&%ctvPl$_sGo=NB zoR)UM<7NA17}dCD$KcJS1W(S`)F7?_hYng#9{&wD6|&YNhcItG$SHEz8Uj15qZG%1 zt_`M@E&1Fog-8bi7}ooEsIxV7lrns~kgrG))R0@?tCApVg|vY14UpumH-^KO%7p2_ zYLId{rXkFFw bo%)5nP>+gL z%vwUeyvu0*>c~Ms=ReT(IAkZOz&hg_Ed3mE{+FKQn-iAB*`}_`o4r;5C^xlS-O&h8 zo18!a79@xqTHQmIo(niNcW90AfOb96m&srStPmBrmkY-p-s$nGKAX>|u;>{0IJ|2H*}u+g5l%FXH+2XV03 z&i*7+{@)a&dFn@VE(IFM`#i@O=-x9RrZJ{haJ&V^oFy)#QF)pE=vsAT;qkrB{} zq2>-*ZrhRy%@5tEs6DvWTkiilXHVy$`byzOloA=4Gxzi1x=Mt!?RBT4T?~FGJx0rNZFNLboc};*X2g zx*z|FZzSU@^mD^icRq>>+-P{3{pr=)I3I*5WnMJ+m`>!mc=QE@m{ACuGtTdaNSQMX zu-VVsrcKkPU;lS&&!8F3!QRM@qGQ>^7${QaM|vQ*tTnGe|MD`gWW;38dhOcV8sO)w z8Kk5pOd0NcPMtPX))0V0{f49mH0=xL1-o4+gk|z9Sk`lFD}Auk2EJL=EV5_#m1HlI ze*vXgRYXPl#Rp{B0#}%LtX~5tHfdxO9!Q@Cp!$J0!DZ<7Uw)KDvPLhiZDw7RUn;{b zOOaPKN#1+`=7`6-2`t`Sy_PaYb7>@4jaBSIxrzA`zQYrSTtxg8ejdBrn=m8sTZ-ao zWkf4f;km4Ka$3JPms(aLuYzSimn;LGM{p8^-V%c1{#toz;Kav6;ad>&v6SWeE@rz> z=Z3A*Y!G}tq!Esq!F9A$abOqjiGn&TZWOxtL$;+OjA&c}>h`J~!=e_0FGJ>Ka6;j^ zpVH$muTyJ2y4JBWg$yGKZ+U^^2ulB7rv0EK@k}1vr3rEoz!CmfNc5_MUxj2k@5$s( zUd5NO?UQqQKB0s{9p}^^=Ya1O2kDXQ5Ji z#ZD|PG7;a4ft3N@B0_=>NUhm1I00u1db#w8T0l(nz_Ly+WR}P25C~wd7XF+Z#%nT) zm2CuYvko+x<$;Vnw5o?MBjv%_6In9x{iPsSSo^GM$#N_y1JA3b$o?!14g-}iHi zk11D}Fa=I^j=;OARU24-*gVbs-r)X3uU-=wcVqA~%*y6Jo$@xRT5wX=+hNG|Zd4PT znKY~U^r86$gim4h0%kZdS{bQ>dH7K0TJ5AEh!h;z@JAS992nrG3;y?FqWviV@)Op1 ztNnH04q}1-I~x-rg{{u+1*%jJf1d~NBA%Xl99$lX08N_>+)=fs#h-5Ep2{?p5j~rQ z7R7%zg6X{3I`4H!IQjKHW<68t2R}~)G@(I&TWFs8%$x}HPbe3>-^L+Vohd}|-}J+J zgh_0N7nzUJjO~^_;pM6oHBRebOBN(O_5Pe8C%fe%!?Mbp%2w0 z__@5BGwz!F2?CSEGjp)vYY|Uk8lP$K=Yk^e)FWhAj7!bAg|&f3&WhVW?p$8eCA3IB_=4 zXC5Cr#S*CVda6p!^uR^I$^04Ys&Q#cgLO#h_r#+JaoHHNpheN&%@@>Q6^k9ktdy8c z5CC_@D<|O8RQ;)|`7uCRm(=5;SL1O72Wvk8CP-lV zd7j18e10g}Jy*l+3g{E&8c5~V0S@%h#vaBDuoGI<*dKdh&6$R_(%vE|Xs1Mj9GOa^FPfeH=PZewv=zy}>g8_ldDE}1kfJo#}LDn%_s1=oZz zqCmQP@gYoJSQx~Bm9id_OT+jw0`i{NMtmodY&0(ncnkLWEps?n*5qz9T^2>|_husq zpU?`-4zREo(m^6m-_AJciyT%*hS-qbm@J`QJ8()Uzi3cP_V@hriFA=wlt-1 z0(m>Snx6qpv0mwKXw9Zkj|17Qlzf1kzZLao#=NHjcGEQvqXcvFd0R10@j8=`<{}(^ zRdC|{?Cxwz*jdpEk=6yXAT;tI65k8S<=7();5#4-1?#)0Z=P{o6r;K$WR<`zT}jn!dnsZRicdh&u# z@D*aoOFrU*d=+@dnGRNj{Pt#g^mLEf*=`-|KgNrvOJu1~gP5XipxH3K@P12FttEz| z+3sr*gFL2*#S)ai2#O(fqAxPXM#MkdhpfF|Md1c4)gX`y_hCd2+Qa3MMV8;4fE3PLRfDhJQ z8L8pKnvdD)O=m9K0OeJ0k8CZ92qa=C3mJ`N1G)aKW=^rz1pf!Y)r$rrBQ^!r*Z0+* z`GI^y`)OzEOTL9T#6a;j?jz1U49kTOC~vjMN650^)Lj7+I8-SD5%>?zuv>3R{Q4Y# zix`M8rN^;$wh-~XFgILwk_=Xs6JT*V^ds>vlc4DlJa{fa>wH094LKZ+_0-2EOiGuh zk~Y;~0nmB8rP*`VlAk@rAZ=zllWF=qd*R5 z{p+pQwbAMQpj!gTu9JSrS{Y;%VO;Fk5p^E=7Cl=WOd$#O=t!KX@a~3~OAP<@xxoMR z0>Dx!Afethcix6m6#z>*)jy^)=VuaOb7C~%C3{~d=E1AhYiWH1a)^bO>+q6YJz))!znK$Ucg-sRtYNaq`~ zI_pdYejsHQqcHnnG;|Lf0aIHfuNueHJj+imCL_g7(*NH++FhcV2P;>R+-Lwht+5hO zH|(7(0+n&z2!hoR*Oe5lGmWU&o`nuUl>ds~Z0)i*oxHIQ;yrufcYqPIRKHr>_v;&s zoj2eA7`Cm#6g|!g_tm3-aNqwkIXWNZzXx(AD}$#wkUDBy4)PJ@%z1`)x)+H{AZgQNzwfnd;%uUPb7fN z*Ino?6I`gR)8V4g-If#t6EPbXh4iHyZll!wE(%?`-RQ z^5LVz%L%ZMfBAxIoP;Z$?DQ|dve&wLWFrD6<-@^71!t-Yqsxcw(iHhQkXV9bHE_@Z zsTbZ!{E7L+lJ6XyDF`1%ohu1O`9&_mRX z(#&V9ifNw@8G+=H5TnnP!tBDs*>?dmyzg&wwKrY~*I`({hqZWtl7L}lR$O+AmsUh@ z*uDfNq~UU)K;e2u`y&YGba{8na|0^d{k~2#D}?*zFTYrImN5T?>o5<(W{ib{?ZAB^ zv?~Peh?si#*Ph(Zyhf}K)i%-rUkX*eN%kZ)qwnaD^ROxfyZZWP2;(5$!UYZpLhgP_ z=l~g3mM4TqtdQT^|G6O5jiK=!sDN7&Y~aUcS+WjS>+v`)-ytK zS57kk5D1Q5yhHAZwb03=b$ZkTE8p<9{Xz#ZX77}FV0GRS{j3o@^$Qi}lhe}AxDU4O ztZr*NwkO^_Q!?ATtp@$T{%e$QTRXxk!DOU%;VUkE(yq13KN?8E(xu-TNJrYwm zQ+NN39&RUXnO1m_T6oXdNisb9a+(@wmL~@;q3Vcid$ z7SiL>on9wVFWT#UrDvf z?HsgYsX6E-o3dzi0E{rhP4NgaE{HAn-Z{7g0EZ zX}$tK1QW3MgM8qIWFr`MRo|xN*{b9k{B>+A2NW27b`2FQ&c$^)plg*8* zfYPt6xo@3RTFih_miL-nN36y{gvU=_GVDhL|D&?nr;-OdVw2sVdIe2|Y_+sjCmOt@ z1hg0xj;aX`C_$-UqDZg=iT;u}%4m*%YYYR38V4*v%AiVIO@Jjx3>LoTxGV%}_Rsd9 z#p{2~Z_b0Q#*Jq1A!x`tEV*Wb&cc^XkAd(6EM&vBFZNkjdk^99_hO0YM72 z9ZxENd#F_C0S#SGSAjy;fgp)w`rUMd1$`a}2mTJ-Wn28Q;$w;OYe0>Pp8jf@WY{W- z0p8V8rLi*FszLam;R{f$fdOrB_tia_+57OnEu>oy#LsQEi*L6ABd})M*MUAakttRJ z3C|xC|MoZc(qOjMM+>wrjbbg(UoSzj6D7bBTUfHr6!eb3yY6p;U?sbWQA{8mfCs?T z#)a|uNE!SA!HaXjYHH1fq{ZXs798H^{~j$hco`X3sRLW(dC>L5%34g=1m@4P9gAID zWB&bY{QpWNCAlp)DKT|B5dHndR(OD!Gf=HxI@^qm@1}WREbtz!t^juRT!8&0#}jaO z0i^T&j@E%BNc2L#O?YI|Fg6m7(cb`U`)2{d151h~M>@FVfzInNceRc>Gnu6K0kmKd zg=Qr7HK4V`wgy-UYyz}oKI)P9IcO?B9ta#<1z?AOt*#9>Vf)2Oqe1$v@YPTq2((ef zs>^|hpQlws8Q}ti8u}P&4<3%q{C1ZPb*X!TzOvywH$jJ|_uGh)$cRWom7d8~2`ecH zBRfos5Ys|X9NYHeYv>4qYL##8GSjv&uRlg~;^puQ$*>U5RR*}&hV3R)n(VYGjL)1g zu5T60B*c0Ib?X~_IR=QfyoaFzEyF5hHR~E4slVXbx#HzUf~h%Av5VCS<=h@hpP#dO zpp|sk3{<8TWQQ$vSqdl+an-|Fuio0`mg)@#=Bb+14!Wcv*-UC{nJO(>BU~2dBtPW{ zXLW327yQXo&D0)JKxPIlGj{nY&;|Kwivf0Uu&Q6-4U`?DXRx(j9!6NyB5s(gmrZx( zlp;c6M>Ah$ga-xoSRQ{;cs}d#u^?Q>-`3$1jUZo2X7)OANM(QN;5b8&AYr6r^d~B8LXhIW!JJ1T5?r;tX#}(*276Bt-WHe5L>@H{OHxCj;h-U z(!M=l1xI!&Gk)_H3hMXJ#>h4EwS=(){%_0$Mr|`9E9I45^)VVnL=b6bj0&f5WWHi^ z$Vn=7WR0I}7U8nsFpb()8=r}rZKSYKQbppW8IQ6Is-PlJe3PxBwxn&MEyU^bmlpA2 zkk)LnVF>%cR|P}K{nMzlBbk(=pfARpty{_AV1k}>t^0o2zT6}_IA`Y6Q8V1BJyNz$Cz zk7=Wnv7j#`oNZb?Oy=rzc-ddl!5*^1Bck+3U;QRLpl2v!F)t6%a(so_Lo{vaM3kKN z&VG}faZ_nBQ{fpWvgW99&}k+DGQD|LtlG06;4;hJ(vzi|&>~v!#+VZ)rk>1v%RG6= zJvUOC9EGhABddVwh`KAY5$rabiY!(u8gQS;>dMPD&hNATvb7~K;3uaLq8+@>fXAe{ zXFX6lJsx{s`97;I8X z2@y|N`IBKsC93i2L65BfSr}0A&EV@Csj1BOP4t-b3GBD`o^jSEEY5+;4;7_Zm+EXE zs(q!-Tw^^_ex;0yx9l{XB(P5-Tp?pTOWT4hH4m!hkXc5K#K(M-&7L>M>2=sG9D1vy zJ%Mrla+1hyzxz1j+w7SX#er)xJ20OvJ=d5wSi=q2?klp!yNmwlVxp^c=I-klknS1? zkQG*2m)0u44dlwqHpeqBIA+Jp#H+Gs&gDKF5y}|ph>c9+Aj$ih%OUMTI>ei|{7p7r zc0ag=VqCXbXUA6E7O3zY9~1UYRu~^}lzJV7 zMj)@mFB|7&Yj&zLkt^se9nNIpCg$5?B7E09O8aL8v&d_hp4drk$G#_H%!VpgOcCGI zEEqGK^P(PeVty=cnH=o;O?oDc1<~C%Hq4uky;b1AqrBN~e8ZwYTfx=ARqcbzjQa9? z{i}i0?VbXyg;Z8&Atndiw4)ltDvqp6?zfH9$ur?s?z|&s1c^)Fwja*Dr9=)sv2|WD z`l?4LG?| zOp*UYMpZn`Bt7l?h&TJvL1$@O07d#ccW*7lf3?;g#yCh3BA9=r`c& zRh?-Av=y>T4skn{<2w^Np>aets++N16^NF6duBh^>hJ>d-5`>G$ZJ6l0e`guaN zr>XmjI&lZFgD&z!;g3}RigwMM!?!k%6UpB5v-G&|`XdV#L~QNv)B7v4v*XX!ezG|} zE=W+?Tg?eeI6JTNJdBO@JRBhO*qtGy@*2#}o;-!?toifZIH6$5@s+uVFA458O7)nb zCrZ?!gG)IlokppMMoq4Ha+{BKtaIG~Op`RY9e6{IdK1?RB1lz5&&;#M&)0ntPWRDZ z3Lq1a60d!C%O|@6jty){Ee(k z_%=nwo5|y=R+z25jqZv-#<^di9vPnzJ?EOUoyIt?do;tVcgRRym-}lWOb4NThtGvPd}FMieEim7EgCQrJ-5suo4>#$|$P_UsabBqT!bb zw0%rD`&+Yi$C7e4p?*9*xP8(+`Ptmwr9_3>DX*WpZjUYv1sRH-Y=80GjL10dxEQ}? z@VV{qsoWP>ag!ozG}i`%YF&pHw=i`XoZ=V_eJ>aNf&_J0v%C6uy9#eReQkOvFarm( z&U#*pYkHryyP3u{FK4yqM9Ov@J<&g_?(d+XSzMY?J=@Gs+Vwiu=iHsbeKquUdtM2! z#+fs!HZIPV#avylx1Jo>B7)ta0GO z9kf<|QCK(LIj}I-XBiQ8;ToE@Pa@S9|1nbUkwt?EE!bnioT1k}0Dh2aiL!Eii#5do znsGN|9c0E$|Jeh9Z``#(QzA*bG;n+ zG6+vP0lN|%rLc%`rx|J)Ru>+_v{bdK*jE!SwWl+p_ZJA`>&VP(wsFs9G3P1N=cakn z{!Y*?h;AxB>7+(+ntPn*7@lpDiuWJS`n=!MU?5Jjtc*_9>Kr3NkLY2X>V3DitwP2o z?IS(iuDYnk*0H(&be7>@qJ zmcHROFOKi8Ny>iHIXllfu2wR`?-toVCW5OlG$V&wlN&!Kzbf9>Y91j@(^0(TYZ6kM4d%AbEJGO*t7B z>V1BS)58oD_3075nOD4Yt<DO&$Dxac)PD8J7 zZ3-ypwP5=D)85b>7FdBm)y!b{pa=ha%H#<)fSRo7^9` z=09kJ1-ck!%Zl5a9!42?9{;*8fg#tQ)MLCJl9;$}W22dRJCINOsXpaz55yxZk(&zA z=>bhr3jX9!E=P+6yTIsA;&Pf6ce$kD&GF-8!+2gm!w)X61GyIk*S#t_YcZ$qO5Ngn zt@4tZMV!U%22coI9;_E$)@$Mv$&7Y+%uFprjoYG-L{?j0eAC9GtfR-L@PvKd3Uk{O z^CEOlCsQHsDL*`9v>Gq7kf&=+Ps+x|&AAnK7q_q%tRn7!0VRS0E({n|;_kYxyD7}? zR7$_I5qmwMrMJWiv}T#|JH@;q?uh% zRQ}tzenF<6Qoof#YMe)^>1E*f*FcXz*5}Ah2{h}v4c9d7qs$S?ieU;t1ILFUPbaT( zT(ig({K;H|$|f`95M)DeS+RHfx^epA#tN7&DbyX?hPmFK_G7{>W@l>+?_NyC3Va*w zL8E9KABYE}#;RA=t)*}KwN>g8-5=yU8ie{IHhQ$U+Uc`DAvJz?zODAB3Pcd+p+C#etl=_R7q%U zmWp&Cu+pIR&+5kXPMn@sbKa|<@ncu?38$8Y=nWAKg|W&zCCM#Zp%%s>Y~Mk`z=wFN2JMSpCp^N*NA8 z#j*&dV`pmKf6n1W8H=Fync;`326l$mzx@d|?UjypBFNd+@H`LpgsargSM;JXI8R<0 z-7@PF67j%}%u zooINaVt2(FcJ9xe?}VDJ=z5-Y<4hf{dqy#F9;a%$Fz?6~ai|*VPujeBM48WiY4}0P z1DrpFvDO<`*(=nK{5VN9&80*pwoe}{7oBQ8_qY`oKMJd1dg?V9{Lu10=Rqib67l(! zQ1zuy5wD}FuAumPVni!AL6*}c?HHns1^RU6W)D6L;ic78f&jWdH1(SE1p1siO{&f= zoPYWXn_Ax&68$0)f{ledvxF0wbIq^$sTQ2X*W=T}%e30KECdMzqYve;&b&`GY$>K~ zsh)GvyN+lUMRAy^jYp&=Ed0VIcWAQ`*M4bagLdP*6w2?UG4f#^FAY^v*+yn(qbdBe zh95P$!s_Kp#1+nWzPab{Q=v_N{lNLKMk(fUL$}yx8~gzCIfcE6+gYBTA1H-hutd-r z*}mMk`^W3-b>dsgMw&XU+4Y|a379=Y>Uw{&v;uHM3zp8$tg8p;4QhTeNAdZC#NW@W zsCLd$s1Fhk$QbHAn{qRmseE{OmUa@baFfO0i#j(!gxBOo>ghu0$tpGd>G{s(bqn|A znX}8(>sQ_mrcY7;5*Rn)I=ft%6b%hX4m~_uc;(+vLEtLlB6Rn_r&z+s_#BtC{)E`? zL4Zs0;%GqE%d=2|PC#$W-oQQ0`6Da+TI zsdb3uwBqQanm=7r30Q)%@7T@@wv8>ky%slXtCYxyIdeq=mu5#>54wV*f`Zz>{q$m z+}E1}YHy?bBtF&Gzv6-SI``$;*^{bz;xOqI_ni)MncIgm2Yw)zWJJyzmX(mELbM7_bWHO=!jSi~>WMAlM^h?)M# zpPXJlzNUS0$Llz&YuFN%gplTMo576^ar+%LFnr}|O0(U@lDE}{lUZ{kX+;6oAc}hR zi9HU<0Wgakz$_LpFk3jhWAY0+o$p#n@x-KJiNBS7?FPR-pVYo?mymq7)?v*&Q;j;|6ZtJi0_oG8L?@Rbfob)`+^HF2 z>UHT|LOC6HBpgIRjiCK%nwDCE8LE=FNxBh#Iq20h{q1HWGM6-z& zq?l+%4!|Qa$8##d6mrVnHdgXG9*(->}HNx-BK>=Q3}73c2_RAb;%<|C!I?o|AumM^Kw-jsIyqd2eD*K-x*);`ZtuN6_=mgBZ`rr3Iu{ z{kX#6LOo^Sq(Y^~47n0M>FBZ`g_ki5LezJkc1|WdHGPd{4m=tFN5I6^xnw~XxUopf zOTBx6(1rkhzm0E)nIA{zzGq{-r&GiJH~-j?k$Iixb+^0A1nq8Z-RN%<1;J&TW42#^(HlIX83q?%5qg?{WgmOwxhw>AjjB(1{W4Z|EleXY#yS$z*D5x#H+oNv6Dx#(X2p z@jxVc@FBIub#W_!rC>_TmSGfbuj|YuG;N4~Yp<8Dyc0!z1zY^_QAV>E?crS!51}dX zy2%XjHw*D3lj58)MeNHkVe%O-S4;j`$n)>Ej39OM!BmgT9qkwDyuLE@@;v$8(oiB- zf~74ER?AYGp46?a2Uo}4#%J1?MDd?;h3->`{It2DdLcI=TQ2(ERfoXM`zf@kJr(?Z zY=0s&w%dNorX^7*0ulH&R&(aZ@B30=%kIX*o()^i$~&k$OvL~6imwe&IQQ3WF5$5A zqovns^|IkraRlhmp6)hoZ7Yvb?=KOEn(#Zdi{xoqbMsjP7|d#pKa=A z>b6ys_>9gEO_ZnnHDg5{S&>lw6W(QDO&uG%iA{4KQ`R0_=WG2uVq6~>O~}$Xqx+{% zFIa_fw`3JfNOouP!$LRJ!xVZcO)uIjuBQ^M7*Vq;~Yk=116*);>YgdevO^ZI!of z+CC3gWJ~bFS{}oDM~AyQ7q2+GDjP-$;S|hzy-PkU@5DTRf>r&$UV!g`0zHi0%rTMn zJ(}I$dl)3VYZc$$98Le$tL+o2Ch{uCR!x%)*eKw3vVTxr4RxX`|H?J-B{_!5BV2x( zJicn$x>|Edbl$D>gInump0>mXGmm}fQPO7b37yOJXOC$u%gE|sb?|A(iy z4vYHv-iLiF-JMH!OLt25(v8v$yR;xEpmcY~(kUPvN-P~x5)!hMbW6jt%jf%hu8TjH zdCknZ=bZbTxn~ASxA}Oz4>tyx=N$Y!-bqt@@dpYEC+KFYVH|H|aDM7HG9{H9bAZ53 zz+kPzeUnJPf?v(44Ue5C&GhoX4+?nS4I|kBIAH-iRJlOx)TJt2pv~YFjSeC%T1y4`e>{vkvEeDo|MfQKI1{fF9uA!d zK80nj1^bqstJG0mDU)Bx)AEKxDB^uT_x*>284$xu8bMr<(WbY)TYF|B%{>{E#V!KUWr6b^R`a;oO`0Fn?Hh6b<#@B~y&+ciNv3V69cm8^60{kcS z9(UA}*r1GS$@7@wPZme-%1k$=a2PY22oe0o@N?xf6+67Ihi>ZB+nev@OQWo`j4nOD z3@0bE6pTHVvNN`wG!UM{w3W}Vz>WiC=LRk-@tGXw9>Tgp^4r!|$dkVPx0uYLRX)GZBDM49&!3puXFOBz z@hq?D_}t<9dnlN|Qai)MPrurkEr3hkCFJ0t=5n6%;x>Q&e%!bBvh}aaMho7{tD_b1 zOaIWGKUn|QfL>w#j|Z-G4+NIgR8M7g?Ui{5{eCsll2FOE zJHA0(7q^lJNAJmvl4_#`)MaNM{uYCayL;WsnEzLLVtzw+r0iUZ&~NIB zV`905oosnVVPGGXs9vv<{nLFBiwy9Eca(LD<;K>#-dN%Y?jO~KgYh)^S4;@w8EOU- z`7KuPDpSes#QICN8MTNUw6cPJ?h*~I7EJiCtpCd*=$H}nUagtu(m{Z6tb>rK{msJO ztnvq51z$H>Ug0N(h@ni4_-r#=TgS0e=d2ct^4r=Z)IlF%yRzhlZr0gJ-Z$@`9v{vF zJmDYQ#uyIuc#r+vqn4@CvVr0fEM5{ZP7YFO+2rHD_dMawhU}~~! zXLd@=pqPfMZcheBMIkypq2!JfT5X^S%rswq|GxgnzhBlppAkq~HsPbB0+yUndk%#+ zXc)P4SPdD=YUEdAWX{3UpT^qyv9`R&s>>x0L!y{V`sWw-WsfGmXFsPt$CgQKxrMJs zimb6!l8p*XKq5SI3>(3D<}bX!#o#mVa*`RnTgS0=nbRH^we=YEtpdAUt?Zt17eh)w zP<%WOVa4OQ=uK&=cz;TK;7gJ$zmVa!~cjiseX(K<|#KZt`bfS)S!Oq6C$l z<9C?;tT5`}fmd%4-o#Vtj5dZ(iMljez4YaO{wuKLM$L@-2DYxKgw0-BTTO;EcvF&a za^cC;hNm|YHRYen_Fhh*B1czveBX|=l&7|R7_;1Z(-|qYlmIceF>R`RJlCfpbH)lS za~mvAIgNF`AAakm(c|cZCB~1ayhr@z<|p#!F>$?;2saD1-dv)C3FpnshxRMiRkX)> zKl6H)h=N|$cr+g)#6Zl@Wj}Kg!EXoSuzs1VOGFQr(ok`i6m7W%g#4LH+>Uz-Z5znI z?2XbJGpl^pIbPd}s=0!sMR_?g+cL2gw&6{PHM25cJB>W_rUpxo6Zj6%qymMPPI2VQ=2c<M*tH1e`;p(1YTZQW z7<9q5@8KVSM;RQp!NQTTu{YjEp1u2%HAXEG^0&zDG?6^8f^!G#=aNrm65laHS&g?8 zFSp2K>&~Ht;bst#{S6Jmg^aKsU4us$ACj92!YkbO@{0vL_a4+u8v+as(8RD^1qU zGsg_n;cNY?Ll7Tx8kW+JMI;0wx1ACVyIFILGBIID6M{#gr{p;TlJE<|sh`n`oSgC2 zVpV={Kgh1rL?$Osw_7O~xJ=k4a}ZTp?0HbdH;};#H_CZzmCEJZpn^7bU68wa;!x=I zRX{91k-1D%tN+U6>$`UE`&*+ZO^Ob~=Kwhu^U^${U#YAbC8p?Os|R;1luwHDeX?-f zZDbf)eDd3pc6k5CQh|aDRKW|mSx@-1QBe!))sZRTf)icvBp!(#JOOEi|0aglUMqvB z3{caP>-Ju%kWS_0g#V@ljJotp(!F@(3Q68moJa_P+Nbz2Grq^kjlUYlmjm;dU@QF5 zJ4mH=_vO7EP3~!v-nqqkPVEY!LDJBe-@11FvN{8lEZW!#v|ya|uvfQnv-&@3-;J*_v7Z*m3gHo2Yj@25~C4G}rx) zB_-+Xz{x)JTS`rRzY7%r7tOo|&(8QNY@_O=aoa?EOOCB~MX5^+I z0>Y|VfdNWoxGB)>eR({|7F$GgnwCS%75wp_`(oDHQyASQ4qj2xtWlY7>4Q%B6L47jj6=GyRNZGs?Z;&zls_g}vx)l3VJ z9|7A&o~PJ>-(l;{+zyd<7ov~=Uw>1rJ>h)t`$dUXR8NZvFm?#8I#m*fH$~}{_{@&? zVemF$7u#w0)Bi-frBqO+>y?q_Ow&Ww`*Wf8ve8Mubo0CeRn-&25}hue>zB2R`0;>v z-+^RBO=n`MC#!j@m7k9DqT)DWCPj$uX5ePAYgRgbdo5LsUka9EfeP;AJ^}UC7@znr zmC1h_FC%_rhOHTRv)9!-*UdY3qL33LVqzySPI}HOd!3TjMZ`KR`n!I; z(>Te)J3HsnLl-TJ|0r1*aSWhOB;J1}*I|SuM>;uvakV!f^)u;nhs-DR9kMIdu)U?7 z%sA)LXiutEG7jBmlcLbEBvrepib*AIroeEqk&dHVcRKa3Ram~5D{bWMy;lIVqD3S4 z^JfHqrXL0ocyMR6yLZ9QUC6w#F!0L5)#oa0>-^PNg@m;g5%8(pF8sOZL~H<+g+-Y| zKf{i7C*KN4@5I4QP(TY)B4{!PUlFitlS@$s!|OYJ6OK1D`U2PIlTSH9hrTXiM^je! zUHxfK&)q|#`!f`o6T?!e0Sncg=+v7^&{fyLO2 z<|4;wd{0T*4+%d;F^&PX>}O*4EJ9*2>NO%x@TVIR&H{S5xn<7-ApiYb74it zawXHSdLc9LL6xaoPrn9=CnOpq!cfavDheh{FT%Y377ED3knlRw-khayM4+^)T2P=Ig%OO@liGMq=>WN7vKV!Tsi#_)FALA z=hbrJ(K7v0Uxld`V`VI+8nc(g`oAGuzna!T4GR!sTH@(dd}lgZud{kz4J@l7LrEJ( zmeYuo0JoPX(@=dW^&AKbwDh8l{)%sZS*;9~1;3|5CpTa`<0HNHrf0De>3gQS&{mLC z`Fr&NWIlJ&EBOuLUnF;MTAGi5nAv4?u=gus{|D1_dE0RHxmcZ5>^By1^4Ub)5h4+L zG42h6kpC)t=w8t=TptWwK^6Wu74YHU+1$75#&i_22*01pQI>E&aYQ)P^Bz!gNDBJ_ znc-aC*)(5XW=yxVC{9xOK481S( zJM?aqBKnmPu!~(#M9O|z87$8U&}{(Hx^amdY2DepkJs+Bh~EshNqWkpn0)$oLxYDd z4;$TYjQxuUN2qmUxkO49jm$|oMkP8@B~Esg7&>y~SJxH0Z2HSO)w(1vm8ycvz#?1w zW!W7HW~WOHiJkY6x^?2vdbzh;n0h&wTW$Gp{wa-c6QZb4I%WOQ8!=%Sg*TU3Dwls5 z>3UiT711{OvaPaI7ugPM&h9H_3U))OWq%M8*C|Lb<_EosTiz^l+ia}8Du-p|dh&Pw zkJ8Xb5s~|5=t0}d2IVTZ+JF2Rtjpa*`KJ83fFDL%ilKp#3@O~*<@ls>6~h6e9UtXS zufWM}Sn!jG^7%J6(fUY_Lr`CTg&5;pfjrLgY>x{5xkqt=_pg1;(I-~m%{enji`Tp) z#@}KWDUCrIbA-)@0Lb+=XEV4GE>uZ=vs}-{F<5&w7jEIM`ag|cx**LmbuYrmJRekK7eCM@+7sZ{7LYd>*<7ENSw3!m?3 zWz`WqyQyddhH{YLFUi%ZW@=}YZk*aWu!@<7F$k-Wos>t8J5hmI>RiA8ho?I@?02vvoX@N@`vIa zqz7V?V7S9GbrH|$Y(RuP!%-HEQUW>$3SyVAQf@0VIs+bMO_Pt^s`$zKiUB7SmG zS;eGgVXb7j>`~;w_~35`o#ejrF_;c3l71VxkxYgC+%E`m~SzcQe19%@}2q8WWk`Ihsg=v@vfg)p7|6JRI! zOhuP~R-_+l`&c$~rw78FbFR7`be!AL+x{d$N0XMU#~KtD4P>*<*kyi~Pm0RJ{nC4o zd4y{B%gZQOj);{Q(f@X7)#anuZa47k4S>%2ez5ra2d8CSOC?0A*C_5Gty4PP1F&>a@GJy*mqKZSay&eoe+W4!0_)u_QT0${-DAM!> z2ye^5xI{fF#l1Gl=}W{L`vF<~_1Lmq0{TxCoDm5BDy2;?N0dsQaQffa)WmPtPez`N zq>734O1u^cvXfFq3OnnnLMa9GSDlJb6-l1 zbHHcvSr_!VeRe2sh&w(qAlK+l1ZR6)J1s8iK$V&F<8P}YLd{}XYk^fzfxVv*pIcYo z7S8?or#N|;?#wHFPz6`MKrU)PYfwl_bFaQ@C_nGwE-v^b#k=Li45+@Ri{{R;R4K{k)!6^dg zo5qT0l3I3U{tX6UDwFrw5Yn=Wnd2aKXm@AaT22-X0%tr&}T{7X&nPqYZ;H9fA0 z7P%lBuqr;Tt%BLQm6;w(EmXh>h<`pyPZ7(!&*AOnE^lTT=kN=nCBa5GJ6Z%*QnT(%2v;z;Wn@y|!k0RcXKDP;^uD+(kPK_Njq& zkqxBRRR@(E$T+u06tfnP=}&EOp-q-cCPiUk&|ZWzER6>eE;5P49-y66gv)R4mPfw9(YUSTJ(B|YQ)FI(MD6e(Y#k>D<$lOYl| zGIRL)({090*tiN-Fc;xdrPxT_*i6*eOg2-U4!K-AS?UZwVm-;$)bveAE@kU5pZr&7 z-?FiLF%1Hw#1svM(852nU8$Wi#1>Z($*Kp6&mVcx_Q6X>Wq;XZ61@dQ zsqxAF>=SyqMSpbT0G)E0brf>0=258Tl%L%Yo@^|a+b-lkIq(7B_Qe2owu5mb1I)Er z@?Qh6{$42B7#ou)US^y};&PNd6yWYopE&3mwz z@JN}W+;s7cQY;B|Q>>FNk|vwpXYtFAKbPdQKp{#&%S)^B5ZrVo(_`p_@hug@?V zHK_NBu2?&+nWwaZh^oEGWXwv<$joH>SjydV-z537L2SwAh%JMD)!)E?=;D4(5R!8= zKK!rJTaFdSS?rZoFxlUDFit!AlXr0c#Oi-5L7GYL1M@<*m1o~}w(x)>(mG;G(6p^~ zqN#!mfKG64Yo-DNKqmm1F{*PPzkCCfV1%9hU|?r1}H*$k= zHZd5GESpkIj1ee&ZU19rUQP;1Xx_zswNh9njCJuvG`uU!ohEK!Y4_(Y>4w#tyrMmP zLr6qu13k{m%95cCH>b!-)ZiQB=TIn@9rGc-U$QdqHTM|u2n?5Wu40~^mLwy(i0i`cTU=)}i8||itJTyucak`thM4 zCYw?=@QB{6*@Tmas{vF4bw8SIt6$xoq0}%~ien{Mo-Hl70_XCHRvSB#qKD&A#59n! z)Y-cn3f`<6k2D_QhlfkvK1fN~*c!&dicCOwf~&9of{gx`q%XzQKIkH07Xn<52Ui4Q z?UGAM6oh`6+}~>EX79U7wN2T$^3qFHi73Cd?Ws3|$}YW4X>L6S4vcn@NK2~uw+q4w zW+3zX8=jW6W(M+BjFp8t8lk6X)IGnbpR@Z=^(ALD=yt9)z%M0vLmmKMeW_c>ZnZ7f z+djG3l&(h>?q6rK027_Ztz{&AO(hME=qH6L!QXzA2@?qU{=UE9wDq)CF8gi&lZJ?c z;y*?iz3PW4FyD#D5&r+JJ2^qIE#*JDn!u?}PMuGzwe>&U8rvIwti)3Uf~tlG=S`Q* zsv3WCvechG!l(<$u;!~VW8dpnV`jRaZ5;|(t~s9CI49m^qnmcTY44I6W~D>IEmAIs z2#_x|P$8|NBKAGYrnDX-ucs&W4B4|Yj|0!`CfY}}W^9!R<*ylU%;$5Tohl}GP^E=Q#jepB1-xHt<-he=EfKV?qH6Qf5dz1y;{ z4|qP*YDwLMz3&QwdE(&UEG#aHLO2kltTqH3HRNY_Y$FV63iorYhnBU>Uth9BFL$qQ z9$ku!9{SG6o(m0t5`M_doQ@x&`H#n^y?7W6yE}*7&}+VY z&xYwt)MEmEp3*YswsU-3 ze;{)dHMe&>L%AQIG0yNBU~4@|V}0ik{0*bP4=fwQzu*!lQwcwxp?77LE`)e8&a_Px zFf;Dio_Y8UJ&pnt@GZiVlZ3;=L;iMp>oMa-gtaR0k99OC(95+F%6q1#>7Neg=dX{~ zs?T;~Q4YT_fOnE}GL(=^yw@8kz1?c&ukQ_#FSjV3?nwu?M`eWe(xJjzZav`OHHBL& z-{VzVN5|d%9SOgaA5nS;vgv!MEK{)IEv+02g(3$%jl*SW`z_`Wvty(d|JS`Yw0rF^_-2Wx^A&c|M2i|c!~mVwNniv z`CbcHTx1dx7w@D|Tf=p_7W^SL_}VE`oYLDQ_MAgAb5PXCNtDD*u(iu#BRQU;niKv8 zpnLB>%^zh9a%duKTJ|INlL{GttDBvC-KsgwK+QDU|22NEBj&xW|6op1;czmWt>Lz2 zw2k|{ec)KiauYuJu}gRPNq5Xh5fH0}WmR$5gkr8ZB{qo({@QA2XlM?e1RZOfc6a&E zm08N<3y+-%Dgy%p&AobF7y9d~yY;2Z?Cs!%ZlzueTjprQ;d5H4O&BzBR{NnKF z`%m!yCOe-P@=|k6eF9nr>6Qzd-XD$XKkl|vEnCzPDv^q-d*Hw|ge>!vvsOw;$d7Hp zMd?h*_wlz@hn}Kkmhk|i|4~zKn}moj^e8_Y68aRXYroxu*Uew|39Fe|R+zWi6+7zJ zkBo#sKxL6b?0vwAmQXqfBQom-HFDV&Dv0D1&abgdrR+4BxBTt`m6cJU%6f)y;V~Ta zLxcO5n3e_Lr943*Sddr63ZIRj%B?!khA#P`HAb zK=}IpAAO7Po&dMsrx6ebCjR#uuf#1VGj}C%xS$jh;|d5sBtVb!wePta&CbSBzWGK@ zijx}T4JVV9D;9qSoDO?Q%hjXlTe}I)$5(`E3?Qrn$Z}GQ#pVKjAtB)Z`)CmUr_(HJ zY*9K&f!orL!2i3u!}^Hlp43o6~K$Vv^g>zbn=Pttr0oxcqaoNT+z+}2SI}8jGIQP zBqo6MOj<`H!&?MSv$$8^@66+i7Oq4@-N#3dhE{-+xG@M44b5la6B*O?@*9>XlEUaN zh%bmU3UHbAXL-v>nc&lVvz*1YAvywJweP!=`j14PYqZs=(aA%B znn#z@P|V8L>ZuZHgM{Z%GOR^nF*;H7wg`BeVXJ1yOTh+omE@7~?Xd{szuWB6Aj@fg zQTeg6yZKtRGBn!?T4>@li|D+G7kfFrVIC&2XaeV`^0W+EI>#CW!?>1FMf0Sa^D7X^ z(1k!odvhA<2`~C*KQP;A7HIpVvqm|^-MVyA+uzaJrdV`WsvW1Y{3eG0G0?(t{_qQ2 zTYanX#zC+u#s7{+H$NBkK~pFjpTwghHvY}O*N?)`lfKmxgw1>9-eL>cDjm)lI5e& z8B7Kwjmb$_`+&VcJS-hHbAZa9Y0?bgZPJf)XvT#Ki z5uYue2eOn%pQZ1)ycuO{$F+=89zm&sc{151x>=C?-7C2@Ltx22fP$z}P};U$^<>wN z_-$|oJon{Qu~is|O(K#0BRGybRQM-O2OAj8p1|?BqG@#Zi|R0Ea=3io3Fq;75EE zs2uk9>iq#VbFp!<3FF*SH>P___RKNvfUpxjD#5xFCQ*;_fEJGq{mzZoil?={ksCVD zOGT>S**!+#dWfKPO5h#2D;!)hbc&THkw{Su%7zBzuk?j6I?q%qr88l{3U+oczd(a* zk@5fA84*#|)@b{li{FtmDW&69>t{d$sQ;hZ4X*SXmN>Y2nSFQCR|*klhfzmb$%6w~ zVR;2|E%VmjvlF*8tb9e!q%Be(+$P?Nut#eV_0!FIG$A7~4HE_}a4P;;GrtP_M$akm zdB{8j*8vg4=8Mq!7{C68E4X_f4kKhKKF#8>d@S;>*PxvQ;{?1Bd&tRlzNBYvMS9o6 zs*CfUTqOzk%`UVZ4TR6_7P@_a%hw%{m1sAT>uvjCc*^PHXG8{X1<&9)&re`49`CjN zTjy3N6J`<8`I)^_Vu(CW$8JCth;0_Slbhj2(E5FDCp&w@T^i_Cjn<@G z_9zVB54Ik&EyjST`!$yZ-jPus3oh)=|J~tL){E(8Awq87`XH@FXmL;)BZdBLFP(um zDZqB0mPLdABaC062|WG|r&h64gZhvy;2|Y|=ga-=#*aEFpK2b=#PK|Y5`bHhCMpty z+njQokFJHAb%1N7NGGQdrN~&~V#8fJ{_hT5JX|z?MQ`sEI{Aqe8rApUrkHnkdQA!f zW=>+z@;*px57vm8uB61bDBf>t{)wiHD@l7Ul)O`5M`3MuusGm&I=2{G6Z#E^GeP32 zQWnI!M|%;O1+^|*Sh>5ll?x^^vfPH{k7*+@X|?bx+9qO9B(z2%X$^%(jN-u$!1H#5 zGT(g|?0H?1A9MXZ=+*vcI)v<5pI)b>zbJ)uUzcy)9bjP}yuj!XlNK(J#j@3-*yR^= zQjlja&bA`^XP^?c2{Wt+dok(D{{_-HWb7bQghDWf9u$`HncX;I0T&wwrMHI_lFoP^ z@BWge25o9fB>g!c0sKFfb$kkb5Zx|I*Ld%kTrlTk9}mCSA(BEyCX{7V0`6D8sJ!*2 zgB8tJ8#q_zAKMmJ@I<+Wz>37)-Mj zUE`n(5XVu(e!MsG>!ul!Xl_I(%-S{;E6!%@{_Gs0Jizt5Y~vz*jxXty^g+P>y}g%J zqg?c;tEkOagzax8ZIz$O;SgF_f@_9Q^YR(2ZGoC z>c6g_r^7rEyb8_+6*3UAq)DAK*0**H6LjU+Bh86yj$t#L_mU*%GE2sMt0M70Dbj~rk zwG=1(EtwZvu`YP{qOIK-4a-9gbL*!;p%bjkx(bZ27R&0d&1C0KkAo4RarPpB`rpGt zfzcw}3)uZ|jW3E=S5TtMPniHv=F|DH@b%2(t2~KObg99_^Q}w#8pVnA@`?4=R<8+g z!c~vha7&+Ka3R`%I4C&b4c!S1vqO&asXO7=|H64QLzMgLq|EKCO9p7ZYb-8~lE*3@ zc# z75>)xi>q{S#dr3THjW$ouPoxQJv7I{T?UO7$6(&zW-YjJBtQ7*+=>G)P?MkH?D8_q zL~`S;HY8hqQ}!>`t2RS=-+JjXM4Z~jti;kKv+I>x@vO;hTsVmV4~}Z)2GOH^a^~O) zy1T(ZU7-u^O6OC3wGt#}|EGTIZWf!Au8OMRwOSN(Odc^*F25v0a6?n69m;z;X;bb!|=e=&zWQiR< ze?h<8`Rk8wJ{SCW2u?sadXN19pcG5jwto0Cbu0yuPeBl)_5wc&4S`-(2 zFSG!nQe9Ja-n_8icc@;dqW)Q5Ju?z*RT?ZjRo>Jt zaUyuK{q?g1L7ujjAMemkxJ$wbgW5HN`YNaP3t z@i_5CQ>1J)L%P0xjDCO3`OcH4L>dELo+fQm{48L2^c}vY8~7?Ct}hg=o!0V5e7#c) z%-h;X@CWhx`e!K7F|h}c-IJcrjhRLO0zK7EWF3DM8WURhP=PkJS${n!BcZ8rDRrz2 zD3}LI**Hs=2wzn5K+#BBEQCi>m3VY-`>I)W5+lUtojIE-Maqpnv$9^Yo=mC6`tVz& zpxiPjHF68=`@BU^1v5K(xhkCCtH?LnCfGfq>yMgYo;m}(CPcMjMivo{%}XM}w4-2) zBYXJt$c>sWWGH)-B1&+p1MTAnOpk zx8JkR!EifBMp#!+d0KOETajnx_$z1{J7W3@1AG<8Vu)zyNwVZ@K=HiW0QkA#|9*(R zgJ0;5tmqFhpvrHbwR&gW1ciw7+K)u9r1W*~Y@1;F%0`PIhd3 z*rK|=g#}A7?=Uo_XQ=VwsnOTo5)8i}bm#m0m}IlrS0X2d=xkP<0AJ_Zi!p}_)`zM0 zQ)-h_4vew=42gR6{Z{qbnE&Lt>u;@mc6!DbB>4VI(82teA9Y7Zh|Wk)cqAb)7z{dG zYO1h~kOW|al}mIu`S~>u>wctaROwmS2=Q*TEZPe?HXjL127eT`jS*$_@r(5T>`WZh zDZLPRGS!s?LXX&R>V^fb{zO?hJ|{~ke{HESF;Ry`cS!VaE2D#jsU&^%`j+na(=-0F zA~G=<|A?{ zrPKW3w#w)$;$gii*7M-I?DWh!lbb=}-linkm+4#_701fb#BI$n+vslO3 z=k=<%ze>Zp8iQ9Xdm2>Ow_CnBui|}*U*#fC$H6bGna?qwbJ-iZCf->uFD+7>Vb_Pu z)(}`Zxv1pVY49z6*!kxyMM@Mldnn5N8JO73-FYucsqgQ#s^j`=mt|n6W`nl{oY;Fc zNlY{hc|awXg!ho_Tqt7m>LMvy4?rK+Y;k^HX{D=VXFWLjrNT?J9DAfxQ(9OzGLN z9ov8>6 z@vVkJ^o>BTiRj=Y_OJvB#Y*PsFDU_5>iar86Ovsj%}HmG$pUlDrdRA;f6RSzd9GWC z)3S$dI!j%hW!Ti#{|!e#>Nns#%Z)&L_tA9}o>#4ZWhOocQ_P^Y&pWW89j~yHl>ylu z%5PvG=$sgs@4NsnWLj}yHqo0nk{8dq!0n|W$JQ=f<{GX@hQUok0n4C5%5WLXlVu9R2g5y3&09=E%&74GLG6N%sLXVO^l#z_txd+qM+ z*zQ(CF4!N=Csw%`AL&s*$F|l&4D{B_$_h&e2J2^Y~qL(ekj1dzWvdw4Rvw<1zV@b z@wWm_wJ>ZA^YhEbEGVem$_qW|J+-3%eyw=V9kxqBY-{-?7I8Ke<1%_2RGK92tEM%Y4Dza+dGM~{nIT@LqWT(AIwfBDt5fK$Bt*okFyDWId8#$y?gi!ZXE>OjoNTe)6o*9w^sjwHqNKyF2qu6TI+x444s?*d% zj3ZM+P1Bx<-s1_Rpszry@$seymBG$BT}(yA`ba@We<2LL-uWlOQH`ww6$H1w>}!_h zK_CpB`GiYf>hcXF0#{#?i|#Qun9Xwvb7{eQCFQ`9R+x5xt^<+6wpV2C#FUwHrR)+=4@!&fjE7g@x`{ueC%_10|C){69 zUG>9i<*QN2?PT%}{7NT$IfdWfTqxcd_c+ZEgb*-%qa%2e9N>B7d*Ni!59%)Fl$cS6V`DssXNV0K{3m?qS0Pg#{gG_+J_>5eefmdBg!$b8;#bWWB zihs)E6j|h}9}(db5Y{!!yi!_R%o&yp!QVJVN)(LNA5GVqX`crZ8o9n4^&W>7ZJqk} zomWMb)}py;%qae9`da-mo1FkcK>y7(`yBgjoUUz~5q8pD%!T*A#%#*Oxcy|_mv?F+sL^BDz-u-n)bae zSudfvGrVPkOt|@D=)7F55j610!-w=HVi1LpmM8!L8k`X(U4>622=OVu#I8m_FuSv1 zJ1gdTsIT4qUUyl=Iy}_wE)3bv4))}(sy-7FB2 zp+wSK)Z-%M8IqmJ2`$|SIrSRJP3CQhQwqFvke!j2!IOr;k8=x1&#~p@Pjm-@S~jm#HCf{GESe-CD^UHBU1CJULiR*Kx9r{ntKrcBNIf4hbcb z&m~PPt>d(59TkZO&$uMaJWJ_&%~P?nsXN64_e+QDZcB+;){NM7uk8$V)zTR@U(G?H z)$@y+5VDy`9wnyZRc>pAXOgy(^~&tCU0jp}_L^_^1V zun6rIe~1p1ajjFHOQYV1q{6yrUhnBFe`btGmPVVW7|e;ht<_{}c|$ZSuGLdVyY+~5 zC*loIMc4B;nri44{HPh8QF4@jn``)p+t>%;4;Fy?>)(X%H^Hg0V<8pW_ZP`g&DbtZ z3MF^n(`aG%hV*<(j}E&ex{rMf`b{l;#sTw~RqU~b8-dvEZ}nJbREDh<3$oHeOO*z5 zsN+wha!JVqAJm71%O6y@pM$o@QmnR_($OaH~ozfsd1GjRU6QpEeYb=YNK7^njL=rG|& z|C{m~zy`7Q2*wl30**#k%Rsx=xwwP(Fx|q+cTKIE`O+5C-x4cc`*L2 zw8_(yK(|Hh7PY=n^{Z%a%x@7B(Dz@{G&~PP56VCw7J_dT*la` zfmpG0ZqY>Mp9+IrR^SI+=c{ao4?sVaku_rFhhxKUq{{(DL~GapwUt@XqSF zs(CljH46p>hE$#%Ud4%I5d|T2PZ| zHCrcw9-o%W7c&Vs*DjHq+D=HBANgyXU9^#MU3;}D2o}jM%yR9IqX_&NVZh)C^m8BZ z+VmCG1jtGP-_&{=!*#OoRWM*t6K-buPW5fO#mV&UAMgTsP7u3C;Y-z zw#EX7)%8w}W+NO#`4dOi31e6nc8cRhm7cP}){1g!-G7t9Z-aK3FVRzyvCX`K5z7U` z7F#YmZTNzXNL5GB)HfVt^0*{kC)MQl%6mNbsh;LX?18P zAW}t#%pX?#HSLgTmdSx6{(b(Bf=){*NJ(*c@PlKY$drj!ux8vqc6Ubm-X3wP@5Hj# zmjRdl)m>)Jr+~0;8;bW1cXwCEL@}c)4;M7Qg^tD$Id2E&S8<%LG+`q;857JR=~>b; z;klt^nL+UzE5DJGr)tqWHy&L!yAbp8_I6P6jr4g$F+(tOGP)*-yydFj_}hpJAx-pE z@uL;?=4ip)st!xvXu-7SW6Pn*>7Q;_?BLBkFLipyCmc6o(cc@mBj#1$)wVY>^S zcMH0$L2+tz$qz~Jv!qzPFHD}s-kMVe_55E;nrz6B3JQ=?A?e{8f+a5f zS~@6q&P0ddp`Cm(tnmM70rpuDmnYzu)fpQu$D$Cic-;BP?{)x+UyaL}jmjb`5o)bp zk>>lf*heFNH`dc;@zmCww4S^1Zy4?Pd<|ECr95Q7&0fII(nH{%NQ<+EO7iLLx_!nK zLMD+hUs$!`AO-V)5B`VE!TBw4X|o!uQL%`%W0oOiBxHBUwQT*+jb{x~Srb5RjRMWm z8*^8X*I^iJs{0-=xoUHB73C=-e;;vL{^OD)yLphzTkEJtXc=LL?eX0# zBNam3TI9lj7KshuRo1(0+96R^OUQK+@TLgx&9oZW6*P;`&sgJpir9>QSl0Dx4VV^e z!|_jKu&vj7qT9(^vBG|-SuCu;?XJ_X@JvSl_$qBbhAoaV|M^<(4wI zR`e`E*G0vwKIEEz!REI!M|WR*cm^`w*lMtE3+p!PD%SE$EKBajYEYfHQ3$vM??)#! zEbz2?QI-7WaRj_QdEREpPQEHqrXc?Q!E-GDn!6Fw;ML*U_Nq9GWkjU~(pr4L^DDvA z!tfj3#{`C4TROxjX)k>6J6u33a^0hlc*|dn0 z7yy!Y^9k9WTETfEHk%@u?T3s)Z!>^&?h}f{_)0(`wyMj0$u3J@796-aUn8Oz8*%tH z6k~2Swr#&tJ+6#9R`OLdZby&gSKrTsb3=Y9rQgjgRhJ~c&iPCuCLER9l@ni&uCic7 zFV*6sNS5+(^;)M9f9rjLqkyZ$H}ZH1NH3k6FHeWnn441l(!{g-f4zy4dbHWAZ1}Wz z2^N7rQ(pOG=KhvE&g^bDnuq>1Iq|#?QDetN?Udri2@KBT$*e6fnd-c^vT$1u+YQSu zdTo{kD=xI~$xN&k%#*KPQ;SBeI-=bTJ{)KQUJqmxA~Hf9S1(p6={l;1#H-vzqm$J# zX;ufoTb9xW$~RSs8x_`itq*b2uB!=$`(H@K5Dx3SR9*sjPI(hZ6nEi6{$|Nsmq>~# z6;c3-P{2HMSW20(BYdZacIW%DgN@x~(*C(t@eXb8XRSOdwL-0ixmw$xx94$(ifd>z zW)|sN88m0v(;Eshl9OyxR%J2&*t@=-@YVr3*7JP7dH4Q$2tx`^1^c)j%iFt<8r7sCJ$t*63f8w`Ne>KB78l^(DK;_Wc+NV!JY}lxI8L{hOZ;wT zVx3nvCEUlwl{lMD?%EZU9`NO`YXB;_;-!|Pbno$<_wjN--SfV7C z{wjP=fe-qPCrtUB7WMz5>8k^x`kuG(ql5?ol9JL5(hY(%E=a62DBazuponyXOT$u2 zOSg1)NjFO_&CuUZZ+w^o( z39)yOGY)WG52m^$Rw-TY)cI-U85}c334YG}evfT(-%$qEw>_}Hq;@*2vluS^Sn#q^ zpJ4u-toxS0z(M9)uu}M&_tqb`5t44%myvnmgt}g(JBY$LA!uN~6Y%IT&)ainoU#5F z|1AooaGn?iW4R014T&kot^LkBY?8?(->BaG7?Zb&y+`z@g2MXVhy7=y&oA1jhiEy9 zS-C3Lo;b%A%R_=RuMiV~`iSkbg}vr*$%P+Wn|~kl;>T`eVRCjGCe9G?+{?&?(o)jA zs~}tVP9{=apeNe=MFa}n( zXoi(&zTzJa**g#084n+F2maR~zY;&ARqHo9Y*3(RM`>&u#$_MNSCEw0Q2mR6&wj6^ zqhVqslk2qEQt&p(@(V*`ot)&;ila~u$c>q*zkh zX97tgfX+YQ2<8IW&3>Sg8nNa5Z3FTn0i`^S%;dsTr?-`4>T^KjuV?aqD@|0Z@3^ zX^&ibwDLpw#IG7PYs;mjUpx}s36%!?@l?YDwaZ3DgAD7*=^~=tYst(B?EQZR<4zhE zKDyG(z89~j(Q-Y~op4A`5{>UjJ|3#R^AV2e5$bDe`Yczz2U7pFgI34$Xe_0H2G;}O zO*1siCxX+HL1VI8O}UG$4j3;F^u$*WbrSpB#^d{U4eXL?zJv+MKZLr*j)pBeN8P zz4sdg@fh&a$-rYmo!n5|XEyJDL-B59R?e0A!kBEgg4XidWHRVV}z9p+5Q zz)}`rm%yaYz8qN#uXve!43L*0`C6(r&kC%=(I~u(q2}Kxk zua7ZIvD;$Zfn(ac66qT_(m(`vX#VS6qd%thrfX3r?Og|6InV zB}Gp}M$2V#i|1V8!7MBtIph`8Zd7Gii7`nSB2f(6prYc@V}mmf$gdY@9UP zi$mq!CSBBQntg_}F!CWG-j}89#A-Z_{u=%(6jHMeRkPBRqJ@GjFbrxqEuO}r-z~iK z{;G6owgoVpF7lKVPXgR_wOa{Q8%0H;+)PJ=WN~AEj7WQw76dn~e8vtwt0Vw+BNPhX@RmrG18=rnRqVIsFc> z;J+Iz4&@j=mnQAQ;ti{#d&c6ln<8CyXg zImFKkdefD}(2DU77z6->_gnQ8oeSx-!yGz9yMNow$;7=lH!}KVKv)fUmw_Sg%B(4; zFh~J$UnUx|U!JW6$(burrWY6Nyu;#R7yiZmSR?t9LF~$1PP~TtczHXhe}4X`3CGOG zq2_a)-LX;d9*F%lCP2e;y^`v0uK-jGUEI5DrT2tTWmtgM_MNe`p8J1ZmH!@LG-UqY zsQ-DX0DFsH+4>%AZwll3i=}Qf?goa1{QQ3DR6V+*LmA*ot9Eu zm!t`BXh1znS;Rw4JK)Ys-!%P9kQdOG{-=R$D2gT80PyRhG5wuE)wX|ycv*IW!1=gG z(25vZF8-VLZsKQ{LmW>*<1U=DX}Vaa!iqm#7#|%=1p(gAH=YZ!|1{VQ#dVJMvNrp> zm5BO7atl7nGK&Ylc^ZPN|57d7!s4Qrle4v0s0CBQb-am%Y9@(u-svI5d`Ku$$B^nvgB3Pj46`xYOnLXw7eVtcIgPde*m-*>uo+>V&dKNUc~!$@v4)v3_PBU zC0y-0Mc!Tw8%%BAiI!bI`eo~~eiWKNwzI)PRF&+aEm-+z!3$lK?kC+??;t@hFaUOW zmvOgIm06&4otYH|If(ah3NQuU>){4)S)4EXapN@qvtC>MQBmQ<7nTx~|Dve&p3(}Y z2+{<^tuq}4>QxpA)ceX8$_9~&KWP66+H)pmbRc=sMVn7LTpz?QjT;#o z9I{@(+D>yR5xg97z_$2ybhaK|_GRQcEmpiLGdV~t zd$-iTumLD@rS){*9<8l?S1slv3Zf=3?COpJY zsN22~Uk|$_8V7O2NlwmAdJK;B8epKW*iNGI z`FL2|fO>zD_X6R67KVHBUU-wD>%8nCq7KUyJ-S|!08$;0!*#XG9qoQ6a2|PO$d+41 z3Ko;N#gLgNQ!#6;FT{DorVY8sesL}~ymV{SX>OP@T3P3inGgsZWYYVI@Bpg#G>O|I zip3U@)k5=c=;qjkpux$uikTubt^2w~3z`cffbYc5jg1*!!ua_>d=a2PU}^|1p6!D>(pCuV%j{N6zP6$e>N7*mHQAd=V(tsaIOl`a8j%i>_8>X7RS?$NZb5g*l7u$JV_hgINLpNO^?5B$Cx5 zM<`(H_m0-W{qB#f&1&Jp=4t~Xf=A(-lff1&U*ZgE-FJWtkR*mNhvwlnJi?XGDcZQU zgYaf6+xTu5C-QaTpFzo(yxid0{o7fihv3+mBunbEG)6&8HkaMBI0NmBA zmNLD@=MJ^*E|$p61jCw7EFgm>tc&*U@Vfivu$`Hs8)B|Wjq^3yWo5x=@GnowgGJss zOS?W}57r-iPaCo-E%;k_QRqyXy$(p@oy8L3q%+yh?e|fJShp&X*Qj*e9N{PfFOA1> zkbbNj<-&hH>AJ<@-9EF|%^=uamHx~soS+z;q{ zg7ZiBLD-*A@!5^$FAEQEZ*1@s53;4IC(dwbb}L86w=>lB5^i$fu=Swl-w`(4MHjnaG@Y5Qj_ z9=^btEfPK4+38P-Sl0=0mdVVIxr*Rt_AF{0m4dPL$|uBzt}PGPCWJND_v5cpy~cTq zm-B3&t~)!rexzW%e$h5xnHJU~dD~@2sfWCrrK_gg2W3#q+Zio`o%id_QZh!Yc^(-D z>b|NN4O&mfV)Fx)IZiBgiAK?ieNqj#Y0=6;fi80XhmA}gzz7uVm(?YWS{itnJT+J@ z^%|(h_8IG{e+j}~(R`g#j!?aM)6f2}Cr@>^Q1WXbi3@7~;V50z2uQVy zJnXJga695YmTV*CmLZaQ$Y7jIJFkUV;RK>N5$B%K?~d3+&;u(gh1B>yG5gCq*3_zr z>L^8aDodq^@!m%s*@@tI_g*Ju`_`5$!zwOG^S8$LH^vTA?WPY;FEUtG1*hQ8Ms;-{ zbF!Tl536n)PP^)wGkyz7=g-QA6+D%bv2fwtGI^Y&a<2!w<%xRoy?UYalQ+7q=yAjx7F>_3E+R@i2DG#lEHKETeR=)R`+0`NWq| zPbFxiG0P7md7Cq&3TZWL(H~eC=Q7@0)a3oTrZP(>9yt{&z1JpHS&4yf2szurW#e(< ztHDwh)dieyX;zm`Hy#;3_K%Y(-n@w_V+R7o&2NyW5W`YXf$z0TqPNBR;{5jkQRB|#(l=C+ugs#etY}Hy%`dQbzOgT8_ibkub3uPVck!+G zvSty@40p4Q4+{YquO_z-FJT%WO1!0hJl6*6DNy$oR{j^6?dB>T zoR6aovP=F)!8+`5e+Xkn?y*lX@v_gMMoUimy@@QF-p>lRs^yaAfMs!IajoAZfE(o8;uK{(XB22!;dHyFaJjO*6{19Tk zdmv*o^#v>$UVbB^$Uy<84$%{#B)U&xZFqwGZP;;jr94Jgq%rHVCx{+y&`Isp)A=ug z1*N~|f>*0LBkIGyCppE+`*+;D-DBv=RJ zpPL<{z9yIGZAVFe@yT+YpVS)bI|&jYxn(82Vk*)40IEwCw_YlC^CP_UHR-RVpza#V zLt-&4{n%jpz;Jr`>>VyZ(Lmuo3HbWZmV0kY@asxV;M(sVy8YHkJszGiVpZg^L6GE4P z;M$X`K<8Gw+!Ff2W&bzR?Y(V-=81(~?^*g`7DK%J#J5e#eMrzapCy*1W5IpQjWsZz z^jf@X;8DOy97qh+-aK@hnu`&%9J`af{E8(X7%aJY!UUN1gG&-bX=1pabc`?9q7zl3=4 zu2U5HSoF{7WLNjPwpKU2o3{ZY90-hMNm|zm32cVRF9eR_0=tT(mXCbglFRM3C3EXV zf{PXB$`ra;qAYX82&Xa+zzUR|!OE8vx z*Eio6RE4~|PqACiGfb$1Ah72hwGAEoo2yC^h8CZ-1Rm>y1+0m&#vU(MP+XM)GK@U&bUu9GjT&|ge(^9mVNx-J5NBG=-`(Ty-96ggHH$X_Muz za(9iP5r~dyjR(Q|Sbp$X30L?rP}*EH>hv%J&-tT?KdD|Agb|K#QW=-#2fqoDmk_`* zAC&jX`%fAu!m)H0iOKrYl!tKL?rBf%1_<4OIU^wM{2~24pF<$;tL&h<{Mge5d>XcC zLTX+MtOmcR)?V{hKZSpU8l+jwYQ(+S3`FM(|54>w3aI+PO2}-ubG*+fXg2;&VxWe$ zt<`MxHoFHFE0)5+z&Z&jte!sT&M5qqv2>NlSM5=fB8!KUAjgpT=q6&*ux4L9K3zYn z5L_g{muZWhhEFglkHMELY~xN)m>aZadz;t5rCS8NmhsErjQXWzylgcA8|TRXT=DZ^ zklGq$-Xbp*Ili%K5adl_DIecrN9EAu1|{fqFNtwb8$dq1V8)%aA0|aGgz^^WrZQf- zf<8iW6>)YNjb+fT%7P|*cnsxctwVXXSA0&OMvn^p29HLZ!Z=Ab>MIMVCzPySB)fLs z33uJA^Q$v%n-PVjmv%`wv=ibtO3$hM7^x(yI3a#PdmSwx;%Z2UGk6>=y}IDUvDbxG zYjHDYsjP_+PLn(hR>@vObJ>4HB9XDtray@haM*_Pa|gSs?817tqOqhYm|GDe4Fn2T4psqrZz7H!2VL)az+_>I=z|XlTkmI1i;^ZX80b#fOlBeT@4k>vr z{oDh-#xQocsQcd*`T+x)8~Gk2CCLnJ#dF4!$|p6|&-g#HU-C~;uAFIS;6gyG#n3}XS54Nj*M_%IvV`Q7nn@5V|?c}2=^hJ4YWV$YbA zKSgS>h0Y67-MA-Gq}H4?`A~{ZS2E{Yxq`XI<#lr9zoD!1xCiYIE0_Mved-TgNPCH! zRaQU?#(&Ob8UzcsR8){)#47$2ldLK&3L+p%cKP5MY&lr?91l0;#6xa2O1$UBEKEqF zbFLYM=QGUmi!1?LwA@ykjn(hgArJ+q%QQ@_vSj&HYscYtu(q#+j>`~b6t4T z(fBStLbUSg5m^PlCrvkvr9-MWwmmybDL>il@XBoLu|#=^lH-1TqP#qf0SyOJW5Pp& zeh!my5Pf5W^QolSTg(#mIB!1lLvRQDUoAk#)lao zjGHs?6t4t zi#UE?+s`$Rk%|Cy){fJGLZ9TMS*OH3Z2hF0uO^ZL{$j%k?^ik5z3|%@;>h}wUmdDo zYro@d`g^aI&sD$l*!lI?t$AgEI&8-LIB8Nek+Dav^u9ov51yuh@+)&?$EtVfzU?HG zQ-D1DM>jEFA$Gp-8}7;#M}34UNQqPR$E8o_{dFlZQ^W>r!>HLvy((W;LlUfZE7$Ni zQ#Hw+fAIAiDsE~;3oA-d{X+qXAG+Q2%5mr_0vdc7@2z_F*L75M4yB}n0b;f{;Qrb$ z4)^;dY~`{upx$nrG#$y5mO)AXxeh?WXAkzpCRSi+{B3nS`G&;7;5hj@sK1}k{3HRU z98R&_%3q1@R?i;N{0w&oNQXl;m4U1TYuUODwKI2%%Kwg zVh*7Bq6HGN^D()qQw-TGA%Bl-;uty=U`VJdXD>EO+JueG?{1Ql^T&+#r2NO3mtur} z3Gwf)BULWWMIuyM3{Gk!M2!8f2M#Ii6d}1Z+c+7DlY)1V05^B-4t#@1lRYspv67ll zJFCyF{RsEwGW}kNk&&^~XRy@&)>`~>JyyU4m=0__@MI)7q(56<{cV)dfdAzR*OGVX zawy{?DO@CQtBQPziTisqrJCYHVKfZy?o=+%=X5blg$nhqWg{gQgn#5Fv^BV-q)KqJ zVR*M;@3SCrwr6Tv!0KDeFp zZz&81q|3nlS$B;^7Cc>|$*4{*hrt*xYxDH{JR1ka|J>Zat5~7Q?+CQ zoPML_gMuparCTRbHVq{PI|J#3^+^A>rpGDZKmx-;t^;;y(i zyS5=ENKQIuL{sJ17J>y7kYZ5f$NN*`7rgK~uqGk&?=N`M9IF56EiGi3>9!NG0fSny zwD;kR8G3DZwT7&DQ&FCHFa16~wfglwy0M*MpW{>i;}=VwsIHdW(JuQ)s(OgmYaTBk zWknl81nd4?N7x!feVO#FPJp%E^v0Uh4 zd5`k<>;gDCRT%Sp(siV@G|}EM2pCNIlJWT6&}TdM2_6S0-p%eMp)chTH>-ExK4DK| zaH4m0ILrHbV&efx(!~!>JS33&irWegUbIqUN)%kc;F0;wYcb)0ZCbbAul zNyx>nyQQ7hF$(Q^8#ViDlRRNpqGR6(WMNg3zz!}fg2`iTGtuHH$mtfIBOde5OEwD? z5-J0O>KDfHy9S!OJwO8uM!Axh5E2SevD)$N=gpeU9l)Qn-B;vOo962WeI92@7Jg+s zZ#%ENBpS767RCj1lHQ;#+{N;SO9z)zcbske(=6?dYHxUa3u~ldRmst+U-*DdGE_(PLpGy zIT~GUl!pI1iS~3~Hk>cH-ZVMZ=uI^r4N%$cml${@0S{l#X#7l|YxED=a!mW(g`L!j zG8GK)m$We1=hRV)L@u5n_l6Jv*hrjFj+N*4)8j~VW^uKPo~jI4Ll{u}bgdQ6(lJQi zz$qQm^wT`_=bYW0k?O{ZC^V!xyf%LcGuBepzULNrxEMI^<^y?5F0>3fKA6iS70^=h z;Mj3zQeQ?zqGM5i6zJ>ZKD>cthDXPFyMf9q-qc44h+Hp7&rYX$^Qtt3Qro^83l3u8 z%fG6=I)qYVXjR`jD8dO-M9FcMsb=Qj0#Y&FJ%7u^({Tj0eceM&9Mkq~`p1Pa6C zkXS~6%cf8g7g$$VS_C{LAp99LQ8j~uvK_n5kf15nb7Dt1xrkU_j7#)Gx3=A7-v*QIn-daX+jWg#s?v$NS2w~f%{4F4n#$lK1&F@l+t#5ZzU9at%*F2p+Lju zk{1+TNH&6_xViHOtl*XO_y(c5@3$Bb! zY&tq_@Xzg+Y7sKt`_tdQBT+y-J<84UV{}4Yz?gp$abbp+X-V4bqjr*tG^@LNDzAyY zV_*e%PQY}Snn=T5jgkN@JN+{4xmIqB*XzQ47JA$i-cl9?$@0OdEU4?)!NKp%m5vvV7ewcoN{8M?Kp`YRGN>ZKU0d+br~x@Gw0h zpR2%sMb|}&b1XPRq*J>f@m+yoN>vi7g^iZ`QRW|!qAgZ}hSEFrz#X~%7n^`07~V@y zdQvf)?JW|2VgwTS2x^$#Ec~^g#RsA&9O5Bkl{0Q7MqNyQn@lh-em>v8x6%tp?OgJDq(3^hSkSaY(HTT&`t{ z+)PUdnhFP;cn)6De4NBC2aUrM$nqf*TUnkV$+aBl`wY_x{){IE>LKf@CHgNF8{Bhg zlfpBZFnt_5T-2PddrpRmxrT|OBPD#>{`3i~kXQC)S74iKe(QwMOZRpY>0A3fZs6NU zV@HhN5?_}cqz6d1%-CdT=HVTsEY=U+pRXB@0Jt&ONi)J*aHl@`4NN})qU1@}^isRc zvpyUQ6_|V8T<*U9*}dpvgQkenq9gCO?VgQ!o(&5f2PAaeBcH{x5*o$Dv&N*Lr5mkC%#u(}lhc%@BivTsMkI-g2jxvzTXXFL- z&oq81$E>skS&;FAO~BE~UmE6Vn_NrhyZ%g&~Jd@23{;OD^qdF_RV6LJ> zSIXj->aS5rgw&7VaWp)KA=LzW)0NkRK%%lFNiB@wp~2;#QJ0&7m|!D#+oWUk9~YU3 zpPzqwDI&eRL|2Wg^P2}zC?PW4252(uu#0A1;KSX|d<02B8TYe5ax9|Vp4h^W4Op&7 zYpwU-c5j%(O=^P=+(2QHDHH^SvCLL~sk6JdaqM3^38_~U%D2pXIl}v`+V&UFDLcWQ z#*~Gv4BT{Nh9r$SJq`{xz8mqbWP3BCQ-JzX0u{~hhi%p`YD!rV{=P$hV5$VYoe`Z* z?TISC-@%$D~v2@m^8vag+w8?z4iQK{uzZsB>_m;;08DLv6RG^j-mJ@>!z zcCYi*D1*_2f|S%Xc|q+!d(KHWws|6A*k~VsK~sE zdoay{}LjskyG8SZzHxuExvI)4ss?OO(!=5b57=lj@Ui4*Uu!)+k9LXrC zDhrBHo-8007n{J`l<{G*^c4!dE_*;P4d}bva6+Z)fE;Hot=|yGl*fUV?HJzVpFu%9 z-BTdL^XnnQ6S5~ej$A78KQkF@hhu~BahV%rRiu}JMz*Q)wc9yV4tuswsknqNhU4sm zssT;*Ok0f14J$&SWc1B`$XRZV9j)!xj0l&Qs8xOFX}}|T ztXv-|&pQq1SGPh9#slicnL_T`Lf_v61O1`>oWy$igQFzTS#y%}>_gJaHDvD}`5b$q z&TLhnhRH-kVWV{>2(J0`TOA{d zS{=Ex;isBH=-|N@PEpc*G#eS)bnp!PZktu+kXMFr^Wx04-YF1|)E7fq@kgrmBq)MYd~$2)ee7ny$S(* z8S!iFyd2&xB16e0K(iA@67O1k(+Y;@kx9LukIyZ0an;5(RT3V?e z3J;BFDuroabA-&&cmC&yJ)s!ZhLf9v`CUZ$o3c%1?ob(ir7`(pL^XdhqnM(9rGW{* zu`%~xX#HUQoQ}HMFE+d0d3+I?wuOV=KX)lH-aMh}rFqrbfmBcEc!ejAL)w4y(|K4- z6QN+}S5vxXnH~3m$QT*mBeL{cIvf@?r;`vAE3IIP$NL%_!=fOB`vG2(9Sh8Qswbc%$$bc+QxihC?PZgeDp}+vX(+2lqW!7I!iXNOi-%KTM(W>!uuLc zAqScgXy!aU%4R8i;Pf$O)`cG(H8v#4olWzHXO;q)^_wmMk}j` z_}Je2Td54O#}I(Pma}>y#rKs8!oTS$hGWdC3hkV48R-v*LY+3B``+fg#l{>j<1WSy z2x%j7%?(XD-kl1Pq?SDcvE<&oPxdOIO53**Pu@UgiMQ0PvnPiKZL+I!l5M?)QZD)5-8+7v?vRsgAuvsEsRjpFm?dki5l( z`#WO31*V=0g=|hu=Asy+;JQ0!Fd`ZX!ytW`C53T}*lH6!8**{sojf%usV`~3e^EJ+ zH0PFFj(=FPIlQsIBt5k{9oFHzwy}+wUW@;7sDBOzH}> z8<^pH8yjT$kqs?Id40zn9aWpj#mOma!%Dg(KaR+nXTA)07h65GRLmSe48Ny^MIo+2 zOlbuqwa_z1yD4AIli)b#5sS~H`pz#&HFC8yVj}7};>FQrKzTeHy^iJvXH(0%fH1x| zxz_;`OBM3MYt%l@acrb%?YR8W8{*nstJNyf@=DULNpip6Bj z7xjxZV^~fVzul05op@rPp!hfptW!>SIhwtXp&NvUZ@MNYiw)Thlo*Yekbpbf^C)== z*r0#k|Wglz2>zGS6$~u_jeApYK@x zZOx^|0nw*-HOyGW{etw9I}qlO>Ww z_lL+?3^%0jkA_5o8&?zm`u)w|xRGXg+>**#&TQu;fRD>=+ua!)`>?7vpsTSShG^pom@vUITEEcZ4c->81sH`1Ywkt=_>+vbC)BQOSF1od z0nLY23L253*u4U=)V9sNz^6_)o)EDAH|88Oa2$N?QKE2?`@^ot25Tx+(Z{O%UB$Bg zT@Re*DazM5E6*>q{@*YCOK=0wOtlIafO!Q&6gb&Zg5DWl7A?SAHm@h*McKKBF`Ecc zP#lVH2GF&82AO@^OV}lbHC$pfY<|=WU*SIsif4W%QW1ijV#bJ})3kC%^r|}-T%y!^ zk|P6^)=#!e#P$EF*qiEWT57M;bneWToNQI>D`;qc&)KcNVAxx99nU@ATd7=#ISC?zHsIc2&mBB^Qsia!`%f6k^A7 zwHhqvg!6UsT`VTYIzm5s_0&fEj6M{R>n?0cFOkRgBEHiqTrBpOE?(6Xa}$nwZXV(#Ez>70bd`$1{&HmL5_RM+#7;7v;uQ)2o|k>#-LL(5bO}NbSPxP>IFedwg_dv-5=cd9r+ab? zixs-u0>*z;2d!-6pGcHQ;2tp=k7)Q%0-!~$(F4*#VB9@yJsbm~#I}k$nF3Fir*zA? zg+ImUAOA=#{`5V{KCIBCBB8!y%mTAqwCRRNV7(^U&dG7JNgq&CE$!xsS})HzyRBnc z4x7fBQ185E2fPp?=4}0#Kq3+AfBFE{+PZqq9w9_ZNIuz@%fl)z(ANuHg>QOEup!d z*36vP@f3iFmBoeoL~BYVq3)s6a+a34r9cw#H z=qNR00A@w~W)2b^+8YS3leq4_;%w;r{n0{8hEO8Q@`NF7l+M}HirCvwHN@$^ZyAoKxKUM z;EO;W<%IxI7C=St7bH0$qMdHx#WIi_2YfcpDUx_qz)-PydPVgG#imS@lw^e7chI=W zJufjpJZ~ikq*JLA(j4oogS&(e4OcVBmoQz)9U2EK~(+3g;=8D_zzq~2<#Fz zHuPVegR@I4m2CZ;n0E(H0GX~MLNepE?_c;zhzuo&8(#g~NGT5yv8F2s_N8tkhO-z} zYK+^t2nwxdTMEk6Z6GJVP6yGTmh2#(*qZjUHCKqS!)Ris7?=N8LM7v54Ur#;~tV z>jODaCW@@rB2DbFbM9CA!((+qwj7CtAtf|Lix>ic@46j;a#z=>uIVWYs#k8gt#3M( zFMqA4wWd}DP|R^K)7D*`#f_|d#x|ixb*|& z@a{2+w$@-?DoZ%fYQE{+X3`Q7!1bS`Yq5|UnKAbFVi?bGA^f2V1q96RG@U=tQacyf zBYA6oSC|sG-aJvd3m;+;--v;=fujQf84wQWwU2>2Y6K1&!2;WETlI!%^mZ}cl;-}H zw{UVE%a4jOWs}%Wz|)Aon6YG8e^hkzT-g241ifzFX!mnk*B)GzUrhA1Gd?%1>vo}V3>)OJ~!z~X)faEIdmX+iT1wYwvXf5X04JfD+MTa zr&{cKIqT_$4KAirF^)diB#RscrAG3trS0dCg!&ZP)QCEXnu(R%>Uc9}%PD#0VuM?_ z1!SUH>2g12z}PHgbC!f2j9P~dgjE?BWBGmE6Jv2xZttXuzLzGX`UGk(v;U5%AMpP;j6KY1ZC{dTHotqZL z##;QmnZ_Xq+j!DXxyd$t9~6X>s=dnRwvbEYTNfAdw-dw)aH;Ns3>_qYj%4pkBLL6} z&oX&gbWoM7nzZ^Po5soGW_238yRX{adJPM?rSj9W3P*84YjChM9fzYRI&N;er;z zcwvFbuF`Lnqe@{`!tU(0zwYj~_nX;xEcxW3*ZG)Hcmr(2!hDtGg&Gjz*0g5CF$6-n zEAw^@5)b2e#eVPfhSK_8Le;zk$EI{NJOg9R7jit;yqy2-ETyMxUBiDuhRtI-SwjU! z^|Jp=Zfb>uaiEmZSg5t;@OO`Om4Wf}PUuoghFmtDj~fw}=gG=l+n?UwAU`dME=(Bu zi;v!>M!QWZg`?%t{Hx-es8#CCseTzP)%Sn30In3uv2Hk#)kilppDs;HcD8d7aXE*uznr)X%K2C zAK(u$O#wN^$eI?u-H$k}%U>K9Ye`Gr+C4DXy0_$EqR&tS zejW30@R24Vlu5y*I)mz-UWIOnsWacK|9n)8Y4)$r)3lE`y&cc2uBkaCZh5`CqMTE8 z^lnXZBA+`PjoLkVN2S3N8Ol{L>&mV2NLJ`jqz{~S=kfU7wl}9W2~UIy@bDG)i!pHs zD>jfF8U0{xp;A$p+YNVPkdZi1tW%s*QB zmNCtDcAA_9R6Dx|a`o=!>MhqMMb~pr!{y?q&?MU>NAmy77Zpl~A)$1jU1)6Gu1SIm zw{4|A?>JSu^4Z|Hub96pRMVTM3V2tR^Fmp%*!8>vdac4@)#5?bGzP$#iTjxH+G54> z{|q-EuNz7W^Qrc1XX_~%89mawKR;s?^R5GG2fRR3V*f_qk+Ss_Tq7QF0*v7-;~4{W zj4kJIeZ!@=v1)z9Z`WOeah=k0vj;2iMee;DHl(t?FZ(pd@LT40s_uYJpP1QLhDBx5 zl$9;hk7Ut1fJFpCb|pf|D+>|JoA-s;vm0hgEhFh7{Q?OwsJ;3X^^?;QTRel~s zRa~zv1pCy%2zyPhT74^Dy?iFjP7=PNfTD;PDiV)_bsz;FW>Ehg_zdmZDTe;h4$>fO}{DrqvdMcBNg;guDtJBy!k&_w_Q z$?5ykFPUR0ibWciClWcl>pbF;=JZ~1-zxbNXwCweF*+{b-1M)o%3W}}_oy5Iidhkx z30?(`*iIHsmQ<>HFT_O_i5`xCerzUz#S|*a@~5}4u(mS`)@|f4St{=>1O0({F}p+q zV9+h@E@M0W2a%@>C%>CL)hv8%Gmbo!?P<&nkfbQ;T7X+v!tXFk{)yny0nrD~UlUL%%2>o|Fj#fE_Qs$W@F( z+9VzgnOJDP8Q6?fuHj*Ld92%<1@M+k9s;9E>izy^bsW>t_C{V4O+)|Ka2k|L0 z@*r;ZcM`1a7<+O^IT6HcsiQQE)bYKCO(h4)p4~{>ij5ytj<%|1XUFQC$i{30y{=Hp zB3lm%u2E z4W72XxU*p}7Ao+Qd*AZoCOPkGxp1_c5Uc#w&-o%`IpX!|TSH!3$3L4Uk<4fg&<* zs`a#Ev5_{T#w3MfjsCg1+^SuZnyC{_Mt$0y=#W1nvu`bo$$3j+j1Cc1{ip%ZI6aWH zFeLdrA||&2T3x(R&^wHk17&)_bwE^|Z;IGHm76_Q&ZsB^JkZ#JYXMuW_EQvxIoo2? z{V-i{IXE>0;gM1)c$GH|&$y9E4-Cm6*RY%ge}&$7`Jkk5Vyq@#g4J6bpK#C?E*ZL69!} z08$c4AoLnVS_nnD5Q;|xjvz*Q?@16sKuUmwrbkgaNGOUFl^W0>%|HU=ZM^rKd)NEt zt+&=&Z@u-_oj=&j&SWz4%~yZ(?b!?XcK6F~4u!&$(Zzcxov+U|DhB$YowQm@)WTnm zdSvZ>WNEj9I466ZV_r@frMMxao#$BbIa6eutrODm@d6vL%&&mQWNN{y zuP~|<%)BKJH-y}g7V|pE!Jo5-jlB`ZHyVkLo5SpvS57f24>FJ2jJk6wT>{7b$;IO( zShOfW$7Em}?x^QL62-xr5ydDNoqjC0OeQNLZ#s91a{29h)%hZXg~MddWo(M&$Qyh1 zEZLY^(A}el!hhUjcz@d#aN(jBlW`e}{g`uD9O)J)#`R&(+$~Wkf%Bt*zDYjt+lI`< z-Re2b&zRz{vMw*$%7gph75~9f*a;V1Va|Z!*6;*5zkLURvDw)do0bMn<(QOIPPz98 zz#jT%S6!c;4LMV+tnObmRbJmlyPcJO^91Z;LH_8tmX{h^gf!MRnqr)fiJLQIGt#-r z)&-Hb-E~Oj4+$*&yeC_NHR7ICT`22fblbcxj*U?OBEW6=V8C}ot%BhlzRJ)M;hlmH zfNuuVR8AYboIZ7}SHdy(5$mppAXO`)0c63&=%w^#xsooEk55FnF`(UuGRwWv|S z-wbqyt2OswE4;R{VJew2?VhQ`m^}ZELfKv|v59A>a3&UIm$Bl4bojOFrnuub4 zr;%D8w6gZ9_(c|+*R6OpXY9^8x}H;?ZIQ-$;uM<5iU{QzO!s>fz-@&W0o2oZFjM>` zya3gB(T;V2&pak5{oByIox6N^gocg7f>@?5n0go#dRvg2-h$(9*xaqOsa)6tHpvi{ z>Ll+VT4s%RJ<&v)rM8!Zy8umj;FHql=ro5>;3cuWfZTp2I)k|5J1H>0mFH4fh?Ea= zH8ElpsIB>P?T#G((h%+jCBUMe>E0M`H?y<3r)mxaYg1wArAXurJKrA}d6k2-V2A!r z_$0CZ0pol~rjdTp4qEMPuf^&yz;L#1vvzXbwGCx~&iQA+Mke|(yN4fSG|n=OewGr*s{<`Wi9 zYGxOkh6jX(Pg_4nT?Bzb60p>n1SMW$+>a^iG)n(-a_5TNQpu)9j@DYWJeB5Hu5qFA z@!%k!LH&i&k0TPDT-Z2VJf&$oM*!Hi@Z*X@+;N|DOz-`q z0M%K$vB(!n4qO3*C%~gfNh+O25I0MJmApTCtLyF*$Bg80N_k;P3b?X74g%H

tTw zK*-)(PFOJH%y!UJeM?+bB9_$iE>oD|d8h4GMnu80F-$^L6?sFgwY7DP>I2{)E)T%; zX48D+(Qgyjysp<7+8oyc;UxYH@lV)Oh69n|ZMQ8fvls*Im;q(06RP3slA`;cIb!cE zZ9YMxXJ3s0hM_el_c(UzR_n04vv;Jk#I*$h#cU>I=t;WVisrhrz$&gcUT>~`WKKho zzyam(Z9~ALw=?xxA_av)0S<^!dx;^IhJ-f^e>bSy)$HZ@@G^*|wwYw(w6mc|aUImo zs8!^~Hi;1h{E570{_OQLX3$#Kw!U;FOBXjZH`9x1j=wM~0aS;(*!1kvCUIOgMUR-h zkwFgL$qINVMsHMTrdr8Hr1?^H!l7xHbL>425^h&P*9=ms#x%0m@&h_ZRFgx0Tp^uS zlOHBF(lDo2c`f_Rbn&$lE%XoGp?^L^`5VeNP&}t)*&HO?J$buG0<$TOd{bXDS?|TT z00L+wEt5MhH4;513wf%nN-6!p{z9)QK7=u2SSOe|)q={EdY0A#6E9T; zkJ()?g9DIg^WeQ(ar zy#Cxg8-t=`gFYn$PI1I!q|{O0dE#{o`sV8`LfQqXQ;IH2DARxf{72m=1_>pdjMbA_ za9yR5Lt+)H=LY~5oT}a~-SYmZEQRcPny-OrQ0pe^C)vreAtc$rX%$n}{HNmWAu~Rx zujJO-QbQbtfKF|OT&IlNM?O!r?lKh0k>QNc`zB16(Tlf5;vlhF2x^}!{h^+ap@A~F zfi~%&%5|*tP=iz_)f9q91~E40dE+mNBu~2^BnJ(#J2>Bobq{8R`dggjR+31g`Og#E z`S|lrfwIfM$8;cd3p-oQ7aZFWxPV*8CyJ0ZK0M$yagfM> zl`ku5P5LMaJiiW%aK@H<?^OdRb&+N~NoN}3ai?Hf8 z>${3T_Ly=@XL^WkVn$UqtdWf>6H91MV2ZXYngHO<|iZV&k-5}`cJnW;ff`g1rMy7}zM2#(_&#-tFzfE;PSg30tfgL8jr(xq}aLv2Z z4s;3w-MrgfP@k6DV|6f7we_r}qUPWNr(0#2glIU{y3e;}dpoz|-usnuzrayN5a_8$ zW<2#>6SbM{445!)lB+P3z0Tr~>9TijRwGis3a;T8P4(xvk|08cJx&o-HV;WOf+~Z9 z?le99G|9M*?S+q*3J-|sxvFysQBn{3*hc%OO;V6sF8z4OWyvi{ZkXZ zw%zF&){ya~5?g;FxBmPr>MVeMZZt|**vqHM0NE1}5Cz~pp_SULl;zH-ypULZsT(DL zMUsHJ@^Oz8Yo$F|BpysqFg&P{HhJv0yO41y{5fKwifIQCnxER7S!~!9rq4eLBk0LH zkH*du+>9sRYmf7wIkp7_PZNpU-u=fwpft>_k#T!QGCIwCvNDFH;2j?OtSN<5UG@}> zvMp27N_|nHXZGIXXSbg!`CiTYiWl2v{Zz`{2%%te6kqV zo=E;3YOM}}GY%geis6wH&ns?$9py7JB6dM9jic6JQ z+gcxemWls^@Fx92^oEz*7ChXL@r_{-w^G)59?+h)@{n+`8rD`z>YKL=IF!9Tiiq1a zh4>B13!Nn!k9b>%h#pg}>^>#h2kgBBALzm(tC27@)q%l}hBcUapT@di43xEzd$1BX zQvRdEjVZvB4mdTvcy{XCH;i?o4^3dXuU3Ufk1X?~1vwNItY(Tx+7pB!lE;*z+r4sK zIxa9adXwSW#S6}~p8QnC)CCM}^!~ZDgmOm>4*FKB&g>XGOM|RY!}%fS%&mA}%cS`A zJfM{Kx92b)mWBY}1ik&G)$DS|rK%#XdSSUidx@dS>2I|90&3A;HFXGV#gQcD$BTkVUT9mR|1t55MEw9zp6r|wl%dYus#Quf0Kfp}a| zrC<8wJOu1BJu0@kq8ptn9@_fIv|g5;)8`K9*+?h9^-Dzs4W3+-(qn~MtY)4C0PbDq zB(NvUvR~P?7{PqmA;8)-iDpc+MqxkJ2(yuM9S^Yj>zbyl)8;L_XMMedb zkP)Nf#1-6Fb=bfvW{#wU$5J&B>fy@ZRRoC1n{b@pg8ylvQEb!IGd?EN)hUKMRXMo5U;-EY34(d*uJ>2H~ljIpAk zXkw)*bRzWLbz3bt8{4DNTeqw@noN|<@VH8w3DSWg-bFlE$BNa%mpM6AfW(~x;H3oy z^y9Vn_D>zG9YVH?g13vSPOInS9W2>dUFQEP{V?~<>f1?jYb{$bjrwwljm)B^ifN?u zF0Cp&Q3bL_cmQ-328^)kUMyS#{bcKFpP3fR)2dZ&JT&TtHRY_5s}m(aC)Ycee@uy( zM}F6aP_A{MII7Y6gAa05YckR_iD|7ed3wg|LaI3}Mp({FZlej*BQtxf^Hr?ZA@yoNi01=@=sL-{ zO8m`{Ti<_k;xONO7yEuJIbdRYepa=S>4u5awgGk)=N^r_3DHZM2I3PkOhf0Y_^k3V z5rrGaFOf`1#<#^By632(JysU^GU&ieFgItvHD|2}C^?N+h+`UXLMs zo-C#5Xpg@dqK7WMs~d0fu_-tF-O>wC?q1iyae;WYV&%y;RZ83teS4#|uIS*lN$b#r zQob4I+mzn*o8|QxsM1kGB4Hu*d5U#2jMB0)p6RR*4kksYu)r%u1ucmMrCH$#G%JeJcn8L zEJuegPR4|kp*sK?)QSTVpE$$dN3L<;q38Q$_-}OD24W#)SjYv&k@H}&W5rmN2gieN}B}DiA`hA z_;;u^3!6sge*uAHTHI0_Ne;-yy4qG?%dxy7VCySBw0$Q`-w1Vqkg}Lm?l_lHTE+#b zTpn+KFgb3m8ofvrTO#*qf>#uv%M&j|B3z|Sl8+vH&~GZ_ZMi1dr_B^0Dd%OsC0ngk zfmC|CWobC8WQRnMG1TPTEi9^K&rVyxISd$O2QFu|{%xcU7iT6>mqfdBo; zk3`CBzNMt$Pu@4Pk&$w^XJ1xQgcN2W9GsZn#DOKx16xM+AT zW_;5-3QbtFMf#|*agCYU7A&i-iZlE|%ZP-^@o*o4A3a%V`T?5EF)s`lsH>cr$bEA{ zk8OD&8pl`;N2y0C4sYFkCN&Sp@#)e2M2J~#Fx0ZQ?~0Z6a|#1`TC7!xK97(lR2V=X zNqgmR1})|$IM(GXO*I5o&rWMus;R$oN8+|Mf>Tt}-Kbu7&URfn{FxkZTq>S-ps~Yh zb?~jYdQ?09m1<_*2V;+mh}liDouZ&bMCmz*gQc;}(;jPMDVd3gG9aoRIwQHiRN1Em z296(o!d5?Al|t~rdz9MBcqMrhT?Ed9FY>;w_Rd`cK6^KfGut+DGjK$8qxLK)<{tpa zl>Ge48S#{abi;6MZCkBVK0a0-Iek{1HA!aV=|RM-GEh%7jTff_qj0x`0@6tHYsNGn zK^Uf83oQ!&B~ipq+5slR%jJQ$A0^v0Rvm}Qm&gO&p|hYOq9seoIUlh!m%Bm*-fQA^ zU}c0=fk-YDYqMPo+m?d<0T}U7F6qXth>fZ0d};0``)bR(l8tG^q&gcJ$FBOZec?*} zmfl_uFWlQg4ugjx0Db0iOt~}jLsa>u30_rROdlo#dLc9KS<^`vy8=fL@Z>YiE2q%2 zXfrEl$Sp6)ncKNuB;M8&T6L^wX*cnTVeXN zkx&Zu$ft?>fcyHz?Q@br>{HjPm1{HomnEW&mZ>fg2%|OVSW2AMHN6|<{eVM9td|Zl zc?@%2ePy18jKQgV+Rw^`m$^Q-|GKXD$}%RZhTKvDNb+}CF)K@Q60G;7XUyb@k=Pqn z%-!^ZdMq@0y}dXCH5Hp`0<;pu;j=RPGgOb90nQPLe>92)flk$dZ|Yjx>2MoNSgopA zHSC@wCF)9nVy*$mHR^Vly08bSbbeGW^dknq%s@5S%#pL%;m?EbeBoAG=1Gy!p(i?M z3+Cx2C|qsIF7Qd9M}Ky%Xj4YnSD;6Bak5P zn;9UtGrWi5(*vY2fjYShR6sxJ0#rVU?^uYTox{Wc9QwtB;A-Fk+{`ve2Rt6o_X|5qH5!;9=tXT$;>gFBkrzOqd)f9JN|AL0Yh~4F$=I}) zGYQqVYXuHlS0BlrjfrI{|Q z8*jkFGch+V_5Oo02ddWo*~k6j$FG8ZwgGAXT6eAS$8>Z=u0I2IAW|ypzIl(5{R?RA z=0C@6)$*KD_WQh38+DpO^a_f@V_xd7~xlpHuql-ls{fLt54R z$e-Oaw6Ss7EtsBmX^-07&~gC+lNWMw4@-u0SbK#-%+HB}At51K0yRJa>?cO_!R`|K z=auM(a;|N|Gcz+NvM``mSGRZ8@0>Xv_Y*;@-~m3XkUsLg<1k(z+~DugCsX@&(&NL3 zZ0uSwd-kiVt9IH;_}UI2-UsGW6@PB4iwEAe8G%Bf4o7*PyH@7F?6wHyR7XWh(h0$kY4*{(IC^4e8sD}V6{<~xiYV;+bx;Cb> z_ey8#=SOXJtSu-j6zj?zB_0(VG1rhLr|Ee5b z|J%X;6&fVvcYr{4%>2$>K0<9Re7B&sg8}Je?XS&JxPbN9+ej)Kp533GZQqPw?G3T2 z4;5RYG@yiAVq%%ivG_v`HQ2e=*SWk}+ZhA31GLWF_5)TJ?V`bLiN}8~=hvO{6Q;c} ztP9@PeGa~AYs{d5aUObY}aMe{(MPFTufov%>uw zsfV`iX9*Pko1?zm{9CiXe)N|K1O0K~r^z~Od`|pt?z%!--H+)+qIcv3&_*QJTA~+7 z=Fi5fDO!V*67`O@IL@A CUk*Y5 diff --git a/planning/behavior_path_planner/image/behavior_path_planner_bt_config.png b/planning/behavior_path_planner/image/behavior_path_planner_bt_config.png deleted file mode 100644 index 72b6fbf36d119a939e2d1bc45f0233980065b385..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 179116 zcmd?RWmuHo_cw|lpeSO1QUXdNNC`+|pp-I4T{KDDQU@3kxoInVY z(A_XI&z>0uIOq5Kzc}Z4-kj^q#Rd1hXXn~$eOBzXd8e%Sn3RN?1P>37R95DpDjweX zi+Feh6laJ)iDT>ZKj6=4hx@YXXTZnvj0yUk%28U|QO(ZG(dDVVDW18losB7%gR#A- zsjb6vJI7^$8VOK|3tj1fz3Ed&3p-l|bqgC)yhrvH47_{{_ngcb_;~pEz_SSd9T6U0 z2IVIVa%$>jJ&f*ncno;55AUhFCM=A2d`xii+Fpf;7gm@(`FR#!*y!PzQ>|Cd^AgFi z%Ls6!ol(yt(R`zN!RDK)?km-y*EyQC1V&bi8n;r&i^SwoNC;Id&XQXQ3$O>gWqMOf zB+KxwR90}Hbr?o}XFb2-o+5bJ-z?9qayFk9;vYMU`nK&+)37ny)dFUJ^m(9blTUo~ z1|EvVPn|mPuI}r5;th{OO6ue*1p~v0S6`BgfVM{;DZ(>nj$ZKaKH;A}ed1O56h8im z*L1x9Uk&S9Tt|mpeScY`sc=8z3JJM1Z$BfZEZ^_aAsxB14D-y#ytbd1o10(0R2MSW z%nEJ&6?IFETzbAH>;tB@Z`&bVYvl(`V+_{bDS6&}Oz-6=A|gWML2LLbH#hfS7m9L2 zZbDE3vbwyl4x2sO+n7Z@#16z$`!kHu0kPSamYmEuhTJMCG-(ds*w{F~rCs^v3tPdE zZN=1w2N#+v#t=*T?z1Vo6*c=6-Ihh*r~?e3~6#;xWmg5+d<}Hgd@wGKB-Q3*RseC`}HT$;j7hdql{_#zv>W zq}eF+hm~@)X*8!!cuCcw&Ftdh6VOU0I;ROc9?K!i@kjykhMOSvHvPoT=4mJ?DZM45 zPckbU7?fhb?oztoVb$LOfvo}2W`(h4g~I*Dm~Qe3a9mID&zZMx3pn>ZnPpYT{lq9R zU;9Z*VgBOrym@yI^VF|!R6-$r1G{#HcfQzK*xwxY4y#~a|0gk12aE9&$I{*J>yaR5 zn*WMqkL5Lf^!|&C3b}<~yu}@A@LQ+IQe(O;UZ|fD)1vkRBLlYk;);PnbMvL)GM#VF zq{F|my^l1Fy~OzFt7g_zi0BgN!cUADQ}a9*j?5KSR#q)P{Lig7D|r_vvGJINiRd^KJg-Au#wZ=H}!qG8?}t;DoHt_s(z9 zx(vUJz5DW6W61URkdP3j=5nX`0?*wwPVIb#bvR5Zxx=+>dDXpVelv((Qo>ZnYwvXcjDd6W!a(8v>C+yIMSb%m zXABqApnK{`ZquC``b;~wQe<~sm}p)zZOfz zlH|Fo?ie=)H4m3Lte5!gm*`DZVd-v;1LWcg8oNqf)By~Y00^1j`uCmi#_tCXqi*mN z&XzmzZ8lq4ds?~rv2N?rreNn|MV#h*o8~v&Lqz7%57xL*_FF)F?@$M$Wwd12UVf=^ zy*m$+hmyV zR=;uA&`|uXyh=V4av7CWz*z`S@|eB?-Fdh*>al##YlrB)Ds;{hE;`oSSA*Q_+tk6( z@lOv9aEAW9U9k}Uh0VU1Ip$#apFjUFhWs2F-7401n~IX$9^M~AAswBat5bC>i*&aJ zt@0{Sh-DaZe;En{WZ8SWBB!Y-m?nlXRE$q{Err`FgMy5y8Q^D(&rX2P&sg)MSTfH) z1Z7jvdY#Yjgfr0}{2`8DLTd+yJ_DDcq;)h$u0v6txut*K)7t;M5i91l=4&>wyBXgOz#=!?eW-914o>;u9(C9IXWct~+Zh ziY|V4baea*^x)#+V%bvpd^l5qbWxmu+Ew?}Htt=C!Go zk{xQmgKk>`=KN28yg|d-xofwr#mz^`opxuHe99Z(T##xp00~x!gy@O-)-f?)CtMt7 z;4&frbY0nWoRzK~{;z^oG>)JZBq$sxeQDenN)L6K@12^5pxmKP@a??j^&EcRBL)Zn z1n}Jz)@igkfyNW2oIcT=KYoy{F9+vtmonVa%$5mPNE8u(A~(|bEjqupCW(tm?sbIj zCD_>6DTP}Pm##8H?103|h8GtX_Z`q;W<;rgv=hKQQSdtwnu?@m-3dT;>TcAJG9Z z5kqWrd6^9ylyjS|8^^y*azlmF!RGgsaGQlgj@2XzLAfCiH-rX;qmwp-ukk|xq~A8lc8;e#O8VnCY+#MTh^vK!1pHdWLchedA))xT)&yaGpS?7n zLAV!M7>ca=s#B@#%4bt)ow`*9j6=okf1G8VET7Mn4;R~=j1Wd0tUEMPnVSHfjpa92 z48JBwI_$l_ShhEpMO+C7WLyIV4_{h>z1-+#uFKR)J(->O*6#;oQ&|v%C4hrLxbVox z2pazF+lApK!=*2&glzT0O%?}>sQAr-d@&30wRt3kdBC$4KpVx*1Ew+E^P6aUdVW*$ z;tQDg_V;$MJOhA+zz|@6e^XlJYe|Vv@FPa>l|HcQ!aY&@W3cxWw{+nE+NpydUFFh^ zWR{OU?}`FsO?dI+tfWihlX$_Yg+kcqUt=Xngrme}h7uYc(dJcLn^`oMUhkl4KJ$EE z9t?uoguub3HBUB2bd8QC0Zk^7rJ3X23_k!YrPU5Jn!-n(8}$KXu(_VBbzm6S6g@dK zWSDUlVb<*2oFzgU1%(6s+X5)NRREucL7@Qe?SeZDqXevaO#tlX%?Se@&?$W}eoF!p zonnLCT5GK$oIivmO#jyZ_ngH~M+W$e9Y6+Qd)pICritG^>0Jj z{!&Gu{nW2T2`vu~kI{`(p%h?S&UU5@ArKf-;c10zNN7}Y?9xFGh;-vHL^6PgnZV84mIh^iN-0kjR4F> zhfZ16sWeH1g>BVlZyntg4B4GYaJw0x5p61HJNyx6N1^?;Y=a6xR;Z_ai175snDb{? z6cavnBtJIaoa=Ghn@xjkRRN)iKpR%TkfLFsYSd~IJ#->OG}mcg616VrusaoFmlKNh2!`JHVn)a7pFK|_$SGUk zjo6b|tp)bGLmlBYCRwyiiBDbAY!$ z32%i;);OW^pVqGp)gXp|aATkXfItbIDCl+_?N{&iH%UbE!^HS$1g&Ml6P$W=sD$lJ z(91n&8#{P1f3OW4W6vcAXv;g+q>mNL)gDp|Xw0zY#S+{1dMs|;Pf5YLm%WxffVqS= zrM?+AnN7FG#_~M9-515Rw~5uG0U#)OoXOYRCol!LnV%2QVAA!rCl#Q*e=~u*bKLI;^*k7)ZjDdK&0sK^y*qsChPZ4YYs0bEWz>tLv zeS@B;X@|Tm&+tgoT@eYaadG}OPP2EpE_`cR3%2uQ+;kTQhP&~5T z6bMTMz6sPJzGfLPiQ5DqT>(7e+UvJWRD#z1^9VM~;_^pui%a|^iRh9vZ4PHfZ;u49 zXp5IntD!y#U`A%Z({XDO9qoV%2hh1cPgP8eTUuHIKrAjB4hU;f_nL5aVWBk-IhVI3 zT+>A7F`1qmA{TzJ5+G?kQUj2NsTnN#;}^E#W;h0MeQi>X(8^T+=!5EmDQ@^$3pea6 zYr+S5ma^q}dIg7=tzp*QeXiRxBE^rt<4A$m>M!X4ULv0nYetIDZSW zD+m0Mg4RS)Av?DgJw6}gK@gp|$TIL?&}K=zZ8>|W#NPAy1K@Fl!=XMB9!q8B66>)r zwEgr8ungJ)MmuSKD|r|g#LG*-aq=wM5k;H%eCSXE+SPxo8DxL2QqW!JW`15OCypfK%X{ssv4%?Mh>nEw89>XcOq0Y^1SUaPS6J z{q8VaA|}-5U}C@rg(yTJ_gQ7pEH-T`5_*Oq7TJr&5qz-PBPvUxi^9rk? z0&r`SytW2_^<-uhQmt{&zI>qgD406RI7FBQI3QqG6@ZGs1akbuvHa{;iwm{M%+1ZY zYpm91YGf5y_GD@~7IU^F3T9(w_o>_xXXIht@$wfBISu>zKZRp`Z)CH*ucO1z-}m|( zUu*XJ-dKuqJ88i7r?2 zyNoz#0je2=Vu4^Nh!ktd)_%|;msS*+{dxfWd+E{jq;1oQ#z`NfxlVa`Qp=mO5$mg= z(0Fd|)%OZXVs815u^yC7;}HRGy}yYT-3y`%F>AF1p_9dr>0k%V6NT2p9~TO|A8aA> z{DuEEtvgI!vV(!(YP6E~T7=H`=N(3&SUAv2JR}gM5pdXK!-21QFKKd96zwJMj0eCy z#wr+5E<5?26AzZm(P4bvrmqXUt$kX4F%4N zgTPV#!Un>(7&1BI9RXPXDyQyuHsCN00Bf4qBeHJ_0Fbf7#%Hpr@qlaa3Y*OXL|9?h zkfu^0TW30jMYrLOMsxUT#dKyeSqm9_1Ug>-c=F#XO0<*B5GaUgM3+=DZ;$!ZxMBwK zy?O|4JhhF%G!FAQCDR1-J5nGTD$zetX+})%`9efg)B%nNoum)(Y?4p1>b7(<+xR(L zx}D^4c^`!7F%CuzS@M+_fX_I9~lz4KQLc%BwkR`NO1c5)a_V_?866|eXc z+xvqBbIBGo;Gtu0X-V#uA|l>M!X42}R$vGu(ebZQBpOIKtM}%OePAk^43{sS(jID! zP?Cs68(|>0vaOcarw8F4y^rZqN&pAtr+yVEsE~sYRJ-&wgGk98Kgpj!S4BLne+yi1 z3AnQf{eFLwJ@Ac8Lj@!~q~T3@-V*h1t1ikV06PK%VH*^kIuM;H@_PJs7l;Q32UYX> zfC6{UgkkN9Ue?1k5V5_#X{wW|nU!Lgm)7yzWc-Ie2=%hJ6l@kHR{*1EE!U;$mKt=q zoyJ|r^ufM7%JS9@N*!ff6&= z@uIi}JwLlu8QLMF_d#f!mCm*7A0r-aP3{&x5Z*F(_waC-d8OviSu+x2HR|=E_|D55 z9W(3g!Ag`*^mI5ZiW`w-`uL(3VXpBLSG;~hB-dP;p{|t z_m>Yr?0(*3?H9Kt{rPxQClW1t!!PPdcYg;+M3xDSCM{La{gg!f7z$@<`y!LW*~MuY z``z+M`wlX6J@>&_G%1a{eUF9~FfzXv6{P@~p}5E-ij>|#z`wg;HthK11f~HFRPt8s zsxNw(moZdvws@`vLRvwP(_#2qfO#m&l??@_uYnSe@$o7xNC-0aZJI1Y#o`&Ya@)D- zdHI2kXqIJ7j0EO3dMCh-X4dA}GtNZZNlxawb{N#DE!G0c!>b9gE`=Gq_JZl-QIX$c z)4xA+ww$Mz5W8mJs50H27%yOz1S>FweXa1YncH*+0S;>xB|0e3@{`$x?Z2wFN8>>_ z5=33livm%qB3+xbiZedu@z>DZ`r0UAyT?1P6Ym%BC^@WvlOKo>tfM2K zm4Um@9uD^9$U96lM#c-KAj;sndPIVc34pHpi$(Ickw<4+MtU6Yzc{V>04aYI{A*CC zM!0BciJV68YgL6PV|fKQ#RA?d__;-U5qt2%6Nxh+<@zfPK2b`D#XFCQ7hPgh1%Nyl zCtv|7&ZeLSUh=69>|o~!4?UJomw}GdiI&yVi>nVvTbPmQc>Yxl1mdh{jI<=j2NCVc4|Se*WJ`AFr~ZmDloaAEcJCyqm=mMYpHBZ_OQi^XQ4j)ECnRbcv+FYUximkJcT9aJh{6y7o6NdYPGmBEml;0L2XkY-5g;g=-hd zxnE+*@s=7#AR9sKagy>S9D#KAY#0t#t4x6_R3)0kKYZr6FNN(=UA~6&v@|LhYcTLU z#9_2$;eQg%XTsMP)9RR#QJs?4*os}z`2%=(Z|QIo;=)bnXvcI97porWi>Zqy#9{4Y zaz_@7HJ%a%tXpu;8Jt{Va{)kgjT;QuMrf+M_Pz&dfX{gi+`|5|bMi850}W;d>_cYC z7}4t=hlb6`)%!C1CrMDg*ha_ojXdo6z7+OBJ^nw)8;LCQ^}=$xy1y^BT6*+-KFrgx zD!06~zs!Uw^ZhI<;uJj}}Ib2tS3R))8s`%i{hEob18zx3F@q zOmTGZQR}R6V8>^)j-3YuBLns!Gnvis46$GnfoW{PfWmG~N#Kt|jr$fC_)$I!;yvh7 z==Oe>u}a|RcY_1qLKYV>q${0a5l8T&2QrwxYCmWKgKxy!5c6gvGXz2q_Q+j093;}n zhC90Cf#?Yp@84i_5D=VNtnb2nBtT>gq+5W1zo`z%Sxh@h)k6~0eh~E7T0ke?pre7{ z(2?#JV_>vt^GdsQW>3NPx>ey=JnQ6#2dUtclC*5*OW;~EJ%Vl1y^4bDpEKC5aCS)T z2LZRWNqw))9@#UWQ$J4nLVpvZj1^_b#mt*QkCwb=Tg#QfRJ}=VLbjgXb$w8FSb?mR$M5$y_ z9V3B6N%HxBegxgT%~|kPO6LB35Otm{DzDg@-xK%g4$oYgV@_PkH5|=znA6v&DbLKc za}tq#Pz@b(NgH)v9eDrnemOX|E^=8m+(mfb#{vW}a-|zGoUu%YURYrrWpb$3g0ZEo zZLc30LIqO3Lo5EG*P>y?m&vVhrbDf7Zr#o!0=Zt3q<&XF86D;+=>6qnpkrkk6jrp* zgzHv&=M2`$0DbyOH|b_=Z8;k_cEoRNbX7Pm&s|ttdL9K2N@V&Y65>9`xYtn}yf;A) z?VE~$%^l_CCAJ;V==cV4k0+yX06Ai8rU(tv8BmoZw3*o*< zk9i^;enBy1(5bh_pw)K|NK6o~dp*tQCu>2yg!_NoM!%rqg15290-#fEv4b8g3W68B z*4)6`b(iHcceWjgn)OtVeWeiP8QnwSQ4)Ykf5pcA{hFWt_+xw%;m4yQMe z+cglhm%lla9Qx~J2-$ZQtc-w>&e5F0f&zNf3=kufy{7--6>`fCr77yXknSw(0D_QC zdvjVfnHs?=MWp|BkElzI?+VNY^|~hA|NIH$&(ML`nz4iW?7?Lcf5&=Kp&1Z!{;fB* zr+Ho2{-Fd^DP)2t7`-U;=jvVaH8t!b9$xMJuED{~nw`L!-`h1P1Tz)ghp$?OZqgw3 zFj(o9Sd3aNI|~!&oy(MzNK+Ha(-2AQErdykKGtZL%mCInNR#>U>eZD2px1Kh zSJW>PzV{8!dTys>dhfPC=0J$JCnY9{5ncoRo$B}4X-rtJyQh=EDrj)uc&{eOO?GHM zz;R$IudmuGZw8!tj6To}wNIT+V*+HRPXv$RX^dP|xpviR3wbFHOfV~X2HCqq4R&=hvgUzQ*x zf;hW~uaO+9bO6Qt{f~PNRQ|k6qk1#!cTDvLvjIqMao?^OOU}x5R~uMIAPDvVH>H8t zJtS5kRZgSb&VL1OOzUt<^Ybq;;C2@;FbVGFKJz(X102&@0ou&X%zT)*D`G$S&(`vo zlJUW55(rK8BV5asOnF=(UhM+o zQ4KubvuJpEN`hkp&KIY#D11~MJZR&e6lP8Z&G0MPVcAjHtlaU@8O|!Wsz&<9ZEMf2 z_HnD#3;U$bq^^@&>l^CB&eL`MmJhY~^9_27MpU!mXh;4vidO{G2;uK264T#rzPO%7kz>6+A_h8+BS!F+7Qk_>!`PV9O zk8=ZYkNd!8IIn~H$Rs{#3%U5FC!wC!6N{0vkI8jPo`m&PI^S-g)q1{b*<)9wT^(0$ z8H3|g?N29AR#sXtDaZ6$Rf#nh&Ai&!6|$KbA4L2f^uWJ>@mm30uYD-DTy2ae##AwV z5oX){UJ@1g<9c3fr+YnBjAf4iRI5HVrrk7lVy+TN-@UpO+M+e2ya;lfDl4z6eb;Q&*x@}hVMQWZ$IoEuo9&jHRK5~}p zBPq&J>2e!l6<_Z68;gpkl~^Ui8gT$QEGJ3bshXjf#8Cb&FZHu2HZjdoX*lE>W#q^Ha43skuJiteZFrVR!i$0~OC4 zKl6NESu5fTQS%gA8P03@L0~$Zy_e)FwP=UT|EizQ&|Piz>(uMl3qO4?peC~>B$h+| zRh&T_P3uHIXJIXLK1Mm=c}pKx4i^4|6*N`97&!~+GUI>0?1Ov*A;vXoe0*|Q-?rJA z$*QuIheSxLc8F8Tw-sHzKUqwz5;wAm^6`lJQ$4Qn#;TrW?Ww#fu9N{6 zlGHT&^K){Umk?Rb!sWA0nyKd#eb8Z6_U=Z*_OkL=@-~OlLJu#zM1KYTKFPiMpyTSU z<@{926**c@S+AN3tyM%+{k6JYwQl>m3iS%x_=6%+`v^uk`k}nh$39=e#C_uOtM_uQ zWqG&w{|Y%j_Y*Nj>mz~#Mx*8va>z2-Xgr9jstG&W`!n_L6)0`C%KCgBhs5`!tjW3< zvoxN0_5$1Zpb0fWx`^v@8u_LvbFk8fVVikf)pldq*4f)%xz)PLqy-Z7CQ~BpCwO<~ z;?#Ziq~9m)5ji3DQQbe6SXOrhnY`|7#FORmw)f=+SbR3}+h%G}Z=)6VcsCfWV!OaqCi`b)t1Pb8n&F*VGy;;WlO%ysl(ITVBvsG&_q2?#& zDPWR&wIz--tPrl=nbSY!T;Z%5C9C>H)w5ovr(PR51c16Psh|)#02|JfC?tKk1eLqBNU!#MckoKJEpu~j z%&$1)h^vBu3(Bt-(NpsiGM4$4pIc*$-dopGLX=N=%bh!-y945>=R^b305~N3NOj4o z^Wd$^uN^-*+Ww4WGH>%%b1Eg*sYf}U%jV2Y9iKg_zwA`Q6_I{8sJbeCYy|!JdI$2N zD7tDE5zgBnFmL9xQ!N@L_T5T%*+N`v);NmwT4@x^4N69zulEdDa@4*5-uv{~Nw+V_ z(#sEqjM2UASz_6jq;r*lZ7S=XTq7I5tAZg5Gwa20$xh|-R1XCc7-i>t4yxH9qLt68 z21h;p5~P#^yw@~Hm)#d8C2?k{kt~B0jz92HbIdk1iwrla3s$63YxDwqoYO7?`QF+$ z3)uUIabv+&!+n@uuQh@3bJw<=Y>ECfG`|)da%c z>eN)nD9Uhxm9_KV&|)4+RB>ecFXlsR?0qT+7(I|A-Z z=gq4EN$Z--6%dt$GL%FH45whVMNa4yi&Y^`wZ+UQ4NbFk#&gI}6j%Hc7_w+yuiLek zBD_e%weK3m*tY&^nevcsPTBaDPTq~*{VeQ4T%SKpec6@;EV&ulz5jE>6mGZEUDJHF z=PG?g#w8sg#))%3$MO|ss~@P9FNL8FeAG*3#keXqM4YTqAFT!3m~gC98+kVZihIH1 z(fnkZk`O+!9bo8gt@wi=ocy_Uj7jA6Ij(bL3h$`k(8rB>d7cGd^hVia-`A8Umr`3> z#xOM`p*AP&p5|O8c99LAE75nw?~C5^-oApCXC~wB)exoh)b;OI+z(Uv@Qf^ON*(P* zYIF2(ksMt=FEWFlQ?&b*?Al{Ja%&yol)ln;H)K`wO&cP6n~Z6p(GcV{5|_$Hg7Lkz zP;V7gEnDh)i*fv^8-@f*2Wd5jFP|MrYS+KsR1hh&sC$OJWjDYk z4&mYDJMLx~9F4C1@$!C>7K)!NYyA7UJKy(ZgDVdv6AVPV#&UL$*E0>Oq_ZS9C`fA# z-V}VJYyS9>fbboGs0P4QOYeG73TvH|B`A{HEq1bWp0LQO#G;`G8XZF!?djd)Y^(C= zWtoY%)7UobSEG9%{DK7HR+0XOVNul-H^qo!lBzf{6D;CNZp7I)joo*?ue-b#--l#M zPFx03j>?(*91|r{4rzpIefnn5Twmd|QMVkl?{s(Xj|;h_UUHn8qDIqJ==`5hVA_|3+z3Rg22+?0Ov7wNdtmU7 zT8+95{HnB4g;bc+(4?vAm0WY8PxFtg5_E@=guiVG~Closoe@*YKRYTW*4%j8yV>5h1=x4FYSM)|Y) z&KBipjAX!DBloWE{ z^JbB=qD(@(Vkvob)}?cqSsSm&Jf%Q>wI&axIuB*!*mBGmbO@SB{Tb&)*ET=J$B8)J z$LJOIw2XBENaX4ivh4GCtNeGAXvxoMmlfzOLzWCjyS{FiQbUwtLt5ohqp|(Ow=0>= z?zwyfk0Yt>+TYCkuP0~^<-#dADQb4Z%%A~ z^umhNfbo2p{T0??HAx&nKZ>4E*5Ch4I#42A^p@*&Fy&{z?lu!3=L8%p9b9E2T4b}* z(V8e*o-{bkG?g@8vx$yZkePKYl0U+YD<|O|rd#%H)KcrHVQTHkAjnbYTgPq;t_;uU z?1_$WrL~u(d~wf5e|?!xc&zGWIj8y_o$oWp7TEqyU*v8Z}#eGKp+tPz(>jD z>+PaWT~CCf5-V(m1id!1AU){&6lJ#y*=R4!gM_NL607f&)N{~xIWZrm|BFlfx4XOh z>wIp7?GFc#QjtPT=V}zffg`Sw1*6nqD?B_iX&alI+u(@*EbQ!Q{Nug+$awr*n@vqg z`5Q!0R9DN?IRu(|aINzlPmsJ21eP|pwiMkB4Ga?F;^QfT9|?$wWfKrz__@9hmRTp0s`)R6{7-X;$bo~;3`WD69O#cH%RdbEP&fpu0ApVIpyUmKh7zM zNUebA$1J#@Qkh*8&SV@U0WL7i6|~&$A{83`1oPf1Y;Z`^mFJ=Cek{4Cvg-*#wfl?i zlVOij)#X754P=*bvrz}nfvmRo;95ml#GW;7XA~%o3B;3SX=UXElC^_%mKPVfh|X|; z?DfZv4HR1G;A-1fD@r=L+i!`Pnsu|#*Js>87GOHK-SC8qi)(IiQT(%RyXdl*z@0nK z;q8fP7s$SU|2_lqX1c(=kWFyi=m|Kc@86Il#|_N-&q-2z(^dc%X!bvDg1}IvT~G(O zu#*9V#hhL4t9;QnMd(_;TOW4XR_ zr}4`di-)=aBZ5RLHIVUdXSQ<%2QoaoCuCd`FpxO7+%zFUAN*+3pWE}^d~Z$!6LW;D ztm<9bq|L!+-#&gFj(l?^CnYymF}%C4PbkHT5dTzBaq%z8WN-^DBKP{?N_?+K`{EXb zr``iD&PafnE5amEmDQ`kcIg!rdg0&Q*3G;?3@fR}s^t53neev(0ZOIOu41=kEuTOC z*je;WUV%aCpgfD|juXqOJTtZbB!@GNWQfk2U6D<&9-0Xwop~=$-+P<$Jv}|lvU3Xy*{;aZDvu(IE*3A~>iz~d50eAvy|n>15MQ8GHaAa0 zGxbbv#ZqT`qG({=z;}xXbm|!U)j;;k?`F`kLU5(v4!{>XpZ%e(OjB1^ZS-}oO)Z~I zEpTTd-Vq#MSoP%^tnGU00wf2Ci#q6=P85>$N#Y)k02k(_iXTMZT43>MqOqva4lvBFLnz1!raL?G5^sMrh(^?Zoh2}Rv)$fLxOyvw-Q zcEmEv02fuj`=|r1hUS1YY_lr3_;Q9byV~^nZa0V@zkN#tg8!r!E@al!K$74ZVl^o# z(&6188(5#eF}@8Q z4n^O;vqdzgXJyGVGBUF6F@My`EuZ7?`a?kf8{EF2I8OwArndK|w&7c8e2wa5_YY@W z`|jBZOX-?^Ur!k0W5>y#VeE+zYFf7Z-Z`LRjC+m0eSG$;bJ8&WSY~D#j4D-~zc8JLP${D7lt( zv7YWXAUsazxpEJEO^2GAI@37=H@8;m6PT%D1rDWhN=8A3uI6k;nqhbQwQUP%SV2f~ zQEawguB3E~p?fT_h@AF7=Kq)S^72dr>|s6Vt?-263;a-|*+@xcY?71XEUatKT?1)rYwNk4k_jL$7vwk3Yk^ZW)QeHg5f5Z6 z+D1-6cq8nG%)F3mLNmw!I<*H6{Bpr1L=H_cACNNr93VtP(~$x<8fTQk(WdsMaZV4& zT2FHn$q@ob56&qpJtd&Uc0LsVOiU3zi#hJqg%67FU#WysUbnXB4plP90_p6AAWgpv zNKB^k>Vb-$UKTio(W^l$+O@FY`~YT!f%-NRRX*H15S zoWZG&w8W&@Vb){T1a!#*fW5OIkGvZV+PS&6O$!GsV+72pX=s>bi638{3x32RE;+Gn z0eK>mp{@&Vj3k0nv|j_aUyis9ygbTf zVIj~$FYc}mE`faq*ea2t%D(Ga{kQEUr8PE(83g#R9~(4RKi}`FfWf-}qHp{S5!#HF>drdqh8`@rsIoCZdDq|srwQe6JXAhI5~)bffKBiN z!ixt_ijIci4(1jqsI0z#aY<-FJz z$i3J_FPKBM?rxkT=zP7WC(m)#Nehw-OlHx!Cuvi+^-{wqZcV*Q85>VBSbk*QsIRQbAj_$8u zE_d8He2c>8=hjSAT@I!onaRc}bnZJZ5uDT=FxbeKq&*Q?)vg!%G2(^tKBG?RF$VU< zL`3dRQ=(%T5?1ILwZ;kj5)^77@(YKtQYHUc$+z_IpqN|Mdj3NBbKO1RTs{B1#szi- z9X3GYBKc=)I1h-^`51$>Z<5r#y8mFu6He$SCvbsa)$sGaqo_;pbo{<#;EtZH5 zr~3N6Zeq!=z<$*LN3$LBfLO2k|0xJjF@GX6-{&&d$}eQOy);rj?ML5zi-5qMh9=6O zT0gd3vFyo{f>%qNJuYm43Fi-A-#JxHrem+FhDp23LzhaRlz2D*Bmkl-c{lg z!pytQA!Za*FrKeUN(y!j9s>RV>Zz$Y*xT9UM7I5+qUxXtrRyom^Qi(?F-9z{t=UBF zOiUi4|96NZyreosqAv=hX_r(P3{15|85AoR8YE6`wfueH8&8uM@8TvCNOsImJQYDI#i@^G%SBQc!-l`*=2BjL@!<17S#HsLT8ZqL zR|Io96`FNO@5I589R8u9p3zXORZ}3T&6DU5@A5VRA`e!-H|h7cItR8FYJR<1j$uJ zE~~Ima}k~9+cg%s9JaYTot+>hmfKk6(Nk(3N(<{sx|RFEJgD{OKc3${9#mCXdd;!3 zCrU^J*HN0r#Z&0j7!FLExsj5tSz0-apMom!JyI0B1zU#p3~*>JP$K zpKlO`Hxu$!;i$qR*|vn5I`X{FL3!={>i%x{K9l)0`AsO`)GIm9jL11MI`xSp@k~+s zhXtC=sVs|Se@RU1pHjhEo?JR}x*PnD2@)zs?u%?hXM%W1LW9`$I_2laDs>Roua~X( zPRKOMsPc*#>1)-EKh=RM&6bx_A!vIkQ<7Cuk~`kRX!m`u8s8ma%TRjNIj*C`g9 z$%&UAIaPluHjdg9{IimfSWhX2>+gP^Bg!(Er5s0kOM|(2X~kHET#sP4NTAoL*5Bu@ zP_SkAV3l5?*{I9qbMUgLdgqH6EaGbc-o5eXL18rSW@f0&(|r(oXVX|uKYBzC(hHC# zs(=}ob@ie$auOSq#Ce;XT39GgUp`BC`Rwk*>fa8i+$Eew_ho*6?7s!7+@QR8;TFxi z$=9a@1b%h*PUGYIZ@zH-LA1O3FI0vNoKnw~S5Pd@sT!Gl{p;pu)jLy5cr9pG|GJXc z=jiLACPC~(#2kb`q#K$Blw}a}eOY#0sj_LLZvX>{yDEnz(aEZQ$&hVse3U{>6BY8v z;mXD7Q^q+56t4+SeJtUeLI>gPZI>er>LjQKj~EGSNKf+yd(|g zLQR*H|9ND6-)Sbnp}Xd3{YSV6osWKwsLNIQp|hh+>X{>yq)v|Mc3mtDnmKVB>$`kZ zJx)&S?kk_Z7#OUX7RvSXut$-RGtp2-{u;}kP}ni-d6wNqND?l)`}mQ4ldJwK*8^9) zrzQ`Pj&YxGjuz*|W0XqgvkDqkmI2GPeG**o`2)ZN@H2eyZLrQ4f1=!;kBZ7_iV%P8 z07>NrVU19+vCFdrnJrCHViHr08xI`{FX%glscvpgZR%!G_#7n1xh%$oi7>NYd6#Zi zPqb;%|H=AE+a!0sW|6q~dpfc7^7;Ucu0GZYx3aV#6%pz-!gJKr_I0lhyzE{nyk#RI zC5bo}-aO0|6`nU)Eg2ih9n0zMe8`8j!zU9X+;!YH~cILPyjec+3eCtq3Z zCiZiugJQ{*UG+;PmGDmyHm*-9F_FtK*`GSq7geO$yBtGv<|k=DRLDa!&w^Jk4g86T z1E0Q9_Nf8$Ct-@{A~_c%`2Csx1rRst?3noozX=?VgEqTKB^ISU5w)kmDxSOc4I-if z{R0^aOng&)itNffb7-6d63<%#=G&^CdXtl(T7l)7;76wC%G&(7dW+$Q3}Q5TQwld% zZIPfb_;w4aeUOEEc9ti+{tMn$*s((h3I0Z@ACm5FMjZnLhNcTJ^{^1uu2 z+2`sR&(#eXc-H;3v;O>6=4Dg9OBC?dzNj@{f$2*g8W^h(xoT>z;;hWqezv5k zAwB=I+01;goY0o-tFc~j`gXV4l*Y$s<*vT8s2Wt2rMriDRrHlG%jds;zo(#Hn)xlG zH}w5JEwCAS=tNToljwT3HrTqyBo}?(Tswc2fC%86>D*joMh@3#K~Yh``t#R~3Hi#oX-S#J zX^AX(Kkl5FD7W<3vnZ-wxxbluK_SeE7QnE;@M!LM$c2U&uK3>Vf{31&1B z&1}mN;8EBnL$?o*mOig7ZoN6>IqR6aDjCHw^kf)X6Qy{Tjr4RR@L8=tzZ0Q9BXcb- zOTPY8m-Pk7aoBV@Nk|aeU9s%il^09ivf8!HX7H~evp?V7pBt&vsfrhBxz2j`;?lC# zeuNT-`^;}zEujhk;ozU^P+Qn&cn*|_#Ra?|RCBxXxk-zb9Cl6|ZTW@>Jud`pd z5EDRRX&Ffx;7|iuYqGv8W?mz7m0+Tr!jBLQ24a*&nrGO^lj4^nL=FY2mF~!J%>PZr z*taY>+7A&S{p47J>Ig>pzr*uJy|x<`=)D?`^vZ}lV7>tuQgmP;k~-s-Kf(K^9|&Pv zU%@07G1?DgXCeV#UUukZl2Ge(a+(97D4=6oXwobsKFFjmW~6nOn#01Mzb+0*eyA4l zw8SvEq$SQaH;%`}dL1NKxoCh0&ZLk4IG9Pe#q`Ptcx&b6t%fJk@xPKtbRP zk1j8zvRZ_dA|3o=&i(p=)k=Lfqvy{R?lSP)`6|U%_6HxIf+{&|s->sGB7#UOk51^# zxO`gA-j8#ZUgQ35;^I$ln^;-}K7IW+62D0}WBX2S)=I6^QtueFg7p04Yqs?ur-Wy} zKT+OgD}%T@Tus$b`-j|8Uh#A*Y@Malr0^O-1tJe9FV;6mLA@<;*}{CvoD z%YhE%z*6t$GXS5X$;tfF+5mjl z(_Ws1x)c}@z?As>VK^>s7;z8>uxDxVT&tL|&49Y!Gs^MPy$K3$Ee=luYtP=4I%G8? z3-&w6eZ<=9y5ZX>{}Cj@+l}?&8A`jf4gYrS_#uJve7%iy24A(0c*^6#5D_l^z~F`? zSd7&HZ25K)`-qpPBhM$@8j0RtP=%|0r;quJ)}zk8l?f_El=oaW+^yCZa~qx%m3XJ#u3YHE(RB=>>JZF&Z< zvx>qb?!Z2O=V;1J2kB+T&aBq^8K80n6c*;yJdrgqBuOX9Iu{(UT(pi;}I*&q_mAE3H{1m+(Qa3A&iu5kuVuM z7M92A4`!FAnAf&TnS_)52$Sp2sGVoKc$lYJYt4XTKq=MSj1D4vd#~ze#;6$slzd-h zr-OVNJ~=)>xp2#?k!uy#(o})n-Q=>(eTVpJ9O7IsGC3Y~PV}0`Xr)ckmS^?w?Lq&G zQcs%}JBwc2y+)Fr5thhWgRFKGxrR?krNR)~>W?p1e`>W9znQ6G1a?vAqO$d-<)+PW zx~tXv8~EOpvjQ~-1;C0{WuSv5lkid`!P3-aKQRn|z=m2x!T3s$A?w9ZI6mRGk02rk zPNRN*z^|{rqZqT|Sq<_RB^!)d5pwt55K1i8PNF34gl98RG0xxB$hBM&-j%w?Yobhj z_h-QQ_g2Y$T^76gCDy?gvGl=Gr;Io%n~;gMi- z-_^>sMBiJBOOgY+EQNpK)~qEiDxblRe2dqZ?SCJ@l4Xp3BiLIO0`mK({CT9ByYYO) zZU-3EW*168-)iP|*A5oF&(UQTZHBU6Q?X1_2S3Zt3oj5RjC*w1{*| zDJhL~N`puveEa(TzmLIq&!KSc*=N;UbMG_P5=P|~sr3d%NIxs(M#4He0itE`BXH`f zGw3^YVR)ybOHi@SIY=)jyJ|Fz4vIIx8?&a*rTCV69N7ai+sp|Kf)WvN69mnem}nEPW!N3xxV4?p-PY;j{uhq z3o_KtqQjaZMvKiBiuC&;CO`1@VcfR9ZLA{LGU;q~e`r$2((v;Nje16ZeW}gCdxtsf z=6b7Cc?ioIpgjFg`Lbnxd3jC&pN?X75ah(~)!>ztm6My=48NT}vF2~eYOhvgPYfUw zB!}r$3F6$vyjGSCcUF-6F{U@_uN_j>2d@3p#ACHr8ecoFb%hcWss>sA%cR7{P?{R^ZtcJ3v;2GwciI zj&YZO5lO*k5Y0)?iq?ie--Q$WmPH#qGIui%c~SR;f{8-JiPr(UyU{XKu9V^af7JT_ zfQaEr1>dK2!9y+Y{(FlW$GEM^_1Jo15nKIvoi6|o%T3%rd9%dNG6NG+A;`NFrO0kb zVaW#Q22Gh|Q>$o0jcG%x$R%O@|c-o5|zd za)*VMr|yf3x7XIVA|&EcwR!DkW!FAMdwZbyw_|m)t3+XBd_IAV%@6{xT2(F8lyz*Y z++|+34XOwMTUPW6ddTyaX7t(zTDt4vd;B)L1yNKxqIp(rTAuXf%U}=ZG`r7b&BKd*oxee->M5O{4f}Nf71j)#*8a1X z`qYfpi?v=iicwuB`%=+LdO^XDfEf*zm&cBc9b;-mGPHKd5B96+1)WE@!+-9tyqJo2K$G!H+mthCQswHRj$e)y@Qax0o8t1#!J5@ZKbe53-0?kZ5@Vv zzSjd5*s^H45G?XTu;cV^oy`ARCMT@#-4R4QWcY5{8UA-?i&@ux<9#3ZUFwL?d-bYu z?7HrUDKB@+1t~4`MDx4?Xd{q6nh@{(Dh@D*>a?2UVrn;!wY_BLEMM#R7fwq+~D8t(E*Td8~g~m41Fac=?BSJk~N;IzF#)q z)RNRnRp-e1#uQ47&3P=q`fp`8*#F0@2F@ifySw&z{>DeMttWiV$2)DXR2fk4;jh{Z z2O5e!QUw&`b`fJJBkZjcfUlfKhU7^!j z^jx*t`IFJq(Q-VxbF@KH-M;97P#lNnP_woN(Es%NiA*1gnjlb&^JkuXwcF8BL--e-K z828v3_q`z0itpvjn-q9PR$qsZllo%og!KtMX8nz}W|MSi!WRb=1U zmkmgGhnhNFU_Vu15v?7ezEeG*bo0>MTj30xb{e#?ZBn&3G_-yfr5HnugFS)sW4siw zP8Iiyy25RFf;OFhP}D<)F$q|*g0(ZeRxnVS`oqp-^5*F*&yAk(Ij*RcxW1fo+mzD2Uw;($@dhsz&*LW~|}e@Z7AJ zt&vud@8Ei|RulGtS#5ew!v(wI!`ufZwbz2LIW3qikpPP#Op*N~G%$<^e8ecc%Yf_AO|dF}`Vy?PEIhodZO9$L$@Y|2v-=#=w|ul#0evwbiU6hd z<4Rk0=dEX2R^|6%@>pzg-ZrGV{Km%t4BFa{Y_xs;+$3O<+}@e+T1MSAOx=$zeNgJx zS=uQKSb{G-ef6bP^@|Nvh?qoqIQXgo0ANoEKRYaia zJ?<$E=D_ffO}OabQRf103L5_)lK>MZ0|#17S9s0rY{u}cSCS*pKz~)aR9?P&H*R{c zYv5VVe6}>Yoh`KpcTlPBWY=#ylUlCUp2}tjX+-!7ef)r6Sf+liI1D>>hIG#?k1p zVPB_MK9ygk!;?D-oN6hG0!B-??nIiAGR(73P&0=O4wA?<;`>XU-X|zpM)eCwYr114 zTJzn#)|Q_LlWD9IpnUjiH+ap3^vwHHLFdn9{D1&yiT(su@{izir(hSs7EV5m^k1)mNTQ81xX}b%MY|*dct;cE1l+3GQr$A> zpN`SbSd$&uU7$e`UjSYSaKa0J>{&W@caAs`0T7pK=A7_YXN&{(;<5C%(Ql7{$mG*LR{@47 zbLjZk;l$YJ#GlS7@khc4{;g*U0|WBU6(b{URmf4U9mx(xf48;PNwE+gP+oX;@o2Symu zoG9)Jl~(umLTIj4<(NWl6$j`!Otfp%g0JSR%FeZ(=um#Z zkF}5`3<}-<%iLrz@U%34UrN-wXyU019r`zBp}nI72WW7?k8+Bdu+af7ocx&>8+i!vnRghoF=`S@jOYK_QL z>*oEKTP;sq-e%0NRs?Y4gCt@h>S2f8$zVOguPyLa-Hf144-0(KPq0Y3Je-3iTAPX|k=^Z7wOA_Ny<=yClF7 z@8|=|1Z2Sb8*y?5BzH?h`biG;Rt{G#ASYNl?EEO`iTNUf1WpB9-dwLxQ>`EI>7}%*<*;!*ySEBPs-wV#@`G!*9R2>1m|Anr<5=DpZmh5+^Rs|A{~o!X>;E1({HYuhN7As9HP6w5w)ab; zRB!9j>WGZ6=0BFa`Qt46KnTk;vODJ96%ARhrL8JhMQ*~D1}$;jnY)6~ffuWUIH-yn zk$6Ab>x{>Eez3Mi#PRYBrZ2trmJX4Q0C0V1CWj>HR*uFc{kCsbMb<~{sX2FP-UE?0 zF8h~Atwz1AW7@42$aBBT8KLjk|)GG|u4!_#q* z!B6vP=`C_Lg@ny!lN!}coWIGV(8$k;HuDBuT$1iNgOT7Mk6MmKlO))2-)Tv@pd-g# zoM1fGIelWn4Kfek++y5VFuDSdze`+f=khYXxjCIE7pttGYn%PX-ON3PG8GtJ?i zjZ|N6wsQfUVaAuV=&(A;ogo^Js)k-2-Ns#OK{$B~0 z3X6q5xgt9necr-Zw|T~yTCwS#LnUsqqNRr{CsS{n67x6i5UE&O=KMT#oHQ>!J{`P% zEdsGP#7o3OffXit<3bCFqObn$jLCegtSlWRY{na1q5qfoFM5dL(!AfnV4EV9zCk-i zCtisA2U^%Lmpk64v-IURLABE65urZKIXOHk`U0pJTbhuvgRPmJV_8lNu_WaHGkLRI zJ5Q|)HRLRbE;MVZ;rOx7LruGWu8VbxBVsHF2ZB4}68ua4Iy)bYZURrae{ z_9@&5=-IIU5j!(eh%H@(AWvDTaR1SA#~h$U;yrkJaDH9pRkD}3e$p))NWF+03ODfG zfK57v%6u+jrhI5vi=xxf(Ws@X@0CCoQ4Ne?-Ea6PD>74c=@7llZpxNp??TIyhc_6J zXkeT4Fqhg32^2`*_Oxz#hxhoI&96=fNk$LGRWQgv*iY)*8HKjC?XX!$X3g2YYKyq4 z2tlov7A2OYMiWt5_K6UF^@#UB^fc)>q#wUk*C{>Yo4JW$fMxSkm?(_wlH3cT@SYY) zTYpK09{#k9s?9qD$@|O9_Xj5V@G$cGZ3xQ1iD<$L7m9ARY<{^nGM5-8Ht2u%55c-5REJ{&H*ZAK$&=` zC9XNs9_jKov%cfa==8;@V|0@=MN&4H(yi7A3$ksIeA^LpKaGHYnHZ>O|5A{Us>st* z9!utc%0Xk>(f3t$+(TMzIklMq?O}HnYg&`<1dVdqSC(J%%rfMe!Lh!bc)4^1NZ^S* z?kxGCK4#xXKLiIY|9Yp)sXi~-|_l; z3B{U8N6W2)Pclu35y9+$_kXv4YN_rps`ows@8{lgt!A2l?H-@6#1DaNt8#fvkC?A)b zHd|ogUR$v2hS)gsqe6MPE>K)A__DRp3N0r5x*^_QPQ|mpt=qr;FXtB&=i?wRI)t%* z-%(ZV3#}giGS{jh&>=GO)d|l0re}GUEht<6<(4>~<5CISWJ3$)ngaivUh^}_Ni-Q? zIs6tH_{95#H=)QNog_4~eJa?%McTlD4AfGP^AHklLeb=K$gQk4RY9grs`(jnEvP1n zdk?Gv3d7qqw1iq1Oo*+}S2jLTmbry|78Q9G1$kB%|0VB02Muh}@5!m4SP%MDFs4{H z*4dK*OR3Oe4SaG6N-h4tOz~$uPT=cVO=QK4;0* z)Q$NY_TsnTUt@g%jx+M6%UqH6s8S-}g0yIC1bC$p9XQDaokR)bxJWhuL-1!X*eUVp z4d3`g$Vny zdT(TK`{tL*wRgt!R(*!*-(Jq&b_%3WIA1eo$z!w)T$GH4xr4EaX$Sl!dKG;;Jfw`= zb>}ZdtWbDjXiv~!DhJ=vM2NDluTHKtKH3VvwEzu{)bi!15fchUWiR5Wk2)mLyxfvg zWh!>(tkKZymJ&i2qviQ|!3=d^FI!U-@Q@q8W12nC)-@#oeaLHZqmi(8yEfW2>$20r zt^`3iWiMsmdrD&Btl)th@(&Y+ZW#>=zxz(Ws%|&WYT)H|Qk??X+B+i$Je;AB@Bcxio zJ0u%eF@j9gg9O}9AqC)e^Y{~B+;ncP-ON5dDLeqO{NBEGQrG;wkR2IWTxM{AqQ;qq zN1PFY{zWEm1`31e=i%t+HG~AOqGeSw9JMLKGb#Bq^4Ej1Nfj-+;^vD>npxg4=5=;k zzYm4yU{l*f;HfX-^EWeX?7}VPN4)V64OQ2_YN``A5ywv7M0UA7o93DnU_g#!a4)Lx z%V%|v|FqqR^UiJxAL@Y7OrRZyelOOH%CzrMs<~a37YI-d!!|PqHs?6ohB8{3z2Mcr zI3+zJZl|>*q0V1Il>9Ipguw<6U)w9(zWRiTVlUKXc=Hf*eZum^R})s|Smyg>QycSHw-ye6~}MUSrgi&fWOrGsYnqKl$7R%+*~w z(RJbJ@SJQ=2Lg5q#r?x_1w?8*mm&>SLQk)>H1@9AMokvPT+iDTmR#J3puRV>b+Cq!F$Z&1l zIBT@jJNd-0#K<_VE*PN&?8=LE{FvCECta^C7h1k8rC~D)8k3{tzwi#hm}rK66i@he zBFb6z7k62R%oOtL3i~tZuZ`E-3u%jkrrT|cx=$`VPCcXtmTa46II^zlFDjZdMRBAM`sO-jNF2yf7Fe+ z*Ud*_eoVjOCg&^~4gYHLKu%vk9;w#QwgIV7UIrc$_*DjpP-g;A0~S{mv=!8+)(TgZW%iQcxYZs#PD6CoC z(P{g4r>-#AFw+#eEMQAKMFu8LWa@sV&^@cvJ~$8Gi~fK|ozabcmBUp`AN)@F_>Fza zSQwj$a+UVet4Yb-*udbac_-N%v5B*dzw2HSjE0Hrqtpp@hog9m85eZ})F2s){Y%EB z{zWY2wk@5~)>&mg0_uq2nN3asWcs(RZBN;-$rlI+Q&R|(XB{V+(bjn41|ip+usY6w~n>++}8j>8YxxSw`iV4FsGS|D*n;C1=_VMDbCxzJNE z>j7UiIbXHNTwCX!Mg-0`LV|QsW*Ro$2pq?Jg6g@*NH$i}w3s6=3v4LG&xb|24P$4) zmLYPhs2*C(rpf#*bQB-fNh z;kH#zl6@+lzs;^amM-UzsZ-UmADZ0aGw;2p4noR*F?ClP83`HOg*m|G1J~T3t1cS8 z!p#_ydQ%LhTH#18?id5(d@=?knx({qIy;ac(4J5{YavT9H5D*ubbEkbxH-lEaG6C^ zFS{TJI_scEHhJk@e8nH(gWTxr>rU#xm!i<@WTHF=ugbG^5np82BY!LJ2Bz zus&{NhUw@I>jSgk<7j^!@Am67nz@X^9bMhG7#? zVabPZ`)AL(E{x?FKDS-a8spK1a#2)_K>%cQNF>l+IMmHY$;IdEpab8|4J{v+RpWa# z(XrJ>lMCMcxdFg_(^~H}Pcu%i_p=Y4GKnP2H2jHiYdl-WvIZ+M@rn#}#GJ$W@JNd) z3t4feMC)gLQj8Ue?CgfR3h&ru?2Y;L2x2|}H;_eDcz-V5c1}PkIP=4>uMQ%>H4ClGc>1QRdN1MngNZ&;&3H$hNb?s*5q1`V zmLlN8DDBDA#MKGTZU|q#Q1RbCOB39Gje{W|4=h}Rj&l1<0|c~E`t#Ca3)yZGZnjIu zy5U)xYBDTSX;OY(bi5%tyHKJh)!sbsR7VV#Eh>z7(eWoMw*9Jye>$w*se?i@!VRfA zi0oW`0WIk3N0cNT8kL4$>h+7+2IxJ8`)?Ywsxx&;QuOMW_0A?iW{SDen7W&Yxf?b` zR!_8R(B!%s#Y4|%=(QSTPcTW8g~860A!y`W-GlCX zy!AFJT@A)iLWF7O@u&k+7cl@J-O>OZYCj4fWJ7WM+LKL*arDDntx)1qSXZg3LR{TQ z;s;eA;Xk7yOKFSXwdGeRn2Hn({T@@cnA=ELoKzMU$up2{h{lMfCOC&~; z#I|3{)I|0hyZ6a(vQ)QGqqE$YyQoNe?p=Cn`bXFmW${RqqecwKVzk>foFJ8PGw{~C zJqn+xR%$FPTzMuL5@P?egRZ?$$@{G`Ffej60ch4E>p#=)UNFwjN8796toaA1kQrcU zgjicaDOo6J!dxA3<4>GDhCt2fWBFQk(=Ubs!OD67@8LVBcc_~h?zYW`H_2m^C6v6{ z4z_`l7W2x9>sho4W0J(KCG`1E)H&42mKQG17zs4ff3=$E!6;5BGUTL@;XShM1gqo! zS8+0#3pJj1XME;EM{?2sD-wYMP}qDAkEAP(#3}UNOQP_1z9muV4=??m(UW)Z*aUD<7D&+G=6AkUf60PZue_I8`mO9W+^K3X zQAnxj0ZiL0{OK{`{TJx`Ja+F+_QecYGv3Wt*eA8FSwnt9Uh!|*z~ho0 zc_k9^^B%si>(E3e5-hKuXUt6+JEN4xNHgR#^@|8Xg?n!S%$q2iGc%FH1(*vaW>z=J zH~k^49|){!HyCLnR*s|yb#xHxEGP!3ubC*syMSrti`$KIOItp7CqQAU{&qZvJYx^& zt*IuKfnAv4!x+8mvJ2q*KrOv0zAjVy`{^x`#c0rl8?B}BAOQ(l&GpiI-Auny1t|(~3xv015 zML;+a{y_f|>$`@hbnSlr*6p;v-bB(AWEu6u-L;p8zq0&cg*A$W+0`Y@#W+d(J{I+I zYNQ>LvC#D58O8L_KYJB{C=Qnw-d~1-P-4VPw0~K9T(cCgd__d+l%#2-?kg&q_@UnW zvTxX1NHUW8Pcovkr(PT^*s5A&$s?IqfZ(fFuQ$&3Y7^^0j-JWN9;=`?(n($o)MmTl zHH+w}36-n)1P2BiZw({o{<_k%4Q+L@T)ObW#Hd*r76G)<*0L$cLyGihYqa>#%F4(u z4UEY?O#A2FZ;jNLT-ddF`MbH%!P6*Wg1PX0D*Gfp z%`1mlT!oRQ%w%MeP&y7l)=1L=yD%0(gvz|rOBokMW>hy0V%mBnrdpWz(Ref;r+1zF zlOuOY5nx|W*Ue}|tjPim*~J5=be%qsms@V_#D*Nn+8KcR#HAc-pdbW(Y}8FfH5}DX z>Z@P7jZ7yAnKp-)K)$wUr&k(Dk<~f_0KLL|x%l!_!t`T{A6z@e+%FTTyMh~*f~_4Z zx(gY>Dx--}q9>x1pFQK(8=DSSenv&o;CpEPWP-n$#7i?fkeTSwY94TmQUYr(nWaS8 z^M^s+;aJ~gRhfQc;8v_UHLoOwO%0X3r$9#29gq=-_RH+Xn8Po$mNWH~89RG{9I~Gn z#7q_fl0S7+XYxFYmmht>!+#qqsj1xG2XXw?q02k!=C|9|jRxg-8%29N4tFk`!j#*f=*^|GS9tge z?L$=q0%q_iGV^ef4qscCJx$~Z%oC>;(nU8db@)vSV>h(mJ5m2 zX_zvm4=jpbLxiaWV~XabyY@d~#~BxlzgR_46U3hTym*-rgbHQHM1Vef13{w^lRvq8 zD2uai8sy6h50O5JAxp@s@mpt+B%H!NL`Et@n5gl95#2rG)gax`12jEGo|) zM7p`rw^|@~)6hh68uB)b^fu$o{9=;`330;5>y`xm+X=3727@p;3NvMo3`O)H_pS~s z*fu=vSZk^RjHGQic5Js&aXbcRAWScVTV*gXXfZx?{3}^4%xbchp@|k}ANAf;PA~x1L0YNrqqW7zTdNQ5jLg>$UGb-=~I@ZC>x-+gi zSsdS<@_`x4BY#1$8E>+~r(R!ArJ(?e7Q$d4IKBE26nq?v4z4%kla!~e-xv|GO8GF@ z&H`!V#Cb#-;3Of4X{1d)tmIS=4C%D7a0CP=JYGM#KP3oJh}rXO5Syc6jnhH)cy31F z4s{whl!9`{G6wHrt1xzym{49aCF61^KnFG1a5ad9fLcXl5&yO?^S7AF z9K^YvmEy?s31c85%DfhYO_Q~tvT~|B zCtzu5;d5FI6MNJCn1!`=qbPkv%DDiW5fP+{#YUBppBq?F(Q(M3pPd*cjh3itF+z^% zB(VW|Z^FpfN)EE#B$J!UH(YX2>cKOztych`q?fa!Q-)Qswvc{|=6){CnFKkiB}h#K zai<+Lg*~;ZjDZ8pAKMu;oQBI*B!`KGAh)pE=1sMJ1JGcD`A)B~^EOi!wVSX5ZfhrV>Rt;J*i{VztbG!>Y2fq#LDddu|Dq z8#U%`7$Q4cQf!fxtuBR$Qlq8O^$_=W@nhhtArs74^4mEvDR$X>uW~=K{aR=tKR9ab zIiCk6*CPb}0V?V2TomZ+AnqO`4%}af;=0qZi9z6c;Q@bKG zqIoSsM0#jXuP3y~FEqLTzq0^yb7Z)hI1g(giFMFF#^Yl}Fj8{!(t6yKB^;b@_?Hla zr8hI_`%Y3)2+})9AjtA53ez+~&lbW9uRO1|$SiL5ms}L|%tT`3cXr_At~?nglql9H za062*yX*uzzhoNQXvV(?!=4%EH7*w2(3Y`_oP+n}@OaIB2Fos~vw~Fo1S=iqZ@PK> zSa;aO`PI#J&E?cn%LftVy!?p0hL2Zh*dM*9+W`fAji8`c+6cg3vn!`>y5-3@w@fVJ z3?+nq*ROThd?JxU$X27J*$o*fkKG0zm|V^E2pjCcA((<3Y-|KySzPSpk2u0W3DV22pP#X!Dz5NUbZY*jJ{@y8 zwn$Y}1poHVTwJ>b^k!+?3Z->*r3yfuEpKy0_H)M#_kKzWDa9j1&@wS3I*Ed_2_y|v z&gmRY?OzWtzEShng!VY0p$y*05)%(vbZsz!E%FvJf+-?~JR{&#=vyNgioZH{)M=Hn zHA_hkLzDR?^<R!ju0cTNVV0u=~1j-+|XJaF*{104G|3Y71=kbRi z&m9zkx+Tur`HmI%-&UkzQkO*lK=bthxY1#@ zRwo9$H%qv~4#TsD65d3nk3BlcAbKxsz)E3tg~pW-ZlmBb01g2zCQ{&RbjE*>|MuSh z^7>{jH3?(^Rc_PP9|z%UXSNkOQN9ur(PHnCsbh*-NHQLiIj!>Oyd8T^8Ql{U`tyUI zaImT-D@ln!TiZif)chBNRp@i8!FuGVYJ%U^adn~)D-*;-AZ!T)!rr=I+&W|78CZDD zMyu6pJV@CU==PIU7l+MNyOSu2mjak+(n2rmK^L?+df+w&*OEa6nglNstP<9U449L0|Gf5Gt6&pMi(DCZz z@=%iSqM%CAxv8-4U65sBykwVr@gVGnDN03gU?B6u%?F+!fNUAito)@>)Y7dS=J-R& zxwCccb$*FcTU!sR{M1uISky-0QO`dxLm4Li*m(n94z^7D&U;%t^4BXH;DYRkF#N48 zL91S25_Ph))QwK-MswFL<#srS`uH&)ct$#@Wd?hHM$o0`3jC!>8d_|Ym41oum+=OH zcC9Lf)iO6@#hAPRqhOGqXe&>4*T}i)hb&9)4%#=9#HUY4X5$ES>5+WlkE35XM2C4s zxga8vO`*=1@Wm^Ik8LzbAbmU*Cpf$M=J~r|ZznKt+;&i0DD`fZ2=8n$dstV6mWZe!IabEHo&ha7k*GOgS<_OMwQWS)r86#To z)0>owGS!-J#V7iW;SsA+&M1fZ42_CP3|>dkrTKti!6j~79Fz$XYu)f*Ty;r3@C9uw zu=q%A?S?hzVWY5UJxg~GM}i*6jvCwZ*fv^#t)I_rH2EW%u=#m{7jKk?_PAad%FI~C z!8FlPV{2q~5kU+S0#BRxyHo(O=7%08lPa6d=2Q;CS1&oPUt;TP7`&mRREfXf=Nng^(uQbH z+3Xb#svs(-209v`?JDvKQli1lzU$gPT@A+JmeJC}cNC@qO7!7C!=6xHULGmXPz^_M zy0XVc3*Sv8^JGs2jy-y^evFI9(t;D4Adm+dbQtO8nNKYcbE+_Fd-y~R2ag@wUxYXC zZ!?~La?Q#I&l;yu+9e6lJQNg@Uik3&O&ewWIv8%M84(i>7r5B(x*3rm2KscNy;fad z9xBlP;aT|_MU0f_JsN{>!MmVyZJL<)gAg{Lv8sdWHb(f}Npge^~cRdy{ z1_mOQ>X#E3Hj}_7#I}zf^{zWn$Oc7WiL!to&JGo# z7%Ig^po@1gz;4^p_ueJ}f6we+y&9e+k5jBYxY~B!PSLWmQ^TSE4sulD$Lz(VeO=vS z+Q%4x%vxa8=bqdtGeuWE%kA~-xG}}W#r-&1=q059u6hPtb%Xv` zig)sT3_bV<^jDpRc3*+A#DV#@#Gg3rTDO5{krx=~ck&yI%2w&x*sm**e0c`*MQpk))_o|oO^?TM$NK!+>> z3{8aqEj0?FC^Ybp$^Sj%Pfn|Hj&q;T!36C7t`Mb@>1UXHyuwk5Of{1Z3U7}19cOFE zbaizb&)RQ}Pwh#X7x5Nt)p7_vHWQLq;e@S-dJ}=oG|~RP6$-itA)@#CF(6o>(4Mv4 znA+#x$ts>T;9=tZSv_dLx3rK5j7+Qo1>XvV4{mG+bJjGMCd6LnP zJ0%6tz_V}dkM9DF&;i}Q-F6ctCCo35bHQLZBxVF2O%L#~bUtY?F+MvN3!}sd%;{YL zK^eiMV)6%pSwd|RSH6mETR6Yrp=~)7&;H^gbbjzS_U#Sc`s`PdH93p-6Y)z++~5{o zP|!*R@dR9bpKbFM87)J&eLEI%?|~wypnsC$dv&~^9YQFl#c33uDptu*@{_LV224ex1i ze@*#lBeYENk_~NU0Fqr;2-xfFsp(j-IQy!F*CKa+m+xtS5MtMKW%b%jW_&-7aYB~? zog2d#QS{1hk>wsGeEgMN4iS{G;~;QRvl8MF3xZ0egl=#Q^&_lcUK$%wg92@~gMj!B zJ{abL2LvvomiyKww(PjQw+ZfU7o}PQCUQGhYt{sEn<$UkZ@6uY!rx`4uWAqj&v3An z%Ed=au&wd)CI@Oq`nU7Y^(dT?ZtWQSW+dYfOGlq|BqN*2Rb3SG5ysAWU$eA(WmmG9$rFd$<6cokXV>RZ<3j<=nK)+j&B z(ZEpeL7P15$;mfgl}=hd*ilTK9p6)+UaPR`M ztvDVSm_gkUu=C({zg3{7#O_hI2NfqgJck%@otBfk%^0U~g}oEH`xCm^PtS1>HroIb zPg~%U5NLsw->zu)c#8oc9-xI`NpQLDMlB1cN@B2Pz* zLni+EOWbzjfaXUg%@RLsW$#F-zx}P@Cs$T+kVFA$X;e}K!`Mx*x&kzWpv<+pw6RFxnc6bGO0y zxuIdbtRx4;X*WCC6%mtqM}RgMIXT%d&S_W<_jDpiGsK1W1oaA2`Cr#2Fc3wp_w(%c zNz%1rD~bOkXfQ-V%4Fg_bhf-{HZxojkKA0PsA{qm0PbRhi;r(NBzuw_6^ZKtMfRmf zx`-l1Y?b0H`BQO$&F|O*`S||)dB-tFVKAORLyabaGd`*lm&1A??kkg4R^?SaB^w)TwKEFIGOt1oqiIVyBDnxG}pm)=m znsXEecO?ly>%QE{N0zuOA!qj7$jHU|`HG^!cw!A_o>axULOA-8Tv#%JMaszNj5Yj zkSoABw)rJ*%m!0`u_e#B=a*A&8rGLIw%0$7q6+QZDv_f!6L{76@)>HGthb`r5~JM@^b zMn5!RzoDj5-my5aC$T}GzO6H38~I$Ql!Qdp_5eD6koT<&YgGz}E=6`x!EHYjW=T>~L5=xRyK|`#?!$c%EP6Q-9}*JtCugHdE2r1-t{OSSlx@>FZw|<&8{T zOXzVW#BKGHVI%rd6YuLC3QEcz4q>%j(RTrZ?s920?gy&W;(~$Sc{-?*nTo3CE{{H* zOkJO_ldIKZ%ILiYVuy`?eyBOmzbNUlT9v-?sdt>?N9r6L$D%%zAO|f>YtMl{8VZBo zpF+A`ptCrUYM8N6E)A3<5!#jrkcfm-PC}&9vv+XN+e>a93ntB<-WJ8XdwQZGDfY8E z+gMWlp}c$jLT)8-G{k~8RLgIT*s$R>4U@{+mD&d&_}hQD*mCkiji;#LFaR4UJ^5nBpKP!~2`I$Gf7ow-6$S$}|Xc#uRFmK!K&USVp zo$t?u0NKlr;40yfrJoEcjli|%VwDQ#psek?%@5B!j{bZ-v z0~i}gADHzU8wci`ZpW71{W&|c1d_9}O|Eu6R0sf|`W?V}AfHM%B5|q?MEoYF8zTTz6b$7P=jo9n4R%D2*A2)C zK&v@6KEAkN=9_m)Ep5{2V%)GO-UD0`PwFRe>tl~2oDZ8y04`%obBiJ)s|LP z!P`8r$#>x2uC}tAf4*vv)z_z%^m%tG;6AkJf~-6;O46)jm6phiBB%NDtxi9C(`zSvV+4Z|QcL@1yDGX5ZJ#0|5sBxKU)c#VsExS? zfq7y%x>I~cY0iVp=_`m|08^)Bv$Pa{6mWlI|MJYT_n6|G$4GSjqr>PRpI00A z?d>-H`nVEZ<&aF7BbXX}0(7FW!2CNNpsc#}$3qiNq{Dc1*)JX6ar?dFD=NN3Adq~` zB-Pnn00Xg|m)~CGFCKOM20Dogb7seXR`)A_c-8H-KIU(*2fqW4P#v_z~ z+K2>=+C}??WVWa?O2dK+j-sL>T#_lX1Od`P^a~kKiwj%V>KILo2?$0{8_*RO2VdR* z!C>sT5cogwb?H6rFtMf0bd&kDKn@?d}o{TG`Y(h*CJwes}XXRe|wf)CHem6Xz zf~xb^FShIJ>slXo@~VZF4ht`tX+cL(FWi!bhVIpx_4*mJ@&#a3F#Rnu;3_?!s|hgU zFRPj`K;JeY_^Wv&iy7<_-10DW)Cq+u@Te=F#s&|pa=;}%UZ+Z(fiv`TztVu(-sfQ@d9*FPxi=>s7K1^ zcbeEVjWz*vK0aw{K)AYWg{{n_V4Mw%=A*L!@`;T=u|AJY^}4m}q3H5rw#VT@ltPTS z)1e-lH}wx}x(M#K7Z4xc^ws(qua1uQXeh{jH$RvA1_mJQzf-H}5e0fG6AvE=mq0s2 z9Jn0lr;hjQMh$$~^yCtx?y(j9j zq1@ZAx;ehQoFE^8hoEVc%_%5|%d)kZ3w%7MjqJK?>nuUao}$H0jjY=9`ZKOn>v5oJ zLLRr??U^96ap}wa^5J~2rQhyUgVP|h-Fi{FS@+6{1*xL?rql6?>>mIxZcj(IuW$&3 zXsrEhfiyGXQe)N$lF>^`o0oY=OBa1X*+)r250;d1bGk=IdPx@hk?8N}VZzuF7S);MKas?)vCa_mrgC`221UB1Ro>)4$08DD?Bo1MqA@dR9vv zYIQ*TY4WsRLKT%X`WZBaeW|Z!<7b@CqM7Yqo`M1x3g`%r{n;S!ne;UDrDu7fAfYCL zgpPy+s4#t6tkfR>2S+Tnc&JGz&8)rH!=y>!7$_` zqV-w{Vvo=G#$Yt)?QVLT#0+ImtJ*^V2di2N78Vw`BsF_JnD>bBru~WqjAMxG@Lor{ zOW5}4B8@4zc&7Itz15Y%Jiv;os%1^WJ~Nu`?l?l9nlH6yY>WVbO<_;~9lKn~p$-rG zK*}U$g-Z~z7XiIsYasXAxE6hS+>846a!6oe+fMlKsQ>dK=>T7{m$v z&VWF$27*nOzcODhoE@hay8AH|uKWs?AqY6VG`I~*?)2WS>|soh2)?_!+kKF!`r65f zKn_x2SPNy8(cW2Mo?#SbRnR$pbMGOY#N5QC;OYybTS8+9eB-xHRk8Fl(9IMOJCq_NajyVp zrk>2SMC~90hp&ND%yPF%cSruZ`Goz?;atSU{q3VaSV57)(T5gjw_(;?CE1OYyePhU zuh4ibU$SL~fq?;+bY$oI2lV4X%M_=eLvjlSJ`y9~&?=*dSy;}@5|DBCCsJab z=q9W%t|cM&+hB(kS|U0)3M#7d^O~}+f*R}Dps|aBFnBFZ<^fIOI0S>zu;jy$#%&r{ zXXZ~Fk#oz4VJz`01KTp}XVe2K&3?H4_mfFotyM4!^F@7xIz$I5l-%2o^YX>)d~|fN>#3aIciz@}R3gsEO{F@C z#u^WMZdMMHkn4|_b@ zPiZ9XZ%+Zo?=zB30|7k%XOi+tk`iqf7*!f{wl`zF^P>px0ixc&nZS62@7SCg!LLlf zfxaBJ=wL8cfC7{gQN%QtKUd$6k9on5#6(4bJ@h2@NPv{V8$Npay&$QFBVd{6UPWCE z=(uJb5v_q0m`;MLD2#>hEy7_fPO=`YfNNce>tBV29sZJOoJJ@{X?zkAu?Rjr2uK3_ zKfc~Ns;a2#8wCRpL69y%q+2+2OCu#MozmSUAs`LX4HDAb-JR0i-Q9K9@%f(j-tUk1 zGKP%fIk5L;@3rQd^A~doW+JZK085Ch4%o+_1)wvIU+e6shS=ATK-La|$SM>h2KTx) zr{NV2vBXchT-DQeeqc|MA0S~kVHYy)N~%Ro&nmw7hcN!3L?O|+F$^8kij?CDB>B}IYX*VryR60oef_bb8P5qpb%n3(~Fp9xWxRrjN z6u&UMmH_yoNhc`G{!JL9yl1xXk|}JmEa0@AAGP)-sB>qZ|HmH-TmeY~P+#8vd?ny7 znv#5=eg`EB|L?CnpP-fhypt0FF8V`Rx2EoYwE+L~>;K;uCeQwlLk@~r{oh|Ku>VTn zayx#w_dYOk!>=^_-c*G_;V`^Ed%uXC9)ZMMD8%~=0!2m6x;cPi<3oCS4=QR_m_70D zUDb&$D8QmX4^FVL5^LsUG$_hc)oG8Z7l5#cnA(EAcK4Skv0!u?dc9d{`WLHDdyTw$ zYLXJ#v~OGSbI)SEoPK|XinTr@@cet?ZwHrb@`;}6uj+!$8R@(jS$^=OeY!Wf*FfsZ z&SU0;o_^MPEo7cO*}Eb5faVk;f5Z__>p}g%$ns{@p_BOp|tu!8Di{BowexG7&{t% z@#Qh}nhg#na`kXz1$%FBv9}DN?`-OdE+afsMdF?Dx+oI9=I_T-KUDK7zU1-MqvZxl z6`>a}IHB;R5IX`TVx52mKl>qH_Jvv)!y2sB$Fx}JnN8k(+L~J564R4RNj?Dr9K=h@lPk~7~p;WXs7m0qPqkPQ{ z(?YF(FL8BO+P2ts6VI`FgB*nYkGH9A6emGti+Yv3_IaVTXwrx=<-h&LUf&+aPF>- zx@n3Veps=qALy_`#byS^r4vDCJpC{*^*_2LZY%2#=&psjZ|AuhTPQdu^&E{*mvG(Q z!m=oh9%)dsF-&{%nQ8=yb}x2?iC(U|$#|HdVY_-YO$&8)eT${7v7NcI`e{oH!w-)- zf>EJLU{ua-9g~l4E!7D|7&R+-0+Gg)%1o$#j+n+JR??a(63jFvz~Wd_n!&0wkt(c& z!kV>dsQDT>=G^q`KFiI?eaz_}NVB9gt5&*Li2!q~8n>k|<0K8GEn(gZE7`QOyWkhlai}o2_^Sc89UYfB(__XZ-z?$Ahx`3j|OXS#QQ0 zrZ+b?&kDwm`0<_-pI=^X&R>B|_Fz`5aQMImSjQl#QgqUP0dzPDQ8IP~-S)f2My2c} zql<_tVooln@7*Df7Aj3kP9J{MhnfouDC?jzsnSWCozr%LSzuZ9t- zw)MimqWP3B!*Y42*Bi6Y%|>ufHEBg1L0I{uB|y29=dWK)kpLE&6347nyrb}-rWsh6 z20JORlR|#siRO0(5Q^fz@LZDK?;b;k?>~KTdX#hF_5j3v-}y+WeT|4l2v!g}%>msn zUmrsX6l-^K_>?6mxxo9h)n@y40<%I@{j0I1mnU=yDltF(qS8b(oclQpijN6xOsyHU zzmq8T6fD!OT?oUP@d_70SR$ByQz?0|>)~L-pc(g>9`2%t)oxDh*!_w6oPE~nZZ!zV zw4A7%DrlEnc>_5N6Xf)+@6)u}sP!ckDYD-CYS zPmQvV-294_V9P3)mZtA_$6&{Cy|FAQD4POM=aajor>4G)d>(Xk^y|s$rf5fx_g`u~ zVq3;56VM}=qn}u&M@W&7%T<; zOv)cWo{a`%hWniRkp5~Sn=`x{kWRh3({rHUnqjSc@d zY$U;A9F6K=Hf2p^4E(-3|9eHd=_#-A4lJduG}zu>~qKKz{5Y$kQbbw_JPAof8WF;gW`DkP3by|F)l zdnCDuU;A(p0%|tv!%|};QWHsi-2I%K`}-bh*7`h`0z*V&E1FLj0l9FbjM31ax*VZV zMXMwi!C7N8w%fPoy0+f%yAJz4&7G;sA0%UYkCMjq?45#rVzNi^T&rlI-}Q;VFow!# zE$6pUV-8W~DYzZP+>#TT~JN+Djq^G?MsROg93^i||r-eHQqvZmHIG=#W=?)6|d zF>wuzcK{eMQ)g7EB2f`&IH%#dPfE#_iJLu zMQ4iFShP@BD*D+Ed45C$AOF^|3$^JH+5SOe`C4Xcg6b?Oz0^5tW-H~D{>xG~vc|af zcOl$L<)NJR*M@jAhj}X{*#QFbXnF%wJQ2C#oDgMl8U3H;FTksVPegMXEcb;c@+NKv zvU>)&t2G>jQE%b6Ua6vU3QIID_10Y?K8{r2%j6jTEmCB5BX-9KT6^8g(v|W1FUGdE zq3Ao0oH-m8u7RW)_0!;2;mvmw?@<&BVYR{WwZw2b4?|rZXDZ;6(^n1)oQ*J%J&Km_ za<2~#V=CmBkgXdQ&v8>7#)UOgv17ZRBna9m<s+Z{dfAU;DPPu(tdkcoi>O-0Zy6Zf$8{|7DHhJ*s<#{~8DYN|6k=YEk zTrH+^=h41mYos;Yssv5~3_@ ze`1dRWS+Q@nB(2?gebVEwbSHS)tVzI8)C_?SZtOi*pK`CeA1y0upA1$CKonb8O^kg z`U(-BRQb?dcv)G#G}faw=xV%2;J0q*gDQ|D;jU5dCAett$Ysm=`ryWm#ujUd$^+hy zkARJeIJ%e|%UWgjg+ukkiO>RELU__hEuOsikeDttu@AfQfj!&tSYGrx9=a3z)$3rE zY%7h=jKlW*`0FNS^BlVLJ6Y^0`LhGA@BG5*uTQ_avved5rpoJ!Q!K^#YmTfcd&};1 z;0eOeN~QFGkrQEWu&+vT_{Fo)0=}5_z`#-Td$C>*W5?OX`YXv&eY9f8D&j5GRpqhj z8evskUdH5u=H-2k-edL!>K?<{odC`TKXsUmw!38RfL5a}Djs4Ok&y5isE|_KZ>fqKFY!SA?O(v=@#uy{uP)~7 z%)!ubEHKWChK2@ZxN-^#)&bo*?D3QtG~Os52*33&~TL9gfVQ04;2)ZWFMO(f^#HGr*PX}^|uj*ly#p`#mH zSR6Vg{*j1fG8`g^h>R?qJE&Q(fC3YsROkcbYR2T?@bDJEtKYM+#Rdl>6)4fbfQ`(| z78~Nh&V2_-JE|ktU`^9SO|hIF`f5uJ0*xD=E39K|vme*GVdmt}g~}h8;2?=D*avK< z8WXa+=j~6eJ4)@J3OD17f4mM3m`^Rosh{+RY_FA6`1{_b5E z7V@7-TGeNSyZ7`+cy#eU*<(NePA3Z?QgRc^QJXd$-M$|2KZ`Sxe*T+oyAvPrS7!Og z-lWNlO0%DfB0m?gZd|XZ_w5=()3w(EHRY|hGduYD|LrwZKD`~IM?|qV}u&d zU8|n)^!5N3QuEOr0|s+ZNfPhf%PygqKQh@ZaXpdtqEm%uT;fx6UkS8&{0iZ%;o#pq zgL9RJg+@+OdGhDK(^rvh|574ybUE3CoJdxO_)q)Z;!TOs zc`z#(WHxGmRDu&lsW6nYOS|YsyPL!Zb#?uVtaF|F>x@CFb$s+13Rm}ah;urzuW4D< zvyZ(gozH*1cFM6~`Ife5iA9JKpfyx9$uCqK89htG(Q%(`M9}145&L)|TE3QUn;`MlO@ql7Q60 zX1n!EPH*E+j7Cnv3f+h8$K!e>*<;7oig4(HFyL&sIwfOh$6pAI$TTefbR>wEvUor7 zlm*gtW4ss$=-((B;Mm4M{=_2Gxa6ynVVKSla#ab>KB-`;G`@6YNAsDTwRx1lPTpit zw}B%%7N76nt@mJPf7*CLCm16n#mMAYxd%xKgP9{IzCPg%Q=_&Gjkx<9Qd4s^mK`6! zA`asu2-{$S3T}7VP}>Vzyg^vUOwZpm4!%|dZe|LMvr&@ZS;>U%&{~dc--r+01T&Gn z{UR9UnkYV^7H`)3yC-5uk7Z9~K?zHx8N3D|m7m?+9gT^l70_l<5b$;!RCV}pNJ2*T5+tTiEUM+@gT~cx zYmQ`T8(Z62z?j8zInrM(dGH+^bYF3?QBe4$-mg=Tl9Qt$!CA8tOdmKH45thNnTOM9 zFU8HWHwp}JAY@cjM4ha4pMeea(jD#w5+1_Tq#UC-+ z=i&3%cM=W8`2=Y0jg5_PMl5XXGw24hK(RqqW+5y4Rw9NLwrzn1RGF%UG5h;wW##4Z z9Jb{Bu?&2N9`J@t|3c+66MxbCsnh)XpkCJLS`t0-FeML3#g<;;SZ@K-YYC1{{f)=_ z*Eh|9EM}Jz$R$(LGZk>lu@R+$zdyag7rNN zJgexU)*Kq@7%(Ve3$x?&U;;iBH7)+H>5Fq;+2H82$gRr~8R@<&+ zD_%Bot5^P9NM4IK=-*5!xN#%a!N{NO`>=K|x@HkbyR(k7>dfu&s+jpu*IrFUA*k%| zr;YSh*M^OGpT5HKMAt&Y;=Kx~apE`swd$9#m#%MgqfLXiE`#HZFs}6$3>J-NusOQE zlVHhfORk@0o-~Y3mwy`rxw})oGXo4FB1ojK4Q`PPW<@>@#td#+l$Uk542Bs(s~>6Z zRJ`?-JeGT=rw@o=eTiZ8)|xW=J-_tXH$On#l)b9wW9Qk}{cGn6T^6qA?NgiTtJncr z%h#*Eptng@!C6=Nrx6?ZSp|A&oWYA+`L7cW?7K_e9Sk6owLnNe?N121X}*5~h}Tdx zlfjAAglg#Z9Q(dW@O+IF)7M(QBR4{>vY3#?mBf?JtBGS=O}&5TK6F0EPZqtlZLjLt zx8)RWKSHD@Q?xv|;_eVQg@8*QvP=2mDQYr#Dt3sCYyNo?Wccn{)#2?;Sb6hw`ibo* zDEf)$*D8-Mx#da&7re4`xSBc?vK=MKI7k9=K{`rMnO7Jbu*pm>iPH%#N_NG3#lJXY zu!#C|gv}SuAmZXaTJj0)74dE?xAXmv>{)8nT@)yhDg#Qu3At81nf-F_aUS zIS>1i+L7iEip1jyFd^UYRGx6J1%O)3%{D`o{nTYV;b#M_si-t z2pxNtIBEqDQ|s~5V`NGVo(Y|jdWRVEI&xiCWQ2Z@-~^4mwIj%qrxJPBJhPAD97?tn z@+qNt0$9*PuV=5nABbGm?8(Butby3R0U5w|Ld%a}={1a^3h+)LCoE76A^Gd|Og&a^ zAi5V_C5AUSWQc^Pj?T=ecztD;B^<$_fWvn~PzRAzeuLU%ChJgVCJ^iL1-#sy4z%w#4Nq314 z=p7gAvA=!$#$Qw4BE`1Q0VHYz0LdE$8_%X+Rs-fmBm}Rs)f?U!Xz4*zq6};U&_g$X zU3<&E^-tGW>xEgs!;nYjPFdf%HHqo8rwa$wtVc*3-#u_YUavvb?23xGjJhuX=Enx& z&^*{Ho%{T+pdhadh#p`cWxtLNArOMP0CfZnIp9r(?>iDu+X1awRj@Zaip}<4VyJcv z=v;J5f5paPb11{0Q%DClRJXMWTpleg>CFJ;mL8#6!Bm?*(+SuiJJrYM1yDcq{@Z+W zw{5s?*NzixUB3j9M$UCxj3Dc^E?88A7e*#{>|0P+3u+NyvMH1zM~B`Eh{3>ef@#st z#nL8NIGnCm{78iH^}0j9-JEXd>+6@;?Tos=wjXjxkmrFR9%5eU808emfi9#H;%mo7 z0`ng0d}gK`vzim>EXR%a!fvfe*ous-7$PB|x~6bfAzy>VGcp+ew$4_a_ME=FbQ`^3 z&2uxquR4qrt7mfTftIAiIe7p=5Fd{xnR}sFDN2*~u1Iy#?y$Ng3dfm8(Q@PdS^&mf z{!V;6EXWgYmyzTZKLTbm-u`9w6Om{lr`nh_Q?{@H@(xqEtwB}Df<=mEG{K{dTa~*h zskYxSiXUe3ME8RCu?*L)Q-J|b(XTMle4m8Bg*SRKkOp_;zNjfa<=Z#mNA8z9BsFh0! zFO1x~3LsW8iy!E#us*wQ5(HQ_C2_+>igfcn|hA$ELF z8k0bB+!=MCScS3T{k+;Eacbo|x|ZOn#MV9Ur(G&Qr?lFWhqFYuRouX7KtUmwCoLz z_y$1ZkLt6OoFPdN0kikoQPehZ(bI1QG{Tu-L5&D;d_FvG8Ne;}W+hbYT_Xm=?Zg*_ zd5m2O6!b5G03L%8)yt&Mb)f;7x|_+bcke30ubATEM1(g+b}Pfv{hh6yxg#9khOKLK zG}JT@YLsXnZ`oO>6FPUj;1qB_%vWzc99s1{KEbUj62^7GKRdX2!9~$@KrN)`)y(Pe zWyiELeFQR?u%I{B!lbEZHVv54JIKmai&yHbi54Ida$TO zL^8(4#;JE!>;(U4U_b?%E!5dhcVQvHWe{G%PnYV!n@$$M{sv!D2ltN|Pntm2D8qAs zfsBm2ec?hbm4KlV6CU1re{=Q<&Kt_!vJMJGVhD@TbQ%WK@u*m zL;!XZem|F0Rc-4W1lmVX$c2Edb<-wHRO;-E*YEddG3kX;xSegrn?L|1d0Ln%17!Kz z{IA8Gz=$I*F5bFhcluWlMK}=t{XM_Ol{5kcH0^_`08kG*R?d*;HHz~E1+YQ+JSM}3 z%&)0Q7&v-X&Vz~|v_Lcqz&VeHJuMPF_E>TFXT-OE2~ST3pBH!rJGwV*o=Ap z)RD)6x_fVBOwqz%GHI1>NsXQ9tHy7PiM%wBEMZd_-CTJXS}Ubew%9gC!XWDX<0kHM z+uogmkE@Ic4WWGmOM7pQ#118Ry!dlAbh;kj^xK2=>t zVMvxLWCRMEbq$5CB$gJ}BU;jYTf{mIc_mr>tvs(hBw9%}&f+zElqsiHKVwH^UNxG6 z;v^T1>;9f?wKoHKaOh`*=LHrtdVcva;D4(>uER5T3jx&Dj*TXA!qzSQICG9`VmQq` zZJS_T5;-vwx<5^1-d>m=tuhs|aac!PR*vKljQ4I4huWFXk8XVGW zUvOS;wob`@F+vnpUMn^&UT%KFsy(?)5-@<(+5LPXzjlEw`6U$z>|ay6`FOt6s64uc z$trA8_npWNhEn_?ClFSOyFcYEQlA6?(CT^JmZ55BfMpeXe(lCGU#UsmhG7&8%4ER? zeiItK81j}Ob6{H`i9xuW=}PCO3>n{87=)(@HqHWh$;!Rl*|M1}H!Su)_?NiJvxD#? z*)_(i2BpgA(teFF@e$#``2-9izI@f*cV6)W;)r|%x_^ysELNQFZ+gfVtq%P(E&8rR zbn_q#SrJL$9SR_!qIa#*p<&=~Smn#|_LMwzkpC7auP?A-c#9>`K5ZJ#`YXMmquG+|UrnvmC z763+QP@6A`y_9Zy!;6H5s?@*+;9OZVWw_ryuX3r_)(${IDNH79JFwlqxKM6YxSCCk zOPF!0g9Mzi#a#xy(%o>J33GbO;g_C&c1u*xtmbN*o_!|^m5apq9w@_B2#0ICEUF=T zT}UuW#hMFi#0SY-j-%t_LI8CN!lGLRvg93mzBhi}KwF(kVOPMJ{HA_E+SQdSI(p@a zK~7FicUDPJ5r8xjCMMLqy}jX65}!YVJN9sQC9kG7r8sU+Vf}cLYnobpks1hQ< zk*u*RiHg?zA_KF3V8H6+uKuWLPOmXA5D}yg?LZ_N&uWebkTb@{R6To4cEF!=+Uy@L zI&Zz(9Efip&y^oBseIx62}s<8jE$+}vm{r5Ckdu)3j&S@gn}P!Hzh%+aK4yO&WHiZ z&r-*uzkES=z@bmCx^uvTlpRE0=N}OPinr&ii6H|617g^rd3kwaZ(FoGIy=)S5kd5G zYSauCApw%>aNW>Hx5t|;{{5$vVI?{K_d-Mhh~sb?-{~!1xfs0?S*p1-RdAoGcI;0#VX7$F{Gi;tYP$=HEL+BmeUY*gjy6oO5d*Pu;5Zy8T(DOqPbtM z44sa&x&>*xs($Z#Y18%J*;Hs1+4fcOQ`CqI!F6Tb?sX!I4-XE;$SzKQtg$^T=LZ!` z$)_?U4L}CFC!ei7vh6%lnsJ8X&6SOtyjT5#JDf-hS{)Z5LgsCA&;<|DAZ=td4M`~vZ#=S z-w(t>$RpFMPv?G0T}MsN^+>qcZg#MdhlIY+U~jgbp5yL-eEj&Iv|#MTm%Bk+mRna| z%H>I)>u(F33HR^RBM4Ih6hE!(kr@0^wcHpE;X-(mKGoQvU?~0H%4AjDVc(X2;bsC= zvC%En42Ai4P4LK8W=LREa^)!5&6J6+zy6mWjZ!J!czL_5hnoqi0Pkvr2q=(U`znhR?LDe?Ls}*n`%(!0MrVs-@aWPJ$Fgy z*eRF|G@(DzIs-JSYE7m$^N7U_4a8T!(gOm-NS=vrxbYXX(xX}?9OXC&gh=ZXB8E0y zm2T>5;@V1uZD@3oHv(0m-9{P!>{NvXzaS&;CZJq74Y9n&rWeY7{q%GNl=c^22@!q2 zR+<3!kM&DHN|F#06KBDv`vrCC>hwmCK|RcwfBt}xo%RJGmgYWDE`Oq{p}0sI&Y_;? zR8>_K;AP#R0LRtbDV3UfthXHdlbag=v~>APdItLXFe^WPOinKHd4TF9p50nke<5vq zwyLhKZdeZ{PLh0eZOz!kL>HVES_g2fQ*kf%sKHnY*CgkBfbyQT$&B@UoOklYObZXaHz(Ms^rg$Wj zU!|g_?=nL2=mJ2p-bbIHYu$&d8GBw@EQ!pPHFeULF9eVvAWf<~N=qB)J#e-q5%2BH z%@Ak$daXFfIUAi~-cV9zLl>Gxx?3U*_6-u^4VN5iCUt{Y7<(*yZ~xI&r@qX`0(xM4&xoSk(mGHetXlLXZM_OmKWg)w&Gjh%zZvI(%?0?Xoc zLyj%IDZE-zYuaHpGa@j9@Z^n9Q7-cqY?Mm7q%=+>G&X&Os0^X-U=;e6kF z*KfA-q}T?eQ$ptj%=pB_TSVWU-rk+kMZiyZ9=HDmQ)?Ym)<>m70l%mAZf=G>q}|m*=r~7U=Z}}Kfq0cm z7Q?r!jOh&lJO6vs_f%8?J7d`>CR!R>&)c?y0O5@KwiXY+f7I|-4ja*w`?Iw7ss|$| z3sfgF_X>`@fbGRoNGxMZ-~;(d2yWHe`Dl*Vjg6z#BUTa#Q^S|%28Ng(J4sTReC2C4 zAcY-Wc7zfmR(7uo7^Dcg0f(J2d6ZWo&68!XXer<=`Nm-iXInd{JYlEGY_oIYM0QTc zU`AwF-dnbJyy(Q}@9~$3gq+DL??36Mk`Gu|(`O@8c!-h#`-eG1=gU$YKM+np)x^4_X(Ebq+f-g`30!!K0_CyRiXZgu2Nd_+mbEA!2S4pNk>=| zLKWc#Vygw}>HvGbHDTR48}Mik~mDx>=FSLzqc~q^S7nr@%I|sNrd1 za+FN^&;SXGsc}S-EXw~oTUOOG^QhS0X+U`t+EGZ|91#ODhY_ z*z)#Dd3U{~NE=?)hl`dRE!gNHkfoI2GvqmyX%)L0oxRo^3q^o<-P*Q{^@y7L)w1g_ zXGrz7{2el$ii@y&-W{Vcp9b?uQ8=ISYlVxOmsi*rOBGym5PWDs@Xc3m#yC@VrY_qm zYFb)S1_l&QfIg=nWbAbBM8FTkq!rO4XzaZawzY-a+}vblWnI=a z?BS$+q0B>X1HLX?9v5Z+?Pvq@qGSqpJXCoNxJ_Ws29+Tl#BfL-*h#<#xY=X908aAb z9(n}*A0WWfg82HiOwVI|eqrIarKa!Qm0?h0lCZ4P&YxHpyW(qr9sTG;yE80Bz!%aJ zCmwnSDI|&09)3SY;GymjJe%^W%*_;yEi($qMY1{f!6(Mk&rR0M|0EGQ;Y|PDi7s-L@!U9OSPvSUIBJ#p&ZX z;1n%i)eVbRP*DA`B5tS`l32HRCnk?3UbmKL_NUpp(`8Vm%V|hSV*&oXdJXemBG05G z0sw{D%XP(uhr_l&Y2!fnpI~Q2S6Cbl8&ZH6v^PCLeNPVcAY9Ir8(w|2D4(IErhe9T zboTW-rpvp#+aiq>0l?=NT+|KD*V=knu>~AL4vIA!6TVP(?9Y?~*8Gi2V+x4eB3+Ar z|F)d(j6o?P@D@NW-XbK$Nq`D%}af^HaZDDHt~@Yi{Q*pPn+zLikrX#DFhQkCYoXjhk_F5;2+BJ z=RC*#aPTmcle(eM2-DXxYj~T{R_tm`@op9-&S0=>+_~GCH*G@C6wp*hol^NiG7glXj0ib;S0F zxwqRyz6-_5ju-COgRpF>!tKiPRAi|Mf z!}ml{MR{iR>0T_5ZiJ0T?qX8Yup|0D7=RAtDve9dZI|zwwpgxJX34TRckP06Ne%x= zzLJ7CqhO>K(PM)+_f0bCaa<_|=%37H+leh9N+HB1OyCkxHLS<KohG=@iOl?3Fu}=C_>Wt&20-Th30%%0w3Pid z2CK-H8f)p{2Lg#mFW&G>m-fdJ?bc^7zzx<4a*L&-)NlPU!h{4znod?9><4@J9QMBk zccnR&?hOMgWDf9C7EjrN_AlB@@h$}!W61Y&MGRj2p1?+n;tA}7q3i4GJxqm4{ZPyI zj9FG*9<_lTZYLr)ApEx4*O7N-Ix>`(EqA5yMNce0YR8Cad6&gEum9;_{4C+iJl=TelIh_1=vE6l8?PTjm&|Z2|c3m+Oqvt zt_Wt!K5g$qxiz=Ovpb z&@%@L)Gdkx4z(TlExq6`Ho9@xGy_r%Kkh+*Tp#CvDw;%Zpf}v};V7h@q`V2~GU-{v z^7N3tDRfvpGCb*mlF-WU**Y#dj^5|P6T3kYcEER(`%6E7=Vte}13#UPhrnr?A>Z>@MnhBd46qJ@>q_3<%{ww%wG-687B! ze&W&LJn$#&_oMPHF=(2kOQ~e9u*`mVAKW&@BoS~Fllm%`+Jn8!>q^~^lyA%r!qKEM zh`K42VE*(Cp;dnNL0=e*u|eUX)^$5xBN13~?38fWef^?P2eov1KGRfOxi>mOnO)n}moCVEjxAZMBx zF8K4Xh5X(u&2`Sf$DsX}_wQYafdDVcRqZbo9@9DN8>a-PEM9Kci-ansqR%NEQpWP} zx`UZy+r;ujqCi6VG*N(m{JqGSX6@%V73p3Z%2w0Jy>pm79R3(>Aj5J#Rc8ep50IW3 zy>a?W`75tnPQRBwpR(cw_kI3Nc@HC4>`fn}HBIJwr{n@}R6jF9%t$DYXs_eUdbi6- z+L!Ph8QWt9oouO_>1v`H3E_)=hdCt&SZ_uV?&arjYnG>^uG409B=pMr#+K)2giij3 z&kzv}B~C%qqLCRdINC5O4Z283EjURsHyBC^n82eS(r9#Hp;vwqmY|OfqEoAa0%M!Q zsl(;Ny!b4Ujh(v0Y;5WXWApQp8X8aN&p@+=v-2^TtJ-^y$1RU*(8Qz$aFM+O1M5@G zk1T4{7M(kG=~H|0A9Vx@EGxD0@=k#@@(dXAd;pjRdgo99&y}#LDUC=*I9P(Isi{HM zNb%DxxcTA05}L^Y77!$ouUIV?gS*$#fOd9ZKoZ0z(6#GpX8&^^E|Q$Qz8dSbYfx_u zf#zWCX@Y(^#l_hGiU0&Cq4WA%P4}B`0Hc%w=KzWkQmCR<>uz=`j>QxUsMetM&giII zg(@Au8NXfZPVjVHfd~Z@W1sMBRsd!+Ca3Bq|qrO1HiseHOFc0 zCnz;F^~O0-Me~sm02rTvC~C%9bgrdd&^^M=VD^V50G?2k3s*u1Q~>NBt|G2ZOcbCB znK)0C^gRxXF_jDaXnNi-(;xN>2Gkr^)QeknQMy<&uj6b6Xy0o<0$wO$Hm0v+OtueH zZ!z{obx_LN-DQBfz=QeVaOBYps4RbzEw9{d9G!)n8;7rd@Uav)+Riy(+|!5!3;1tJ zEAvzRGGvD`!x5=M0%G(pv4m)?#Tp`%d4UfqZTDo{+HUYv&>VFn*#p@rlGV$RzHw9G(N6Gf?g7 z1BShHAtL_pSL*YWEW)|}#Ho@{HonNbxUVTZe0feS@6ONi|7lh}yBok5nz&^=YtB&} zoRSN=(Y>e4axmra0QkdC-lD0*>i<-CRfyEoTy7VFp}8VPW^NuGZ8@u623qha%0;VZ z{Abo7Qo4C1V~qb3py+LK2q*0n-k7ib>XW&rYB_8D0YAibyKTb~7q?lG z9S_hWpeFp-&iVmRxGWvFmn7VCB`nlR1p6E>ohq%_%wZX({zw`GQ*p?d?I76w-M5X@ z^FKP_?Q5i)*SdLIoh3su9M>{nu_o_@r^OY@Z`U38kRlQj+l);=TB6UCuf~lo@Mpl) zt<*X8|0Ff~Ai;&XcH;#;Ez~hqKqcw`fF5vyApYQ9d~^Z&*JjX>3FaEak51qgo;qq` z#*-R1yKkhkG&Wvox;tD09y$Hf^AP}|CwHKj9fIl{qNwD- z3|G=up~OfpDA=#LJi2hX83}XmKxUh70nPD?nC91ABPusNF}@wDzdN$>|a zUPApFcx~mm1SeHGquWj{>l>hE)tb4g)~w#)G-NFd|Bcs%d%l8ThpKQ_EHKR65uU@c zrudv0j?;y-%}D$-hOoZm5nrp@z*wOj9NXTv^cI;yJHU?b`F2WKq#BU-+{P-|3IkwZt zmICwQ3({hNkiBZMoLI z7Kacf?^KLzt+w_l5+D#fA%}hiI?>&=#N%K?2c*DIa0|Nl;bpKifq1uz2lJ@BxLo7D zbS?6Jprr{cYUo5n3^%wysPL)@7#E=_v^8*cC!OobjFVYA9tx~ph`weDt5I`0?xD^T zco>f1PzO?l3&!a6VCi|M!^SI3f;aGNi%ujijhZ$h0AM0eQ2Yi&;0>VBNCN;;o?Ctl zKF@1oi^#IknVrs9`?L|A@UCIL4*r7FEwdX>(5^5sy&Sce1x=t6_k0A$YEAiWXo-qH zrd9gKq>mP|+=1nh{Sz>=NO~hThFXn{9 znbRJk^86tX%9z4l=r!r-N3DflZ8)$FIOK-ECCO6>E~&!YDuw}e+6M?X)-O1Zf8Kh) zOs0=Se)Dhty>0aB=h~Q86)sc|--{yyxW4AwiDIa{2xtsMNwNP-n8XjlCmc0hqgEMF?qBlEa#C!@Y?z*f{@d7*$T6*ZufJ6XJk^kdYz|ciSVF0R5vp5zw z5>?gI{4Q`%4>Ny7NBg#F{|0){uCA^e>DS%;`b^=8i9wph*;!dXv$9fz2N!lOT$mt` z+@hjT7aR>)3??QfE6(JK>MOUOA0UuOa9DMEY@nQ^cu487g5V(CUle-?=TF!GvFO;m z+iB2`+d3?uasodGD2`XY0_@4sc=-4-E@^_6P#$u@acK~+6F}-2bldP_jKPxr9fA*z zh`fES8-)jPj0I?EZpGO*4!m_fxzxO}o9iK4@Vi$CXs%<&SO_{Ua zc;)a%7l%;arm|09o+5K%LljE8n85=6J*CxAjc9g^>c6JDnU8_s7p4a^ zG!+&GYE2Zh_vWU42M8R1qbtC6o^RP=_R1wPY(z})PyiP?=tRbhJ)HJmEr1~@I1d6W zf1U1T%G=kJCFG)-wl5pFRZ9~N9)FHm#OM%r(;uL*6Z{Ge=8k+Vv8(F1 z=~Lca6m|k187T+Jzfb(tghCh+SE4-aVv$O49@yPgqLJJk5@r=Jn9(SG`F&^u&dPH#T+;K!g@Og?#9Hh<^H%ZIp9$W!6s% zeQr636=Tcx5hfLH<-neFw?5TL@ZaDx-V*=&V?UUM)u-&NKePI~v7DAS!JLyK&rNO3 zc@v}u|73C-Jo)>+9-PV@bf38%a%}SM)&Ic35nofo4vdFD;!vYLa$^esaj<~CJ!|?? zvoY`<%87cvA?pdF=GE6x=iNv#sJg>n->mQlnxQ;5xo`Af#GQ}iUEjFhz|#izuX)yo zYj}xJ5u(bHxs z>j6V$3V#L$ia%up1Pwguw#SL4u-!6;(F-MBo0t_+t2{qaX$VM6=)_Ju!C5y?oB+VJ z>zMq7l6jePb$|qVt&v!64U0`j3Mhim$?(Bo(CH=?s&fXnKd2&ySJQIIBhL>yDiEwi zOuz8lmw!LXCHx5;Ssgo4ULlKk$0@sB&|eimO4(FE;s5vYfBQy}0t&W&2m4>XZNUJT z7JBmk?b{G6(1QH0pMnpPo`Vtg|8oEzc6c#ZumA1v&?8&F`2{B1|9XxNTya?psHC6i z+vo8;fIWwkh%&jHZ_6{6l`Cs)sVCt=FMv@$Fx?6?0DyQr-plj+3snAb|LP@xu7-55 z{relcWuRt2FcqiQH#cp7ZYDA*$t}+hHlkbnomu?sC!@(dawzSIWn4Pa%Hj~T(@Y<;s43$b1m0!#48 z-2+I-LB&qUd%gU;ufJdB8V7pOwq6|!?V|r!@7447Cxge~*U*52tdx&gJvRvM66nOib=3UCTUb~~;fC~Yh*<+&Vkf9H#DJbqpDAs`XnTA6H}K2> z_NfFkyA(+Kn@ebbAuQX|*Y|;#*lVHQ@v3eJ+>;@Y-+*j?`J|hOZ$)p^q*C2(L>TI5 z19ppZ7aq{|gMil!O7WfonZ{d$7t+`4KI{v?I%4y1F*UZhI0Ud5*E~P;a$p(6qEj6| z;w1Wh{uU6yJK}gFy?V@eH;-4%VM_Ub8XJ=_X_S(7i7%|k-5mqcBEis*{&9Wn1R5;O z?v;Vg4A8DZ$9*)#(0@tm;TK1tT!-2~P<4Nv&3C{Oud1OTrKW~YAG?=H%9t&k+=t?R z{2YKKys2TpQ3GDo*4AQRU@Y6zuESM=(Z?tWtl5PBSR~YJlmN@0e*XqbM=hv>SFC}p z-FiY%8Ftx@6XaK2W~@+aG`VD4%T}s~yAtn5Kvn@?>gG^#e}nUxOM|AWY9DC*@mW~- zB?|BLdlnX!Y;C*7{@&gdaN`WY^M*E)YAiaNF-&CyW=WtXb8Q2xs7Wnou?=NrewUVp z|NIFDJc3YZSR}dB>RK3I%(G|K(q&(1X;mxyK@teb^L$T3W7_iUN2BXiN_4XyVASDJ z2uXomr>v|@o+n8Y`Fuf9MWvS{j9cK_w+$+sWE=}Hi95u{$HzO^ns1~)+5O#rDL;`?KM?irC9{<4Z-d-(e-}FWC!iNYfp3u&Y;J$%R35R*E2rR1cVZ2+R zT#!s(7&@3vtLh{t{eS=Io&=IoNSkmu11zDlc|=$@FRdTIYT!YUVjx1(;S}&}g$%4J z<_-oDSb{*`qU2+1XzW;BzXp!b9(W=*(9jh4jJm>zh82}HfP$7DG(#eS_C`6mam#jz zV*~>IEofr_={}@!fXzd#>7d0ZXl$)@49a2Am~V!Lk+HF0$?X1r2>T9juKTxbqf|6h zvJx$$C}hhPl|)ijh3w4CY|J$MGERdms04 zAOHV-_gkOu^|{7*o!5D7WAUceTd-(JCv;anH5S< zW>_{DxW|Z50FU)m*O6=8fwkQko^YJjdlC{Ew=G2|u`9&|m3r^OGJ~A4Pa_&149-V= zZ2?w9m{B-1zO3OJ{q)(hyU@LYWa(|; z!$PIr7m~rgtbZ05=mkKNhO!Q7cB)UGBP+DAIR)Gku0`9!eCOO}!X*fuU->DN)Tp4O zv=hw~UteG5?(98<8}6`o=IG?bZUEZzEvy9yfQO>bD>i1|wULLl$*9l}%tSl}>dfSn z6n~;b`LZn0^paV%-1#DFEP|f3DAgviXAD#O_wU!tb2x#nO3x$qNN5B_U5<)iNLxYX30arGkc^ZeI$73`!rYiG~w zh;d)Qh$P@AB4jd76$C&C0&gK5Q-`$?PfCB$H}(E3F0*#Xi@FuNWC;>Fyq)j86X948GM|HjaT&cK|{pFh9)`}Z$JKxbXuGbCj(9F*XR zJ`V{IT*wuYT^DGaKVZs3KQS{?hW`%w3Z~(zY$ojAXJnLCR&KdhECq-K<9^MqO0w6T z#zeuKsSIElMEO@`Mfgq9W1tc#5>~SGn%I- zCx1aDlwDI(lbEiNvhSUOo~7Z>x95dLL`WOAwc$?@Q7rRvbxn=ZYWBT*viFqic8s>4 zNo(da{6>R3+&dg({w%OBpv_1qRC^9n`4_IQj+d2{r8`dQWn|?$&-OwSx#!0lSz?ab zsGZSSEYEJJq~rnBOMXz?VX;0MT(+v{|gPktvt;wur`1r#Bg`OcY|?Ksvb09xvu$^sjnuvhIS=j4ua z?i5FfQCpdhG}j&_Se~i*LPO4fMs`{7{exF3Kwt?z_Mzmf$mHXcql{Y8Z(?6|xJAbA z&yse3E&=Gfm0_D)XYv~ob-DohGxavHu&@wA1WU6c-tsY|iM0{?g)9xqefOE>p_@v4 zz1eX@Sd3}zD5`qNmx~VS0uTp`RPI-eQ!@Pa{MZUQANDoSUG!$@?e8bVm=n5$+kOZ~ z^I8Y7^0G@^xC(;ScY z3qA4l^fb$|s;PZt!bpVCi$%ITB$vPkr=@?w!1s_n$~6#-Zb8eAbNG3yOS3WRY1*G5 zcf)l(=STA8aXbbX%EQl}#c1SietCMxZn)tQownm$WHO;w(_lnFUxV0H)zm6*L%#q| zEiJu={}mVZI9JjVU?~c{d+~~EDEyEISOXyaMSohvv zYKdB#!DhR|UutRwU@auN;MQ$FAWEaIu1<&$7C~$v$93`4*w`2$-uxNZZDwGmx~WO` zCAYdsTyTUg8F0)CSEi`YLl+hn{*hs<49`+^vW=f{2R=SuTW7>RQ|kmEydB3CxkMtF znVCOYbw}cN?PQTqgauRFy9*=Wx!ofLN9YLkrmDaWa*FMjUWkagF7Uu1!6VdVnyF{_ z9lS7y$%w5gEY}|CeEarI_|6y;$n&iH{Lhimgw58c=}5xELu_2Ndmd8RLoM%*;N^e2 z3t4vU+J$raPH1UIbC}A^8u{tii5|drx~S9y-5T{l!HrV2L&2Q2fb?sv=RbreM30mA zs_nqznn-cKXpT)36vQ0Od*@kGd!x#wxm&W!6zyLa1ZF}Nh`Fkgu$R5DVM0w>&Rw-g zf{!2fg=?auq%^6I-SO<%GsTyu9^f~-uS}lJOv%m`vidwpfl~!Z(t75P3XR;Mg9l$X z`OnJ9$-NSDy1beVA0|8lIH$>FW_mgXsn6TDZ{w|Buv(X)%SJD1$AJmR zBW!FBF;AdlAEm`;8#W~@8u0{~FTVB##LyJ2Ouaup-fY^k1qoy0{yWIIN2+9B+FTKs zw)Gc@gwaWQ4e+SXf(S>*Z?f#+9NKIWdl2-U6Cguo0 zqaJX6?EbbqtBW~14KMKlDjG@=qV|n$oXI+}Y3~{L77D3fxBQef)Rli4gHLDV)fBOt()7V8twelqd z`!mdFxd2%F8XdhTBSThKR|oRvkHo8-4|lQDAjdk97KM;J-7@#$hHk9dWvzEYq*}S%ona(G|l6x*S1>~UPOfW)0)9vxW0D!(t+DbVf>GX zCa=@L%cPS-nS2$dBrFU-rj?N(@dB2r9*~k}!$dZHE5 zpvMrtd12xg#_fU;A0CyIlxX#(zqLwV3r&1ed1a&8Zc0YznSoizsZ?1uWY2tN*}JzC zM{m(|$IgzQn6_aMFnz8`S{xG~;hUFt8Xh`Hz-2D@b%9SoVj{S+qlEo|Q}2vWWC1mYS|KNA9_NX&)^^=e% zp9F^}bT-?lnlbZB%zG~JNH&NB@^F&mp!gy*|H1i>)+Cjd4H&{4ptYS{@~lK(Z*M3# zaQFexvbrXPOQFcfSSTcT(yF^aJcwO6RiFlWKOErpBA6d>PX=qFjL|I|-Z6;p2IXc$ z+*ey@*-pYVgiNC}etKX>3~CLm7XA6j-V8MY$;9kzd42s}&!P{L$HK(4{WWc* z&UfTs=2=tiNF|8^g&19c^26mqP9mU*+7F*`brtiY;}+yRV{2_qgckocmge4HzoggK zR__i6-$;FzD`6WwWRli-W@{bR0+SQ_0*Jg1jmWBq(=UjDz{m8wUT|jxD^nLTM}eAJ z+t|S6DeN$PFQ5D@hAtNJ`vpUxf8#;`JY9GXdz##6DN^8!*dOy_j zjaea)^CLEp21kigr56hUy!t{951h>cTDV~|tH*q!Q$3Lx>1J5O7MfXRAAJH5A_Gjd zU}F6Va=K60RiUaZUXFaD1WOC6jV7`_j{nQL6krJOPZmLc{Wt}1Vhu7+!+2F?18(6e zZQHq%jhj2I>0%R@ns1_`y&w}Ws;)+zl~Q1qywpHP81t^}+YOK{XRcu^{(hSg9x@38 z$-kNJ`-Da=*0O9~v0kmG51C2h@YRyio?Z=ITb}Cwjw{{%*Chcr!KgN)0S9yL+&TQ- z@cyog-6u9~7PE;0g4W@K2R)IT?xCfvz(^aR>vY@J_6RR;U2K@uXfadmU6UNXTQ zzO*c^opbvxVSYOgh*D#jrK6)TvX<9(#=D4OgGt1uthWHo5sb*?rtY1~giCH>KXKyX z==Zl^3KeAr+|r-R1vq!DJ%zgPH*mb(vTcA5Wl=^nIu<=|=*TeMMS`^1(aGrzheE_7 zADk!Yp27yX4IED>=-MG7QNjP+Pq^)&4oY~~!N&lGzC$%->y90)r%nYDY1Pe=O%yvA z%P>YC60Fg`*N0ctN*%-_F#(}Rl~uFm|i5K0_8VIcke4Dk{Zc0%i-~3DHZq z3KRYVSEnjmC_wri#U$)jkDu|xSUdkv1yYD=wQ=*~{^F7Lm|=>2{h9=+CleDBN(i$F zUV+gU$dQ@d7k+8Aa~?mArnsZCbK?7#=@(G~ds-AjVdCsWTgo+|*~&^z5nIQRyL~}+h+HW0Umca{#c!(%%ybZpxr2{);BZicH!oQ~M`5%Ek);6i^N_7O^Wts;>KKZwWSJduL5o~XAZq5ie0JvdQ zy#*GBVom?>LK6yzQznErVzgR-S}U_DM{X|yr>&|@)48kJgkNm3Z11pQgM7^Hm^vRg zUq*j<@miTuTUvknu?~^Ts;b*4DWfs!j>$b<^A;YMr_21<)%F|8Oe)&iH8l~ZTXSvM z@dFIe2fhFB;VA&H;Nj?6cgJcR=H&c7CDcLEyqwn?toS}6!SnT-$_DdVBR=y?S-q!67Th^EK}(i-^sASSe9k zt0l?B)$e9x{06rnZ1;y62Bu%+NeTlyrCUToGW+TM`_zuXSPwc{+9r{)SeumvYv4f` z>U)hrr;i``5obDkrq9{B51gqdI*FDCW9m!<+bgeG<(ET-z2e?3i7&{R8+@-xi6>z1 z&J#2XbTY=_+xG|w389w!0>Su;D5^*>^?MWk#K^+W&uZZWet55{I{}4^ zx_8g|&K+Y^HMm}h`kupXr;xEaCk?0Bzd1SS=d`|&J?7NmmGV=3nde;z2!uc48f)yQ zXCg5G@PHAC1JG9}bYJ~3WJf!1fdcKn;Sf0+n-7da2gIFeBqb#Yrw1jLVraWGI3R=q z=~je`2Hr#zv8b#u`GV3T`Fif2)2H*a+;ljNt;Gqg6q^s@lS$`4iDfv^I)@LhxnuiMyIdOO*{hI`a-O!$T zDB}^;h~Za(kauC6C%KVdBvL)L7rl|PPQ0v-6l=q79y_)@zi|3x%WO7nEuKq?wK5JzLuVUp#V<1h8m9t~Eh+f$z zulW=8Jh6!tU;q$HTkIAi^(fJ^&w_9TTaW+v5v>*= zuV+E?#UtqhuTYgGz}FXs`xsL{m?aBMn!`{s+)xo#Eh9_6J}q!(tYcfz{cU^y07%In zRg`u$F)@+t@+F|rXAu$AST~Ui&Iy$0jINen%Kyt*BtG9ED z7v?vh9y*u?iW{;b6#CW3<9+=7Sp@}~lKqFSiyGIwGOIaflTpsSZQC{uUm46FF*X!# z^u#S$vltPVDqj7|&8I&!h9)N1$^&pg{?L?bQRcIo1W8vy#&xZqLK+@5@&8?PCZgd= z$nALo0BA99JaD0AnU$551o*1Xv;dYNi@3~jDJdyoL)wv9rLw0GZn%1NpS!y|@-%_p zqwy#=eQ>gvvv)5`M4eVTLHFrN2$4to!su|@6CTe?f~cS?4b9)JL3 z`uF~!TLen%xH4I(nRELP7ROxAxh;KTE)Id1XgXr(22ciSlY?+$##p6-tzqG4f1%m2 zm5M59HVl0VV`OBH0f!Q@HUMpc(Adhz;6q#407P`4W0R=(c?rP($pJ(%D!@sOE-pdg z;om_zORES_An_3(av->?&oFl&St{VQ z*G7tuqzJCzQ=Guy*GShT#VgP<*_NVq0U4xOW+q|K=%^FWx3bveCW2jyw;{6Q2qkai znMhf|YfGUW{}1TG2|xl!NLob!O3jfzWu0xKybIm zdZ&5bJL@tOdh*0uS@&+jpdzw}-hlym4GntSK#(Zl+4AIPBch^ev0~&U#vX{iGnO#0 z!`I+rA8u#3JSfre@mA2MpK&mFI1rWjn>V=p`?wmP>QhdDf6gPwm* zPR@^fmpcfK#h8ZJFTS(xLq}&PG3Ptn;ead|dmqf|h``QwavcB*J--PxvhY6mtNx<9 z

    3y(SOsb9gSp(uX@tU2yFIevp!q5`s|BZV7|*J&X{=#arbl384Q^Ax;G!Yhk?} z+f2m7I~~?rCMtb5k-!RBj~uxNyyLQ(no(BDF`&io0ZU==87Z82F`hw#g^;trvnAZ# z|4t#v=uTeO1;}?sUY?kvCuCws+}9S3k=_w%m*OsS{MXjR`1tnH(b3u8TIm1&0?MEz zcsL-=_-d}hDQCJftr2)6(G0)|V*vT%k|U@JaHmqUHW^WFb10gtbWvBEhT{$k{c%HD zzOms77J;Nx!#JGiko^8_z^3%-3k&C$~m5|KqkMOymZz=e=1ARDU#7?R=p`(IhzC=*iF=7FU+&9xe%4C=)%AblMlf9^!V z=P(qsyZ7#uMMDmVN8+@++J#;pkb-`u-Z)KMT^MEc5(@cWVAdQtc`}ta=`tET2eE}7 zg24atuNzRgcTMK2kS19fUti-!ck}gy7blI9SQ-4~PhQW_ZR+|dTyq&+ZIlmU^BuNC zFq|1~{BGXp3&07*d#V{zv?2OIyJ={y3<}oId%kPd2r*5~=>U-#TReCmUyWSyU8ii(CIUJ!Q=bvKOcaagIP;`*ihPv5}glSYLN zSdiDH5Z9|0-k2cD3@6%D-z3Ul@UFHqi_zoS16ai5?yhnFoVC{OeZ1Lt*Zk` zGCx1s#Gl@?vdi!vK}BG~Pc&*+FNE;i`uR45`En2{S2a#GK0dy$-@YYgM4-#i)zt-P z0X3!)T9z-kbyBl+;M5BXB~P9_iFj)Z6jzH~B40a=A^@r9@CS*D=VR)6#>WFtL!m{9 zlT^{r&`65N&lg9$s;sWw;V%y<^i(ZY$9%W&kEV^jxZnUt&YwG{iwO;a@PaBY!?ZC` zYxH8q7ZDK=ndh3_H&Ak-M| zv$HGFNYB4*_T`i{*cg1ym{ld_&q4()v@Yy=_qD}&MbFAA06znvgP;uu2FieP5;1C- zwNS3h(=#&S2QUa`0xk6$e0MQ&)F+Nbq3DO&00O#+mlo>+#Y4Gz)M2+w%UjNAK9r!j z!%nqfEzYjECXcKbO@Ea<$jQsQKupwIdY)x*dyXV4lvuO#&iki3vgf_&;NTE3sJItxKv!2+gc?Lr2*=+@@<%5Q4aw^Tt}h`> zBA<5BPGE=s5j1__S#|)geI6W)S-p<8PApKMmy#mE*#OrK3Jxv@yahCBc0kb0)fM1! zTwl^V7`1F72;Ty>)T1S^(HYbK~gP1NusZV9Wg+Ky@?bo|7otN3RAwg#af%NXa(S)3a9Kz5f}4cz{W zroYVg$Izq)G_zwY`@@GoR1ry8$mYu`D}{1uD{^dTvzDL$-JIBBkyvn%2+5iPH&hJ` z-^s1YmIfH>BPui|vK0ot+wiLC&r>S7K}Iyn2)mxrSxsArz$|F;_aCD{ro|o4|79%e zM*5*5bPe!#7~gRYjvnM_)jzWzWez@Ov{97aX!>M*4aAVDgG0X1<7Q+w<6%NQLU+2# z0-H^$G`O6U@CC|w^_-nWakF+WPN)h}JO$4WSEZ@3|UZSvy%<^Wv`^ z%*3ImRQk*7=Qq=Z%yj>RSy|t{eUP2~teaw7J@2ibM}g=9x6FT2PJU^fIJ#Fk68~@F zs?htj)#Yi3tv(A5mIIFH8~p>G6)6Eu&lQ=l)NCRpT$<~>r4G<2^X`mWR;c)eKO^|G zWdg7#l}neTpgMVB7ZHxAqop_4#E0&u{3B&j_bzRybb>KIbp);kxXVcyh8Yub?rxn8<*EDB&BdU2 z!5^Yzf~*7aYL#7RlY^gX(wMjp`5)4az^JJ1pQQw`JoyP>X30J6X=m{7! z+~PZyLR7MN7$E(`#mxG#m6*3URE38?Bn0r9C@EgIW_5IkA?qe)^pL_^z1dAkd?AgR z=TS%p{95~fHbFW4!Fb`i_J6*dI?>h_G^Yp7^$y)&EEln{X-)sNg_vNjGco_qJ9IFK ziHQ-F2IBYjojZ39_W@qS+W5zfN$R`l=$gHb&_uffXYYU+F?p=`Wx`SS7htOEzd`Md*^>q7h2_h@sjoSI*|0yM1K{Ei)LA5aK7M&$2CA3O*Ve?4ZMIUUgOqD6@?N4% zfy;V?ojvZI_r_2}-C=;HP9U%T7@EPMJ$d_<-{#x5+jXXs7K0Z}Ow_xaM@~pA|K-D( zcl<2f7af8=5wUc&*|~#}ax1ZA1=(<8A!_G$p078%p1FwQsf3uz+O9n=7=@S&?KXv*onIl431HY$Nd%BJ;IO;VFO?>@s>}ba{ z@17Ci!%I%ga4vYPkFS5dY)Jf86F5Vn>+$$z>B9`SW$7$h+Ue5Q+DDzUV`bvrSy+;s3Liale^*cc3muStBHticdFOpH?5TVV?{YQ_^yVlr(++MDKAXDT=HztezQva} z>#P;E3nSVqX4I$okbGGV-K5%hcKmPx&?P&{l`M&et$RUJB%EUI=-0e`!CEIQY^ND) zd&TBm^X~afkaB5G9VS}X2KMaxRr%D9I$@T^gmKEv)J4?c@0UQ<3psYj{G!}NDw^{@ zO)VcN{c3Mrl92q$@)$!$wt(;Z&eKzWVggWr5yUGk=a%Sgt(U7lqDj-`Hs2|l?d0ri z16h(E*;YCr?%cyoL=HocCP2sz3=h9HB7&14@cQ_I_n(n2)D*C|{N+W4Ms$hM0VCQZ zNG}CUstBSx&;)W_(DYi`+lBr(Rae*72jNqR<_y3L%SXJxTkfKOLw5EZa^(~A^Hy`s z{6ucZ%liyB;-l8+4wue{Pkw>L&=1lMF*Jz|t?$IdZKeYUt{J>)B2>>VDj<9$7QQv4 zP;V!C7XSuYG6s2AT3aV)^RwTm&?K&L3oDxSR|v_zQ9{12_q2nZget#<0Br*%dRrjTNxi!s~9Bn{lMOOOW0_`t^#= zN?==?|N74H?~{H*&n-_EeOx|F)TAsPE7nv2*ZJR}+dT~cD3kE*y$|{NjkU5ZFB%yc zQ3c5J2Lrn#6kyWtjPI7HyR|s}dn>OVLICgl2RFB5&OSt-Qz%}|JC~@|r)GL8Ne>x`#9T<})D-_D$-d{LO4bSA<+u)_ z->30jPj2Ij;g)HZCuhJ)Pe4Ec++6dan?7uB8%>>t6XG~HIE*^ED;-D1>VAuyR!K;C z^3wOfUy-`H7xkp0=ej?zoUNoHnxQCEQRjD-#L!(V|NfoI6G<2?^Z9AQPom~RHm!Q~ z>N|J$({_KPaEYNSK}IM>0$dYtiBwB6tP15N;nFGi+(qVv>wNPc;wF29L6 z@HKU+t(I&cs+>eWQ87X^vz&6PSV{w!LYrtitTlKhJS z18e6y*TIMhJP87rK)_F&QZoB_>g;77BZsNq=K;I{osvQt!~X^yDF7J7O;y(mn7im6 zpq>|0;b-i1`@CRv+c-K}i3ive@@_4oqUf(qj*dTaZH+Sw5;N85s19uc9}fTklTT zUk6SKc(2d3hsPwridYX}_BD}-U8zD5-{k+tJG!pnWz>1|zOQZC(r4r%bkWZVjCy|v z2|rpB!MK$10UIr*YFQN;T&ss0VKe!i_mQw4U>rPxi&oR$EV*+l>F^f@(zw$f`@(mQ z0>s)*2y39&JHew>$Ar@B0#Y&&o8Lak+Q;rwU;GVR0}Lv<2&Lwqvb!(7^;loSDc`-3 zw<|+W(PQe>fyQ3aAcYj#n20B}hqq*`&SyM-p?(`c)yE$`a<)K&C2@a^g0{9_?%)Sm z74gCcg%>f;iLN_gHBQq5ye@O*XhC_R8YR$NG@va5n_b~WLnS>5mI7|sbhWf-WK;sy zt4%9hYde~DEL8_w2hZzt+7FVFI6W2HTBVTXnqNi*9pyT;4d~5l(9ceYGu3TE8ydf0 zi*ap5My|(Jbt-bsOh)&y`iP)M2`HVv_)`j&baqBytslCE-vF~UhL4-FU9}h@liq4Q zf;I?&+Y;h;&=t#`xqW8u#N1r0YMfMbOkXR1Iy;9#zC{w4K=Zo>?9BHZd~h@?8j@fH zSUf#gi^1aV*NvvEM!RJ?E+3WDce#H3IvOHuY;1R{SMQ~@WnE6XdDeuwGUz7{BPW2i zA3GS|nJC4sD8fL&9S$Z~o4piZ|KCKLgJ3Fcq<8oZ1ni4F_h-&lX57?O=5PMOV8PfD zR6n@qhp9cD)jY+MEBtgo3NT?*hMhDRuGUYXSIGTlj97N26Oo1R#b~!0t*tD=6=%;p zJ+qep`WP5QRub#2Yihl}IUD7xdG2u$KkY@9bNkm}*@xS6-;?jFmWin&$RP#>N3m=M zLkaPPnXQz@#>TW<8YD%?$*QoO0wj6$Y#o%K7;>3FG(;PSfYhx+e1t$C8 zEIZ@((o%BZ6Y@qU=^oCe2xN2y)9fhAbU4DD_7oIpq+FIi&dJ#l4;g+5c@bfn=;fh1 zi=LZ6LL!In)h$k#$(=y!_E%qDDf+QKPoA)`vVzFMX{5y_#CbYk6HBdD#+Mrjmy=j) z8ee*O9mW_B_l052T%@BvV$SY@hlRogE%fwTT3ZwNSO}tgy1jkBF|ymUmoEpF38__e zb{@djG{V=Um@hDLr#M(sAMyFKE7Av(_N>tz^zTeg5;7(}A=4P41C_KIO@Y*b$8clU zoHe4KAy$)1X*n>T?@CF1$#-hluIw};cwht2WQaZ+z$~N}8qI(s6fk~{Q3wKrM%M@I z<`gwETcNUThsylla!?X@8Jgt-u;Qagzk#{gVADnjb6Cz!f~G7k9^lBL{P8N~)wZSD zpsS2KtR=J!B9#yG^Pdy1r5rKfq5p&CAk6eLiV?7&I^`ai(dWA{=1dr_LT(3QdSy-OlAvKs-4}uZm}|od)W(!x15Sg& z8Ub!NEw{FLlQP<6#6T25Q?SaPRZD5s%rp&d?XHzr=0dpwT=Mq%>O3fH7Fptwl2MrH z$iPOHjFI61`cnTZm{-G^rea+3#%^7Zu8}e$9FYU>%^WTFql1>(nhX#LN08yFmqbub zBCCyoE5uEYZyF&|2O|$|CrLGGP+om{^lH&f-BYN+TmSR!K1zD~9oJS; zLKMf6oVC`|{9!A#n6_{b4fN&S9gRHX6AmpQV{G)!}^ zSe?BZ?3I_72irUe)EXhf8>j$*HWPARWjl1gF$9N%Oo5{S|L_%c#nx@xRIG}qn<@c- zdD^^Is845-PAFJ%ba8U}`gcZ6QH2J*6^%l7aUJ(XR$K*B=~xh-lLt@~HUnTxx9XM{ z%jw%m^a5~rvN-(T9k=hCB6)?w@PB6#6^!_l{lAu%QP6C4(OdQ1o0-#l~i6U||Y&vH)ZvsN|8S_1M z<6RLL2PE1zCj1y1AQpPnzmeU7(Shi$qO>{_RJitQ4)E!9BeS#Gh*EOdAosufxuU<9)l~4 zaf?!1D4^Ad`xOLP$9|ZGFj3%z)q)gK?%vr?4MOf;JXLM?u6~GEQ40e0Td*MU?xNh= zf9w4kXvRnaBC;&!9d)u(wmuevZq z^@dl!l(xe3Znc)9#hH%K=iEp4=tit{yQ+qhoQ=h+jw(rxF@XOTT)W-=1a_p#^UWE;o1BY6h z4DiqegCIHi49bPXMAQE9^6K&FT1j@{9H9ffs_~yIF24Dcc$}>M1He*N$wE&QhNK=H zipK}lN38qbpGs*mSc<3)Vf(N_t`xVf%nWTq&s}IFG_2(RW=I2-Bu~e{63TvgFqnu% zN9Yc&+7~tfRlNrrxU&o=iNnlT$_@zFMa%@i`}TvWZj1+9E%7im5VEIN(rB)OoE1*Y zklgrW_Y1?fC0$+2p4gTEaT#vv0|%-xeMHPbrMhfipO##=Z9E?h&P)x2q#FuBmvlt3 zLUa|PJl32dI4Sx2=@pZh5dUt>k91HHF6(XB*Wj@4bT0!FVyQ@T52iDt83fKlU2cYC zj8eIFrl*wpRk?Y;p-tH~FvVx!t|kf@gh}iQbj>&^z&)4tnd9j1>+F;XB_b( zjF)ZXn?^Ckh0Fu+hkcDn=R^U=Y}pw+Mv7O;hre`hIeq$o%iQ0DV7@@dZ=V_-Czw`T zwh?QtrkXf&%P^b8R-0)jOCOYtQ+hr`*aF92r?dgd^0zK93)p2aCBf{eioE+Y8K&q6K!Cjje*q{Ta(HE9Ma9 zEd)O*Tl8yfO9(M#X5LbSk-e|?GbUg8obSm_JuqBVOaG12(XsaC!vL0VV0<>bt6-J1 zwGAY6Wjj_Bg{nh+`B{w(@(C9H$6I@MNeD-L?Y0~|qaZrC;yPT#kV_YQsxMo0`zIHE z5Sn3@=ku+%D#(;gBX9UZVUQ3n^)$)e&rLV~fC-TB%c zvTD0>m{F?rb+4}pkpL?y)8&b8$As27W#zL-)0vpAkK`f+Ac5jGGET3Um_C07yB&ZU zi$N^``4Cgvf55cJ$X7!(PE6hthQXabv*$mvgO*v%84g5Q6*i>zI+daNXiK&Pq!w9$ zd(_30alj{nS9w7hNg*ui6^r-P3-ShJ9+uja0}wS(Zq%5*KLC6A!T6<43|UF+`X zrl4%!FgjAWf_`CSE2wj`48h{V%u3h<@9MEm+H#>=n&wO`LB5PaRkM#S+-xfD>)_?5 zIeq#BvDfmF$M&X?S-}_E^R8};Z#Nz-czKg*6QBO}Aw z!Jz`pua=gUq^#N5*{f0ddRoCd6Vvt%=k4y|fBD^if!WT%fg;h$JPob9%>4h!)3tm? z=7m@fqd`#xUx#+wozhC(N5~QP0`MYAKA1S-sQS7j&!{9F-3w86qGhU1B>>U%Yi~VC zih#Vq1ngP;2QFW^QiiMn84reF$dr|9joie|*f(z~8E90@2@OmvSweb(kxr0l41J& zC%)gQ7&_J>s0@1g`i(7eY6sKBZI~WVXCH?j0O1uQF?}d7jR5E?zGRZ_dG<$Z@nx!o z79XCZum}Tz9()pg``g(39#Kk1_n)izB8VS@PUMD}f1WB-%;OHMDU8r7p$qr9WBvBJ z)!E8duAdg2_#AspUi+ez>jQ>@7N;mu3g?YRR`uXFnG=s*CI=1Wq-ebN0-#5%Qd(Jc z`;$L@M~})cx25es+KPAsHu3@=ZAc|W+iAco8 zueLvY@F1a<7c-L)SG%gKQ)(Kwp{<7mlf&0W*0O1XU8{Z=1!$)4Rz;zY&F0tC)M72o z;zt%On=xz1wT74mxw)Xz{#!JdHLo%JqU z+}wqS`n-p|_DG%3HA&@V6246+m;jb%#wdL;+h{v2>@|lqlx%A*N4hqebKt&V;Evck z5xV>*M)A`iGsX5lU;DprM#ucu@bKgO{78_-h(Yz}n3(F5l%{N|59~iQQbEurKH#W8 zO8C&LSuni#th!>vvUExBD8KshS~|aBp}aap^k#-x^GW2`B^X_ks}o>^ittaAzGlSZl1^> zbbh-ASe(7h|2>8KQZk^aZ!g zTegrtjf_mC-P!SnmtP)LFxv3KAnurw-UT++)zt+iuFc$EP5bpQf+kLa_>$T38mT(! ze~cClbBV_L4Lw}Ph|`R7zFgnQcx(ax(U9y6w7q%~94jC%7vMDyr`Ya8pW2PyumD_I{O- z9Ho}TD#7WexnJ;y@u-&k{GYozc@BU6{ykUV`0PO8N=fc-13N>*KkM9<2_xRRi-ZhU z`aT<_3`@XaGTO|xf>r}8-L9pfW1W-pvvTM{etUP}Z%1KNJ-R*q@fe())U(DgEWac-5@3>px06rAaLmPV6#; zxVuGmX9Z{nPNSL4J^=wjW_xL9%5>J3)Pb@=gBZY2x%n~*G6I7{szyvU6Mpv^@*7m? z58KA%u@?F?F;{^qmk@#+uAT)67U}{wEc6N13nCWlc>65T8La7962h-G6(C#BlLPqKJv&m5NWn>%dcDR}HhlDkQ`<;$u9 zr+S(5AqHRl<{rG|coul>5l!>-jZ00Bt7HSjLe42Ht%K%YV|zv-+@)Z*vQ+nx#T+-|x#lZ_MN_`H)58enUIe= z{*I_afZ^IQU7pIs6f3CH^*-8UnU)q~<;oN`-*vBT{Op-D<NG8P-zzO}(%>>P@7ptE&sGweBHPvm0HJ z8+i|r3ieb=uJKY(Q1oEug_f2t@^6z&Ek$MJK1tMmd~?Q20qYC9?C#u&fdY-kw2;R= zq`Y|7>!?-)!*>J)1udklFQtj=O#A7qkP$n^1G<;`S|5BVO3TtmzPbAEn4 z1iLGN!nyJD^Xr$zlpn`#(!Y0Z}s*9OA%K|gAv%h|odM^Y?F7BO~nUM-H1lI)8Ra9WK7B?5nWj=?@sIt2k zro7|m>FK2ao%K#SDv*BH2V?{h4brt=ENi5D_wEJhE;J&d9Q-nCNou3 zC7rBxRhr`9g*^uO%y&PFX)sItF1>|E|1I&7CPR~%*`YIszuNmMdAnxs|8!|<(qIiM z3q{hEr?bwRGPObn26EhCC(*BFKf-L9Xw?!E4^oxHE%R;OoZeMfJG%o`R<~E|#0ei7 zI`;X;4s#E`F-zR1*{=64k#gJlw)_G$wTHgHZk~H3CI#%0{c&<#QD@!V`$}6hX$~b_ z`BARN(b6Up9l!NZ(6L;)cXbC7vFglVQ=9JX+Auk`!omW| zrS1Ok1ATOb3!BkrPkDZ?kAym)ax#Wxb!+!x%^gBX>~&n6u@J3a`2>jOJ>YaMj?s83 z`pCyD5SYQroYlIZHkMbfR9LN4M7p}qWkkLEJq;)v!!Wl5@-jEcEn6%I;HpH{C0K z{QGuGgQ>vU6!-cbe17dDCf9qq*G9WZNR9_nau=?ga)-s*-Z@^ZPh@df+1ZnXu|j|f zf9LUHxDGl`;`1K;oI1rNC1et73;LfikxUYJV+~4@a~;Nl;k$QwPj*8dIC?v^(0d1ykFrp0_4)I~XJ}Rf1B_q1NTgHb$vkOx#yHyVdusTHG+AApJbG*Vm6rHK z8ExUmUgdHm9p_LFMOXQm@oVHb?D%ky#8kjQ+LI=Lc!`YI&J-y7rt~o?G}Sd^JxdSqN4Am(;yw*8 zPJ42Vk1^~Mj^MGhlBJdV{Xj;;!sOf-L&6oG_{Isc^v91$dcu4O7qeBms5h9?XJC;0 z(Wck+hYp?Ruor%)t0T$Jf8WZr zZ-4FT;6k!4j}PH0;ClKb$Cx+iXlO`r&?qbm;NPwL>8uW`r?-!SV+doKSaj8Z3TZA3 z?brC)*!YC<`iwF(!XTSH;V9<&U>l+1keHP8MlI==O)ibjIFGF`2ctg)35`xSxSKBB z%ghDKo#T4egUJS9H)FuGt=R<(_6e}vOZsgN(QlVYQHudA3qsMc`NS*7U9m*1@=n3@ z0VKY%arMRKf^jr#kb&!g9}IY(ljBoeeGy#OQqxQ$F7ICrUz&Hmj{{gR}(*Ac>A zp6|ZD2r}Dyw3&~3Qwv^2yGiPumy{rFE6jbv%Uz%RQ=C{R5pqP2WnEB6ckEZN;XX%wkczCK_@KGI zJ~it$5?!0z^sCqWF6O!2sWs{EmHR_>x3feMFNyB6>@V4De&s6bx-88hDl&!GxMzd2 zWPzJ_pLseNQCtug&ohgisL^~g93ZJgYqsYA@5vWtI&$O+CBJx>#T;)JF^EUuxq9zn z8Cza+6pQ>hw0=uaNQhTNWU;{|y6(?lmu-s(6Crd?QiOK@SlK;xs4ycsjV%kXo>v%} zS?34q_Dj3S`qL)|w_+xs%5mqUqwBo!=;XX_q*9dw*_kuTziwGpG#Mw=Z6Y;<3m@YO z-6ZXKoK{xOihC2B@lk17xuYMosu0=AY94apcvWH@M}{Rj8#a+hdk)nd`8|4Nh1}D~ zWxs>>5s@eE#;bd(Yb#6oyuZM2o)Iz7S?2rj_*<9u*64+ywZ~fii!Zcgyl!~ly#L$> z!6`J~-L2M^Q#wRtb+VFLvR+Y!X493KS?PU`{-!1{3)N5tKQ}mHPaNgrwvVknmS)Q{ zUI(SJ3wDN=zIQoKBS%wP8{_CMv6yTT_oYbZ>Vx2i54j93&e+-8+iz@2V_E6hLiD9R zMAQ_xF1L4gRkuQ=>~zFl0*mB%shH!oEVwqKyiNnO+96Bz8^byrpO@sqJxR~+{WALc zM->Y`ZkI!@84ert;@s6hyuM#B;n1I zr7UYaoFYteGODV3jc2J>mEuuDVL10@jrK-;A@hmE;`Rmy` zw!gM>UAZ)kNN{*bOvk{3!pk$)thpyGwaYg5w&l)X7LV?yL4?AKS#6lO)#Y zA7o_QDzwZ?r&iTjq}*dVJ0<|To&Dv_p`jt1Y&W#&sUd^c!JcN1)#gb$k4d_P3Za5$ zqtE|rT^ z5}f6SI7brPI%SFT*ThIj^tc`lL%y#;y}&C}yU?Yxv5vHHPS7_tZWo^gakD;VB{wy! zzI0@21RJwqmEp^&<5nF-kLz*Go(&a~m)VIrhK1irLxZsD^Bkj6;i@3N`}&*T7jfv%Z#`RaRYb4#SUI_%cV9v| zImzqx7O7cp7QMOt7l-@~dm51cT%^+}OPKFI8(Ht9ajTw}eJh#4nEp@FmoHyR^Uzm0 zFxq{2@@<`O;}RazPzPqPDOuz?W*&!J;e$0U8N2Ctqv}|tP|$kv4c8B zCG_ms#iwD!sa!eAy^Bw0?NqO_rRmP?uXWwmYzwtBG9RcSR~~BCIor!;_PU%?{h)lz z-zPHo$_#Y;;k?T~FMM0(W3C-^&!-QFS<0X1Sq)A*_$mqqsD6!#m-e28uIE3iN-h^* zta2N=ur;jOC3SzN<;Imeqo zW~m-*V>LQWdN`WhqHQ!3BvNtxa?jtt@=9`Z-3p&LqZGjAGCf4nC7TOW9TpaOEVP7u zL^k(XC#u9)*V@;YZBk%on_CriPNNHEar-!UFoJ7qXrcRo{c%bMu6)8FoQdMRr2XV2 zw}*(KM@3h6K#3d8S&3LmZ|mXCJ8vi-%w5+J_h9yW!9D)cobXe2ug*+O@yu52Z*h)x zEK2|6tIFa^!pq#f?)UW+91n;4j7e>Oe6eRjvkvUqhWglE7?h#h7Xt;st<~S#ZSx&% z_B6eDW9*z#(yH0Ayfk|4G#4OU#}w!q1o+6VA{}|qEY)tI>w4;d6HcD*)v|^ zm7|vH19y7^HHHqKtHa8qQ|9h$lMK0#s30U-m5N0}Z0v=Bf!g0UTjrty*G zhX2L)+bT;(ZV0ZMws&eB?64^df-#oyU7Rpv`ihmx{5|jJkyQDg3APo`>T4kn>Qmds zuoaX<-E3YX92~3Wpi}&Jl?xl)2=YBeExmblQBMj-gO?{c03Q0;|Gv65*!EY#T4Fwb z>r9i=3EpM*qU^vJwlJ==jcSX?~v zhY>p&r*ts@=QFtiCWNKcuW>`t@vVY$Y50Xr8{;=GJCB^-F#mmT)mZeBTW_vu-z+B^ zP5bvI={2``)o-t1yc1Dde*MK}D)RRMAB%A9{X}ywp9`J*eVCq@D192VIWg(+tD^B4 z5%#IsVx5V=SuY(fHHFk^5NzNlwTn{(I=&U@^rqwUU^sPcdQ*X+!m@CMWxUrA(5(ayTE@z-*=C(KPaf+T%0Z? z7p493$KdeTmvl3s>Ow3)RZA%kIg~Nw*p|TI_wu+r?}4Bo9f?~HE%#oW273J3X)FvZ zs#U9cO^^mJObD|(3~i@|%VW4(!_+apP$|||=I?Zw5@tsqOV)R{=G&g?qLwP&d>Fj` z=DGSUaLKa#VkrugM&fUwrKKGm0(EDWUqhXKD#-EA!`#2)Z=Oxh&3Q?i8O8Lyc}V&9 z)vHTEd`MMLkA-gj;m*z1!ottrtA6;P6L828fm)GStUX$2U)#D>eShuE>-WWP9uRic z)LeRS8~IE)$xRymKi|uZ+TEGi?HI0v`MC3cZJs*h%Fb6DkG@*+y61OBM%M4|hSlb} zo|bzG5RK_oAt5m}>-(L5DmaOD@%P1EL7`{X2;^4+UD3X;1ca4jT?b-6}@xETSjiKk%NC|;U*+l;2Qmp9{tt& z9;ljWwYR0Fd0A}fPtk|Ck`i~oK4$4rsq0R{*1wJ?)36B54B=VmBu&+sP|^ioj>Uw~ zlbhb$gi*s~Dk|;6lUZ)(66J@tI2QdcL6-?P^?5&Sid*h+z5~A!>L{y8NT2iX`{^Vz zc4MB*e>ppBz=}yRe-7t$1Ll+@T)Gq4T^4X^z9yL$eRA^3okl@O2&zoXmBgTf%X)fD zPQomU-=uzYKSJ`lE;2rj|Ib%GRy~szQKo?^VuB7SK~IOhiuoy-{MkeqeM+)xl*mjh*=qNmC3DF$6MZLsK_A za&N#%LH*4?VJ6(Ex>-`erzsoWp62l2QPZrrKZI{u?e}MVc~Is~b91jfIxI3$UPBfN zbJtk_C_*t?-UZkwQh=ZLM}cdtW>VKtjxRwxI?P#o51x07cZ&r(-Z5M_$45sU@KTZc z|4!}~>b`uY`;sYc#my=-H#y16VJ&EA)9Z1CL-h}jp5 zv$rGZ8~Nbtv7bNXtAdB&D|wKosXV$_xPcIX=8?O`vC~iPD#CVTFY~#lxq4DJeKy6* z!euFVd6+C4Su4kPEuJWl(v6QpmG1p&yEdVu2{F{KfTz;6@^!$-(M5f_V6>uw{nTDW zgh-m0`LWFM96gznkLrg72n!GxwVE%|pXmxm?{dOhLSSTI7G4B~+)E|r(7y(7*j^hu+L zedce6J=@b0LqV|}8>!BLdF>jkyj&bgFqN3$hO@Kt&xyvjSQ)C3V6}58l}CvymXELa zJv#OCI9%62jQy>UQ~wB&OBf0$6zbpM<3D~t}BG6yQwC1 zf9|4kTz(2&#qs!;ZwqLb*Ec-i;1;QB(r$j9d1@GK~$`u1qPT zZCs~4)&e{{JWDvYf1+c`cEG_pBpc~`EEty6Mn9q-{fvh5#k%kRnYa%pqVH%jrLZ|R zx-(6}W{8p!j^TOcBKbz!dTVIONYB+9=RTFq;L1@Ex47!*b0?{i+t5ygqNgvs zBX(D(1ws;=s$E{~e&#u&={bJ&A+As6WkOq(u-bC`w=*;8SrdCo$2eDIazZORVIjQh zpwr|rYmI7BOd}IYPUr|ebu;)-ci)&N>zyy5K>ICr0|^22^6tmue=eGuY0$#T+Zh&q z{YuZGN$y^lj9%&M%k|H%gDZp*j-s5<576Yic7I_l9qCRbq{7hdy57h&H&5|v;oXa} zq0Q`+O;1d=e=uKXaVH#{bt&2}b*-DL3>BLdGHuz&@Pc78%!h(M(*+<(cJBDXL0fi` zH(C0N;OMI?bq*>2|K9t^f9n=ehALK~;-z{MLX}jeIO}0bVl*UOz+cQ;IwCN`)Y)!K>OVW>Sv2!S}l(l(WI*X4t z{>Y;bVf?$^c}g$`(yxFRp;8R^?0|Dz-C=e@RD9;T!BNjmP36Zq3uIc~=0^^G1`Wfg z%@Zp$E-pQbf~flze@M|c$6W@5SBA!YKQ?OdR`DP#B8t>L8&%>DlrsLPZroHwa>(~K zW~ZnqJF;T@j zF-1+LGJtWu@i<63#Muw1MOA6m>FeR4s@_-~`il5g$i&`=oZUC}FHSrbZxaY3HM@1i z5)NQ8TCx-h2|$$36Nex#2vr}ofD>{ySH~IPR#bGh8nGUYuz$Y-K039u=v|4As%5;B?ZM(g_IcSQoLs6eHv(ik~ ztT6t`=&EebP>#6aZ={jX)=)5(5^owO;1c%`)zV>XOLE`we>NQhEW-mdUI`0 zy%Ke~YZi=Xu^}`hNOzkrAfx!4GC=`%X_b*X zii1ZnQIW@@IZUJcCOb#3b(J_hSHMsHQVtXn2%}VEPGD>33e-rnZUYJD1!e#KYd}M3B=0GZHUO3Pa$73sd`?f0Pes|oPT8S z4QH~ff6KVrAo5Z5ToWJ|T&bStns8s~_b}17Zr+3w0$D1@OCt1VXR8*Q!@F2@W1ec3 z)lonXey_ERi=Bgwj6XT4$iT(-hh+LuaX zvONAB&}3>#d0IrkNDRNVA{<7po@t94*75QZs_uh*JeFs(`;q{(-J@PXCY)l-jM1*{ zBqisk$zM8KIkBMT0JdaxWtmhgCSPWJ4=W+z3B=i`C74zq5~mB16$*kqZAAZ)Io$+9 zjge%K2s_6|!G1+W%Uc-5)&Qvv|5&iFjGBUJWg~YTta-3aAN_lLJt0`PsSFn%0y3q` z28;VjWP2kukY1%Fp0@xCW(*8J#wSX!ZE4}~OLoa3`tZeXzzvZ{;1OA$ZRJCWR1}~T|K(8!E(Y}C zo%5rGVw9h&YQg~To{4k3JG9k_C~cpZ@aZkzR?*Ya)9 zsS$nKtUO7T!JSLcN0VL7_##n23?;aG>DZ209OC+yRE`K82r$5>wPIg}%jzvOp%>5Q zMGg{aeQ|gXHfYNMYn9m8eK8)%v7#x4Ncgo)JZg%L>9JxdO5IE=Mn=Wysj2GU(pPz| zcf+4^Rc`4m^Sk`{ldFgzrWWP38xJ8o)6>7Aj@_?PMfVD}A$N&@w*QP)v`Z5&*f{<8IW7-{czL zm-a`4()a$}+m|5rc}=~$il{eobS^#?eb-(`_X%I;ywQP16V=#`6N4# z=g$b#ba!H+?i}@fNJDR~Ib5n#sQam{A&?3H0#+k~5}FaOR;#U@NVj{e-A|FHFM>7D zU-e}^(e*{F0-7qLREVql50p9&v_%8deAetkHtH3N#P9yv}5y7QfOR=);d2boVNBxl@nfQF57LqC=#+`}#1KjJ=3} z(gm1Jp{0=*vp5NapU12{u1c=d0`zhb5$wZ{xUI#Yv3#w%QBDcj1fmO9uNo(ZrMO-3 z%55#EjPXx+nM)@BdoI=0Yiv>EN7BeRU$2I%%hWLX>$+Xfa5I`^%cHBH8Im8q-ckWI z#Pn|R*9MUuMe8u0;3V7(W zA4yG7(1BsGzDG)_h%h z_SfOh!}NlsJz@v}l}5)}*ccM)uJhR13`Sw+d6N8$hj_E+lzk)7kRhQ5o;^+1=%Z}i zN!ZiUIE%P(;6t%2xByLE^D}Wx202%r*rrPb<8Cc6JtsHu#zTW{6?Eb@YF;kQe^kXf zMp4mLu(TMHYJh9u$WnZh-kqAAemT`iSd+W`UQjC7TC!RSgw(c;k$cVc`qixQH1VB+ z!taT(Aya8#I2!EZEIud0{CWM_()Vrk)`rhP?Nz78omDld%NL}MKSG^D zEGUpf_$kFI0Q$*nqt%Z+^L;7kM_y<14+MU8>fi?XWA~*RMy`PzSiY@XW;M~6RjsL4Q7Y3 zl$UMAT8r74Rg7F+A~qZs2VQc6!h6;ZQkX>1$`!&)Q`2Q>KO*HZjYSEm!J+|gO!T+4 z_Q1xK%!+l|UVs8`5FM^@1G3p3;f5!mX_Qm*c8txvo>RHa7#-kG^Mah5ge;cF#vci4A7T37>;MP=7(DcoJv=Vx1BPGcg?5EY8*z^H?tbu+Cg|QI#9~tWRCd1s zXigvnz}NNZko(DzWowzTK>nV07m#D&oE+NWZHGALdiVOqdpq04Jxwrf0ZEyHhv!E) z*bhd%rfQ6;zKn%m#5k;}Nc1H#$v~+L9^4-jlYl20%_+iUDsE1<0^jcnLb^nAXKf z!?m|1pFj3=c`)hijd&~&$Z$)=AK4n2Ba91_r;F0@APx%?6;alS<`*P6;p{}Q3KC=k z;QG+8XYn5XRE-I8+~Q2)7pYQmSOEu75kchn0DT|dTHf7MZjBnn#Nc}8g%iMQ7$qb* z!=lKV$!p$KGG9q!|Kt|ra5pJ0S4ep+`2}JHdXax^Z|@5?IvRvw87K~plIyR+WdR~~ zk*jBr)d@!*sHgyxyh0N3h0cbyL@C*l_KJ0Q>?Ibcqay{;8!HNIde?e_65K>xh;WE| zk$cX{vLN&pZ>6%fA`C!FJCqF$!6X7p~Ps>OQV~gW1ERd=w>HN@T_K$>l!ozdX zfO8vnVqg>jA7%sf+w#Rr?myPYqpVZdIL(E>azQ{TeTjEnLn9^QR!EzA^0a@ zvEp=7ikh!0=&zKGj(RM94Z+w?F&@9Y8u`EIKMW1JrsosOI-k*q`b$-vo*q73Ku=uuJD9K!JL~I%2cLfap&j1+83%~!>&L3CQ%FO->XDw9RCKf;eQS~p%ojil zM^)HxkxLn$j*S^D^N$A|3K=B;nG$PWb!{!f1-~*g!aodM?<1MC@{-%P74A*93Mp6P zkw`w6H8w=S(8zyjD+Ff7O)V`|`RmM86p3Ae!V#%B#7yoxK&6jd{-f;k6H!^3rT*~? zTMF<)Qa^k59kgqY9d8=n zVMlSu6p{KRZ!q%o3qv8u z@O--ex8!)<`Qo7ND^y--aDhjDdtJ~vMxa=_rx_lhw=z^#@#m) z=|dr$v%I~H`e>t@P~K%_6cvRGwc?M6bjqG%!srZh$gZb}CbmORuDBa*yq#+8G|^KB_o4I<(r@MFcRDR1hf#M zM0s}2({D#u1Y6+Bkh?FZmfVXj7^DI%Es&5M5aI7QgeT&?2_(QO zmiUg3IFCog2!_Y`>+464sK>_o-odNCyQh&HCxje_4)`^kNJ&Et8Ge3h^)~29p0SVu zN!7#edNufWvx(eI-d%0@`*4l#hOHRVcLcf&xJ0$W@rTQz9|hw|ORZ?Hgk_(T8E1fq z`uS7HcvMtfkaBj#4I^xvX{#r2<0+`b-Ze%&4UL(gI6M0^`v?(Hp)6YT^WW!BpQ`-* zQ4Mp|~wN_Saw7})=x%e$&d^yC;^+x#9(T!M86Wts;fhNghE1E!q4TVLq zQS!fq)55ElXnyChEcc7(6k_oB^e{o22xQSt$X29;nk9VD3EZ>rY@y;r!Gl4+2l*@j z)3I(yOsEPyO(17Ybjku_uWnUpz{B{huMee#$y)f@LJ?Gvtu6VtP%97`C3rpc367yX zCp7zU9?+oMI^e>%PG;!}hqH*Q2$UBRULL&!XHgMLq`(YhEF+SUXAD!vUE`;}+X|jQ zLfd(fH$bNG@VGzXzyaI95;QuuHL9PdC_nSI##kTKiOD6Cg{X4?X+>&i2x+PFR$d>T zS<=y?7z=XN>VO-7d`rT`rxm32cg4B}H=?HwpzUr9^s~3Uuy-d6U}Dr01P;B|;o)4_ zPnQ|>cu6r~%-=CTk?AW@B0&)bkO;3k`i(rdOWgqW_qd#dyT%ui67Q5!tcLM)3k#qh z&bOu*6=vT-0JB%o{|eohK{z!JZKVN&6*1v4KI!|1C)d*&SW)gd+0$`J!oiHi-U?dmGY%07X;Qi1)LU3hsp z{;XphyM7@F6myqBWDPpVu2CBBnRTej%g?l9L(?_zi3F@W(`GBU(}*GNz7m(ls?bM4 zRSr(*prf*bkXhh)gKd4+^yuS;<}&1GyeVFs?#e>Q4+jQYIJ~G9*ulKhK8bJo=yqu> zIq1}&la30crm(#hxhQr!)`E-Q)RRo?aguYX=D+zi?$^2bo$hu@iS!EC!X+I+cu-P; z{8zFwSblnDxwrFGY@D7FYL46e4~S$3!DhusE6Yu+Oa>T0GU-%3H%D;S+Sd*~w%@K0mIM*)%gj2}i z>WAy; zDu7Lu?)a7xMS_YgGrG<5&muNvQyFFw-Q(kqdBy|(>jlX0jcBF-SOyZQlsu)giwm`9 zIkH#{9bi!n6TkMq{0AdO?;=6M8De`rKyK4^R!ZoV9)uvoQ&8!B2*(Y zKzS1u=DP2;o50gZKy=XggOoKM`9UK$H$|4AOG}^+BXoOurr#YAg+J9Pd0#)XhW@dor4EOw{^4yT*^P`Wg>C?Pk3tH9cmnmR)YYO84->(T&fijx z?laZv-3a8@5m`14C4n zLHySVgP)&$TGOC;4#b2!BsL)<)!8M(blFzdRBapuyM`5zU2GuFeWS8*-;SZ3eZf$D z?foi$a$=#k3jqu96vEpmhX%r71P5|SoQG_t73gsRHkdGaSl-^$-d^pjfcP6)USbx7 zh!#dD^XyC&xHV50!#`Zg=|=DFSH%`8c8OhsP@jndxcaj)-TNl@?-iFqPJ zC7dot4w2Z$xID$h{PXWdO0Yj@Lz@-2jA4+S4Ffxhz0tE^#2~QgYcD1VtMv-G_4i1} z;d%qQ#4!VkEoiFFe_8$jPQqX-_t7Toko#W$b7f2rkkh67JHA^3E8>QM8~{G>JMP{W z?lcCz>(agrgLW{D81uE6aB+jemJBX^#wq|=R@OpYD}Wwx4V6@iy*@t)tF66gU!)xB zz?%oT&xAfrWu4eFjeHHOctb4lmjGHr^r>$mi&MCJXNTWfhj1|Z+zz+1gIFLhp||MB zoX$PT?`jq|ijI1=e-8B$OMB0I-NLp55>&#)m?x}&S++VO#7+ocsJ#3SX?x!WXr z-MnL%!ae%Z70n;8!XpUNXSEry4n<;;o&6#v@rmd22*N^+v#&JG%#aAtP~0D_cmuQ2 z4;Q!H5@C|~HJ*C8-CZ`o^Yid}iH|=GS?MOd+6A0F;R(|(r`+oUk3{>s0^&!pFz{Rp3z*4!(Bu|=1%i)?WYU3RPbadQ zpP0B9bQ0WHRFu&3T+na~^*VsBy32+h+=#_QJ{w>YaiuFiw92mEx< zZ|^{M4G$3@9i6(qN8&rS9s?`xTz8jgZ+?oDz0LPPoC_qd41Mo?YjS@4|B<}gw_O|YKur*7N8oq$a^j7Yuw0|$enO;Fi%3ngO)%~`3S?+xT3H3 zs$&VS$}&HXynLVhV;&x6kkPE|?>m6_Mp~?Mmg!Fqb&{*qkC>&vW7Hm;T#M7SKkDk3 zO2)VsSQS|yy*i;@KX!J9P{syB^mol=TNaJw7ryr{0nq>(fs2JlDjtT&t5-`%TRLG7 z*NucepdFjRzCI=fh*j_pLPHvYl?oN@Ijsi0wojBd_kZ@M4~=d z3%EUltXD)r4Vp3ptST=@Tlt7-OWo`l8Y1U1GQb9XT+Wfh`DJ5+ft`qA&Kb zsp)?mn>%=%mYkgBpB1s}NW=K}H4%=tvoq~rLQ+ea1)|fxmVQxXxN+DiA{K)P<49BS zz=JsruX1>}?hYT8ag-wv%*Uj+OpEJ)T+S8L8eB6ni}0}w8JS0R{D2qH^Mat6nnE&I2B|$M3b|EilJail{p~pI!hl5}4jy|O zsj8Za#qC(~zLp98iV>=~PErhPjB;}faI&u{dP)mQN|NV`2QUkQue17dMp~ZJ4o)*tQ}KW@TNTjvi1@A{=l>`FA9J1{*%23+S1=qA|n?hvuR-F#hkuap7?({_}ry>b-+rn?id%7Faqb#UWDIz?AUXtSJQeG#i`B zKI8xKS>_*p3=An6IfT0>z7eXb>GxA?p%>{Clp3@z2NC*zIQVNR+dp8x2nTu=00Mb! z@xA5!hkB-Th;-Jd4EWLA4O8S4XK!f65b4SoBx(@-m)%?y%*yrKl=cogCnj-OO5 z7!)WZj5T$kc3etFTFj{!NWqUqW&TczZ!Q#-$9ba??jY zPYq1zim=01Zh$urDln)=2il_2qL9fZcZo-!yDl4#I|Y3dk^63yMnHUt0kroQRpf=w z&uWQJxlW5u4H07>Nx_CHXds~w%JY~P#{GY32XRFY|MzVSJg=+>u3DQ}fF&Y1x?mGO z*0~<>M>aNyJn-lTS&EgF#5fmZfsxhy@Yxez)EIs6*snhj7p#vQxq9?ZCt@_{YaXzLk`d_P z;SYXQM(MB=Wg9UNJte+@4F_~z+-&tY53ACpA?Qgq7`>OQB^WYIO_tOS=Ln}9^9A`k zuq~j~!i99M0h1)hRf>Fx7c`4I6G5lEY`$I3E`eH6h4ds3q}PP6UXCj*v1Fi+xJGfo zP`xQ20KsvhSoK<6pz{A%Kj-Wxui42FXqw{I*MA;@ls3Ynr;7o?ZJ1pxlm|sCTG~+P zP;e49I}q7e+SZ!w!$)#b9p1|snMh}OBc6RnI?~GvQR=&2YNTVqC>h4q{##pPnp9)h z7yto9mJjpK!7$;ySriZe?9qyK=!^-CD>p9^WB@zo>t3;=v32HV1VHeh*Y5ebDrY(H z5tq)CgftKFPW3ZEKpcn{_aEkJA}X@^-4SVo(!?vfmduB_tCD| zOwtbomTFn080tQd^GQg2*3=bjnMWoUA1b*}s5)YSJR;Csf8G%5ap!$H(yQJV3X2;TgM{j{K zJVG|uL;|zz*A`7^;&6N67mX+ZqZXtyxdzD+A76B9E&1~AU?^M4Yh%4sQm}Q$+Xdu! zE^~4j!$Ji+A&`I;?}?9zp#W-e{{f;o#FRrq(HIzjh!MW9 z1wi4Q3cEaD^B45>XLaPP_|Qdqi9K7G8$`&Bcj``gPU|9Zd3WcAX?mL2&2Z33G^l_i zN#pye;adl`uSmn(5fNC12HpRljFAq>$EUAd7m4znUTjbY`h?_v8?&=W_##yN<9`BE z3By0OUTehF;T=pbCzTI`AOvVieKl!*Z*N`39x`PjB#8tyRtDIb9)XV!Ls4y9gTH^D@!(Ta zA^L6zDD>1Tpa3Tpf@z=Sloa?SN#DPM_MqgXt!sO||D^4AS%;LfA1iu|&3p0;94Ppi zir}eiqZJZ5a${cRu6pLE)~6Oy$KxQcYW#vm+23kZ-{fJ3DMsYg^u~8&yw!Q{{RV1W z2CBcd`V`PQdeb@D37?9;yKQql-(hX4TH0Rm*Tac}gZ>3hixHFTX$kv+KT^qZp|S9m zjD=5CYgR0_Vgzbh#OhD@YOitIipqv8E{Bx9bnM$emrb>7aYxU*Q~E3cB}mUiN_vA@ zww!Wz-7Z3-r0x*Pd8&}T_T22iMqvLHk3{T+L^^@`z~j`&8w75muRkPJlZ%m#3U*^+ z6t%Jy8gvKM%YD}sHHv)jpekPseSFR=s+iS;C$oT9>khfywQHY;@%z|R1A}xte+j?$ zm+Bq`F3G_zd?mqcCgSDH%u&WdnhM3~Nmth*9vii62y8*lFDYTa{&Ou6&O{!^+Bx!$ z3WxA?Ap^LCO_(mm#xrM;_VYsaOug2$Nl9FZ<*sYeH*Uo6jw9E;LY6^fv6o%1VV^cBH2M0&g z%4Bh1Mf=v52BzAlgh`tm3YYQ0v}Vy#70K2KhjZ{qORG1rv6ygVK?FwMaJh9;gr#!y zdAp*hINo{nJ%r&WC2bC2y*BU%PG|Az+Ugwr>-l*udipgrCzc{xMKVnF$q8%kF%GuO zreuMpc{o*7wmWkn9V^x8X780N{LQ|uGtbT85#4&kn3>PW=bA~oTLgiO_j&H2G*hop|RnW^Ri-(4AZ|De6r(%wM z9jH1w`msd!weGoYZ0xVVgvm+PmwF}biZ?~0Kc{i(e3|^%<@7M8Rq{5S_ zNBwkk;X6|TntA1jz{1!D{X)ISFzkcD);xn`46l5u){{V3y=`d^^+FI|^ zH>3|iw-rmy)#4eMqme$&Cfo5v`qa{8wU>RCd?TR!kniQ$Gc{Bl&me$5)KD9d(maGM z`S^5-33i>+^h-SMl4~+CC9N|V8@?{jY?OReN$1h++wV}Qf%$sgn~8}rTgQ%kqr-z8 z6XTJ=$(-Gtr1LFJ7RjR;IsE2#(*9zogq?k6PtTXa!zzCVb<~uEm#f3UOXxSzhtx?L z@Ks4aq@Q{Elt59@+pot*!e7*-L(g?5b$+cLoKksWp~0XPBM~Z+hKYWs+z?*UW>m!V zWM(gV=cflvbo7};m}e4O++o2!Asw9P96gyF{$tuNa75DnK7Ae&U5Jtr{P?U5??ZKf`{R%^#l~b-q)ZclpLAVS_4DxcBAxV;qYm$7 z49vG*is*$5%?Pwi>DDuqe}3J74MuMI>ZRRNy@^>C)>^n(du6VY59tGni;vlx*RN_8_uN}I(j2DF0PT7XXLky>9v|st!goH*E;i0)m zroY|CQ-8~?-Sr31;t^S6ppUwyP+U%UV;;XB6~%69c4f|ODv2RHO5d0(I#RvlOrC~H zZ6-j0Eet}M5&?`3R^X9OE=)~kvhqkF5V^L7cWtW^w>*!7?nZ^kUNJXgiKFMo++ zqEcf~&?wdNtvmV)X=!a#@l)cIn3&zBCe72p$P@O|MGb1cqPkKXRgQOec*!x<4Gr(r zRg-$;@$RsjfN`Ocm+=UOa_sE-*C5{S6}@FtiDcQi2^HoAr{*(v%aC!DV-Kzg4~?r^ zubGF(FMKvU1;ff`@P)6Mn+LJMD_IjyLDe-jNAPYw-`Aq4<)6*+U-BFBq{SY85BI!F z-i4gML7~KB@i0;Mbvi(nt{~JY7T9TnSot$0Kr{6!HWU9pIO|n>|D^1Dc}{lN>PON| z4o)F@V0iO!uw6t^=P^eQvp_1+N6Zd;aHe1f+eKtz1>?u`l$ADe5~;Bw!54x z{rX`ceKRHrH*Yc*>b_`ayARvM?tPeg5S5t$%LPfBRaUN6z>fzvhSqTJ!!v?N$XYNC z+<;4H34ECRC>ABGAbfe?+t}+Ywd+rqEKAzxiy@n?5IFLYlH;Z4-bzeeuz08y6Jrqa zTs5+qkdEKju+av~H++`R)K63xy0l`}{?{GjMD)va-b-B49vCI@)W*T-u(gCA!k!8# z{Mk9nfUlOq(tmc}`YHaV@z7l@BvZzmqx>Q;V^oX+%(V&XYN=Yu~rRkKf}#O9e|O8l+Nj8GCti zJ9n=O1`{>-COq!0(_tUU=F<|w!>g{|Cenu)*2kFLx6kE5AzjYao(kiofUk3Ff0h5x zodGNrY8DzXxlKB9Yfpu^Zh2v|kh3^O{+QiClpI~{6yIATTam@JX&EH&dirOuO{p4+ zb93O$Dpb#07i`&s3Jg|UNTZs&Fr)OB?+)JJM8ZDmG3iumYhixgkh?e3$VSu~U$GOu z(PbmjSP1!O{Ru|}H8`k4M0n6|!>H(I+1c*^BdxqJnnb%>GN7;DLGBrkw3xK=#22$- zqVBNeCHGV^W8}kNsqV+5eItAB9rH6SHrFS^LeZxH5e1=3utA|P(NuuO0yO)KNIPzf zKfJvSy9*>PSK!`n_*SrS+~oo9j}Q`qzz4Ka>~M=NuW(>S}B)m(E}n4)o+pZ}zxX(uLDG)E4n zfJ~KWWK~vbO7gL#aedoS==(NCvbs;81exs@_gvdDcwWMPvO+CKj6?Zz@MOuPMR*ua zQ7qcvyP!ib{x`hl*=h3xS2YrEL^Uzgq&k^afOUk*MPmQlKYdC$S(ZuY(ViK*ba-|+ zc&&u;#!L9hKflgiy>)y=!(F5Ur7QZ|f$c34*rfjH^%x$wL#zY;6p72G0=2?NYQnJE z^>~==7~^RypUEshim+J(2# zU@-GZY2M_|KUG)7!+wvB5-35h^;FPaq#FzY+8!P=0pl=Elj@K^${fr{hldlFGM(#d zK}j(D=v`FQ&p$wf1(4zTgaPWw=31Vp2=@7C@u!;Bt2!pNnw(Out}*LhU*wJWwJvXd zw}vgQMLb;uGNN;+CFYl3?I$RWWWBwv9xqq$`i9CHumBM@G;TH zZr+4_7tD`&zp15a2cK*Q%dwRQlfB6DkywU)+$Hu&1E6%r%sinj%mO}wzTy_^EDRy= z9wI>|TkiJj6ish?<*<-%qThZz-rMh381Fd+ZX?bFn(G)`OU*~P|O6m6&UjM3x z(=C!%l~Oj2?L_#2^Ipq-f-|{31YSVL4MNa)^76ECFd*x>&e=0m6I`c4V(Xp93>@`v zFx=_IyAst|iU?9rq^pF4fJe_ObYH~uAhfMS?TP==(@l;@jgqsZ$2~m|ZAwZ2wKn(x zKtqM?t2@SL;;Q=6eJz9}@l6e>2|)Z}Wi=5;x^dL(_9MwgO*zeX zXv7;(AC%!d93bQz8ziJ(W1vPOls5oym3$eD#4p~oi!4T_2JNBz3NDI!K3xC7!DkC= z_ts@GPs~?f9)SxPy_qT(ij<7EC;?^#HjG(>ss}$E=|%Y|A2>~x^s%>yaI=t#Nl5DO zi*dtx~PFU105`P#i{%HTztZ0^M681zv2a*!k`8DkDBPkc0 z@kmDlOsWo!ubRw+4$wonx$F%wtYcFqc^}hDJ!^n?;C`hK8c6R6Oik$|#wb%U*V1-_ zXiq`Ko1e~>#cLjRyr#nSQ!{b15;sR3QIjg4v+V?1J-WSZZvLByjMSC{xqsDb6f~|b z?`>c_AF%p^AO7z(hO9SEqy`7%Y;W##n}en@noJU=lP8lEe_1EfQyb98%Frw;oR&uqcP}&an;%pn=iXCns}ZPGvGx1cjX6 z$l9Dz7fJTtZ$v=7th35NlQb5Fzj&;>}(kwI(J`M|0@QQPwI2qQYAR@52#a~1z zgFLp$doHVr%0*2Mw-$Gz4nHxM$uZLwv9k0(Ol9h5wYmg7s^hFe+w!~r^#YVrnYUmD z`H8+aQitEqq?PSh`#z3rL9V!BPeU7e_``~;+ln>}zQF^AuKJW<`B5&@i!Z4k8{?An z#+`Y|4gYCEo2tsLn3H{x3mfs3W}y}3_?K^i+}Ae@Zq)IG{I@y2u=B1jjlViaL}%jZ zjqBl{QvdN2eJt}WmYn~vRSh(Q2-p@rHyT>iSBE@FDC^-Xwf4r zOoU5gP)m@3Sn~3MC`D9yJNPy)B4b7;z-LF;bBC>E6=}y7S||&J&C}Ci*`tX%JCd#< z!o&s8L_rDdNi%FEN`HHD1=E*-sXr!UDC%)iQXS5$UMN~W5rf>qR2IQwXj|prVqajr z{rkRFe{4-NAFWFN?j#pRR8E+8`4XQ(=u$a7s4*h3~&kwh$ zl!mgxht?Rw^3hEvWPL6rMHnz;ct7UNs*M#6pGXK!R*FIb2%CfCQyeKAVF1e|9&bCE z3&sZkNDvv&gyLfb6?M7z8y-sc0<*fSaNbV|Z1A3e0O?~U%U@2B3pUx8+p(WGzr8Gx z#uU4IMTKIc^%0N9qBX!@139PvR7T9E#?Kw!1efVB|LpMoEAOrj1EO5L`h;1qDB}i* zO=B}K!Nt*I$76@nJb}2LN`RGK7^z04bSox1MdAQz5K))Gd|?sKrGyD{@R>GR=-Ebd zp}ju(!VOYW&1DhNQP(&M3d^SAONA>d3SM$7=+0WigWD1^={Hwkn}MsVnlCGV!EIuY zGA=lyBC75;boZIJFH!{Tm5#)7Ujy3R86`057x^GTFwwjq;bH1`lZI*t_VtJn)63*f zUY7?Fd;r86Y|y0@pRRL|Rr&gL!+7j26}j!l+@3HbMutZ23YQ+AX*WE&U3aShd5pG= z&>f7HaHv-rr}^gdg~il#y99`v6r znh*&6es?iI+0mUA10!eac?o65%X-jrE=vVxotmOh_d}uaHfyCSrW2LZ<)Rv@UB%b& z&4G9AX+6`d<$RH!r!c+T{poNH>~9P`m>4D#;3idUaOrf()-bSxi+%##=7{bMGj_bp zu~I8>pSVRs784z)qx?q=jm()(8XYu6#bay2ahkyi8~)sc5LiNqvlG=2UM!}|hosKn zZ)D^_F)@{wbJS@9XJJFsC_=<}#^NJp2XeyKO*bfhK>a(XEU@D=| zLY|gW297aoLq(-cDpq1e@M%o z`Qn9zCO)hPG(KOC92uKf`>pX35nJHTSFa$3!({cgXL07=M<5Y7{~%Qk{gjL^VI095 zMw=kTA|A4_Z(s%sS#*Q&&B;aeEVKhsAa~5hr&1UKFa-J;U-q3SId^a0E-@({$OZ4~ zNS&K*qYV{4l>la${_fYc_&O5O`4V@l<>1DWt}X>H_-8SqtBQ=LVW4)wp$d;LI!*%sfi^K|2 zNzaBdJ>R5#asbO)qy$OG#6}wOll1JkStjjQ!cXU)G_bybmRxUpeqckT$QF3OGhjNf zB%z{n_kl#iBTLbHnQ~jA-)|0uGVD1DB)IiMW+p5Gl(6wuziu%>4CbMKYN%#ea0Bv- z;npuEhjgQV`{gBXxc8U|_v2yUnK>s*U_5j@1Bzy)rUxD7&`-ZQ*$#~wuZr=Ea|^tJ z{RIDE^d*)0U&nYbO8AB{dlTKcvmV7wdIP_3#rkMxDpXmvv#9y=ozkVv?=Xt|2=FwY zAoYg&SD(tyfqq?y!i(!HFT{;5EXYk4kb@&hapCPyk3JBg2%{9d*kS)EY;LC5Z$jdB z=TmYrD@YyiL%J``Xr7=*YbhxYqi3WT-&V1+w5X`OAY(Oc95x($ATP_KARKpa2?x4G zp3}Fn1|)ypV-m2k;u=)|kKy+6VrK{Wguls5`@OZGf-)+d0jSxptASiQ=XG7z4cA*S zqUDf4@e7BW?0rm%xpVR*h)ou#SdWl>wmk%M-Fl+@i~QUn4|)4Aa`XGKj7qB?OHWmbOKa3crJ z!Npp(`0JDaj=|2PhcwYqBvsQXpPcR%G-dzh;?DSZl_7&q23lyBmX<5>r}NRzRWk$; zx1XdtS`WOl&s{)==nf7B7d?&4Cu?Ip?x4!&m{w_yZ@XAe9Y9Ip$}UL$yED6SJ@H-W zLr*gOR$tlM0?d$pY@+&Hn0M}8wLUw;eYf212agZ{=-0jnoYnG_g^eY3@(ARVmeU1= zAT3ZMfO%KtOZ3?57TGG(5*7dGr$k-8OvO&DK!^?M1MA|~Fu^Ms$PLcD$HeFl06F0g zu~bNe<`Y3)4l;x?fTC#Nz})X)%@W%6_7+=)Drf}UUf^E;d*Df9&dc?aAI^((ILHs; z|2+Emvo9&ymxs4s`R>R;;k;vmIx^s5C8dCQxvo)6%xIRNsC_jkVEm7&l18{tb-B10 zy&`TAr7y5Zbnjpa*VdLT)Zzr(yC;aHgz`&ep_13Rdv!&ELC(&r-waNJL65!^wQS{k z1vEdo4mcZ3$dc{-`~ za>d37s*zzPh=_v7>@m8KCP9N5&zI&;O87{@Kx!M7rC#LjP7>!&FPn42_67vrkMS=u zq5|kXOicIE!D0$zF?|e5NAHgY*OW@<9Ku1v?pHIlIA?B+>JaXE9B8oN`qSVb(~@@y zeO;n+{SSQumPalLJGil2ez+Jw%4ufn97pZ!p&GrC4tkcKlg2H^(!u~1vaZn3vy+!E zUT}NC>;%NQGa^-&QdQJI2xwe3TL$V2UL!@~(6n5;`;hk9!WhYo>tSp#Z4rD_Hngl9 zkRQ9{o%QmS+}};E^tobYmcTqFWXeQvf4*fiFO%hp!r9vghx6H4E}AIAZ_qB#)5?Cb zlb0(Fc(CGBIsp5I!asETgvVsIKQ~D%Jl_p}Q(`xoYh{C}&-ac1p+*pOIDh^hV{aMN z^&7MglF|(l(jeU+(j`*T5`wf6(k0#9-AF4bf`lSSO9&_+N_R*}qcrS%f6xEfbN0>d zzT&{)Q+Lcf9mp*r&<#dx zbVl&ys1}?*JY7h-q!=6wZGVdksGHCrFEh&ZiT0bWjw>+k?g+oF;_CxeYFQF*RG>6B zN3Lx!JZLQYuuHf?yHj5`9E{eMnPx9$bW~j^GbZry7C`Jh+-rc^>q^hPhD}xhPyxrSM@f`(Uq7=kCMKa>n;|G!UxCjnr1OeIK89ku|XI!oF88M1!3F255V!&Waro$n7W~p;F?kb&b7a0JUG8f!upYHoD&!bQ z|NRAqf+?e*osWl|6xK*ce)USUO?WCPHm=i5#s>>WWhY(;K0+9&(gDs4kO4azvSeP4 zii}2`@RO13>}+40`sm`3pR~ICpemO%-4%gk7)U$~GzmZ}kE)vD@)`{=foyl8-ctZx zPtsxIvwr`22ufF>n}C^fi)9S32=@W0xB^Q$Hyamye*SamIq@0>euv++1i>s(H6g;V zTn9kE(y*A=np{GDz&blWNx>K#qJyE2V8%p5tAe_^>?<)!Xy6CkNJ4G0wIjOOw)PZ9 z5G}V%DKw1K82O;sq>~wiaex5;(3QByYpGad&5Nt@sYaahXsm2TCPq={f(7qLII&G6 zkW1eCrpi~S89LaE5{|~C=~VG&l|D_)QY!RYXgl*XOksZPE}v%SJ~jsT?c8%`^fr#% zZBmb%`p@XGFcXc|5wWw$EIc4!@G&kHL$WC=)x7%gXhcn8kd%_hk_1w}`(A~4*`1K; zR_Xhw>B4Vu3l+D!TjG(Dd;=O{kr1K*m&Dg-r8ZCtPhI|{Z%$2{!Oq8+5{ooM_kj!z zt)|9@9W$%?ZCLMmsE3uphf_e@tXL=!3;%?Nbo5H&AhW8oH;q2`Gfg5G$~2>*(XcUY zAx2*Z1kQzkYt`yN3v=h!VTV_QY{DF<}6{X-&YAIixEX8Le9HOAW7f(WqHzB{uXe z9MDukY%)jF{^xQxFdXm3-o&lLfjZk^S}^@E?#1?R{+_kRY8S2clZtTGX+Yc6to(x2@d;upU1>R)yaZEBRvp7@wnIy4GDs=-)J={ z_YMk=T4jM9-NwL;C!C5lGr&FYI_qslQdJPU(J zJVU2qr2Sc6@hUPHvr3P>2m$I0c3AYc&u9tc5$gauQ?qJ)FI%-V%>{;|(sRc`j*MvT zHvfOn5GY7Egp0ERs0D}w7&|{8Ij%JY7^6?XmGOE%SzCth^z<8@tK91-<`sKsQYKi#ZXdsO%KZyd=GNB_y z8_Gy`sZWb~e!tC;1`&%>0$zai9E)Lt;CWIs`9z`s%K-0yv*MD654E4+sHks4pu?gv z@k89!s~t=eQv>Rw$Z$^6fNW!(C>z=N_Iz$?cxvNAB=8hkbLk^fR+ItjWug$3` zlljFMi-pjT-*G>M2s2sW?TL>TgaU+9lHpPFG7tzt6+`>jCq5Rid$1Y$Q61zPRF$#O zZ!KJV0HyG_7ntXD5*`Eo%&1*@_ESuW;11!8q( z>}*BrHP|VmA-71rDb|LBC`BT;PNUw9s3>i3D0+}LHXg|Gu*KH({kJcJ4H;Q!Q7qY% z+dHGczL5U?>yj7|l|e4sG4jEIJ^C?H(tY8G0eutmuDe8Y_kdW!f+bV$ZO#STWYN92 zydAnA&@m3Urmz*?z`B4XhZ+R#3RJ(4SqKP6xuJnJUtFA7X&te0x~;i{O+7?e5BfrS zofrzH`yz!M*#eh`~Gx(c=W_LRmRVXZU-u&xs@0 z6iQ%6jliHV!V-S>`Z;{TFUEHhfYrI40aN2S4pdl{--9m8{0Z>_iH@*GjLn0%Jmkwh z{wl<>MpX}gn#pvIB*j5M-1=#>S7As;_e~rbE`FEyKD{`6=+jataCB}#xFKZ-S_nj_ z*(hicmIATd{&WD&F=PS~N2d%039@Yf-;-D&i^C2B%1|%*=9_uHeZ=_svtLe(1DHU1 zga|(!$bwWauYD9-I5cNlJTPniaQjE&ce{|F!e0Zs%JR%DkVp%r5!bF1iXLUN_1FpF zph!cE+g&iO=BZe~(}usV{fhSO4;L^?h}WK@ghDUizuB=ebFwLQ_U7^UZ>Pc)hRSg~ zqCyO+$(FAl?m3!AG_lR!;P6!CFbFJ04`+=`oPuRs zT$J9cs=Xc|C#4Z;NY;&5B(t+I7Qg8^K0jj~+GcyekhV9|*Ci(J-nZ)A3jADITsRK) z;tPj#c6j$c2y`k2MR4yjGSc|thcO^1LK3`*+PKZenEdb#E@THG_eoj8SiHtlq1WB& z?KY6*L0B9T;)VuXNs>mPTW`i1@y*V6) zM!MWj9A|5!|i{v0p;pbp9OaLBDv9m*FU{c3{`_iLD0y-~PVgZ5} zKX9CcGLJ^*4)r8v#ODjw$RB5Hu(AO0ohtC#Q^boRF={vGpwW&%WDU?yZ=c<5ivzC7=#`Z?pLWmBSLiqvNTpmT@sru6d5O*pOj;+>4^eX*x~} zE$yLzL7ci~4;h)wf9D>>tYbE8#B^0j@mQb=ANK+)l=bAJdTCTt)NP!}oulE9i5#CT6Mk`SLKPRcXv~$vuHu1SQ#38HwT8|Tqew>!|$GQb^=Sr z=;)KSA4{H;biSR5e=I2pDroZbgioGmG`%An&9e~5cHV0}vG|*FPc!$M^Tn0d3unR$ z6y$Pa9uWe%TOBVW0n>HZ_ALI}DM#HmDI=+hi78A_;1}Zy0?pm!fpktKmQ(~_eCu{a ztNFe=m{Peb`@rRLA(;pl8)e{RH@tIuZTg|S0klb4TK1hst(Oay7Rny6YV3Ne)3xrg za(b|`0bNx@s7;#kw{H{8sj0jnu7Yx%)|2^I;xZC9Z1nFM>dWo7FkC2Qdakd)ovitj z63rQh1O;F0DgJQm^Ec$C<=_let5NjwqbC1e&{tK{hFvh6S%>eU23t7}3yt}XEMe`l zKK#ob(@S*QcUDIa8MVrFIM_%TSy)*QNg!xVKM;@>>km$M!sy5ARg*#}BfO3cJjeI%Myx}d^k?c;l}6L_UhJ=H>v z&&~Nvd(S_InL@oPqWE4UCC#c|a1lbGKHqm&)Tj-T!&=at-O-9*W4-+h z?|SFcdJ_~`89aESy>u0Ly?)wXlGtVOo@@FU6$QnY_N$qbeUQv#%vNLe(%j&T+9nR~wgoD$bRdWSKzyQP~PNyf@BA|sRXi(y>^WvH* zklTau{_pipTFl}u3kADvv9vVOB}9MUw!hU*+{{EspVxsI zUpLDbNMtJE*p>C{Dhi}x7XfFJ>$^`^zB|v7Ff|7Cxu@}ie z1cU@8JKt*=Yv^0J%kc)~ablb~vuR|p8O7QyNnuB$P~EBl=fw_WKalV;Rw7)_fg)fs z5=^Dr2t{M5o3r7SKT}ed*FVuO75i9@GiH)V*Y7jgKdwJrY;*kFofLVo=hQhIcK6pg1sDva%|y;}9YJV+<{ywWNB z#e%^PR$SP`cDP*8qR#{Q7jvL_J_+L13JSgZE!{Ostl#Wh-hM!F>ACzJ{FUy@1%CdQ z?r3IOzgj%dBI-hHZ+S-KaJf#kTa1SCglK-CQQfO3eXd0<=|k1N=eE>$a<63A7FY^G z=E5K1(S0W#&lI!Co_?_J02TMdJ^wvl_7kqpPGAJyXjkm-I0fFRu6FP`TPry==1REn zdrH!abBK%-^PKq3h4JY~@?$USK`|YD@qN&822Q|K?Nh;0^8@+&Rj*&8!6zqbYHCJh zdeC$RX677hkH5sUxrc!E$w!$t#QTUvNI^yQ-{Saf^)F~XaG!a; zM-p%W?#8_bM6XxXhlJ;=cGs{WDi z<(DtrU>qIYtS9x}Nclkrs)N@-kLe0%12QrzFC$h?MsY*KvB9U%!t^&VAPD81r6cr% zm1nJ|eJ756PoRo%TUcwo!IrwBO2Ks`v<{2T)-0tyMe z?W+l_r!$?ZL&n&)Bh=*}e;3V3+O%4`=&nrks>Y+J^(889gx}}G0ZyEo2zpHW85Mb) zV;{-3gLo&oBF!af)7`H6M5&;FDoU)L?Gpipc&fR^wXAHsF7FqZ1QNA){{H?=&P#Fw zhFveiquy0iRdovvON6#bkzWr7;VgI^Bde}&GZ?GYMIa4r!I@f9yt#_la#fat#n6)# z&-M#$(5*XrB`^Q+&!{3@Po(svIknVm=-!K;r%P~dP{?+1ix{fEK8N4>(_V(%Q{!GV zuN9J!VRgAo-Y&zKjD++~T;6>Q?D3d}bo_@8!k524VjMK8+12{4NJdqfER-m-$scFt zxXhXdKht0}6#iAz&_LP_T4%Sf@erVhWp02rDUb!J&vF-;DEZRx>C=Nx!~Xczu*NV_ z1y2_Oz38m|8Y<~eFeno)4o*A^^uKr5^4%<5As%EI$wBh&1`nFnyNV>(krTD*+BQ-l z=E_`v3^W17!+2XS97LX4Jyq&L3yM;Seyoe%bhl&54cW=}=^c=K8=afOLy~y=NZwP` z+?=89?3)uKY0Ogi1Ig1v-;dpvJWrHpk%C~e=h;;f9>sNUQuh7ZIavZbzp=Mxt#86; z_~FUF5CN4G=FhPG9>6V3<`?4koSYPODpb$Hagmf|gU}YOo$R{awGo~A)t`<;N8I_X$N zT5p0l1*YW#k(95iU9m6TiOMr86Mt}8NEjHv{xcJZB0W8h*{)u{Ve&g?LAa)8&nlFH z>Tt1}E`U0PnITz;>n*F1eiUYwDUQ@}5dp|z{@E1^y|KQqVwN{AdN6ZOSxZKn^q_lZ zXVU+Y8fj7EdR2okw&(V)!MiJ8MDbq?*<;!fC&R6Si*U(80yl!FsOK&YiR{GD z787=v`+>Vo548zzx88Xag#u5f`!g9gr)UytQqu<_-ObL!J&mzZj*-mDHja+H%`dl| zPn`(@el*=8>HYlhVr~MAMm%{swowyb5COmg!iO&A3!BpmMu|}y)hWzaiBjimT(@yd zraY;oo7(Zr(``rV=NkPhO+D3`?jN!R@T zZROSaSfps8(~`&NkO4U>(8Yf-U&ZLtvYcX{9vf*)xEjv2#dn9POPcS$CpX6J=bFht z{EwU$-(sS)xq-K|1|oxh_C}$xnYW5Y%SXq@KkO4a?+|p{W1X-(IuXx(R^mMoAO*Hw zmQN&d?3!L(e=^h01s5rVdFj{R#wI^+itUN}g|)SOYj<%2cRw*a4OE|^BA=sDPASyk zcyHdVfQz57T;7cWYh=|wHmpilbD)}nnz|>0`zeyyQd>B$S7xI9b%M2<{qb*R<&YkW z&Pv@X=d(k?f8#YF&Y=a?a-=RjdU2`BSdSk|+0T67UZdY@w7xrFJaw7(-xoD}_`oPF zeX~XTE$5C&E+P8oY0cOpeFb_0~pfsh@SZjZ3Fg`J{0!~_dYikRhwuT?M z8&p>(0DEA`hFZ{PC)b2dyK00t3T|>byDk+;;J1hh=yF>vA-2at#B-PW-|k%O<1%&b zORgH-N9noUOC1k@dj|l$y1qV0gFhDr;BIILjn9m~b+a*rzHrzut|IlwVH;sFX*$i4 zP6P~q7QuxBvMnulKz3Anz)SdY2qa|@;`H{jO+ns7r4+O-1J3qT_$(jRd9sKrXh3?-k zfp6oqDE`PJElmgE&e&Lh(WmIlrVzN*x2$}8v%Ulx&^q~0 zUJff)=~Z_D!qn2&$H-G>^%QZ(nB4I|3bGasdM~$>32>D4dOrKL!^ z-_7;7Usha8hp!O7@$+X>!;JGIlD`= zgsm_d2(@5iV`HzibbamK`X#~Sf`UZwkaJJk10+Gsd=(}M2^1FUr{a#*Bl#C=xwZsO z6aZ17zF|>S`)1J{fp-caMoOKPW%qj8Jk`gU_*7PnWss|u=emuWBx#o@SJWXse}FF} zEL{Bgvk?q0Pepb0LwZ8__OGX7?csy#z>J*Jtbeh*+oGa%kmX5p+sVLGl*j zGZcE?aW*Z|_Yi6d-Md#*T+9fgIx{gcf|O`YjCz{{O}W|pU^I+vF{YYgER@zp$oBHI zPg+5UYAvS$7eb>~QvOuDZKsSZEG%`7rZGzRqNy^4zibbN1cw*r_5$uh(7ANrm88VH ziXS^4;w6DE6U3(6q4u`bLLhpZ_jAC370VMx{%lpR%Y(jyFC-d^1vh5}2S)`reoH+C zuiE1tYJDk_`pfS3=NVn-#C8vee0M2euYJ&D1M1b~$Szzi$JC8k*-#{`?=Q>87eZ8* zophJTQU}o*iwKR?TDNs|=G3omCy@eIlNI+N5JQH*81M~dWOrSU+aDU2fe27G^GEw=8`SE!A_D$*RoJ+RDK$wAq_RGQcu;KOY#YOt!(Q>Z$BYF4k-^Va(yIY5Z^+U}bH&*$D z`9jk6_e0R3*iZ2Mj7oPg*|$GvdQEJ4HlPpQxXvQc>f+yy*S{%iWF#08oB{*GsdqHQ zpBg3U+lGrLutI_o67a!F&~+3&h}=g+ZBhliod2?f?I(ls#6644%P~P&8-!}>dLMZ9 zHa^Hga-4jz>r=Df7VN7!7zSFVpnTm;ARX677f6lJr5**9b~0a8j}{sPq=Nky2`rJS zs_MSm2i5Ry^VKy<$8#x_BxX!~-qrxqkQ1%JM0(68^;UTEpuD_1eEny5KYQ5k7CDbm zf6To~K+)o!yI*>tnp{K#vu0w@f8TO>`g&PSdgks~K%i*dl>NrWMh9r^y7(Q$ntlO_ zC5LSNcJykRAQoD|*^qUu!;G-R(U72s|9JygV29J6Wm4hi=Xm833yG__T%Tbd{(6?m zmy5G_a&hphCg9!!tsip;=yH^QviQjKocR3W0^&wc`(WF~*#e30tN#`;Led)ppL+4z zynwc;X<`jTv}|LQTBKRs?rql*6YJq6<%IG;EnKd$N_QTt^a+x(TXy~amU{qkQ`h$2 z<%@-z02Njy(eeC@jN6FVu@@0UULIz)Keu>}@4av_ABli(m7m9)e5%=$%m1l%*z?E; zWPgEm<&DV@DMF1eadkX~h!kl9FAu_94%8}z7P!yO&Q8C3wxQNc#99~lXYhJtW<#h| z(*@VA1>L#W)}Py-evPE#U1nC7Zf0hN1Y|Nh@wgZf*Dh2j)=@f2aZtXwD!_k#)ikRTeQoBctX^!52FEg`qIv2lD^K>*dw zKEX{;`}KCa$&;g1pYMXX-w?wV>bCxU$?5vH6Cozr^XSms1i0G_8xN2C-$`bl%2)Tf zHZlnx>iCqInLLg@S|4^xe38u$SAsBfJUpi5v|IY}0SLnwoMfe`+(j^3AU2PnBS6a; zhAkUmelO1oZbU2nukTm?<5rUCIVDw5J(}BUyV`LAoXqvOC`A<;2j`$d!{64N&d=and1jy)#qZg|{ zj+I0?gD74hG|_LB385|(4oe9Qc5z+7Q|6RZiT0OHS}$MTqxJp65A5Q?v%?Mn=RcGD zX&E`A)bT~O_QV#ho8-Z;F;4RK6xGxyAv_hNxI4%F^*M3-`LCK1ODZuF zv;XQ4R0h%W`hu&QDeU_7KUIMOl2jdAek;&55i6)#wQQutEa~+9a_R}iz}CuR8`?RRV$^# z&!)U4yjGIK+1anwkNooYT%}f_F{jv%Q&v!5Q>Q-2i1#>PGckJs0q%#_Xl>{j!;ndZC16aP)W z{KJO_u&qs)3EXAIYi?qG{xngQ&{h2yYl){Po2;7Jlzts>0!Yw6Bj0E%HhN|TXCue65G#F#tG3I2C z=qy|*qu6vGX|&_IBW#a3BZBS_`y$8h@GC2q$>%In2(o1jS&3=mi`gWOM;`d?cVa*T zZyhfonz(0u2?(|MTllK$cf4Du{NLH<7}a|d7+j6C1lpiZ+((9046AN4yi@RDh) zOvC!mRJUR;AyOZZ*udTnLvyc`r z-F?IA?cMck%jT7+Tg1Z6^~smMzN5T7Ki2+dF<%<3|NWUd-diYGxZ3q(^e!Z+g;#uT zz|x{2@c1L0%nN3o{xq}kQb}CutnUXatn!C4tVOS1e^KW+hY*zf!0u+0?ZYb@m_Vc=1P4X#;y%eiMR`Ho&r4|yG= z(OkJrq!JqZqCM|@In%_#kiWW` z|M_B9JelHMVLG5%#NJm(q>V3qL4;$^ua>G+qVOJ^=KJ?EvIfoW>;a(6OA>JuIy}Dg z^H^+~xrfhr>(+v4bHe6Igc*fc0W8um1umOM1A~K8b(T1=z#i)AiXZS3+m()%D7r0w z!AhW&q#9qrp3Vm~>y#wI;W(+Uvu(B{DKEyAO|)@CdB_5G&n-wk>BlcGc0OR7YDTT| z*fI1u-jG#M!LF=Su&@7M+8*$wx3|u5uDO<0pO98{Y<13a;Vvg<=(Zp7yIKG8`Sq`* z%I%MP{Eim+d*djFQtm!Na9df5oR}Ef6E%t{%n<~1j;6khOQUQtUA5-jPg*>xC%JC_ zTpB5Qp!P4w(Xb`m&PUH%W>3MQDP-`~)y2tUBP07gU&Vo3VYO8LXT6B^b{P=(B#|4F zfG+ToKZeomZ@>Mn$vIh!<4>$vU0l@6%7f51+gVcVkvQZ$wH7@wnDI|WGG0js=EJ5D zv>M8ax|k6a6{VK)%Yuj}e5Wa-AF&hl-Wh!j!|HBw=nL>6FR-h%`TpzaiA(i^BGY!A z_nG5gLC@~l_IPz1r65Z`M&v$gW+JU*&gG?_mV8-g-OFt~d^#!BUEPwi`2mS$ozv}J zjvSVh7l%8#xmlyU;isn}x4E7W77^i06ORdy)W5VL_&Ps_732rs^0o zH+Q_C_4lZ)&opSp6W#z7H|Hf2o+=RhK0tp&=|)ed(NX!QgyI%uxV6{m+?(0Wmx2~w zWK06DUaIFyP%b6o$SLcNdl?!Uj>uCxmNaM-NFhPMAojM8EG!Y$Y!K`rft4+nOZ#o9 zwpI(K1M-1CeJi{fZrfYmB&a2HveAZK0_?Z=Ok znU#%vr}+b~k04c=dWR)(`G7z_xn%`uREqOJNmxz$`>XZ&hn%NNJ=iSj)V<)~IYM@( z`FnbLUYC_kOqpTb-`w0>ZXOM0=jB}wCpRf{T9}`m=S?^LX4zh9nGJgFYDAv z4+qa4HA&u!9vYIm1b{<~b(ba!%voxFKJDm0nr^vv z*VgqI`|%^}_tx{z|EBHI(v4S}H&?vvr}T|lT*%+AjW;R?6is~64rn-i6yRE%#QsGbsosUgsig~jJtA#;&-gQizlzKP4#ak^=E zsSRV+*&od)J--r{DB%6h^PDFNPZ#4W(?3*J{cEN)&y(Qan1^Ce+EO{%VlBbMf?MLbXY%>zyLj=1494r<3+`&6 z4O`dFs{PB;KSVWk)BEUd@De2sG2NVADf~`AHEQ?5V;$g>2_a3)g{hBg5{(31$%E6C zb|RJ+7^PM{Avw3?MQS7)`xtBrV4M#DW5p=ao{4(SO62|dJVza{E~t)TtP`JhDiVRe zqtPBv;Rm7k=i?ubl4_r3Y__RBTi;#fV5G8I-GV_)2EnGDP4XLU8`3^t0F+om^ND+l}W zPJW?ned?|~=QOX_#2!VD$<|?Q`lnF%uL!A*E#7ZGi=X7%Ec|Jd`Ey)s>4!w4Kcj4) z{KQK{s0xutAKv}dAAu9HR{kFnNXQ4YETiXnSg$V1QrwQ*0fU|abHJT)R~+l!-vnl5 zbK@J#L~t3|*+iLh%vf;IN6qa@GbjNoZ)k8GFt>^zk7s5#C$-^5f+z z4>6@5?%I!uDgEK}p?maiNb8s%{r-j+5xj~|Z6vg*^sf-+QIXC+?dIg>n(pI*>pj%_ zdut;X1#WU<2R34@EglTw;-P>3v;iaGnAxRrsGMCtFJy^osg zc6B0FcYfQ<^I$VaJ65Xfg?U9J(#RPa64UwZBRjSJ)q5QYEwF5Tmvtxdo%`^y(2`4y znF%q)SaR<>{hs&TTWeXk;(1&eSH*Ol0LR051J53PaG1GWM1~M`*)HO_e?{h5Jd6Z5n@AdD- zkkU?td+?=nlZIt0-8GKgHtOpWQZw<{ybB!ucN)*x&c72HSU$6SxOz3$DHEnQtYGno zsNT>U{cIZ#n<*j6`Q)alr`L-}-CKQs^_BahUn;|ca}3GdlM90e8zP+BT!lad$(4|X zr7HOdp~yZaqD`Xz`SaadPNB>~?o+@$h^^*1_maHcN)06h_3KB+xn8@P)&YoQ7$vl2 zo62{ba1xaX@c|V#-CSRsL8kcYP_`iDeMg&-73<;rHOS480PRZRro&qHZ(7r+1kIr{ zfkwRPWZw7FN`iP3WUsOW?uzK~OW%kjN?(h3dwUa6717V?7<)4QO4p~463X;P3C?;g zE?lObw+xAKMq%NMKY#3jrB^U8pajTST3AT`qnjj*GFgJ&=8=x>8kA?Ogc3;6b8^N4 zbY)N`hLpmesd@~xF-A#wSv0~sKSRc~wY9r|t6(+p|EpV9U%xq8f&o;|N?)SeYCqAz z#a1EoW|4jBcDip)>wipsyfGSzjCzak&Yed9*dgjKEH7vK@0mn8te6;pgUwcY<6oDS zrsU@*Ol+^sescRW-}+SNX7_oNT|7NC06QQ@hL(F`Df!HhzJC1*7z7L?h{)Urc;gd= z5-g(`86i;!ULDpn$8Sy9dO|x1*`~=BPhJAaV?qd55YU&$xY_yo(i=$4zNva^CP@j| ztO^xc8Gi@BE1a`r28S- zxbA?UslQM*G%7K%?DOYWVCq~iPhAc!w&8UX3hUjbSYcyefX8`j+Aj5@n@}FdxhNT8*(QG6PzclNJoo062p&3TYp#(@?CQ;C^pRlZ#O?>76%}$s=^I6& zEfv?+CUtdnA?|AaB}aqs#btmrBr&3o`Oq@?m(Q6oS;=`#5C}e*Heyjg#>f{fFMGeK z7KV`?0(bZ^@}21S|NYDV`P={FM`0@yG5lwzWiYdHGHr+q{YKbN`w5Q!x!PHjNhtQe zTZJUVjEJHH7YZ`|gJY`y-7$pdTnUI*>?JiUF;2$+*N6P?+aR7Cq8d;2@tNgz~rJND*|G9w}tHTz5Fxk=LHGXtvq7x=U z%$$c$O-uf}QIpZ89~PQGc{YcwDH&5whkLe?_8N*D#wR5O(YK4Ud-6O^(s)#Hw6_!p zP}h<|UhCzKSdo*omL>StSL=hQ*QAJ8iPe(B54J~-j4Kg+t+NCQhD!5GBB;NMzj+GHmQc{A~gNl|Oy>_Vd z!KD#P`}tGnl{)MC_q=Bl?~D-;8?6Kn5B?8O?h({t05~Or*X1EO-W9X`VCyYp94bk* z`T1VE*omkMshGUk(?>5*xxwohCNe7{h{+<*2}1Ha-z;cp^tB^RZRS}QLBeDFv{3AK-8`C1lGB4YCAq=LW>4BQKJELXg*YFARY?j9 zLqkGDGnsG%Y>CKt{`KqEBQ>VdFo&I=+}0T-UwMR1PLN`veJgq_YGwZvvO{XWKAFWs zvOr4bQ>wle;GXmWlFfqi^05;m5w>iKq!LvUJ6(kKO5Nq5Iw&M4BA((8!HO+sSy>9W zvi{DoduI+||G%B3?#O!Yqu-bb&8R)8pscliz97U)Ply&-`r@Yul7c^Sk>N z3r*pEXv`-vr8Vu;(BE-9x26g4)@nnvDc%+}w511R3!a{=U5&)1@E&Ir9y!mwoIu~q zx%()i*7syLD!vT-t&!WedtkKlA%4BTd2g=y<;utQEAGn52+82ZXx4ms4vv_c%i$Y) zZOz=79V?(z5MUM(O=yxCDJfk{i4t<)8Aq-lfL$%PxwKa5o1+T2m|0kM7n^GHZ-K!N zBH>`sEwsM>XLN+@_?_6f8O>Q!oaY_~ zC(97Z?MjN@@&6nfTpZkFNw&{V+m^bc1ozvvAF`9TCCU);z$<2nx|RC3*iF34V+k(gCn)C+fY5LZ zPJ#ojWhKVU37(v=r%hpQylBjl8KDx3uP-gzKCL-;CdR>8L8c^fBBq5+_PjlgJ(uGB zEgz>UF7gK&)io-&($)cg_RyWn&4}u zT12amlaso;GQ0POFSp0AG-7_Rvea5kwdzL^hk@>2Y_c>am6md63Z5YzmePsOTmdCC zc@>Y#Zq2m;-tmSsAy{_?@4$yzP1on!%IfMYQc|>;gXl64=a~jx-4pltV+Q<9=EKHC z+0a`69Upmk2phL}0I#B+C)NYsXi)bY3;c63twj}3tn~NqXF|ywSWV|oMgTT|W)TUv z6hR={#m>-V+R{QAGkHp#p?4jBOe!1(n5k!I*wC?mJjD8%#8-?LXL8G@)DgYs@2^qM z4UvJTY{-_Hk@~i|HuZ-3XLnbR1XO}UT#b;KbgZXbkDt>x6za}R#tBrbKYk-Hz>mJJ z&YHsO?$!pzb{Q|NCOt`q;HU5A2Bnz7t6$tW=p!;bnaQ!wsUvBW$iuBF~v~c5}sE+A5J?P7i)&9~4MsQM2d@!#duX$poB(K&^l=5!5WF-dmZmh9nwZZ~+hw zCgokcR!;377+_>zK!!{yB(T?yT+WYQ{M%a?26B;&mzUt{d$c@~8%^o0^hz4lGHM-X zYFB#l!3@?Fp=z^cAsX&SsJ!K&zw}rMDGqLJIg?3#(k95tu+mn4nul+D>*~VloUfI| zDlPir2$M85sanmH`*HV%mA4>TZL=~N8(4;?>1b406f)a23@4e<=hkWd?Uc`!Tc$Da zt6EZ53Q?6)M_RW3%~IJ`GhJp|(T5UQ2VuEJkBB)a19j8?^($7h({#fN1`Ya+A8&9b zOamoL6yl3v^Y+&bA!g3!m@QY>!Qxk??gu*e^*m1j@ObZrwLxF@Qbl6I$4Y>00^+S^(rQo$u7Zg;x%E`8|g(8l(dxgYD$FnyERu2}j!BG+2-q=y`7)^3*J zuP9@9etC(dU4}=jux!25qcW}bC|BpA19E?Zu5kMW7s^{QAnVFgC2L;xlhX+vc_R|f}k$AkY zve@0njgVHquTOe9QB1E9%Ook8 z2ax&06hDwaDvpjkh<9k5FtMv&F^Y)*B7CJGQ&Jm1XxkQETrYSej@T{d@TB={AQg4`8{DNQBg+1=TyISX@i8%nA+JAbxt?0L`D zWLot|7IyaN&QJ_g;Qs0OeE-=OLsM395BvVQctknGytj2|;&8TLWKH{Z4kA+sz&v6# z>st@d3Z^%IO;ulsjJ9d$>J}FlZ%j9G8Ww+#iB-TDYqr`2gw9TQCnmljoLH4f0Gpx9caO{myCMo zO?l$_k<9EivT9j$U=CfiX}pXvO;sgy+n;}=NK>(FvefHR_!rEI0Q*G%B@%yN^b6PU z%-)gn7v)S_TbeX9bsd4>bn70hyN$a^Xa|kfVOG&xU_-h#-7P3?Ay)Z>u_p~gWlX}t z!q1fhcg*KiRaBOXB54`9xxcmX5@L>&C=vk2+*z(wf!hqdQS-}z`w{;?Wscm@}L?=<;<@^daKlBYY z)+e3b?7c6OW`qSe~t} zJ`aF%7$enB?<2VzLyVUMyUfCZ5k_eRXmAhB00`I+{|^Ot459&UpDuP=vL$^#_|L2# z5z)}7Sy{1UXJ<3ty^E;eXgIyX!N!KnR7wglk5QA^LIEiD85&YmRvtno@U2Pw2_(8x zl9M~3!l4)H#SA4PIC>N5hVkytjx4TtF8JSnl)<&MmTB6?h3$;VBgkCdRN19Yo0Qn^ zmFbiG)9`|Qt?-qW8Tp2?SX)J#9?f`~8s`DAvqO~8qM?%Wldpu+9aJU>=5tO8*%Xqv zKRY?JZeoao=e{kbNX;v88vLpsVu}$U44C_s-!k|sa%Sf@WUbKN@~D6M^a)NhxVpJ{ zgJqHPcm>q{e;{>tc50Ud)3Isk79tnB;%>MtF(x!B6c2tC@P_?@!{(1SM6@q1vsk?QbMk=r0HS$h2 zsCl$ToTAa?o}+Yk=Lt>(Wl?gD;+fhSy!&WHLpocGg{Q4yo1Z995UgTiIS^AH91ik+ zoN_^|OF`#F86?O{QM^~r#q*X4>3u=q`x?U1t1)(uWk3D%B%=&75C7dR@4^E-edSbV zCzllwqMSrUj?8_YL&JzN6sv~lam5FNKSq4Fb%rYFw|2^t?7M_9xaY8&@#eT$=bhsPssHgcRrF~@y0rNpv^`i0040`L8LEWleYUwHz$Pjv+=2{;L#oVKAFXd(SCUek(fVL^sC{Wkd z{x6H%wAXgQ#>R$u=5ptO7AepyT6J}GP-enq)RZ(Vee(*;d?6e5)YOz8tl8%qBSo`N z7~fwv`}TuXCMUSCmCW|byE&y$H@z`leFt19BcLE~9fxp&!ezn#Bzj9A#0Tp+I-k!| zS^YyT%3)WH6<)qhm#*N;5B7G&31VsCYi1qx2na+qOR} zyA+P4**{-CO}xEri%>G_V3 z7&@k8sgJ3=N|XJn?;Nz`=(FmcH8! zray7XS_|%StfmUgYqTmUth8&vX4n%qA@ttYL+NcK+o;I6?dssRG`UhMd6#KiX0N1# zbqli3WIqoMQeOUK;83{VJ$>WLiM<)ZXMo0SeR+BSMF8eGEV1Ogy(Ujf~ zXGi?FTD_lGKF<4aew_2Tg9MSw8q`d!0zU^Y356dIBJtNCT(W?W4Pj*-dKu9WvYwWm zau>*<4r9=!)yHE9a*|;WxT3czZlJh;*A#1-4%LgSZ2HjDMZ1j(6i@Lrk>yJd`{A#z ziR5jVWt#wLzQ^k{0ewdyb7|#u2xIpj8GFe?1d0mQ;S8S zjAm}-q6_Z++s{x|fcL!JXksJ9)+X1A?ZKwenx7BQP8EyOt6div6VpR4Wz2L=*T)dX zBE>PgFIJ-I&`9qPDF_*YD9_{x{EnlwbG{Ou6_vHKGtY$gQJM4=`}_CrUx~PcKpEwY zc~1E!8xS(0^vJN>&BZe`tvFvPYg;1#ghXfHi;fPvYaqs%~ zDy%57{x(-aQT5k*leN8!$6@R9>c{akQr>HPDk^$1S=-?j{!~c;t+C zq7aS(Zw@8Dx#P=!eJBN|Ql{{Zam^!MU^CTuuYs5EH1KDWcC zmFR~`2ydXZplIwGe_Dj`p%*Wo7MClp$fb4v%@WDoS_wE^$M`?5q(I zpCWr*{hc^NlnFtCZ-++_L8TkiM?ezb6}+f|Yxxe< zlFLg86a!@Ovmft!T)wU%-w_ORkq#18>UPf+!54#YMbG?ua5BzhnvOCvK?6!rGSK1! zrefZQ%!sN(uwWR4K;FgCN;az{82oy10EtuCiI?Cr9spd)rLJQCxsHsL)4SHJ2&}f) zEt{!6r(ajL~hFhNIokg?SYiz6&70=LuSR<|#!@Vx)uZdzH*7-GD zhoK1X=ZL_)RmSau>5XWyEef&<)vng!W`TE<4#X5>GJ_+0C2GtCVgDCR?*YyA|Nj5K z%n(BM7D;5!WMm|gQ1*(Dy+U@j-m)oVuaLd>%u2HNp4odPivRWe{Qlo_dY{udZ|7CL zp3leQab4H_cE3NMk*RD|@47ecv0?sCFjN+Uc?@+YO($_JrGrT*#2NmujNfCt?rI4~ zm1XUfPYIlJKg^YvB@EoBTI0$&sn5GMY>`1wnuiH6)I2{5x(O(aYsZ82^t}2mIsU~v zuoj(gtz<0pOZN;6U|X@>Ax+Y?qU%TVHA1WK9dlsOm*)EDVDn}&aaSrQAy+r~w)>`r z^P}bf&!WRWU4E%{PJ;XT6f;jIPrfLso#PU>y}ywIBQ{jk=Q{Tj%iV^fXC~UKuv;&| zmu_(^Zs4&aC`Nw+qz^{ybs{pd4(D=2w!#by=Wi24F!@pGA5=Cj-;IqV;Pn^ zca9qOydvNQ9~q$RutlKktPsY)P+>d!n|z1zyo`d_#Bpuv=vh=C!Z=hruw!+?55 z&Ta4$Xk8h13BQ3%mto#|?Pk?K|Ap#})mfG84t}l4|F$XbB->hF^Xu0hi~6_HE-6F5 zFPeEO*S@ZMIn!RF6FJ51QDz=vS#xqUH5Z25+}x72aP@qRsF)ZTC|hBcE=A^Kg%sQf9f^|oyDtNr z%L#c{X1d!EVo7auKUo4UBbPrM7CxVGCqB~tW;_bfankc)k_qB*-8V!btiywnA|X(z zR%+K$mN#-zv+d@aLa7BmG&G2{3{hPjNnT;JfOpfvj$G3Ls=gSQy?_kf4z;2`y`qA` z;+o`@+kh9cBYv+}_?+F1=!ak+gJEBqZnbS(L4YTmb-XYcs&m;x>IX71vhC^W2(0Vm zB~V+Wt${g@A4)MO57$TYDFz1zebiNNb946>x!yBRRm1AUs5z}_O0I|Y(Iy_7)pgB7 zwNHR&Uh@f_LR@4;woS&=yBCtj-_lG z*NNMd??oAmojs1}ZTh}jiEE|&q<`>Gfogn}dj8R`ySXxI$H&y;jFPUg*jD8w=E*o0 z{Dp_V623ZDz>OC(^?>Ii6kr#q;N{u5}da zRDJ;QH8MF_3A_}UM_UMaDQrh?=uDthV{eqa*52Mep%9>CGivZf8*JDe9(#=x$MN@i ze#Z0q!_YN4IvTwtiuv*8df*hIq9)qb1w)$vrx1+2%KrK1vB;MQl_c_yCCt3L*g4*v zO{5ohPs_9Pe<$;)+6nx`DQ>G&7ngbccON{c4Z+9#yEVXLi+|ITr z^S*kAR59?{LSwgiyPgm+BjeKu;SUScZWYyUp5aw)OqSmP%<>Bq$58x6z+6YSxZ&?% zk5qpnAWsTPN~TCf_&X)xX{tmre7WVOJ>(LXXT}$o6%_)uO@Cek4EgNoQ+${?o5Jwt zo>oZ<7p2Z48G02m02K9LzdPO*l;(kF|MFytQD0)wAb&*Ozm~nO6ro=)CIaRn9 zVb&Ym!ib=cEQ?d?dB)otUd|N~Is?+(>qaWP^%?HOD))??_y@4f*S(w?t~W|$7l}Tv z^e4#U%TcPfplY@8$Ria|#303^2Id#JO7Kv!39ADeZtj7$|`P=X%fv9RBL5{S~WADfvzesTLBliGf_v z&>#nYL_y5Mg%kJBf>z`oGA2fs;PP<$lTl5KNN}umEi*AQ`!ihbzc(>4*@pvY@|`Wr zY9Q$01}ex%<@s|ziv(a?#&8d>lbv`m5Tvu=A;LvgRsc+R^tdP#6clEhhL!N?#p1zk zz>=%8SXe#xMD1hcA6M8#fBg9IUsxETT_h#ZUS9rgJ_5^KRks_iw0}y*GnGB6UpT@2H1npQ)&bi=c$2LY}&t2#=`GoaTFK19`<& z@G!9+U$pV&EQn&T#j~ zyDw1ry?1H)_5Y6raQ~EE0U`%GJNv$SzXm6L53!{Dn4Q77$gLi*jQAo!D-5QP8F37`x=G=g(RVahx+%v}9gsxUR%z{Er zKDdBL(2^8b_gIF3)P^5Z4F--Yz&@LJl=2t7(ggfFPI;LQ65>q!3TQz*dR!^a)L ztQBF8FKS^#P>FE`fD>>;Y#*e7jsAb*kZ|DgOCF(x`r$BZAMyKa@cWaj>mH>j4RSoU za8`*Hm2b=v@}Yj$Gicb{5i0bxrWBpIZ)oIs?daIdT#c>I>d)@yUolJ5OtmFGtk@-R z@g=iPp?Zg2CR9>=B`87v)fm#imSdUp_!sRC&PXvs*sh#PnwnQ)gVC^P)Ulb)dXJ#y z7A7ku4)jlJOsO%v83e}??u`oEa!E#4*uJ6)WPY(X;cX?;)I)0lpx&szz*!4J>w(;Pm0z5nK7JgzkT^Iv06)OB*|ihwI}K)#5H@SOeq_fPWQ5ql zT*bcS6Jw^|(R>*xQ+GvrD}oj0X8usKwKF};e?yC~ryg2)v%*w0EsdX3_xe<7>y4U1 zA6D_f1evYtdA5Ceg*h5;!}z|A8`rGd6@(*u=Wp?0CSg&5bb-1hyBR^m?athohXdB! zcLLNlxLy#Z#3ba~v&y(J~X?#bw!pYVyZwznz&-h4uT@g}vH5UP(d0{NPdP z2jwU7@@rq}lB;y3uOG*zWE;0rX`~Ot;Jt}@YWND3`QA4rE7Mb7{ADFeiriN5V&ZN& z9)mgK%Shf=_#^4;pp^fX;Xd5Zd366m%Y&6Gha-1g#?Zv4CE!Oh^X!nMoTh)vM9@_g z0u2dc)Jn^Vau{_ctXqhZeI;|1I9(9YFivHA^q4MNqq%whuqV`Z%meBq5WJlK-Y!fH z+S~l$C{W-ipr1Xe zEGv9g*1l0_6#`+oSgND?%DQP$$L)ryS@OwQraCzBVs3m8<}xg>W1=`Lpk4Y33(-~) zCka6Pb^@oJi}nJF9QuG=$Vaz-Ame}mHsZp0njjF2?B(zxUvowu5a^w=%H#Gmg!UZB zqAAfE_rwq9!4d-|K0w<*q(ulr(3g0jgG2fb*ig(Rn|W`T@6OcDICRnZ2zsXgD7&(< zA{XbKkf57HuKkT<}GL(*I|>ynlPm6n1Zzdql%bnaiL7s^!P>3JOMt zE8U^A_oKmh7Y`bPuq#*Lqjqv!OuwUsw(AJ*x?Cx zjKr#OY^f`c4SHzfV*XI*n6h{NydK;d!i3`NeV+0*$llaG0YHsy=LPKzv{~v9yX+g{ zN?qPx81^#i)Fbq*^lPfru1zJTR4FhHyx`!d*NgNQ${&?t-()1~zO$&kU0R-B=|nL9 zlws45tn1xl=dnusCac0;i$6)B9$y}?F;BZx-mrPN?2E0`A=wczIQ)<+`rzGCCBZJ} zq`re_e_#9sbmzizL{;N~>A0MxicrZ0?^a=KCMmn?eEvx?PPqUJ_(rCr%)kwfM`FaG zS!4oV_3`Ft2uznpyCZF`!^8#!)=;NJhWw^w`ulIP6r?<-tL@feb#0kIBnQJH%u}Rc zItAN(C?&7o?|E;@^*^u|KT;(HSo4X41Fxa8Mh#4UZlx;0=M7!3BhVc2%rje4Xphy&7|0DDCh)+*21%4LYg$q>%Zf zbSNwB!LI=H%)&H2{vQn{Sc}<2|Eky1P}M=~gO%isF3u#uPE}+HSo_L{x~y*>e)|_l z(uzGv<@Q-JKetj$mQoL@5CI~O9R%tUWEbKCe ze_LHN`}O-3(YxSQ8Sz)UM$>*~BUB;?#qh;yE zb(dsIw@Tc^v5kex&rHC zF!%V(V}!1$?@R_(!`Jy@D0Ou=$gr!~shUQ152sM-n-X~v55b#vJDZ3>Zk0@GRFeAjGJ z4SJ0KLP9VCG?{Ta*I!L+IsTdXwKh2Nzmp7|Q1IpsdK(N`#*(doFc@w9N0O@@tC@B( z3Lqry#0Q$1&cz=?eqnQr2+28CswAdf@r*v9A1GvR>H9aTk4Jr|rL*)aAUZGL z-QhduOahJajJ-p4ZBb{H>e!_QIJR z6*JMU3Nf{rYq-zGW(^GuaOKxPyaD>>?08tYO`@sl^iD$kya3EU9E*vaypO%)Q4~e|QnkPTf3EKFB;7&yClX8c9@*I}SOPO>S}R zaj~~`Ub_5YvlA!suvhIs`E;D-?yA8~=h5e`(|wR=t}G>Wg5(UX8QFZ(@Vbm1t33ZQ zr`RPtd^m)j>G!~g#$j}AeP*@2velI0Hvg+IM)3(fP7=$_QF+e)-0ym$J&YzTkgVC254PM}jzX|zKpgh~t79Y^yWR6d#M6q=5dP0ZR$EdsrZ_C2z zwB6%aQ&!~^y_^dZMPOQ?8Ki4TG5fte*#@f{tcYfCCV&@d zQ6(^vyaX;YJ&zr>E(nT@_Smh>nQJ+#N=c20j^1|s3-2kScG`r+#K)W8p%F=b22|T) z7-RwNwEzwa{=7Vx&>&(4$XJUoP+O#EK6{jzDx*kTih!A`6*`28rN>mlk~XD?XP~G z?5LRfX*FTUr8ei*o7-YXV2NYE6rydG+6nuU1MGS z@|J7HbUEFD9!xR#_m6V$Q!sO7*Gdfau59}F`5hcwfL6-NLz~Z*LejcG<2S!HtVvZ& zZ~*FdAYdj{9XpeBgx3(51u{XfbNOSdvSGl7lG<6L$y`0kGteC+xB4E*^!C(>3|e^% zL!jbMy{c#4Tt^|pLzOpj@N8iieXT??B7ri9SnZ&F?I=);jSrsS)mg+<8q5GFgIWRE zb?Y8quQPZYX*XTf+lK;ND)+auU>7}*B-8Vka!`Xm%K`I9P{qC(QZl?tYYM(s7laM6dgKR^AAQ<=?+C=wnG5UHQ99B&Lelk5UbjH~511uZX) zX9OSx2T(hHUKkh_wm()Y^*Tv`6jQ1gHD=LO3a-b!!{b4t$F5uYn3`c?|0)< zoC&Lr6)vnTw7jX&Gs4#VCFxN2#~@!ND@7d75<&guyIzpQNbVhwbO^*45js;zR z^viFdRYE~Mdt6WeHMc4~Xvy2xFgEz~gJq_tkbsQ2)!YCLJ4UhZi%p@kXo#e-yHfp- zfr_b#dC6#_$rI_V3S#xTRVde-MR_#T1GnZHAAs&)w=WKMnb%thd0a9lV1V?T^S<%| zcck~#rP$y7wgz}@U|-A$PaPyGyT=ch7YbQ-2Y~cW9IgFXRQQYv3nb@{c>--HN57=Y02glmhJDq)l7mmvoZ`4%oMSQR9Qy1_0!_vdg9#g<;qOU`ddtbwswM+FqS<6dj z*WMw%H`*AEhP9+CC-Qj#9?oB?Hs^da@&uLHb4Yc&#>PHu%9GKic@{2Q4$)PNGspcH z?Z)IBxW%+cLjCnNukzxMJhUntyvD`D&*)K+iY8mXF;6c!D^!@NDg~a?kdbeg!@eB> zQ@*q!4fcEYOn{R?!M@)(7~lCQgnUwG<2f(;P1dK3V4}jfMraR;DNMG%QI)^$#dE)e z5e7^YT9*$-4w|7;@xRxzJzGCcn9vN%1kMjgK!`ycxTmg2TLD>tZP0GZ|BpVd9&|vT zv2P=gkCrtsFi=q~d&t-VLnttz>NOTyZTP` zv+(l4*~~q$T%4P`0Os6>hsBq<`K;%;hV8nkcdxPUacB(GnV%IO zFKe&j;=LmZh)B@xymo`0MN(37{Q$laF#Q2wi>;~W@Q6-ICuSA<@4REbIDk_P2Hg5} zPE3M=qqbK~5H%HhPkYFZ-|{};`xBSZ5zAV^K#NhUqobo8>kZ)5CTRYC$l!r|2$b%A zHki&LBYldtAQGUc?_zJZKF+GBHe1Sw_Q@+_<67|KMX>}!JOIpW0_pe?fXgfcL7UwxA@4F|bNtg^4~hkk-2}M!E3BG|F22@&NN(Zs>N>`-D^xqIg;q znZ5RT=eq60jxgPOS`nAZTU6<{)weI&u$lCF*#Gm5uP}%8b$GywNKa?nnF5^MWAHBmC{GCGM0`9Y6t33B;$)Uf~_Al@O%WMf|@15JX0|9qSd#4ZfI99kC4w4{l3k#1IRcIu_ zqhQ@gVDBw^)q#h|wNRox1rn+jM)$Q~2lxZ2STpA6=vrjD`RM(?LXCYK#w^ht9JdyJ z`DoNLF)1l@dZ)_25n&I&>evISAi{Zq-vYspVCc7k6MO*{^1uy4@+L^3Ec z*gz;7fL=5@CI*dTVDEMX@KT%t3|7UVrG2B_e=|+=cdw$8nd%Qp%!&-Uo>e9 zU|UKRTSQ^!MLRR$OISveTZSC%8BIv}3kp6pu22)M3iy!7agTGOU_}2DvY~yZsjWHh znjvAxdE#=v`oVMswTQ75QT6$TM0g5RqL*?(X%y-_YJT?* z{9ajL`FAD}%CGr|jfa(fdPk>he&vliwnI>fzsZXe>D>O8(JXSIlxRdBaqREvWGL$T z?bnD>rjNm`7XxU4O5RNg>Qo=S+lkd?6uF|WBt6XN>DAp%ul5}Kk|xXU1O#wKmIR6u z`C{H8BA1%1D8m_J*ZDf7VWY2DsIm2?vZ;_;GERqM>ACRc>6B$p#`g@y4?aHIx;`bh znV7oonf?3c!1w<1&!>F+z`(9t>QQL!d@dJT`?=!Qv}Vw%Zm;s-Yve@_QPs;4w8i#e zN~?_`l&CaX00ZWK%#Xe|uDq@c8Y(nu{LA#_LB;D))R;=BBDSIQ_t^&VS#s(v4u-}7 z%qa6Hd0a*2M?^=YE@7l;_JwN~DlgQ|Fd4Ls!Pvr;0 zi3~`_m;mjp<;d0LrFHn-7uhJE)WS_@09usa9o}47UA+Z{2(Zawr&$GaH~%GpG=s;g zs!_^V=dfZ>O%4ii`fsUFnA=>p6-a<7^oN?k7?x(QWdMkz=swDi1MGu4&bNd4&w=Mn z5Sv@(o~^KmNo~w6DBwLb#3H$hTikL6hvvPf^6P|xfd46SNEyuzx;Mod%;yT8+JRzEYIX_ zZartqgveE?_L%N*+*c>Ea5uvJ95A5Jm{;L`_UITy|%ud{XolzM3o%bZvNxK)XadqvWb}kNo4uk7w47qRGg31X16X zO~2gVe)|9r*l>jy)^zC93`3>V)!TymkJ5{IQ>>R=XC#U52N^|I7Bw9JhNIS~)3EQK zX5}Mtqc_t|dXz-sLU2~R^kne(VwmKZS9eVNZ|L_d?f+bPjlN;p(}KSleUq~P6o`)W zv@{fu+Dw}3b|1_O69==Zs>tDFH`=1KBN!fAhwgZAmvo@HA6B3>q|HFl)0}7{yk)e% z&=~ z=p(ra$>4cZXRh$ z1vYCQ+Fba4RV}*pH8g@iOdv+&EuhLH;2+H-E=~tXc`FE5*N~{u_0kl)=E}-SCagUS zcN&*|k4p%;Bpo?zqm+5|DnmIf7La9VCH5!HQkjH>DPWu;1+zSG7W%-(jes*Oy3ajI zg`EHlFQIeGEhuP*y%?D(1Ql3yYYaQ=6VhMLKT_sk`lT3otw)8A%-D-B?<}ZP54)^Y zwoJn#xJ`X2p#D&>2@;6-rvFn}x5uf}qxG7*iN^8A0{WtpFw^5;lG^$T;jrCEt z^j=KG+-$G9-KD&*T8|V#f0u>78wzomqvbE!!ZSl84%d_};CxCw z{~XqY^TwVA%l}oPPgIeX_Pea6yq&7Y(@4~FQ9ZpQ=UWD?V~|ry?D~*B6V3P+thK|0 z^1?!XY>S674)KkbOd8(|&~{0Lv(TdL(53!65RkC4h&<^o*H^T4pBupJ)yiz+49#1@;DNf~}xDbDlyyp{6R{Sv1Ji_2OxuJlNy7Bvs8$u-s z>ccT~^2{ArAsv1_+|9H;^oI1g=IhYvm%1Ljf;9p(^nG)5saz8?Gvk3YsUW4EMDQLO z0{KY^Y8jl2p>YQ8-Dlg#eg-Weulun%((-ibNCFW0z08{Qdbv)aoKXlA^ghP>*8P2b zwr>iA5(%KJL>(9XS|sW@nY^G^P8JFHj;fHuKhU#X25 z73co?7t%5wLKY>MUsExA?q44Nbw%`W z0d>+*l1hx)e=?7>B(07+H`IG4oNk?^hV<8ncgdbNk!&(Aa2rg=Fwx@d?S+o=PRv(r z%}=V}!l&NWMHBY(KWQF&ozG1&hz#>Py*1U?bcfr%C0zs6}=)yRL*Af>KL7!FC z)v>f=RUw%WxbieP_K3xzuNoGd9WmVrad8yUr6b1Mur&ex#8YL5yiPOr7?Ak^aN2(m zZ<^Wh)x|!OaozhOnq?8aW=$3#;WJHP}; z9V=%z7y`u7^78OtTZQ&Q7AEIf#)lPdN0e2;Rl(IkDlgR1Hhz!A8~uxz$#p1$&}RG?u)w-Pl!9AquZ*Nb#Cm6u`B?{QtTk9^Iv1X-vH^k<2mm)VVbl?8h_UJptv1P!UloWYG zZBt%$B9c=7HMghnJZL^m*)BU%qqzcmVO^@`e4i2dU0L#z-PaaLH<&=dW0r{cp50jQo zep@~(_A8$FHZqx_dty*@ODkV|?{qM?WKRagNqTglN#jM1H#iW+^va_jyGX-(?nx~A zn&7kCuXzR?u6CL1EsK_k^7UV;9=ZfBTM5_+w!yb0A{~&FGd-HsO7c^;m&cn<$B&CR z9@GJ9DIEy?z+2x!KVInuRTFAkdb@@LIko&f;YS5KH>1uH#n7BtV{idlk$S)vpvc%r zv~}@&EG&J>D&vcyjIXs`9Qn^L7m-xP?qnw-na3)}MN+7C)mvFnO}H;oc4sW>@NO%j zd1o87Qe%#G{T~Z}Cz#Udp>SR3k&yNH*=zD?l|Hid<9{YK+3UfAdbe}t{qf9k6TGEL zS8*yjJtBG}=YPiGY~PC_36{gtelIJ-9OyUhd^Ri=KNC=Lcz(nbM(TlttHE#rRfmm} z{Rzs30EE4VggnHm{$0V=H(tPkgwj}r6bs3>|10tP>==ZE_YkT>gPR8ZV|#bZok1{d z;WJ3kf-XSjL-@Ej0V)5CflbT!>By`Y}@a?w}CpRlwsZ7}H=;@7}Z~zYDdj zkl%SiTa2k?^|Y?%tf6bt5}+qwB{CmUAZ&4c3zW+-Z;`r&#w+9)0i_n&$r1>Z1LPI1 zvq{B7kKkDoAw)Jw42||+if9%iVAnWBAHxX?yI3I9Wk%i6wD?C3lWJF>^ zbSZE{VOaM|-XuHGRmL=mda7(J=v10=mzo0i??F&(t_H!A@K+Vr2!bA$@85BK*-Nsk zwH*0(qxJAJ)(=lCc+*^hX=1s#VjaWf%LQm<5(05P0o8~w+$f)df_q|@XUo0x{Gk6f zK+n!uluN!_N5xGCA#|a{%yN{tp{ z;t?a1jEE5-g;LEw11&a;po-k!M$vN5vR=BxGo75m3A0qAJs$2avEfiz(QPBb}85ZsLfIjEx~=bgLKKDGl4Ou(o0A@U9pq zCxIVhfXO(-1w+z4+!VCed?f)m;b6u=kzVcp`Vz254^-RDN0Q)Vgmo!U*@!zWe#0so zB{FJFt*hbUn8X_>lPr!;zisKh-+(BI6xx!U*Iix<=cB??a64LzUOk&bo&`E;*fDLFFfn?qWmH!D+`R* zLTu17W)RZ!jU>9q=7lcqd0laL|djE?jE$9Drg;1^9d5%w<>u%|8&mRq5m)aei5PqKe{JMn(bKqB* zTVwKz=L-!*#&ed0iZ9-0MWNsBCt+GF`~+Eh6Wf|=ZFQ03)IAOs1Zu>1M*r;q-BV(NeL z^YRjCi`y1?`bKLV&0yrrnspI+a=u-t3G`Fqh=`!zIm2o7{JRj)n#v!I+u;4*o@DWG zZb|-U#ImkzmN^C82(h|8u4={S>McKw?&plZ?QR*zUz;&Lc`DhI^xNtJoPRCJze0Z+ zyFHYtubged7VcM!o>8=Q{1z?QM#C+&dtjRxMv2;AbJe$Y^qJwW_-VOpaP+OG{k8L= z*Ir5=@e{M#+bxnP_eX6qtP>I=(~5Z;c@BFiPh1iLGY&I)0jmoY(kr_sL)yW5h1Mi3 znc~W4;^^quCLt7$QGIZVq}7A@84ESzx*R4~neY&-Rh{2|T#h$i{`y_J)?xbN<6XA9 zcYS+bw}Gm%ar37OK=E)jLCTt{mKNolQYCQ%zpJ>-{M)^`9p?RDMVevl7$dP4=WHs0 zW5w&!v?)cns)cOh<_U{=_v6Di&)dX1XH60cW^{vw)PMiLd*FHVZkv8YV{&4tf$-G+mFFky8V`Q4hL%`H( zSZm(xxEpe}bc{u0Y1+D2hpP!DO{5D3_Hemgl#%5sFcoCz_!MITbqGLC&-;nf)Gg?#C7p}=`=nsFVeEkM_j-DV z#24~`EIB;Q_p-TB_^Fm3ES;*&Petd9Lwq6yNd7E-yT!qA9aIjiG?!6}XB=*L3Kc9| z<^XAb|Nh+vGBE(T<}vF_^0|_@*ycwyRq>(_LpX$?A+<=8*TpO7^+g<4@j>;l-OjY2 zes{Kb4dwp#8Kc-Va9^`4u8sZ9e}2Wi_e?D{NQGCy??my*lLT;-HF=?YAe&2Q(6oWq zq!?-nQm#Lk=;=>U`IbBjr!N>?2xVBRqf5t`|Lf>!A1HsKPjIVDwMWRr|WD$GJA*eD^6SUc7uV(-{(TBdpVA$_jlX$b-|`shCxN{o1#q zMnw#k<~@#u%R6q+ZMR?)1sAn&!w-_%Gf>Ix2ju*s)0`a;6;U5;_O=6+fw{_6wq|&v z9mxv3R0lKLXD0>oq@8wTn>bzkSNKF=TR?A&ki3b zv&r?1wH)C?u$rayk%`Uky?F-m>*~4NJh?s_9{*hOv<2kj0tXfRF$VA?$@U(esDzoc z3Op^@K^a~S;j{APQn4rTC!=Bf%ku0tZ?l}TJ9MOdUr#R+sOsC^Pf6o17{k5BZCQL^ z5KKaBPJU@3b3#gQue|RvlD`4dqmT(}A(1d21Py!9F6q#9aanq-@bza2`k_d|9 zaQO5ZD5(-WzU@-A(cvfAwzWlnttO`~eNwt)P_~4%$L-C4iG+o$|JaKY@B#HAH0cgNS2Z z)()own4~aJawx5agY|UiQqDsk%vF_Nr#OC-0$o#!xlc)BIuF{7nvhwgz4^0!5iE8O zzsL&A-v0Nbg3v9YHBLu&xvV5@;LrRCJ|cL97gsYQi8^8xCw@-N*6RG_`kNH|+8q2+ zm4JG-7CYu|X5^d&R)vNn{?UbJXE@A*LMev)7HKQL^(_>127Joxoi!(#iz{=XnSKp?d==q&$h8KDmaoS^NKrU6w2hDS}E0DWXwzL(*gX;Ak1QMuD+ z(%4xx7LR8{D-!OS^1J9c#k%b1m&-S{f_>+3uhB~f=kR*Zr!k)^%Awu6F~q2__x1}a zTfg_BwD$p*CCOb$0fvmn+;?Y<$4R=6XtO-Oc0c?rUm-7mn;ms4*zJQXvjc^Qcy}~L z`z>A;&Rg5IHGPKjOU4w+)P_lmmRX&_3@iRt(L+Pejm13x6G<3-f+T&S3}It~%ckUu za8Zz=&@-b`0q{-ySRiFDF_Iz4-hN&>7g;u@HV>cd_{!1B)w4^fj>^hg;S3eFPzA2yLU&1 zmP=acg^{)~FP|(Y&Aowp)X0M!%t726V($6EXxGEF6sA|jV~8aW05C`xviHGA)S~-LHqEbUjBmXC>D99N!^x}f&>T={Xt9FiHLvT_R@m(S$}-S6^1v}HsE?)D zvGM5xjeVapHRomg_v5|h9DIBCg@7Ds!hGWeSZu`j2U0VF5j03pnV!BpAfq1w_LA+ZO+G&+iA^)ff_7D3MVQ zTr>vBE({Q`K!n-K?bFu=M`4-;H4H_NOcO(}eYrN3niq3}GP% zLlXqHkBp8=5d~;`J$>4KqvzT6l}o+~0Ros57sR$UYu;MH-iYYc*1x_1J-ZiV+6JD z@mEa-o(q&*#~&LVv@5opvksbh9F$NXeUHfKQsZj3ZS>v%sz>KKoKi5&Tc!-NP^r)L zr5leDV;;H}hY11^Ij$}qM%FtL z7{yp$mHqK#G21%7HZUFNL2{jj`6P~!JlOD={sUx4Cu67k-oLe>@Xy<2SY;yKD=
  • *(fh%DKYqIb5#ts(A7l4JHZ_1InL`YyiLK62q%Gfd&%;UcC7 zL4rTYC4D_%bJG$AS{Ohqb-}gC2k_?81V{VOo3Ch>M=(f+L#ohOGBaG_1;JByz#$w8 z<6#6L0$B$#FDXTx*gzR0ebh>0*D$#4I_I`V2i*!0a+wX>bQ=KI5G}#{2!8vKI)IYc`(V7ix zX^&|eioQaB*(bA+*K&Ux_cHgA{st!30MT8e>Dy_|%ev!QiwWC)LrPNrBDPvnZE>iL zeJnN8Uw<7apx(BdV%E8+q2}WHZ6|8zce@qcB}!MB9^@x{k`Rh+{t$9x`F9{^OZzS2 z?0>90QIAZzcy|PS_j+WyRTq*LF}?M?JA*C>m!b(YT>`hPJ|3CWbk(+|ny-_8Lvbqc zi%LZ9e!!1`TL^BlqEL{dhoE+X9zV}dwjAIl65nMJr0HjPcb4A228)JQ^t#Pd#n;Ir zPMr!IP;2ndCZQ|bM-ZP53F6@9?nV2B?mMaNa3jtGa62p^zX!VH|J|YVAIKE&D6fG$ zc?M2e>eA#p^uN6~NA4omIC}FH#%;CuQ(>{`CO+5` z7y8~Ta5#DA#inhsPkU5_Jd*x4AfJuFDvxn{HbSHyt>}aQ>*2I7?ay+mTtve8{T9Lf zVbtCs0QW&}+3!@2`|$=r71RK+6B4O6s0F^u-qLqD&mvYq_^@W?9&3vk^o?J9vwKp+8-5OzEP z66QEg-5}W6ggoXUnz9Z2=%HXoSVTgYz~|r#=&;|i2=IhwEF!M|b)EkOa^DD=Ac*Sd zfXg_L3zi{c03U|+;1m#X-A{9ffLQQ0K-zi1DS^CS5U>ykwI}3}ogZ)b!<%r!YOEmm zM~!sgs}LMNocDxL4-G|)hUmsRZdG6s6uEKjKXAplz?$Wqjx787S>XGu>34q;X5iF^{v`3vfqb!;Re-rs=Sv$e41@kok}-ixj9v0)N_;7Q#De* z-9Z0XgtsEW_mTcXlo;xv%a5WmX^C4hv`o@FS?3xtFPzdX=3d!~sshoWe|{b67GFvF z2@A?rbUz z1&w-SIcDSTjd15dLTeH}D7{Z&U$G>Yh+-FgxUM&-iEYg=xsZ_7j3d}Y=(yhH-j=#( zbdf`_q(%HDLJr%4;9Sv{SH&xIZuwx_Ow`)XG`Tpktf&fZ@a?JAsX+Hx+Q0Q0vX10J za#d(Yd~DhD8(ewe3NDa||IwBsIqud%G~inK@bcfLrYge`&}Z*qcYOMp4-5FA$1n#E z>xY10uph0LdqccBL?1XqKgKi^nOEPmq2eff`Ww-a$EpJdF2V`ZaAb` z;lLw1=&?V24OiOK?AC3;Ev=!}zdE6AS%ehA_HTjLRdsYMS)5(xG5U|*aqAcMLShZC z`2Zub&thR=+1Jm4yoESO>>&*riG%_VbY4Gi23tm5UEL?Sr|qP~C52V3ywhk}D2E1| zFFEMLgg2l5V&$onnl`8Y*he60_+JLir=}zEPq*0YOAxT+0I znRU?`mUQCVLr)Xv{VXV9ahb+oEy=4Ee;bmQ-oN8EF<&Xu@HAjXIcP{}FwC9+#s>j5 zeg?$%2b@S+-K{Uj@C6k{i`UdA+gASTEjJ;lHy5MjlA5^fQ>!JL5GdK*cIr(~H>{ZI z7A=U5-5vFMBhuAH^|0cOT{r=akRfCez)fD1{I5eJdPz;brG;$MX##R_P z(PrLG+feep!UPOs^~eo0SFp}{R$=K_B~I-w0+&?_2jTp?G??Bby3Q1~cHjkx0%k(GKce-NFgE{UO5; zqU~zn1K~C)%}l=qaIvN3u_KrY_Nr zeAs7m?D4|6tK^qrNQ%|~z8=A~3&|b(2n!rcs}ZGOh084i5v#IJE1sRvo1CM4c`u)% z=bHjRQf>KMuc7jp)ifeW1ZFx5)MKx{t_weOPkH)^s0z2lx+&K=KBV>hWxjy}w}O8X z3r)XtxfQB$H;}*>A0T^l)X2!l0-|Pb)WGc1_-ua>i8?in(_g(g5gQk0ww?fU>EW(} z&2(rGp?Cb>|1vv59Y47&228JfXBJJIati>EP9)FEW=a4|`9B|Tv3>A^2l0pQH*AGi zkj>KqcMS~YC^Ik71VYYFr3HEdXHjNTGV>mI> z+IJp1e*XvEzAugiW&E)PWdcWZ{rJ=d^TT$3i^t)OmJHhG)I{FI@pI-wH*`fSyegHZ z<&fUYzhfy>$D^g+<0SyPi4T36Npaa$*U86pCv{Jby*!k+pPlOMGtf}dT(WrR1f=># zuS@a-`abB9Dz}7X)k-?QC42reBe3L!kASQnl={Fs{B@RbD6`)dA()V;Y}MZ$%V+uB z;L0$gO{nuE60e?ky~y4(EI|Ro_3A@y!L#Z@x2v$IUA$y?$KcdJ;mnR#Lh=Dpy}<#2 z2%-|_>&y&vNIDtZ*3$$6wdDC=M1uHBfOn$o2jT-T8$}Gowr@tAC&K!$2g2KMuE7nC zn@7NT;d3r7f-s)@^=q)J^+8!bQu5&}^mKQl^&cV0$VgRamg0t;vHtSQ16qCR8{a!e z-<5cp`A%sEM(3<|n_Z_Ps>0);6Y?E(n~dLfXRJ_TlG3;Q|#VLo#RpygKg|S{eciCfzR#3QdDBDC8~^$(2y`qK7$@497=X(Km=i|;R<2H zo}y}f;Io3g7`|~R?v97a>0izO6zG4RA(or>0a-bK3BJR{1Rb^$b{%B*27@3us9tFO z2Vn9eK(g3C{P7&?LZp(D@t0k|`y@7+-2fX(7qoReaNq-%c<$6bB7pqx@y0e?@yQ?H zusXo2Y7dMK^1u;F?clQu`VNE~y+o=IBq$kTJH6_j*XkA3xM-lWRsF~K-@YMKq!x4> z-jsjO$D2E0o72@J)}dwj=2c4*Y8RhWiA}s_NhGhKXI-9!_7{!5YP1QBa!F-S*muG3 z_$E#Rj2&}v34HZzvuS=LXsuOXDiwd8TjO0x(7(cS{$G8L?j`dN zaaWaI$2VX9dog&=J+`vb!jJ^RvE(%ef#qugoxBvZKHC3}u=jxH@^9P66&aOM5?L9A zXpj|3NJ>Tvl~G0{dlo`S*&{_(G9oi%uS7=4NM=YzRx%-+lN--he+xvuN|KHukg9LIT_Rkwwr)!MFHRb82RqM65cydon0T7qa%oF+%sXGI`# z5&QN0Nydd@^-hz?9WL5|Lz@C~i+u$`xaV3=>?A$jhOENPESNb}P9$uYtiuVvLGw3V z_=#UcF8=04ppI2Zt!c<63NjE!6;!QL=_Zs$m>!K$ieQ7J$KM5W(Gpu~40Cg?!vg|J;@cLL7#d+YZ7Ft}P5E?98my+a$fab;_}7Qz-r`z>aeMnXmeqw*>X ziPuv%aM{x1bt5WK2z5KjG!v3k;6o!-`65+Qikpuh^Qgy}x;1SZz& zw&^PEzD%LN{?2Ioj{zqc*NhA86m)-2z0df2tJ&cEfbJKut+WJBYE>?+#?G$}ey>?eEp+3BJh|+K z%-z?OxSj&8fMmyY$IOK_J;zSG-%BwI2SMsY0Yh**s5*1Bvlytjt>&rYTR5KF{v!p9 z$%pjI?eF?Q%yh{tO#Q$?c(T>!waBu4u=V27$3P$85wD=c$+`M=>u??{1~Ja(JjD+x zudd6t_VF3f{186~3g>Xk>k+$z^z`(%3$oqXY!w;KMcnhZ-5o4>1L)`oh(MT zjBx{G#tzw~kxeFe=Coe=8co5EtVql0eRK{WkuN_!W*2lro|F4mw;n*aA$l!0H4(3B z4Y_W?S1)QMuQxiDygSL2Q(;bdzGeD{>t&tN_j|5Y=f7K%V9p_aslv409)`$j5ROZUhsQ@y-lj29jB-G4y zC+j~>-GI3$J7`S!Vl6~5Zou@^_s2G`p^cLps50_F)59GIC%}k-oWb;*W#4I^;X|0O z#Q{(W=mP|zN;mJMkR=bVtbrS482Y~Bhx4k%=IE3JBzur; zC7+cNIoH08sX0yEH0m;Ae){BQ0ebmA{UTQiJXX)k6#EC5S2U#A^oTa~*+01BNpyljo_JukeC6>;j-ytKp9ubRfq3MxZ zWb-aErWc9`PkibVe?UFGmPV_7U@4c<%zu6FEs07Vo;pXKR=tEJRyOH)m(tTBC+1mY zB1$LG5I{)|Mv&Vac%0heE_>AXbFzj$1c|Qib8N82`|8qJ!#hqx0J90lFf?DqMsYA9y-lyYrRq8ufe?}R+ zzBh<@%17Y6>G#jb(!~v$kLvEIe5`YPx35Sa*}s6GpcfY{R>HmMwL{m8T;QsB7E(t% zUB0<_8`i$vR&VZ%1l-s~@1b+M=x3hD9+&!^^NTNMR-1)lmDYN$I+k6j*3PJopXAO+ zVU{yZuso@z6*NuL*c4qjVdD|q9bYR(U7T<h%@J_;KZ}Rjw)q=JyY6xzTvu zoAqsyO61oCH!((?q}&;_PHWHipV3kB&37xo=krDFEyAbUbj=RDQ0F*9;(Z+>^1wz=yHdAyw*;2U>C2|k)f7b6Rz_R7V zFT1#u-al-I=};P4T7_nV=lu7XMFVshM%kq(FTbYw$BW&4^S)c1VbUY+RSWApOU3?xd>htp)>(ttEY=`S|6o&vUoz>Od7&j(j)pzJOa0m(6HnFB9W)*aDBSon0 zskGJnoKkozNx=WgwL2FR1WvUJan`f?yxx)%c3DqPFXps6SK{U?wY-C$sC+3EPf{)j z@(fTo`5(CMkzzK`@?CgU-z(?zY=#51m?_)6C6>O2vz;H}S(WGvf-s(glbuKO`Moku z(VM2`wz{-92&^eX-VevF2{oAzfYb2W_m1@dR}^H`!**e^0BO-xKyBO#XnrTJX1QSJ zy)q?g9rHVu*5z2*x2idld@#EjPrlCL@5ObtWl`sbEN^#g!njb*p`=jR3L zPk%-UPua}MnDd3yS-!O!6*y#%Ng9%^3j#f5FtQf5`cSJn^? z9_>O}P0g5sJgOn2MBGw285tS94htg6VLje@&(hNc2W~)0vA39Y)6d0kp(`q()RPjd zb&+vp%xct>rpZ!S;7Vm6)2R#T(L z>3kXZ*((B9I%_J9FEtvfrS{axbxzqDT;bpPiOGN8N%|`^Vbkl?;S3Lbal&<02o5+S z)X88EJRnNBuB-iYRJlJKYv0LkNvl*oyA9(}53NwnN#D+#elq4v>ove!W14$0N55(< z#VnosM#a>BvyiVes3%>7z8raRxmNbX8b%g z!4tvFqEieYcQDAZ1zT7H-+GGRVPUjdJP{YWY%4#Qm@bGxfm;ja@89dSH7Hd)zMIF3OCjOdZUzb$V|RSfoXaiK8dLN;!T}iByX=-0FJ2Ox5qn)OTBt|k zJG$kBA2a<-lfJa+`X1_FuAy42Dq%GHQp{c#-@YEB&qRVPe=7{UmE+SUiaH}QK4fb0 zM%l6F7AF}D5-3LXOd@YaCG==k*jXMcpl$Amw~S8Js*`cvRq=3JcI%BpC-WE{t(_^K z-_-B6s7FCt)js&NYnrk=Ge%xLv3B9ex5}?BZDoDdx-~&g+sD+JC?cFN+=jwC+Z@@d znS?=Q%~iGN^ZJuCZ`Q)*Zb% zAhgV9DHhvsKPZKRmp+0kDD>6i;UDYsx5n=_4=sD^K{xQuIWkyrG@^rw-q4R_4)fX@ z^&Kq_ybm^oySr(! zp4dGP%|8eVFkRm!#i%NzM)BwbsRg z`xCz!DNgb(MkJ*8@D&zg4Yey~Bnh0V$x0Jb+t6c@fgz*i+uk-bRHL!)SWnlWP3Rkb z!%brYucS`)=I{RJMeY+(qHdE@n_x>chNzXBpP&D!+q;H_HzlX?HwpgOM48nqcgJ__ zQ%B#QN-9522O&kdIISYZdG9(T9W`bJjiZcJ(8=vmh_IP0+Q0>DWd+X{Uv z>bCuijXI6oj;-ryH=m?DcICDAEQL;$ zL_NdR8viq&*F+^*?oe*J62oo5{3_PcT$f7Ty9I{VvjJCr^E`Fi6Y0Sv%{O%^Z}x;! z_vaUPl>hk~Vojjy=^pIKzpxq|9nBJQkIPr(@y|@hH?qeV9`V6M;uQ?&vD!cc)+KS% zCi3FqTo%kIb_fVe%UkkXnAg#tS>dOFdxP@GzMnC zNCflfH4R1bQuYZGxBVblOWk!hG$??}cXZ(0(tGi98x}6^Pc4H4azbNpLXHaBI(KFwE-_!5uCECOaOn;8*tEk| z7clzN=g+OC3>c_dJq;E%X393O9-}OtpSp0f;9Ap32E}=(YZD6#CBBaBW@DCTXsX&p zedFb7&yAD3TNLX(|FzUYS-EMEH~p{w_->-WYo(I^5C16Acx*deG?7w{j_N;N zjH-1_Jk{F&^=tj}QR5V6)?&W=f4ZIng@C8Wf4EItPnzPP+ER`3pa|=@l8ib3+OZfCa^c=~M#lvW6p?GKq3RA~9*}%%YqZm#>qYz0UlZz1!s( zTC3Z8D7n_!Bk>)^0FxTjmjRIQu=IkBGk{Cfz_p{lcIfWEAQT+RMLWa;UbKd&t_#e& zhH$fWKlSZ*Y+;EW_EU+{pI6M8!V~?zYtJ4!pk?gMk7ayn1DM%*uLplf7?aDtfV9&V z(R&CGDdD{pq(^W6UA%1ok<_(jb^-sb!&}zE8R9kI&F{$CIgocYO+R_?;0{bIVQx+x z9v)uzGca)DZ_I#|NAtDY&)ee(K4dgqYDf&1Z@0qyh2F@@layN&U6-b;ZwKHU8-`?E z!OhLhe6tT1Ezk4!>?|B7i?%#kTh$*G&C@^QiLX2Ofzv{FYKwm@l!n@8*2+@>IZA|3 z8EG*D@lcVYZ3UW&T3iiY)+UG8gSB?B8Eu568aZ)DxkyTB2-5L5h?S{?b$_4Wus=2A zYT}p-7#bbDKBHs3rY0#XNIT@m7wa(9$!vb+8C{Ut#Wyk4Fq>iM_t7I`<@xk zOV?xBp1|i+vAl-QWG=?P6Sp}OsICFoRV>G_0`Esh_Y84`7s}2Q@?l-VACb`D02s7y z9a5C>8Wo66qOFcWeldh$@c-oH@JEK#<Y~?~Xw=0hUNT_K+tk7$XcSBS7nT`OQ9Cnw7){S#fcg?4-x@O_bWD9@@;U;5m9Ax{{VhgETXP!z4lu7`2&A4JyJ%f|CgFFu{uL z#%I!#flM1p^?hi2@9Q~c(H44oukaVfNtXBQC-aSUxNIkIlzX97LLX0uDBAn7cYb^9 zSA0?@7`q${=X>zV{_2 zi(rnoLDZ!26@d|f_7;sxA94Bd3iH=;fzSVAa4&s9V161bQ4TuCw(C7RGKYhDEgA_3 zXDpBtOuHdEX-MWo!99sxzGrrT$by>%`c=67c`(U>GHwi3>+t>51-`|$rWk|?5EhK8 zJFQz^41Xz18Dpk6bK!yyY(Ak(-N+(L0rIhiY;PzOw8*kfUb@iRDH zf5Y$Rn4aF_77=uUJ+&XAm|#zoGW}!rYo7T!SK_`_@LH(qyvCMqFdu$r%T8ofjj>XU zfg<2;{QcM4u>0Wq5ET#kD46rN^&GSO9}7&AEHJ}^QN-5@kk2qwrLPe|))n<~bcs;8 zT;p-QzF%vSC?E)L50K=79*%kl~6?6Vx1F9g371P#L4;v>fgp zXkI=LDAi(BWP}lh+uFBLe_`bH{kg6QPVf6ZuJu!i!9GO;Do3IK56)>6F*T%CDh}p; zFT=PcvMyH}E1dM`D+ROr5x^Yo%pv#VPcv{tVQMDElG7#%RAYUR*xq*fC{}0wy`YSW z4-rFW=)A@cA--)m1DW%Uth6+FH8pzlpakK#-$^1AjA{PNJ*uoR-W#Xi4(!R0G{IG+ zq6kI_M^@i=SVHdrZ}b|c{Vbwj(ReiE91w?ibJ1ezrlgngTC^peJAeK@EJ{EfkV#6e5g4JwQ4+jGVm+3*vt1xFbCyV>NiPJ&jTN=5!z!2==4yc`S=pC z!9j5Vpxwu6&sFX04xt!ylV0iRfWcHB{MxE0ET(oxz@OrWpdH|Ea>(FXWSD{x@@iZA z&`l79!fIz74rz>9`qpI-51xX|m`6PF0_{k6b|=7^=piIr1|By=gfOeLc)tpO7hxT@ zf}o}TM3(;eS)S6AYcJP&0OoOB=(qqwG8(eGA#Xyk-Su?6G#bvqeVjOVE=(k3-L1EV zfjfTLvHL(3m+qnLtvc-Z6K{hgDc_G`_5Q^}09vVS- zghlttFn0ioE~PUk&WjcCK{~<`DDv-2qM+p(^L|~^bHDg8s}mRTPZV1&YF&zJG!dn! z*|)U4INw1%^(W5ws9Vhpx>^d(|i)6VmQ7nTd#MHa-{^b!>81k2~5 zMgL$u8XjX7ZhITDp$@G_{}slf5Zl~J!3PLZKx;O-1i=Ff_LhEnzv-h@`H-avL6rvUN2{kPaYBGoKNg9I}Qh*s`rSI!5uv% z_WTGJcOkuJLCQ}?wOw|Z*j+hX{Wycgh$NE8rJ(zOqqTy|-%UPermiAs0|O4sn^;c3 z&oNPY)6j>j;9Nm5L5W{QL^Mb?GBYz%nPvhP`?iOOA89Yy*S;8IV)O<;y_)g#VNc9@Sz@2Zq&#kDGC|DUR-BS>jw6qff&w({ zX6?5t_#8C2NzM`!8~$L`@Oh*_0~Gw^3?Y9dBej3`e8MvwL}*0(ST|ifyoq9E$PMv* z2;;InKUqmm-@=RtClF0;&yRwCB;g&W8ii3~_e)sVlEK~dzb@Y)u3&&|xUdeeLCbY&cNw1&TW(s_~jP; z*fI&(M}K{65r!lF6Z>q`B$y*u-cp#6{j%p-aw`}+#>K|7iEaq-E~NX0Y*^&+U%!48 z#?I)od$(^1cQ=azbotv+q|~~%rV5;}+rN{f&Y=mHVWpUbnsI6OW+!a6+Zc>Ji*TL@ zw-rRentxNc%nkz;wwCvz^KOC-^UD}B?oEZVw#MSX^i^PGrvxfUM}?lj8dq9yak ziP8s#8c$Y9h=4W9{exkCz7Vqu6LtkWJug2$4N5kVC;ViVaQD;=QdhkFT7W{5n@>H~ z*XmQL!H1{HO9;&rTtnX%00{y`5&m=A&F#qcecIbvk5C!mZDQmKH=uFqy2zFdPO0l3!gV*SlAB(o?a9QMv6t0zXKI~h<316u7VUh(E04P z=-~uuwjecQefyWrPNTCb?m|@Z_8Jajsd7ES zEC^{%({V@$aNAr;WrsQSbnhi)c%i-~DK4PA_4ebv>2JN}yI zUW^w18Nwp6mN*R~8T)qa;sMAMp;QP#{c6;U;)sh@;g$W}Qob8nuKNF_1#qbwcmBLN z90lJn2C$_W_|X0=BCwx6jvI9HM}7W%UPI%H=n3!utZ&sRCSvOrS%WKl9X7R|`|n)z z2r_GyJ|u|)hnl7qg&mSayt1j(@&~+$Mv*7G-W9D)fY_ z8@0zYr5XF7UiOe9KUq*RM01?a{7apsCG@=Vj|;p%TCb^VXfpkMQXvx(klw%Z=pWX5 z1~g|wk5k=OR8~~%vp-gw+}QqNZ$bWEomDNZ{au-jS(*8_L?^YnKD5VN|LCZ4o>8*z zkt)6J8HTf$jD6OOF49y=NmY+;Y|dGBm&F+=Y;Q99dcgU~qVw%S9DA~>KhEEYE|hYU zjX3vcr6yBTCrnl(fnQ{HI>0l$V{Op=a!~ zN4<&NHzp>g%Kk$3W#f?s0R1%-Bf}erJJZncaFncDX;m)9P7`%j_~@RL&bRFB>;y-^ z*gSET%FwW|#K6JQR-DfC?$5s-5<9zyz)FS$0!bh)PyPM<(1Zn|c>v|rxsgNW^%5!_ z#p%2>2X_}nJz&%J%C$|cyZDQh%RBWp{5qJ%5A0fDdX`X5sg%^pLS=d+Na>DJl88WK z6z{HGR6unhccHh^7i45(dxvNe7!$)*RaJ#41@=G`@L*IF6&3H&Q9)&UEU9%CM7}@> zNw>))i61{4;IqgaUw*y_Gmy$+vRZ*+y9P19&t zjC=Ix*uakUcGvCN~RO@1vYXX zMW&@$sc!qIL}a<6ejoNR?!B0cwPOS$@E1IusbMjHo3usMDH^2Q%MK;9O^`8_ zSnRtF9z3@rR;S}9g0L-oH%G3SXWFD3u)qhg^gWGX%#JUQJdEBWEb?0AaL~43STKdBaV-@%;oEsD!9v-HbF4|Y{;coFQ<-ixQ4R*(j z;DS$JBE%l#d&A@7C*jC9-d7?j{WuswQckL~r6mNOB=)GikPoYYQHGlJDX_i6Ki(hf z?&;BzmeTNL(|hT9X@`I~Of29p@CM*P5T~_~5!Uos>e{dLtYW@nakn--Rww8ps=>Op zwg)I+wOpp7?A3l_Exn&`5VP)&1#ln6B%~GjaGsf&InTUn|A)3V+nYBfU99>9-NA9P zsIoMpJKO2$?n-%xr=72<0TM{7>%i0;S!EHGw@vS4GtbfwahIf zq*AhZO)Qo6J;O^}ivxDn|> z2Z%;RMa5$IK)gl%)~#CrcGS+CVZb2{w>bDQvSW(LI4T&3o?n0Z^eO(+=#QvNr}QQm z^Gqz2S8BZDYF?Ecp!S+@vj{7qJHL@tj8@K%83I$DLx&n08hKbaKOk zgYw|=t9~geDH)oZze7^tG3P!8z4hSeXdOmMKtVx;M@f8}iSEeB$teeEz{o<~bW~%- z=6n-fjf@U5`HVR1BMQI-^zFNMuiw3UHz3>87h7}ghhtjIub)kRnuUdh<*=OezIX53 z#fxtcoRJRI_xHyE=^7XtyCy6zf8|zs=6>UE{r$1hA7S@;3~K_IH38VbI_)Xr(HO;y zLTYg-^FVtB$76^Qwl+5U5ImR`Xya6E#7Oap-l792z%{lP<=n8y(+GMO-Q{rJC`PIz zVRw{h;hX3#3U0;KU5vDQRkO6(u$kjm{5Ajl`6IXd^+Qq2+mz4Id;$W#fC0%^DYW51 zH@y*vV|I?TE?(K0mv%G{TS7bdJHgMNlP*R4smFkUQ*c?pz5(U(VZdI}y5FLsqm#t_ zq$FPC40!9x&aRNiV@u4z7898*>&SPg-{u=dTS#&%D9N{J(hiB&!;_QmFy9JJ$`_e(#p!vai*VN9>ItqCN1ghLpQ2lzy3Zqr|_&zb7|3JpX8`yQPR=TQKsYRLpa7o`=z z&4@?VB|`&2y1Ke7GB@^8;3Z04JXwWjN}Rr!q<=S-@FCrtMG7T~+ku>32}Rm6(mYhM z@Ah5DLt*k{W~t9NB&5BE7Ynvx2k1BrWgZ*NlDglg%9(vPU2)XWeyssKzg zY}=-YVh@G2B#X_+(2xQU0Q&x-bT^Zm>Cb=oUCJxmNmpR?p5R zDFKD^LmIs2juDXbCiK?%1qRlbcL*v@ixUI7o9qy|AW%S&B>mMy8U4Go!(3t>f;(OY_lIW)`CSlKI>0 z>l3u+NmlekaQ_x=Rn&iqa&i>%^77t3KBB<5$rMgwzI6A|^n#M&Vv5Lzd#gWZ+#kPk z6L}-(+1c6Ic(_|P*kU2&n|B36Yq`6s^U6ci%tkqw9)x5M9q*TDR%XA2up#>i*XBX@$Pv8i9AY zT2_(K(Wi8E*#*PXtAFN%le`UOpxL10_l~;uXax&+ana!?z1?VJMN*@PTDTu98-K2XWyBO4z#!) zyJUJkqvHjhzJ_4_;*$Jn>#tn7LcNg%JMZu--z~h6hirMs)OaLX#l?s2ta(3LC%F3g zDnM8!EyE%z`^l>->=Sjlx(a>jur>R>xHtx37j;?E*S}4Z%xB*N4QM)t!_|;2^2#;Q zM+J2W+F$?KQCDfaWN;GG7_XaPdyE-Ug!0Yww^UmR=xXZCWlK6bT^Dc}vmgY0oyciY~*o806c(|Ze;gV5paIG8~V(Mw0% z@$&MRgG^ME*;)fk9I7);PEOqtyW`5mL@M6Cb~(S^&z+0xkf1rk(E>Zdv}$%dVvxrjLT=-=O>Xa4-U>+MadFpFE+A>{gp zu>z=PCNV8Z<8))Gl+{F$fexnMDE9`U`oPIYw_!sPVki=l5yzAp1CvG0KWAr!=Or0# z#^AUqt2RQI`;B2T9i_L9g#U-(ALU7;QIKSlAUI&;w;n1h0ryl`s!;d+CfUuPcm6*2ki!|8n z4QDGYD{D(Su^E+$?Ts6Jyu8OI#3cDow_1nXLQehQHjV8f0C09}gCvOj6;GVNIk8jv z#~1BPInHY^ji_+;_`rSbZBD2FDq*wekuuU;g{PXNPdZ);Okfa zii#t^^GxdRBRlqxVcmG6Ok(2FFuTLeo6nE|fJlpGH_u3F$$b9PPuWsggWu0{L6TZK zk?a#;rQ~y@_X%MiGqfa~tZ*!W!t+Q?70}AOn4l}Pne*^TIBTFKs`l+$zNK4?R<;rN7d&~AF0LBjUs3e9VD7{4s-^A?vk5U z_fxu{*?|ARfsoKphTp$`qadOFs&0{2C;q9uTdPAlMryD4rViGBGSuCSw9|5Sb_XE@ zNY2a*1b2Xv6vMeCyE~Jm$FEiN$9`i)W@tVuEil8v3gcP?QPOF4;#nIsxSQi$NQX7~87iQbIApRlAd zTP^Oi2rvBl1$LgWsbl~d852e{YdB0tFnRTCq0iQ84a^&cA4NFeL^x=@#V$hjf%^T@ zRq<`-CyYYyTCrn_9+zZ?SW0rDv^oKb1Jx|>1RsPf8z{X|Fg}c7UXt0AZ`R?DEKqah zPiOEYlc7C%v&RiGNC*zVi@U4J5cjI6e3eACARRJBSIM zNnM<);>`~^6s->Tx0??IVg1$zbC3zQV&n+sZH?eF-GcCF_3Ir~7u zm$8AMF8A}p@{T{EIyz)U()Rg%!0K=8JooE)-6m1KMtl_@bHz37kzzv zXtr$G(!fK5VzJ`Z;)m=jM=?9N0iqGwjT>t|e|`eqPOwXJb=kl|)#uOm-YISKX}5Us z;h~_ixqdUx!}j)J=|qBG#dGIC#gDDX)Y*@?^XC!M$aqb{UZ<|+(r4aO zlawsfOl~$wm*Ma+Ycls>Nc8^J=ua}|Mo$^KuI&t&^}WCdH?;A`z5z8*jH8} z&P5!!(u^?T>+e5=Y;6=~E4+x4IPM`wV3od~lO27lO*#E9Mc6m7e5R@*`xI1 zO+iYpLGt@#S$34IX$s;+84Y-c$=ceQhldA~rp?2T_Oh7A-2rPh?jVh7(8k6__&RgR z*KyGd40=1Kv$aFsP=7VVGo^E_5HFHBj@9*_aI1$`f3zuuOaf1++V6*BmT)hq?gFsy z_H3~4cj_M-8Ci2X`=p!b>hQ{Npvat`O>+1d`G zC>TZa&oEkc#g{GvURf!Wk&#I{m!{evlYY>IwvnxJ7AHcUQT-;I>Th^M4lCeW!j(am zfEQY!kJy#R7sgwU?Wp+!BO;a~`vnF4(HAUKqG}mz*;$?v!`3^U-+V)8H1Jqfpm_Eg z1>co-DJg6=MZz~9QP=~tvxmb%{9Kl*wHQ#qcvrc}re1fHtJ!kP^k>i!``%Ox+O}G* z)^_W+UFn)a#wk5be>JbsoC609u3qt3n}}JvfN?-BTQBRjZQj~h57fHuI zsz@YwXfw5%?ZXB}t&)r|0Wj@7;7CZ86wJ)h?E?SAZlI$RacS=O86KcrXhHW1_4&p^ z+lQB4CZ=4HQ70}-kJX>4#)_uEj1;R*BU0|F)vq6U<5|u}jsRG}@uirhH4o7PtHm`- ztMV5&`okVSR)bFzpqN*$YNbo~g%;=}ylX3K9KTmoE!`c*zfW5LB;fE4Gx4NLCiF(;1`QkkL zUI78pJPEu8xHOIxMj^zJ31ZJoGJx9aJ)%yG&JYd9*O9B3Yq>%LYYb{x$hmC?r zb8!5Q6o52gMtv2JiIPjp%l}115cm7$v?|W=TAT42IV@qBQ zFL_X^qM3E2G7gD9lEJqqxr8i3_T--0`K!aM;2`JN4I-MGaKI51lfTtPv;F`!*CzHu zuTa*0EVAB-EQZLE8s@`z>5i;^ok#khmz+BVbBNvI;!HPh-n`?vSRnQ9DnIY)<0kD) zXL<&O_A3WHbT^e1q(3Rade-294ogeL$_LUpCcY_G|VTds(CyZHD(9KA*<7Jj=$(myy@%S7=u zh&(3$K!hobo*fz)sRgvK{vm(0q<>IQa%!qCu87Ggj=i6gQZ%;@FNBDryi)4f6)=yh>$kTdYNA1=>hr&4$Q&=v83Boaf z=fuvz;aNE!F*|FM_xUufeIy$t)XonzJFOaj%@nd2s~Ug4#GyReM`vQrd0OoX*Ak^%2Xs0Rl0AJ80+v{$ouAMe>3{@_Q31d8xaH<Cl{+?k5$bRT&rk;#gkwgyWUSY}2&d(cRyg~R&Qc8d&7A&am8H;yk>gJDg z@**+{&^<^dSuiLT-u3VlP(%JyD=T8&9`W?Fsz;5SO2!6}_bhLFy-Ua#0HvfsWN~OJ zB2$kqELj7kCMB+pjt<&vug|WK8a@0J87gYpo_fE^L(2oe8sTT~K%Ajx+<19%YO0Co zJp}{nOQK2^Jv)N~D*yhGp)jfs&N?I7m8bZrR+pTPNB_nmI6_8lDJ<}@?;<4F`zc^# zcHThP-Pmyt)*1>3q=XHxrgTc$zHh*f0Ha&W5||rW`p{#}?gfRJ<7E6aq0cL80K8LJ|1x zP}2+2_YuNs0NG4kM@Kk1z}2105k1Q>s2GVzG+=bf(Ad~Uu!fDedDL410F%dn6hIR6 z0jV9SJ(0}7QcoWdry>2Uq~N}N#;8w8XB6H6yn;@_H?m6PL@+xyhDjozeup+92gK|C zD=$^iMT?{k`7cQ`RBpQ!EdXq9OIBf4ICgBJHOc40$KRMyC=3oTF)678+CC}p8c^?H zdKY-NYTz-1UG$jy=tTyC!itZW5)rxu=y>3k&Y-r=i#uy z(u6TpJnS~$U1A4ksrd4Xv3Mx>>X=uziMSJd{I~<)3n^ZN+=dfhqIJd)=|15Oac1S9 zi52CYt({%^j}%difQB#`pH^RUSYt@;zq9~;jF(=zN`WU-GK$j5AYInw5LluVpT}L< z%nr!o83ZDF<22bVEX;rs7Xj!anBwFqU9`U8Q9lEv1A!BZ#ZEdHioS+8ENR33sY>MK^&?vhJ@D-d0!kfs@eHgcHi3C9PVhgsaSXV;Q@gJSH}*b$3} zBm-sI5Y#{DP#6M(im(m%iL#+cAX`0bOyjD0#mPB#1G=r1=}LB7++=+c?Mt|95f~^q z`qTsAJ*A>8Jyip*bSbCzL_pZQi3Y#o{Nb zG{{`;eVoeuDa8W80Hm#?e8cH(0_VF1`|zypi|5@;9FtEsvKH)~U@R*;xlwGF$ooSi zQvRSUTIf1sWN2te)EP)U!R`u#%yj480e;a|?raaWo8VqMnvt#%zz$Fs-+PbWghF>S zp{6h@5P=Pxk9^5~HX{_A1;axqrU-wGLxRL5$fImlR~+$|K~IpKjFU9aZmWv2ii#0r z7=dh(!N|aZu>{U(X_?%}T=`zVa{?VVI2i|l({p27CE11f*Nq&;Qm|;|P-o9$X5@RQ z1kttv!k3H)PP54@aeRS7!w$_1;055qUInHED~Hl%Y1UxG4bIA^fsK>W7YrdV3PNY$ z*#`v|Ff4?~7S`6)K~`hb<~}m-6m7!rD?fMeSPnv1=#|Or$|Zb zj*_-RF{5J+f&x51etgcvM}E2XFoGjW!4EKsNKUdv9SHEME%EpU z1j2ASDhhnYP>^K5K3oW~?pyUEE<^GRT*nv=5)JErhJP$~76r@n3e2qIWT&P}BcV94 z;9+}`0BHwxWj$U|(_g#27)B5Z{lXmd%p{eE1t}3v<9~!U!w*Fxblh2Mf_xuKjCv*y zCYtD5a2oRC-)M5bzP1(~{{ibocQmb*c};wNQdTB|1PH#WH3JK%XGaJkTPSg0|Nc>| z(;>_x|BGss8!{Dv&)R*>&FUY&>d@NnyIdX#m1GV9?N2? zK4@FrJ$%Of@ndoG?O<2GKo*|}T?pWT%g%p5DZsxb0xFIRE`MU$WLLjKkF_1A@l|Ao za?UT~cP<(4K|D4B><(NOgBk>6m%lK+`t7uU(?S^i>o~!}m(GCM#QE~jbwCNQS2?O` zGI2cLwABmjsX)v1f}Zug%Gl8g1UBlcMxx^5mp#6TuHK~!X( zBN(OrY#7-t^@G5s626qDPi;^IVzmlcIJ-{uh!Z8Opb)Dj|6BWw^X&FtkB5!Xs)R0S zIsyYLdmIy^lU!D$u-wdz&JN`dLK z{G|KSal?3SKhHYle!j-RsVR)FphaSf$UG2HKaI2j{dl%Gh8X^(emdhGQe^yY`@PLO zn-LvQ$!g#2y8O~L3gZ)JK}usEr>HhIH#LpGI%gP9TO_Sww2y|5k55~C|MuZJa;ES{?zZq#$8m<*+S?z?=&)O!Gd5lq z+Jl}edXx@gtn?^~NYbO{sGFt5$iU!%6bYoVriqZup+mDkMX-ys2gOH!>s95?oJIlg zRGATnMypu?>OHpAn8^@F2Zvqz_61>Lj_AwBUzs6RLuhNjiF62auCR$v%0N4HCQYN` z#X_d~Gve}Aj_gwD@AJgNalja`*ZfxIml_eq-Ou3huN z_hk)A=^3JaSRah)fRT}rH1}kTh)!;>H$)9x4W0mSJKOKFhb)@YS|xGrnvqDSP_mh= zI_oh9vWR#=%(R7-)&KEh4%|6;6PE9~yi%W+8{=#_BqJjV{4e8nT-vv9-)0vV>#-=X zSWHY(Ui8G50EwKPo2!OI5TWQfiivm4)aRf3oq3sD^5n@*ROgtcX@lqk37g?hiY+P+ z4nN~L|MmESREy`_`~XS?lI0KwVkC~ZetLxxNU%N&<4<= z9?eJA7|0OccP$MfpF0s*$HCNKtr6K0V$ zEBTPl19}0zk7@-ESLX}+^J#k<+#x}*;i!=ILHefUq-chvn_52-sp!P_hU)5-$OSin+4&eWcA=k-%6O`qLk0BbskZ}WR5H()p?isJI86x}i zN+066;4AAdv}9O3 zC46YkUKyF*FPe2KDk^B`7M@&fS}yat{`m=V2PvuLh~7t^ zT~QHfUA&lTaobS_cMM8h%c<|;-Zmlh!z_zVE1H>^-R*ESPiio9h4n2_v>*Wx$B1>S ze{acC%E}_na#otXGzGj`k!|N%QTYlRf};U$PGB61uEp)BGC75?FA1eU)}|%dz;@CO@66RhN5d$ zy26jrY`=_lT{Qo`(LDAJ7CEFtY~NPWwK8@{Sg@!?i*fJXT|3SrRgl$^S-9YLsgy{B zhD^3n&gi=NdWIGG^$7CvzUC=wh+&+}mP(}=Rr@oc3Q}ffnS<@ z$VHNAjOw`4GL%7~uTCht+^eW)(J}<=Gdr@nw0qm>xYJc24gyV6tX%Joeu*NEt9!i} zB6f+KqP6AUb&r<&tDxT%1zL0DQdrVnVa~(CL$?ocVL{>23ve2jUc`JOAM!*TgTKjj;+UR#2^oII=&ru?BMk6(=Me8T{aE8E0+Ya0UrnU#><=LxArqyu(yhOK!c7a(f zWac_;OcI{edODn3RcH;?pv_~p-oD6y!+8&9Ubf=@IPX;7P9byR$0#c`rGXbhe zt)>{``>@Ig>I)0}Ao)H-K!9+9PM1i)2<`Yjcd=lhlgGQPZ)wR+iQ%o$lP9Z7kxAU5 zJJg5MCAE6k(O|7Sz!6VRPtc*u%O9ll=wWHr0!HmLa!+#C_nWT|06Zhvt_S2K^Ps-o zX{9L88W;d+*?sWfhk;x&=eppfeOFgkk;2RHxVZg~%R2ONaFZ?&Vh=FUm+UGxhA|#g zuSk-B_W!GMNm!gbcqesLRr1TrV6Pnw*Lt>_n%!$R6}&mpz~uh>`w5C@vFp{)Tc1Ee zXjZI=XKBWmCPHVg9F)d`|A)kRD?7U`cgqrp4D(g0wK6hg>!)OG20T=`QmJv;4}%~` z1nP#8;vJROUu$q3U`)3FmL?iS=)=ymsclW{&k$v#y~>rqun_PkwsXRP`fql?jp@F( znDiy+)(jyc9>x=2Us}NNNPl(9ZUjMSm51JJ4BrzfC*lM&Mo^3#FF-Up_4ya*@cQQF zU@VPjWN~DM_Jaoxlr8@NT=ESFpwx%(to!4~s2|ei^Ru%=)reXG;EdKxPY!zbz=o4< zf1vRC1&*p?V`KKH5nWwf$po?j*AyvBBGpETJp#7H7&2*y#dZQ6?K&xw5%Wb-p`8QA z`Q_L=lpAPs-owOsA&m@PxC@*Fk18-DLkL;~;Pm$Z!~mbUF!2jQp}Xj#BUT%T$T|}u z&_N*MyMqpC!mFZUQ_|3Qs65pKEEnH_f~bx_`1jX*ZZAdM0el>Ui7mK$m#%wA#kMdq z9s{E1gx(HhO=-tJe`a~CP6RP1P=JP(YRk68N+4yOho<(0+pil)=o=7wT2POgKYff< zrM$ph-wJ%=8bp@ive&GwPov@^14)poBW=SomvWxl1(E*{)RIh>dBs`NS}#UxWsE=% zLr^;ak7moN_B}+Jhr>^Wd;snqU!4-;lof;W^GZ9OT@>(6tw32PUwKh4_{ce<7aMUZ zM@w3(&M1ua0U}>>(DE5QPDv^c^T?16w;V-ivJ^H6nMO5?wJOx^Dbb-DwvWr1i=rJp+{qFAW zu0KCsiB;aBvW}r_nnW-E$8PC5+6>^&oBD zppqc4HVQQH59-|0+p&w}!978c1gb0Pv6zByX)SUe4@ByC_Z#mC6pv&%zSR_M%%mOO z1BE65>%jaiqd@;yV*jja5{2GFuQ9ls2h~-eVi+74AT|}C3CEz{Ae|Ub3ptLu>rTWz zS3~CPfmH>Ideb0Bb)7tVbh==9lS#;CtCE#alw<5g3$*iQ7Hg}rdY~SH!jfNFIvQRM z_fWCA9Q7Q)wE1i!hU@$Vwe16o3Je zb`217cyILs1!&gajP_t8=&VzHmgw)nFW?9f?dT&1~J0YJASjH|BgV2wMr% z?+#TYtI%cbJo*()TNuEmJL>lW=OY%`=mrz-yzWvaf&5(rdA&On?b?+tp~*yWfhW@8 zAnMJarEw`J<@wF-{!D13F>iebGW&Q}ic2sSht>>kCn3maUVwZf6Nc_+d$gNARWiCx z!V=MQz_9mBkQ!I9CL4Gapu$&CP!muF&xG~5kt5Vcti<`l*}22vyf?$mH3tqHKoO-o z#=n_`SDbIY0(l*Q%mHL|c2li2FO)Y^J!e#U7VkbwyC9t$(q=pGGl?3d#0( zFwg4&;lu+#6$@A1uO~|tsx$Onld=QhG2rFm6loQN*fGa-d5$$k&L%?wOJNHlh@v7D zV(&1ZbMzsVEA{ND`IOjsnhPvA2t<}3rDH(&|H&=*=(zXBBQXY#4XMgKr6l>}b9?@F z(16#uhBh!P6QWBb9cT~_AWxyj=;l})ce9WvoYU2{aHwUnCtrg4ttM6tV%QfvQ?y5a z9=PbHqqxw3uJ+p6MPf(~(8ZVV5*<9l_)DbG4hLF?gS|IH(fj=C=K-|W0mBNf z|9YOi2-0Z`-sMKq4C4(}2;u!O+O&7?-Alx5qChC}wWm1T&?hS+_vUJs?zM3Lc1`%v{3? zhU!w>rV>&H(2ez-h2^@sPv$tl4+0WD0_cihnTQi32mo@+Y07Krf!nb!qC<0T$} z%pcXX)^_)ENhRVatK{SD~=ydr%?R|MT)!QHLSA)}OkWQ!47Ah)D zA|$g^ijd4R9Wq8@o06eaB9bXG3n4bjEK{c#L!K#UPhwyr2oN$gi&B$2C(H?QOaTHf|eD z)|b6Py(%g+c=Xru^*fcfqQu8jWzxg0v1^%|nLR_8A8F0pMB-1X809>FqYAlold&6% z4}NecuxCywZ}h%!rudua?vOl5Y9w`1ZtmCHGGe$p5msNavJ~#JF2)QDSNV@RFw_WA z(3pmVhtq59#3BLs;6!6D<4(HQ;OxeZ4aM)aV_vZALM+GPJWSH^ZW*BiS;9Bm3JO|- z@5VCe*m8awPjC2^>0Tc%9kb)qT|p>_NL@2h#eRRI4L}8C$`AMib6>m{pH){s=-qID z*pGpQhiKLUtc+6A%2)jpKy!&sf!u^e&~uE$Aju8hmdQ&@^g$EtTl4KjGwMnMsSDQ4 zDZfL2^)FEISJRIQE=)G2rR~bj&PJAogO&a+*0c8<_Y3gzlc)<8nc!KzzDGs#-+Y~F zX>R5h5U76fV)=msIW%#xF^^v8?0%vSCWEGgrvpL;Os|ceca44Hef10&39zFy`+yUm z#hrQKmJ~te5i%cv!X%Ii`;%J%0UfwA2T1{rGPmI5k_QGxvUgpggsq58K{WJtU=2y- zit=Ei=VEu0l?cWVI8K~60W7f?_%+vB)+{#lWTA2{S6>WF`hdka2xb7}h4!w6HLJFb z-c3y0YV0|!1$P-8JiqJEz=@UIjb}z>ow8AG;}v}{iW2xIoHd9ei8~aMGnhqtI4|{w zJW~KmMdr~!XFrAu_9eYAsFIQ~Acek}w8UrquE3ZK3GxN<*UiAd0n`9wAoWRd!@m9d z8F!YBINd;rcWdaxY_uYVVNi^>R@_Pj!-F48n%am6Ei*}pd(Xmcy#R?|5is5d4Bc*0 zHSI3ce!xAGVQ~O0Epi`pWUXDS+m21AuV23cCl!uB>r_=$VW$*^V}22FVzbq*V_g03 z-pQGoZpGh_F!u>oikR;W3Q{Sj-DwBki@-pPR<74B6`RGoC8Yt%3xX&i#b}!C%|y9< z1&}?_lAqI(XK25Mcx(pxC-_&W-=4Jym-Xz_3@_N20T0KLg*MObS{ z#szagE(dEVv@`G>f{&IWW?Enel#$Ez2}T&E=dSX$|4%JI?xk7`q!2+0@Fpa>P^eUK zb@pVLQtEwBEYM3tdwedbd1zPMjh#%wr|iPST0-WM@ek0Id+07mgE#Q)_{fl!Izm5S z?Dl>+W_d%4hMn$~R!GF^Gc3?VQv38CKTkCKp#UBX`7RJv@Io8Sp{r@1R}~cKeLi4y1`H&2-k*`U3!3>C@-E7>58wh=s2-h<(XIKw5An zvsK&fS&u?m%LGg~guE9n<9Jqq&KP^M%y`?iivTx?9vc%&_AXux*DF_PHT@FPcM?k$rW2zty zm2L|fNKA(X_VWC`?V31F1`t!gQ@Id)k_!(|#Wx>#&`>@qks&nCcsLzLZj)nO`k7p* zj{Ks_5Z!5Jm%A}TsK*n^=b6gIU$R6wvjF38vY#$px)gVFsr-u9c+p}^l7M{=4GSZA z0<+1}j|D_wghqjPQad~8V~o<=#A{}U$>oXVWa19eLDYkfBx3Y-0L4OPyFy@F?=(p7 z2`aL3hTH^8{9JTluSYyT+&;s=s~;MVY>_X;T8r(tFl-psMc0jP<27fH1YSd$#OP(U z?L@bN8=uZ-_o06y;ukWHH9pSRqSN|znJMx-tL)gA0ty35Yz$!KoCDWgTwF*!h@l*< zs5gXbL)ZBXEs3pQE$o>BG1$dX=NVXVWW||s8??&v#~(m3M`$^0@g`8{M2zaod1%|Q zangMgDJr-UakypJ6wpBJ0920PyizK|zLpIBQ|Rp9P9BE(2G9ow)DZADD)3rz1%ofd z3mGnJC}Y_F_DzIQawqUPs!}NxheA_gRcm!ME365W<%>H}53C6|KKoZ5 z070TcfjEe0L7>%u@&?=86tFlMoxqCk_RkXSa!A|r#Dz=B?GCU}4j;%<)*^+Y4eNk@ z66b0Vy#H1Ry2UHt6w1&x82Mz!(7vUe$;j{6xMhnnQdW3Ed0Cmy%gQ%YJmPXO;n;BGC_kD24F>rpC2fRMyL@dEEv$A4YN$ z3JhSc;ju5;+6wE3_FTd;AQ_UH0Tz$;?&zxap(r^B`k%}m^6;3bFtVc2dkbM|kAh>E z%D-|OQi;OT#Sdj8>B>L4VfjU9DyiMq#+>|LEqo>_{me&WlIL4(MDY@s8+z>V!yb~M z+=7Bs#6{xD0Ao>-w@@;iEjXn6cb&UBJ{wkMr+@$(2t&lJt3dXl{y>Ek78UgpWOBG| zscIUy#XWIVVsKj$o{hz14G#aS2C-}@G7w4xKj_^cO+X(G>i}^OgR%=hc`*|J%1mp9 zo6*Et>@m4^$5e^`kMkePS0_L-DFwkdcOW2OB@(db$ z8N!Rs;q7DxkO}bqzpq_;f}!0$`@$AK==D*I$pVfdqy6CBp{0aCoj5-dgO`IGuV~XD zP?canvkH$u910$Ei|E7~F-d^F4pRjE@PynhEZkyaSF9nbmyCA|IKgB_oS%P1dM_>L z(SIIskOiXA7IDXGXe`!oa~qFm{sLIN3)>u7uo@?o%s5|}^sw{n)iT-G7D{W0Ymb7O zYRyiQ(OtgUmO-_;ocsQ1#F`glAQE|xQri-qPGnpH76k1MuYu%}`;#t%6((XqfCs*% znx35*ipfpc(FoTJ&U&+`Lk&z3Vs6KdCN$w>+TdRrlzcxP85xp5 zv40eBb42^7?P;-=qJ|EE;OZ`lnK_%!USPyXkfXdeIoO>)PdXQPYY_1@v`495jd)nO zR-Ne^Y0&WWdtWC;O@G|d=32Hn=E!Bw1z!ZX(7cjy(%#4xw zMoe|w#Q4S=E6a)y2g=n-g|n7z{)f2Z`~F~bbMP* zUoLy(px55e#OZXmn=zS!N>E8@`@e<^ZKL%@U|NZn8RErHyo`TP(7g9}k2^hldS-F4 z-Q41_AGPiI`9H3$kncE>%b$JZ%%8793auEI9C9K8v?p#VF&JK1Jio+8*S*SEwP#ev zHZ|bphWvMbZ@o5E7!~|LQ4{Yodz`rD=Y_nMD~_0uCG>>VKSxt~IUq4eOGhVWePhav%6stAJAzbQjv`W~ z2ltEa-}psh&kf|`u*XM#~60);4ad3K$Tk3%9@l3g~bR9Vf=!;^#DlYzT?(zYG^)7@mf?5|J4 zU~o0(0F~AuhL4Z)@|@w!FbY|$%@5nSY?;Tnsgqd$3|8`P-~J6c3WCFy zju&=Im}?cPWi=sgR$K1qs$Oy?SzK$ikdTn$;VlyA@?Lt^dw5q$UjCVD3^&WXZN9WM zKHn!Ryg1yo`)L~dhGywP1(ns`VD@N>!@Zw-?XjQ{x=`%zHp+7bGzahG4pau;f`Z84$Mx?_;72c8n6ZHySSMuT~e z=TK8l!w<_EU8H`Vh02p%-9;92W5i^j;fpIQGRY&L!(__}#*>WMo+7aug*LloyB?YO zk@D#Hi4$Y@EaQb-Iiuj+w191F3pwE>xLAweo+_6bK~yIen`Q)YnXnobuW05AZo8C* zZ3^bNnjjkJ-6p9UzlYWAj316q(JyBzRzK2et5unFNS%f7t`2wadsL&SNN;>AfAkHd zBUK&S$LM>z6%Q80+LST0Ek!PVIHtI!yV~PIlCg$HGU`-Y$p{1#5h2Sf*v?Y|@bbOOF0_C24`d)uG^; zevQ>a0VxBA!Ey6#ZPQOWil+ByH^qFlr|zY z2Ea0gs;nJ$5gQsiq_~5LN}7B#NL!k?V+x9Ho<j&$!YnRq0J=fZm+v z79K{8G)oYpuuvPYYdh{@N?9dPEQf!@s25v$g{Crw9CNQ^6sWN? zZkqd*`IZZ?~lX+q0Xo!0*%gYYo$2DzLe<{ zth#>1IwOgHiG)BJ?ObjD#4u2LD@UnayH13LW59lRc$lqQ zsbW7`6Mn^4FJIni8Tr&0G14`L)Y}eEqVRk7GSKGz+9F&bg3KiPs{@KGh{+xT=6L7Z zqW3wH|( z=V`3@Oq2(MHbOsoToW4Zj^Zfb07lf|=Hw&3(Nb+40iK|tByeKYqA83l>{jf;l$4=B z`)-}n);Ul$r~?^b0%e#+^rZh>DH0d*qo6VUg<2R(sleV=tCY5nlD&27jl}y%7Yzz3 z6A~8kUieFJg>nX9pzx58BnVZl!M3vmC+%Qb>3@N(YdiGsKy-LA($mwAY8Q`vD$DT; z+Vwc(3w2nd*Q~pG@y4s?hnI@(v{4Siev{5@jVjCWXGT%BQ`}Bd3j!PW$cxItUZ^tV zMqFC7Eq5K_7KV-Lrmmia$__j0kW)$hU-)DsPVy9c77oqD~*-cB*@fMZ4`I zZAGBJi^BUu;i11(Dbd!R^m|p6&xc^X8~z5U@zciBRiK#RG5h*irm%Z_zv?xy(!ER1 zoCL}g!c=2AJ?T-oodCBGTx>zcqm-4E)o3dagviOk5WTbPnH=aSD@s4)NDD}o8)|Wz z9#=a%z@s4JC;?7DCOFLNm4WJX`M$<>G2RQi4;;Agz4)THpw301!nY6@uhL&#H`1Py zfMELon57kTS2SpCXT&ZHxFTfKWly5Mwm%dK-jns5gBU(Bs?3KBh87Hm!^TY{)sGyx z0_`V>yFVg^C2my*X(7Egt{Vm2=RBi|g-*E<`{Ly$39}%D+1-8C8Q;%7zYx1=HI57p z)i8aAO*FdA0HrRjTZCU(7D83kmz+)Kd-3nzd#VJn%AH8AX8O=HYLco4c$iUhw`l9B z3%xugg;a3qP(8$(H21D|vW2V@!pw6m*K z6YLxNiu*hoWw&pa57jS!E$`81iPa4q&`6m+u^LPh>Vz=t@I+{3rTB8z)>+Rvh4xW# zw?gtb7P*x0EIv-SK`NJpOAsT%!}HzjNtSdT+ga4jC@Yhi^6Gb5)bzDdII@>LEVj(d z#`;(N;L7uMb(_09;tmDeRjB_XkR#fuUVLa6XSOwAan6zycc|K%#fM^f6)m!L^z?QY zb@!MfH1kJbZv`fNL?6z@ZR=zx5IN%^GAZxDDV4ZZ-gBn)mXYvh!czUU>wipMK&zhhOTmtB2cnq z7}yi6;QshAx`Ze!z7#8*{9XpvD_hnD!y3*R(Gpa<9{R>YFjfrPobom)ZZ0kc)K*;5 zmozcpq{4kc#FC>#GjWPHW2Q9RbqiO4Z40{NOneKrmX_FChogQ{yL<+nI}i1$Dbc9R zm90M}AZ#3%a6z!zJI07;F__1Rm zyJI<*w_wyt^w;5juYM^-3)k_CfUmuQd_6zQ^CQkY|FPil{lseMha&kcdw1J0x$l8H&Zan%+#6yt4!L8;jpEaZ3>+MPT% zbaqzx@EmB9#%SsQ!cWj~sVZ?<|e zM(M7Jo7zPTvRq(VQ9oDxC%fFQJ{Gk5Ted%?-=N#LT{CBSwNxT>V)qhu)s=kjvfaSR znTecD^4H)zwDXQndQjwuxH{OpNk6q*LKXo_P&TbRgeT6}X(r^GMtSX%+BV!mnuKO& zCbqrp?J*mZ+nQQh=LF1~4UHa7G_=HX1kxh4rg*pBDLudR%2SWMy!LO4o#PDnyRkX7 zvkiAY>B)w{^+QORRO-di*odN=$0B(Ge@ChNU7WZ?E3UcT2B`VxmQ$*#ZRBErgsCNG z|EZZ!TsNiJibzQriuJlBH;Ahrl?P6i1+N(+m(FvHOF{TFiZErHVXT5$}1G0lRdAHV_13NtjbDE%(qb{(YE0ij@kwMsBUm!M{Do>H;6 z;4uXXd^)6~LpPz47fnx$eW@bAC6M7_ML}t}l`uUR&|9pdPP0JB{Dzt_6Msueo6Wx8G>k^kLfN&-uV(l^ zP4Cq6{LIe2;&w~I63Qx*Fh|?A9l-!qBMha};3Z)U;VE+Yt2b{%!rqXPUve*7SWS-Z zBYBY00EB(NkzO0GEP((E+Ac8;(PWe;hK&Z!i3>Y z7AG3+0RXm(cA11{g+nnaxEjIlwB;1aM^Zas%xV7pTJJ{iNUb>Vumi|a6b|4E+AOR< zJ`?eu!hwl%Zqt(h-a$HNY_M9XFTfs4F(D%A@=164Q>O+Z-{7WZ5?kKxX-g2Is3n=j z#kz~XDib_~w5 zO#qvSk>dzDtUKM~ZNNX$ptwP$WQFS%Ez3UW7yzZR#qXn~Jqo!&tmBF)9mGFv_`nL3 zeU(SCTL)>#u6QhMW=hI2B;{Gc4`Gl?5#CHXmoJw=(idH(U~C)@LNgnp<@t{Xyw4!8 zKnqKXA%bWP;e%O&7}tldA&EEf@!44RQ=z?X{c95TpPS!s)I+4+0MSVTrVz$(?`j8{ zodQA<&7l>JMOUSFB_3`Xx;`=YHxRWI;I1S^PHlFX)v8iMd>#GVN+!z zSVK_^%Rx`7g+L0dt%X1wn>XWM{2>jhNk#k9XrO2`^1d}@B}+#iW_|;5F$Sk>P2A2* zN_r6aC{xq{E_`zjtQ_UV%w!WmAIQVQ86&6(aJ7$)CEsxGH1AfS*bGyq6})28(H3vm zwCSH_7l#H(Efu@j3gFJ5`$ASz{vlS1>bgqP@GWd}1t5}x2x5$&sd@f<7D0Fr*O0tp zf^tK>ZIu~8Nz&=S5|&VV9ZL)^AqEi0kgOB@3>yJTrQzcM$0F)@(rDN8Hvt)lVK@V` zJ&8AbMqB$Xfm#1~+PAqh5@bBz^xOl~(EBM{X5lexUkRR7`nhzB39g$g7UEI+jz~k? z`@ruB6C{}l%zJC%aCCjZ6N{RyLiBK01)nAz8m^<^k%sAWDQ>bMB?DCVcmgWumM}v8puwywH0I=* zDHm9UO#`zq0>u&F@81N%(7AR;%>*`ve*2ux3*p1)=sV8E5WXlK>^vCE_ zEEF8gn7PXUQ>+AVLIPCX09_(RH6qW9j z8}<`4H1~mZXLYhE;}8OBS4S$&BbOck#;TXn*3n6W4BPOZp#N~o!XTbL?!mAIN>4tL zD6~-tZa_l|c221WKMiX%P#hDBACe z$Bt-zT8Vopy2{-18r%_6HNh;s8E-%_2x>MF@jy(^y3Rz1otL_3|N4D$;XZ5cpihMc>_-z1DI-W zFv3~Xp!x?0qtf>`IO%xKtbDAL+&gkULHQ+;8?O)utLNszXfi_>q&2{(ZpT}J$B(ck zqp)pYV(Q5mDRQrl_%y(TEJ@RwR3xhBQ? zK01!z=p++X7J~L;I>zp)?r-`h0Cv3GRdd*VGKC1Q5Is(jY=E=2Lv+Bcx-F*K9a;@0 zB5&O<)LRemfLbi4H+Vm9bUWU2`yE|k8Xic)Ah8GxnTih}r~Yh@8o9~1|DY~_s$zy9p6{?UEkKFc1@69o9u+d%M6fFexx!dN5Fq?Wg%1~wgD9*{s^0N8Q=JEv!6W4D^i zpSE6fCzTt3g&f8(0TU7j=NB7vtl&v7CMF&|TKY(y(ITvX(I3;`%|K?uF zhe~GQL=G?+a(ZH2Kj65aH6DSsaJBAgE^=%L6bcc|H*BM*A8WA-K*}-oEaN^pc^No` zLEEkmQDqDE`84|J6L^w~3c>+Na5F|tDmt|({XVFTpW4ADM+1IjI4m%Vlv(FQHTj1c}RZgx1%gdlBta@99RMxK9kXcI-Hgu!v9% ze&ptDZt1Rpx44z69A*3^q-9hOmLu4=5>VUb1^rG~A56RRrnO|u|N0^J>+(Y2d*#D% z^&1l`fskNKFC2P3jP(mSf9W+s`Ltg~2hAaIYeRXW3{TIyHT`E0XiS@6YTg%wE_XAbHypt>q zGlziSVDk3PABw>eIU^rgth$2WTuN@kKwE%(LQd10{efE6wzjs@ezJ2%fbxwZ_F$#+ zUB4Iuq5ma)^g=2p_z^>MYgu%}9913Kqa926fNt5&AC&Z2;&@0^6Aay z&hQX9`2tGMJ-|vqN8`!A+&yLtAv6kzF=+C%6&3w4Hwb*pbdayQFRaoQ{l}5}3QMWO zPRyt-<37DodIr4Og`M6q^7Hc*%`z*I_|aynp$S<=Sw-nCB4XTgPDL6V16+jLo@`p9 zK&fObd`pwvEhA%$B5LK@we3hTNWt+tC9Mw);e?%ck@xg~7|$A&$7p9BDuqx2n*zfv z zllVRC4otX+K-4kb^F#-S2U}I*T>n`E$Mq=5`xd?zl|s5#cl-!KRZq&rJcLkEpdt%t zB9@?`6R|e_dN(2>6*AT%DBUH1i^ClYdiFG^_&dkHAF45(vrj+8vTy<^ds!8jC4*Lx z##k_LPCIhz@0XV9qsqK6J!4<=q;`*E8lp|7c|>V7FnQ~S3D?zj5on1KcYq3sK2gbH z=H55LJIqWFmXTQqzpi{iHBAFE5R3p=^a#BZf|-Y6C^<%>?W`0%3wJ`heB>Ihb)Un8 zb8)Nh8}(I2dWtz5I1;(-HuTQHaz3NllE0F-~-YEm)H}I_a=xB|WJx#hHLG(deb>l{6lqwfE z04n$H?Ck8JRtK8x>!C}DP2v7ng=d5jW8RHA_QPP^Z(v(SKcEHgm^dk1h+I5V5$t$mR=Pf+Qf@4Q9W zDLKhC9D;I$G~q*HQ}OC)&PxUh^=!-KK!5*{I}zOumo^#ELy*kAL6B+#4Pq&DOel^w zeagLR4~$vA;&KTf0@88;;M?A@jYaO|Y~2Mfv(H;ZycgzF6PCsTPmRU}*n9;xS2swI zD`#<#5-}-1jDnyP0|KIuiz?3Nx_|I}P40p{^b{bO@jf#6zQt^OcL6 z25zbb(^MSPlC66|DNmzW-YX`igZc=q<;C2iODMWJGpdosjEX)H^gAU_GT8%CxrUOY zWsQyebj`5He>gQIn~u#Zt^m+aBK<2A8ZFQ(6Tq|w7Xv5dJE` zQ^Mt>+{@%E6jhH~1PgDF7Um1p4Y zyc}Uqo!}gh93r>5L?=A6$lEO-@HwBWdchIijid)eE-!^@b93%*lx+ILhw5l!Fb8

    ZKlN?6o{hSo19yO|rG3B$^( zUKOT7Z-ACv4V@&6@DlfC7jJ)uibr1?upP)3Vb|f|R*m`8%r>jQQe7SYA|V@*I#eK0 zIA|hJ6sp8a=|P3IQfUk2Q-6!5@ea_++RV17juDEIh!+Zm(_ia(O{nIb?<7k|Kk4b^ zlO5gT%+0&Y`AN@HwvU12@;uVFVXzI@0LLc>Wj4Q~2(U+N`8x}2BO!W1=l3VHGyD04 zC~Y%NR3f`Nj!<%fZc^O%stREXoq^c7c0T{(=?{EDLlB)STsZDdLui;kGDj*y40HWM zv*Y84Z(+kPfE6p#D2e^3iJ+mEhuLp48Y*8dw$fa9TrHDa_8P`dad-}|wG(7f?PJVZ z5d(hOZf?a}*!)m_Z@GP=VCzc*>e?Up5lF|4n3U^o~V2wE0 zq*NjUq0ow7_wz$CjCPMahMkL+0n*p4s4KvTNp!qVT*WK9G9LP#0&6jdA8KrHl`cW0 z!5e*aIQ%D!=e?G_KKt7e)RDVoWlg{@J!M-;QSb5r-*lV$nd)I1j(f4Kyh}miaQ18x z682Rtbg|gY)qhIGS?~IdqQ0)5OnwK7Og6a&kb}EaRwdimee87~7udoWwo)?{p6>)RaEXC+KT_}%j6Ha z)c@ZXea_*nb)GLY^<$wZ2mOJ45MgVE4E_6ax9X;=Jbh@jl`^#kKNrgPq=$RpB(>~n zk9}mFMcC_)D_!`hMhk(+Td~V?+5Mhv!|lCz`&&%|X+h84uW;m}mOQn{18en*X~mJX z+@}in+Y;9QWPj``s`1a6b*B5Pf5mP2U7O^yQ{7kqQq$~z8A7eN2FwEcZvJO~@Kd(s zRM&Y_yaW4uuH&lRQNTXfvJ|@@=2k;#6-6v7Jkh72DJB3-%8fx5v$T`JHR}h4sjc~F z4Z@sQHX>BtM_-MfIK@hReZjHCbU)-5;Ip;d-Nj4R?F(XELftLISR&V92RXo&Z1`YH zOkpm9?oV=g(qH-Njv5 z_pz}?aA)KDOTXz>5fun7MJBCd=$kw%NU>ECxPg40`_J%;zc+-d_Q&qRUTX}xq@1O1a}D^5}Tid(?$Xd zfD1JBTb{TSpLWO2oujx!nTczUQ{n5Zflzek*?aP<$KFz%+ecsVDZ<6~cE`Ib__+vXjBP}(xL@c^4(R9@Rfw8Wod_H#yp%s|NHPIUXA-{0|O#PPq z^Qr{(tNi)m0EtD?U#phRLhgj~i-VleM9ERO37McOfQm~ogrSA@7vo0h6%{faNi4&1 zzy~A{ACS%Vk-B=eC1Jt5EouwfZ#WTOKTNpgqs%3UO3_=#TZr0pMEVlLY*Rm0y!5!s zISY$XyqXSzIBDwfH#?pD_@eiph+|X6n>SyySnNdK-1$WxFKR#X0ptO z{R0mEzf>K0*CY>ra(RLfh9FcYzuSbO=oZ|kpS2gFZm+v1Os>My@boOl7V+J(+2=MP zIp7H9N#^2(EpG!j6hO4OdGqGZpkRs}%9lFGTfQOA@{5WR{7nLdV(!tUjYsezfEDQ= z&7>hO)PHR5kA?x3Ms=W{)=)nqL!1Z!O>`n?uoQ!SUvUHxAE@*tWK)dQNufT4Fl-N= z7iL8*>W^dp$Ob)CY<3NqzFU^pwjJBb0nHH5A5O6gw?hJ}jiAxW^vox-~#_ zpr^>>d^2q9+rjxlOaFj?DDcl6WII)De#l0Idgt9M9@#yv4Xlo&(do}U-9v|cvh8qg zx{5C*Lwv!jIQX|dWFCpptC~=!v-f-0p4h85E{?_*guZN#0TQ zTpEI<+!~W*fxo*eG%>9ND0W()qFePbspOC<`=Z|@MJTHcykZ$SIbye>@IwbZDS5v- zi>X>Ie#0fXLl6w>4 z9#tni$s1f_cDr)()J>G}NiU)#%?A_|yv&)Y)ZUBBB!Sni4&<#lUDac&as@AS!TaLeH=2?!|?%w1KrCom!*(3Xe10k?LmvMH{94yvlM ztkQ(GXk=n?;7N~a@A7Nx{qy7VTtw+0(jX~@#>PS=fOW~%d^a)OL-CT!bl0s}MtxnJ z5{Npyg$*5NOxPs0O0`F)hkU&2I>0%9eDN3UUHW8Tzg+uJT;9pads3???Y|6v1#U=8 zZ=#Z*air+ny_mOf#psosRU$sBou#2QPh_Su&jliu`v${<|RmYX$zh8UEK&{QH~#F3A7W cf_zd5a3{JYy&j2b%esS z3p^KMHCI-56m~E+a5T5Id9Q44ZT$S%}c*OY^07gsFf+v5{x3UK1R|NB;qBE{ExAsJuUFhEoV zUq3eK!zjOdE#eabO9vesM35SXMN|L$S~-VGLy9b97kg$c+NXDzc|io*nW|2u@*tZeu2oy9`AV&!=3`l{?Mvhp&ZoT!94( zG^AL`Oi4l<&V^T!|+uu+%6|20<6qa&fHjq#ts%ZkZqp!iSeFXaDi z>|*}wP?Pnt|EH=CG!h|}|EWqyIp)8_i)Na|7+tQE_i`~z`b-%NamuTe?--~FQ^9AcSuq>!?Ac^)c_ zKNCSAlTul~9Yy#HG9IqQjTsd%9WT>}s(%Y+-JL9YDNDhsVZV0m)0$*^DH2_d4YiyB zh7n8zP=qfRnA%co2r*G|cn=Umjp)q6UNSX|8FVT4d8|k@&y*EV?{GJtSw7a2hLx<} zrms%~e~=5ylPgDIv;7qiTFpPx;@HJWw=+p(54ttk<%{1*a362<$JoARdiCnmjI)L^ z9AWfqpR#!FL<_%2*K4+l=mkLd$o1Tw!u2A{2_QDLb!= zI8HI=W6FV%SvsiLG>RtnN-4+j6p`o9Z%P%bZ|gkH6LA5B>o)t3zbG*BetL7{BG!MRNO^sYkNel zt<57Q#Z@P&2$JF8v>g3h3HDO(nH#>mILX;jXP$Nu4sOk9v@;$*3s(ndx`qdoI+!H)nop8MV8t&SVzgc)P^D_xW3v)=Bb?O|D zrdSjFHq3R{GuT`h{lf_|868#^$O^xFIJRfN;!X78-WyDCreJJOKB z;F*#i#s0krcV+gxO*I;SSzvh7I;fy}N-FwwDoW-%xU-6tXvU0K4Vw&wkz4|3A~rc5Psd5HcIx| ze_aetNwg*-nDmR$-rN;JopATJFuc{U>+*yO14~DR&jX|W9;MlKw2yeXnqY8{l(1<( z-1{X#zcX_Yf{5dGfxNH7b6izA)fM^_ydNU`b`>QJup%=14tFO^{+jvhpF=FyXXJ5( z$M%efJv+X~=XD#I-P09xw$gT|c?Wsi)~#{i__s{)9S~tE5+2BZov?7U(EK>SjZmtc zsvtg#3D_MAu8X*^*JuGjaP)A@*bIU!zresUEUxT_6w+jTeWk8aLWPSY!arFI#j*zf z9FOL3PB^&;r9YFU2h>K$z5M*N+%w=}%Hp%A<3}RcS@<1%%#S5jMi0SMYP>Jp<3Rk~ z)UgE2*`CtwBHyeGvv5u}gWW0-X&bbj74|1GDjI^`Qp%0hq!7zS!2-kDuZC2%a^!}X z@+A_4K0CrFU*Zb_605}vi%>yDswFduMU3tjIz!H3Z^9BQf6Rg{h)ICw3LL{oKRdpD zJ122Q1+1PJYVR`4w6(=npx5)qYrLbu)`V52}D4azB-3bQtkU z8ND9g&UAIGq1+ND!?!JIHs6ljcXd-9e`;UTpDl*s*8zfq$v+c?fr*e6gc#y9jf$dA zm`&}*?_S`vqE_UOsBf2ggh>D*&pPY;EUoFNGTu?9{7O(1uQf&*T8sdF76pYU4Q)5z zkLq4sTaqvSyUm)<3&WH~-%)oG7rYRFo{g9Xt$dM{>!JzOd=`gt%4(e<$M6_`^gHP! z+@NzF+77of-BVr>-u>XzRNC&-Ey5Ojt3A-W#(oOHLGewi_H~YXgUSyB!ORcA(kQUnqE3fF&0S6;=3^`WHt}hxKNby^+3bhS{D$@YY8 z6jvX1-qvc#rB1*Hhegp#559pYe?(kRy3o`La>{wc2Qa8(ZL7H8YUzt;OH)vw&a+20 zj!h+$khdxub$PXQveUHX`Qw^tqtAn7c@p`pB}3u(2STnZ*16+lah=_17y8A@y!E?I z1j6+6&Vu|M`*JVh0fU4PZ|zn^fug<>1wy7d-btr>I#D*KzKB;<7}@X-7Fer1os~>#$cBF*{>uO~Jc+ z!&58U>fcdAkVWo!(X2w*(3fRHvz}wQr-99>>0zC1CF@9aga@h-(Q3OPOqO^-FsR#M zC+@F@nxu}NLkVSO-h~KUiGANtGM!OjduxfSfsMVWJ&4c!nMITRU&~0(zk2IMD^{}$h5mHq#U zO8&3Hp(L6!;Wuw72@jB{UKGW3Eomc^{yn~2F#K~)H>fCQHJIc~R+F3z<}8NTcvMrI zowc}G@mogY2LJmSe@FVS;ytCpe?;CE814*mf3F??uiBlS zYyVr6=J(VW@8Jg8}{Z}vGoX%cT40-Kw+_^P&?UkL8RMLyQD zeEo|D1nlZ*NEtTWYHPro#Hc_ZPQ1d0C%ib|Bzb60JM6#yrI}eNi6=9g@OvEj{+vo4 z$mWv>p@$q`ocAiG{Q^c{$$?lZmvag(a;3D=FXaP`%ye}yCu9!f9U0kWJtB7?7^g8= zTBz)Sd1WxXdV<BBqv|y3KkN~mobK{4s#hCY=S^J(<91LQcnr5PFe~NTU}fJ^YwpFupjFRrFvsJJckLueGXHVheDs9M|7kQehf*?!&LpQoP1 z5T!Rcf@WN866^4R010_7MQ!K^X{swl%vlnDZze?eiQ|vv4N2Qr@HBqSG!TeCZBip} z$mZD*+HU1KH`#em<@Yh)PngI;rcY7is&(Vc_ocbpZ$vqBlG-_=7vH&w;lorZt}8ur zI&dM#xD3zKHDdTey{RofG-sD$VFa|7vES>7q7=uP6~b#iyMV>M#b@f`J@Vx27wwcg-WRZRvb!OD{7YoNFQTAvFXu}-*mh&* zfIAKr-!@tK|4YQpxfJnVB5wLyoL9)!Go{c7dc5Od3|E1%xIWpN96xdcHlZTqGyVUU zT)^Ul%f-VAAEU*6yeL!B{Tk1Exx(MeJE5^DKy8Xxn4o2*73|esu0Ia`CbD77`IY-l zx5s)!s$|I?ex$L$IE5B8SsV+Mgxr*~TKaucg0_xeLy-;-E57M+=QaFO-op;A*#`Qj zI^-=*GP0Pf^Mcsy`&K~04h4c@oHkqXpYZEaR%s6s)}`w;Aj~%61Ryr&?6lUTFvQN3 zxodKdme|lo6=^A?U6+(!xxP-)`^*L8oQ@yP${yemzjx zdT}N%YAaV|edm5mXPn!J^~DN*ps5sPf4agJeWg!fctPt~!H=d=?j$YNw8^^5p{L)~ z3K4H1ZjC&0VFQnJN_uOeuPv%p-zFofoi(=HOw{UW&hRYXmVFkvi{bmh*D}vu?F$Sk za!Q?@*beEd00C>WZXB9yiD_33zFsXQ%n`d9J0sPkoDkbe2LqN#i@8!|{M(;)-O8ru z!8Mzn>}5_YIMbXsePyUDwv(~0HI5$z1;S#JABRR^m@!|3?CYo9tyZ%w-n_9b3#HRt zJlMNgFy-^PgS2o0c@=n8wkdaf7k~^EafiL^SG)}_hI&&Z9MxW4e0$ug(ih9}hKyLK zDKNyW3CE{?LM^k_`d1{44VT2--PJfOw5H6(-r}OY|CGmsydi(!Z1ZHneEXdM2Ah#y zAozz-4`5qLnjoe>vRGhU+lnFJ_K3~gfP%T6tB0`j>I}!Oq?(ekZRLB^7VSKV0vr2t zPO~mCF=3K=Th=hPpF8XNYXzxg_9@ibo&vPOp2ECro%~if+u6|~t|t>VIhdFwnLDlV zKu@6PmWlTYscq3vVW!IuQngk#@?IHmoWihW<9;_+C#c0=k>L|s#lPYksht<$_?$bZM32ay%5roqXUWN zC72SQp>(?5R9TGt^_%T8qfyU5;Yw9&<|d+i_d-`97-VopJo8lOa5D;xE(Tj_J6mb% z!flyYa(RU=!e)MWn>LMI=0=a$iTjzxM7n1}H+)f@cU-k7Rt|Q(+MiZfZF818_VbaO z&O2LBwf*7X$%ywP0g;K_Dnw~1{3%go#dB|#k=`=(Ig=OaZX-h_N3~@^rRB>vYmyzG zFhK^Wk2GqIdv4v_p@C-8ZD1A+;piCHa6#ihJ6eQ$XN(x7sjCq0r*Wuup<0Cbz|Al1 zeIte2Oh>SllDjSu@G>FWY;kU#>A`;#Fnesxbug};YI>KYE`2e(7 z0UQ0!BVE2p2Yy`WS+;zyYHDs4_PK4Upy5!H9y`vDvuz{Wwz2Zxeom_L$o+CJg=%U{ z2BY4@ehP$h;7^r+L+FismltOC8AB|{u_d{31B7vgXH)p;QRI7 zFryLMcqKp97{{pQc1~k#@NKSb)f(%=>e@u4zG0k-16ZYd#+5 zc4Ts{lcw)22ZWO?jN$*3t*eLu+Dn4hQcjSw-ob_2Wu4XSo$qdRK`Qq^hGTnN)1ea; z>rT?<$|uZ;WfmmDt^F;lNXVAH0cQzW28XqWOOCPDZ4>8-@4b1w%cwXRxPW&v=H~|+ zUC|^g^6aSzwIvF-Wq_u!59!uJ(++b^22%&0xo&(q7ei5_JuggOJ)vtJdG1aBVLLXB zn#|V!a$r-Ws6*WOW*R%}H5!Y!s=zW;HoYX%ld~bf%+I!(1zd?5SS0JWWA(x)I~?gB z#HO$BB4u|ZWvm$0^SPV|zx1Di| z7qNfu&=am4ZVx4vxr)IpH#D1x8y#_g7sSeZ(iwGNC@|i6b?E4`1F96JT;Q1j8=qJR z=y^WqB{KD}XMKBxM@(c6aKY1SpG&3-!hCnWDwE>rLUC5VEOLEv9^#(5br7k6N4u>@hmXt^_PWQ z{`kDewaAiBgSUfHb*HUTre2toPgTCIR7 zAY*cX@A~UodYQn1vFkn1;JK8H6dAWzW?V5V!t;0{@jN>OW(#$24dM4afA$mt7AVKW zUQ4#Y;q?BJ@;pazp#<3uO^u_AXr={mb2Ja0djWlphhsHWp+yR_LxnI*h`y7blkB3RUCI^;+TG zj__`gY=$AL+FgxmE}B^PqY%>?!Hdke6vV+jHF`mu-KWnmu$Y$U;MJQbm}qj7juep) zSSEZX!@jI7>FlB{;*RazY^y}Pj&Cnv_5=@z``R{o8^&}>yu2t4$Za~QfV`RuCI0b; zm{;Hov!y)jBCO)tb1Oy<&fe_ILVnc}8eHiBNzM~Vz_T-_2Wk>I4loO21TbjzY+`>t z&^eRy&8kvZa%Xu=Eo@M&(otbSSH;52O=+RdoOn>I)ci#K{AkavQ_3%q4Ib4sW_8#` z1J)#$WHViiL0%to4G*USkF6OML~K^70CY;DBeqqK)%0xtFdC~$!pLYzr6kkTmvh0#72=t$!LB-I}=Q-t%6zFkBwvu@7#DwJYZ z^fZh0St_}9Z0c$~@p*AHK!}*w;!r#raB9)Mr(fNtoN^F|F*}pzxv~iO(6Gy)A2zbL z(2TY%2*I#yo7r|)%r=RN&Rd_V;w}rQ-dYtc1To_jQOQPd(a5_ld(N{xdq_;!*|hG) z_VjO2wy39K7Fdsi_OaXnmFz@K3mDB#ymu&I%n|=oL~2-zEd;8q!{VyHsZ;H{KUnjd zu8IlWiSnCj#kzU&ws3olx^d$oG(~OJJazPra1Ylek z;5lR2HYK$aEXmAdXC}CGMN)R3jp%;yJYDi#%6?rm`(eif=5nf>%4a*wxFwgl)EpGy zJE-h?Zas{SlWgD~aEGt{oT}U?H#~j*Ml6)RfoWJ5;*f z2P(P_^WD*_3^C?);L;0gqjWBDeczCOlAIU`hDka2(6*w{!aSJbSj{iYj2b$|0XUV0 zatVd34Wxom6~|IW$%p1+r7+0S{$zQp*YPHno|u)~WlQYVEIzm}18f{Qjb506kzWAQ zV%K*2%6E#=W`GN83fy8~6oJ`+GMluY)?VUnnP9cwrjq;i89AFOegV)(0PcQ(z? zND6lsvv)t;U!~Jy)^U(oicSH|(qAt2x6g1J0lasIO?xjX5V>B^z|(tE}8e zbuSd_ty-H^V{fG;)J|FwP0nl=K}?soiIbZ`6P_Vo>m~m1mY8@j=Gx-T|~T@jwuH13<(Wiy@m7GgwKNn`fjAJ zVfZZT2xxjgHR5{$cO+XKq?Jb1Od|%gmG`x&WO&B1?o|jm1<0qOG zIfCyyQy;=Km=M$`{e7ptFx=M!D}e$1GgWx4x4Gt}lXqOL1FPg#AKcX63 z>cgFo2C!IesUMWglLg*X-%VQ+@+qCh{tCWt>J5CmLVzGxvZ0-;r$)Bps|D4T|MINf z0ZLt`{U)r~5bLEs0B(RK+$Ap25ef?ZIvD%;i$S#eU-Oor?QtbAdaHUaeH=VTHvrknkr9 zptoNXv}tgth;vrav_RLW>Cvyfq={78s$TP`>+N&G?);?Ct(S=XRbby@9$aW$^mCM* z{=kgakgODuA;ys#wYQdhnKCk8I8X5DT z=TIKmnw8POtxpGy*kl0;&r~*vMY`cki)|M>UpJRK#RS$0>kN1QvZ>y*IQ#&#r&ajH znJZ&SiD`;@D(>f9|1*PR_X}owZx7>!qi*od~~ivezjMwSMC@t3nW=RBAB-$P|L(|4l_0$E~O! zFoI*F6y-}x(VyS&0F~HowYlMi%&s;HxaMq!DJdsyT4Ruq!9JAj4ZJQm5 zefh=TH0@tB)Md*^!icxSDWkjI47z@{bBU!SNt4p;06xM@y3Ip1(-9wq`@>Vyp?X=D??&OST94%?4iF>_p z&s^@m+w{)f{@!(e6j&{!zD2s6z$*=*9pP+~K946N$rT{Z?qlJ);Couc8ZA9-C3x5w z`l_`GFYUE0&{PKmccw_3-mKo-#6r07HTWzd!jE^C@um9lvL*)I26gST!ArTrc-cQO zJYJBWvYbi_=-XwBls6~wHB%z%`J~(4vpn)JIJYJ>?)TwDJTmQU3&hd?-Uf4zUSC*E z0UZtHX{>SKYwunCLKmHO{B9Anb+0R+dkh2Lo8H-W8b^$m-XsFOQPh5WI;VxYhSm~W zp77d!em%%?^43VZ?Q)q=_%3=_b0zXC&L~=(s%j-zd=j4VxF#Qd)!4Rr>&rszE5!!^ zX+7TLZzHLdoJE)>x#%R0A*6Z-KV8*1X!LilnTBRo7DCQYnsHw^+AV?4!0I z2V^sDR6v)J%vR`5%f&78M9Hk7u31y68V(V~V(xk(ol54(kEe~)9o|(}U#7sbk#o*@ z5=#;L>8jLq)w2)tlyg_trGT!&{2@gpuZIpTMlq#^;!TQNIXw% zo|AAtQxPV&oOR|&O}{YKMeVPY>;j}IICYVr4u5lYT*9Eea_M8$+E(#~O4Jmeqg-q_ z-evyOk{G4Fc5PHFpXFi0q@Y^Wfp0wCn~H1o0dC_i-DJ{s-gpU5O(AS>%PallQsQmO z8;H?bEP}_5?WVM`&$gYn>Z*<4!|NIpH=o}QvGQF1tL}qWz1`DV+W*F zwYeVkY`2rW6gG>$K8uU_dPWl!&TQuEVXf?eoAN#pHcNwR;fBno>YcR{8K^-!Ix5Lw(%fD_-Zo9l zQK$c?APW-}uQj+wN(GCxb+jS9=h<^G+d>C+rLBsT$Z5+TKF%x zMa8ZSUGvM~`KymMmb!*p5mE~zQj<&qlC922X{_OI0~|AglZoO}=q9ow&n|q+;Rfpr zqG}Yi_qd;&Ov0J$ezn%muj>qM7)^hfv}fMu?n5>gj_tFVs^*Nf|B#45&~6mza#{;! zsol(^pjf&K>)9W_+w~R$E)kY&=98nfS+f_nH`=iWO1F}1l|oH`$)S>}j!fXEGguE# z#WJGr?iWLIQM}J23A}Er+43A3J7?;T-Lq@!`xO5Cs*r7&`Zi1X@iyuDv)vg^+?ASL zgSG9al`ioY!(U3g{ZZ>Ev*LsBTAdNIU&;^MKf+*_@o9O!&H0865Sv^+7y?;G8}nrq z#U#5%hpyojtfAfGnakakPVUaGVnJK?7VeB?DDSm7yi7eD&d;40e$=rdGslOKt+QbM zavFfaoX9c^8j-hNj98ak<&K;neS&*(H|PJR<}JV!HJKa!=@NRdybJzH4rpl3WxNAO zsy5liWHR%EUGh6-11lQ%+{o1aBsMY$l0z*mOfV@q%fXz~seIaItnLU(*u#{J79V(h zM>76*+(ip1qhYnP72_`Ju_Ebke?tONX;=geK=&xTUSADnfH17VGScSHlp4&!`m1JB zvU>L_rr@-UUVha+y?=lk*_W&TX3hLs6#F416OaFGeO8Ap=LhZ=D6YfWT|*cMC%X0D zmVGwY7d((qA-eq~DZM4PAMjM{GiRmBPo`S&T+5$u7T2ZOS}nN%O^Y1f0iuVyQ#8TC zh#VOFMjSvs;C#I!Ec_K@d%!L2`p!$luW{WwQ^})doJj!pB=H7)GJx!KqbQOKCpk2; zjaNo9QDV3>gyUtOiR0mF$SuQIs|yfm1&{smh)D+Ao62vV;PLgs_9iyBVbXkEnQzrI zZ8!;PM>P{tXFns9+4%rezZdl>@xGgX8gO1`#L>5y!_03WKrEV(`gUJ4o*)Iw;Fxkv zrE4o7bsGzH;QBmWsVD20*6N2t`KbeEf1U`0f_%%g7OvoEz2B3jq``BkgNS^`B6j?6 z4@EXJ7_U}> z8Db@GJ^I=GGwF4Q_+;y1p6f%;%-PP^yCr*zS|E0wM*`2Fkw_aSITNf0Kb#6lg&}az z4@?81aItp+uDiohc*B3hg1JtYKX`fq2F4o$DF5_T*LRfnSmH(kIXb(X$;*v ze1b0?83E;D3S}Q!{MUUBL_SdoPc%iSx#BQJWs%kIf%U(6A=!%3rbk7adv3BrzVh zV=hG1`omE^)nil0L#|WelIHk+A+sYrl5xH*4b9v+mJB;@B1!x0_j(i8@r#Z;N$}D^ z+mE~vbF0BMA=i(f{Id5Uh&UM@f$_K!GfcXiEL>b``leL)jMI_^HVpo1&S^x$E{rYx zA0k(f@Hta5rPP?HX)#y%-*TU3lZ+d;G0OeMy#`Hz&$#MJoPnHR55L!?9t_ATW z3Ia8XGnM>p>KlLN*Qv7Gop1Tf%z30m&1ad&0c@TtkhzubGkHdyqh#96uGKvl_)){x z(Zn@u4?^w+|0oc~(*OcxYn)0Vht{V(+pcek{t{fR7bhm7d|m89yj_$EdJ{$v^i?Xe z^qHtYw{bdHht%KWPa38F0hF?dTgJ3{jcBtSuh4&&(r_Ny#1?oW}EaL<03S z8cN1SxU$uuSI#G367=cH$b95h%gk+NMGz68)VbaIH;`5RqKF=Ru8?~7s$&ISjJJP; z2CDD{!=KT)19+E;kP%gzeI)h?@hn{=3&`8>z+5!;e`|E4IM(?UzXiaepZ;L zvf;;j8dcV&z11j22vK~5jg3!4AB<>qmPqh8rOIbS&4C7?9JK0hrbW{?INH%0+{|)h zsmF3Xjs_A2(b+Rwj(+TYRbZh|*?CFZR#o^+hfOf1J@1C*U8?^9d*RV6_t1tH+IhbC zM?#EACenXeAx?lnxddCjOggL2zAVZ@1Xj7Y6kyY7_@-Ar<(W1cGV2J!lX5$Jrn)qh zJKF|{_IwFX5jvM^i4hu&do+WtPl-5)2C{E@aNKTJkPI2MuTVZ0V`0IFZiEXOGvS5I zM8_o4hW*^JHfXt+6JL0nFwQ{Ftofsoh@CnZGZcfKhpq1?fzKho_hkgvbba=e%D~Sc zC4Q=)p~4-x{JJcyX+|+vfanY?od6QQ$K#T`3ogh zj1m}J6{q-P&cXn3tFRpGF%)>jNm6Q;3g6A)WBiVG?c7Ji6mR#`!U)I zGJuPqf9&`SY`V1ZyMdhb=r+=Re8$2aal!f!gY#B>$crmG?>Pdu3kLkZgKv9`glZvx zrb}CYYW1NF9W2&#ZSYWb$m7!mMrN)aHvORjYrnXXy~RACTKD`ZNwL!3;JTwh)uC(c zedRaLINTppoX0|#@k$dok?oR;#7e5bm-hfu+XH3i(ff^18-G7Zp^AD3t*IxCm-Y|+ zNv?$1|0ZT`{BXaZrHFs+#6;}E_645$ffV2U;(@01R3p^)6@qO_1NZGXQ=G${vFUUsS2cD=7`gr<%`{y$sPiY3@ftHebmj z{6g$32?5kldGT7PzB3)gW;yJPc3fx;uCPJ|=X((> z)P29!+n_l~te2FP<}zS5zOOBOc?c!w^V&Gdw?#E&dDX&wyQUbC9`sQv5?1F=mv&Nb ztYtrfE~V_3B!C*W^B9zV!%B_X+sJ=(>C;-k=1el$Bk>O3GV^3C*mXIrvvAf+yt*q+ z3wtnp{L}v;RtBCI&pKcmwh4ZkBb8(F62K&ULQ223#BsM6gl}8r4oM*Kh)dAEwA-u? zH3A*lTY3@9Q=*_JW@P1ESJ+;u>$=}#rKvbOoLjMM-x8S@WZX5kv0X?>c}z(QwFomq zh`{HREZmrOc+<6{M+iQxlOiJ&M?y4j%Gda~Si&=`O!4j00AN6c1ujWN{?HWOQZ$LU z`Zamg$R*qE%(pjrLgLv36q`>{T^~>WpWLKF&Z$k(lcxz@u&TkwAeO!CEWfqCa1# zwasO+)f+QVR<(2ED9?F`7w~>Gzs+<+tQ{RwC#iYkchbIIZbe(Bfx*?{iFJ{d+#jTd zb5apX6yIW16-x>qLVwZ_+emy!DcJikLf9XPxbd6_&hMofdq_7rz~9~L2n?lk=1>D& zGhZ5gNikTp)H?xmgu@cC?{VFs%Kp533*@SpjwGfeAk4c$$4{Zg+SlZ+If1v$xcfHw_duD1?te; z(q0Uf>`hL_7%?0ye}#;jIViuNwHJK+GDa%LYU8fv zs~RYOx=Twv>%%FSN;JG_dbH6$^j5r1ce^Jf@|iqUKJvL?@0(E@kl}+gLIl^79}C5Ct9VYzRX-dC>Q~c9xly_*Gaul=mm*VfJ$T8;+ zhICa5S(r4y=T?p)zs%%_C4GXVaRQz6OD)sHYGTf~K9 zhDH=5t34cplZKaamP^C%W|leN&AF!=9t5Ser;eMJOY?aVMj|3HnFqa0@$yD% z?%EVF|E-0AOwVS8{2R!V2n&6*V3z1;X6^}Ds&hAsN&bmYrELn_S2g%>(hN~wb*2Vl zw~s2#xXc|(Rq@5cJs%{2Cg^SKMVmylp4djjX{xiXZR(PEhes zJLXnG{drqo#2t9ix@|qYc;1r8q|JUC+vXWqX&r9-T3vjuD$LlD)M8dg;f)&T9KYwg zFiB=+D7>XJK740;rTH4?b-pDXQ`xe( z2>h&6{??N|Sg`T+9-^Yw2$sguewO&Ol%nCZ5o=oN4+Z^g89*7;XfJ8;!j#mQP0 znZXgn68C}FnSB}EUdle>utyAUe5BEa@a^w`&=URQd96w4iNezS%t^r0!JG%at#^BT zZ)AOb$!x0Sd<4a_kcc~#T!;K?cT0=>nL9$=$W5=Wd{iHQ67cbOS1+s4Bfgj~xGo4T zJGZ4xZ<}crZ9i8iz0qFAe=%1E&3lum4bh-Xm+s;ykMDd>_X%_H1BemU$o+m zR=qbC_YXjA?evhNIGxX_eT}7i2S1r%dSi5BeE_;;2xP=+Css7?;D`G3Y%&`6 z>8ePS>5vxV(0=p!unyv?$-+apeVOSiAj2Nc)8^7js%JfIm~?Sp;;mO=n==PYGB3bZ znR-}~TwoVdtZlCIq~gHxuG&(voRS!9>4>Vy_H`KX+x5K*qKA)6PZ+67YbA)g{;BKj zWc@og9dv>PS^a@Ndu{g}w;AGrX}0_$485I)9aas_?evs320q;F)6o+K;e}Hw6@vdN^dU z@Y$N5bdQ{J<4wLd>|8QkTCp)ZPw9i8_wknOm~lgQ0vm_1C|t;C16`C@m!qrwNhO{W zu_3;6-g=ey1GWk;zyyY$YE6LiCDy#XrJXlNVz{eMY{}k3c{SPHV-C2GvNVzW9~<|_ z15a>r96whw35e+YG3Q*l;#OTqM`Z||nDOb+uN;6>gUg&W zU`yX?yob*56fbkVC&;uq3m@5s5Dl-!QzYN6g`=t7&F#z}2WYpFPwaT!o|`l|w3G(% ze`U43iE``4O&*Yup~PWg8wNXsGMN6J!M{|3*Fo@C0;DJI=K@WuZIW{A{&G ze%UhU!(v{&lzwu3oFa!4J*Ru~eJ-ah9@t!~V30=6t~r zAA-vhxpkAP>u9s)$1M={^()^3@}Wew@7ewB0FCp#s&*pN|11&@Pw!8J+}iy8fLuiZ zsxwStHB@A2rln_)C_$1Q_s7a{GPGF+Q_X$UCsl(KDa9RXUFT|QW?M|(T=483U!m_TV={i>fv)>LWDQ^iuilK%}mA#`DT`BP|R_MXk9@km`i zx|iYrWI&i5^mvL}V#t!Ienw5zV8e@wl-b+Zdhd}Q95LC)T5x9L9H47iNlqHvfaLG4 zbNa%+rU2KFwahpGlq$4zgPC!FOTYNC10;LhXmvY!xw*S{s7=MK5kl*=!zUSePkO(f zd+}QL=BDG5Y(mN`g36N13-*0hTZJWA^NFs8F%c((#@GEN~CDNYp>5wPRLr z0I}wGr;z&V?fjvFPd!j(Tuq-J>sU)ZU^+86RxJd(j)0wKP@sELHpAfr|3DbXEE`Y z1Ot0*&%wXy(;w2UC?6eO<^{;uhcv7DDX?a9HM;S)N$hQ|2_=s!C06MRxG5mcqglP_ zjW%()%+Wb|In%x+7r!o>AFOoZdFIAq+SZ+^PD{mb?!L#K*2D<|y?8RzN(s($K{l1X zvMg1Y^w}7q6t-t-VAemGST|G~pipZelCkFaA5=-5dyQ(vkWjS$RlU`i^iRxG;N_{6 zTp#lt`GT4>LI}~mq}Tb}^-%5RkVg6Ft%qjdoHbM}<=QzkSm+&F8;qZ62bo1t-uU?t5xSM&jAwEqCZ8&q?GXcVz_8wX2v+izP3Xg$%x7A-%zbl@x@N>iI#z8Of*8IX?QDitD1`dz~cN z>UEy(V$KE2PK4O$E^v8ww=JnO~Z!m>|oL_j!$j>H{sH@ zj$?b?kUz*o>asq}3qGz%fTZ|Z{8B>dp}UE9Mf0~M{I45h%P+$*Aw{TGfDAE+<| zg%Vk^U}XqDOq|&CMOcasW9=N3{KW$J;GAqlsF!p=UsfhAJRiP{L|)HlZI8;Vh4PHm zLN$}RZ}uJ-`=R;oP7g^`)U*q!I9VX;I|<;DPA~IX<`^?X+y#^j+d#rmYXRX11j+1> z9okmSvqo_@a7NLZ>ntC%PqoGZ(Oys_?pA=8oi|V$U!N`MII+@CBo^`Jgd~*9$n?v| z;Kydy)i;qZ&&{#>pd(Pfw|8{*rUp>GBKY^lT|U|Ob=V;D@y_CD!^l;6z!*54|%Pd=1p&%7N8Wu84?5Y6a}>d7BG!qTgA3{e&LkD~{Fh5$=nH z5XNgX`PZMtaO4>aGJLf`j)j@Y^60Ve6eTF7e&rn<-9L)&T6567 zK7Zhggb2^gvqHInCS5IQ6WOc+^MUGK4W6CO^s}^A?ufN|>&}-uw9wCNOHfdG^LJL+ zOL=9xLvu%q&oBLph%;(;IrE=&1^lgtJCE31?4`{CQ%y~*uCEP@OB zHnUsgZ3`FZAz7a!IPy6e*Y|A!3{p(XyNRdw$wXJ}ZC}gtcgGg@m`v03yN7+MS$kjY zHaxzoKfR=i9P65I4U}-N!$DoKg`|V&*zUy$iYN~@)YttDEbDhbnjutlFT@fo;^v}N z(D2RVPtg~-1Zaw1|FoS6N(8UNR$Cl+N6O+;W)-sV@R)vwg%t+s!lN!3%A zkRs5mD9EUuRQcF2^u5w;8TtnQPIP>2`QE+^;}GUSBRykhP4|MU*&1y;A?#E0-bK^# zM(QCXq0jz?zhKRK)_qwDk(vQU?#hA+Q%6ORoe?#=2)x%R%V);dGdo0x%UR9(xPPJU z0333uoSM#6F(pZPm1cZ&S-C?SI*M|h`m5?v`IJ5qrMRX_-MJ)eyEVGijL`n1e0o?K z$;9;6&FmK!szV{qknb3y43}nY`y~a<+>YeH9e+h-O>vuT?vS$R-NqYc6T|l8kt&_u zDWZFX4Uz#;^0j+V0F9dlw>n|VpjbibYA+USy{7J*mP3Cb?zo8rx1{<3Q*$#Ik*24Py6<%_RFY_nJ1cq!J?Si6AyzipB+OIuj*(k)-Kvf2CSu-%{@BfV_)DDQRfv5Y_NAWKnFN*PlPr-(YrV_@+|o1II%}OW z*oM4uR&yD?E;#?7MWf^EJ|@ulEh3HCN}I&Rpr|N*-)Wra0K%EElHh#TqDvV%8y->Lq@v=9ZEp0}e(;@gnH0m(m;ufY?KkF~Za0 zc+)ZMa0-OKN(rnRtg@ux=AE(sSy;$-8$~23-MfnI2Rv}a%f7wJ8dxy?LO?q!#yk!%RaS;5ZR`Dz4QKRa$Do{C^nx=J-0Z?eC^(n#M-M#z~{bwr$(C z-Nv?U+cq2X#I|j`>9jL*=YFR5_dfsSBsu3id#}Cs7i+C&{q8CG9v?ERP}-K-lh+Ql z1nXQE&})Nqu#t;F_B10(-)}jWO%D`z2 z`DA8cOpqH?gh<#2o8p=hc2qcdJC4Q5oX&EDZAm~$=Dn2G+SB?JfG9gYrTc5Prz_1j zm6Z@x;(RBbhbu%MX8n#-a0LhHGi(Y%8O{#pl7f4ZxwVS}?8Bh4T@Ine4Un_y>3b(T z8V8sP*WM(}TyNCmsqcX3(KUq`Xjy}`i>&R(5!A#-$3sRFz5O`Gk)*>keL6!>?lSt3 zO!<2SuD*yeE{V@^H6~rO%zf16K}-HYc>jo+kRs&6TzMmd41a5fiTS~--6`Z9At)=_ zRC~P#I?<$A+@n<0^~FM?yC@b-fWdcp8%8NViL$=EleCW10?_XW)XMv%+Xx@wefFk- zg58z%v(jq&Ml(A6v@?r*;1Ebc11FWnHVj5lg%0=(H@jd@D!-Oc3w zg^Mh+w&TR@RxLuOF8Rzf$Heid4BHh~=xnu0o}AaXSzBcRq*(|KK9ycIs!%gIeM;c! zYCQewLM%|Gy10@oW-re3b|JT1O9~vhsuTMmaF4E%-RNbw*VEI*Z)S?2xBNOxcY<~6?KNS9oyV`m2;*d#QN*5sQ3>{|5&SIwZV8CRmMuac}MAb-0qtO9cd_eYNk1C%NJrdI-$-`6y069b--qu$P(C!j;n|y z6_{A-C$?~ZzV5AnYOFkrJ;1yV0<9yM^cK3M>LK##j!gG>UZS(A12R$3*I|<|G+Pz5 zE$=Kbm18jhEd+hlX27bjr@tZF22o=s1+lQ^1(aM3e$M@tUNoT2q#I9%dCgfD7=mL# z#8Fz0zwcLzooC_VMRM7may=~UtxEz!UWI${qmZU5ZX^5mU`cUSx*F8{BFrp1Ls|1d zUSO^|%w3CzR4C|F`aN)|)>pRW2c)>pYoM+PY>_}6S@DeXAZ`f}$=!m`X(Wy7iZntT zlzMLMj&F&?*4Ctf!O&x^4NpFT%Ry}^BG_mVzdYC?9FN|t?uB_ufmaDCwnYOsMG?ye zF|{~Cr|CiJw6}la2X$ICB*A4Ni7X+qw+yLXB`3zcKY)o(kne<&1GoY zsVmP6>RYUalB=9?8|EIZV8wdGC}ThRs;tT>u8l7c6;x)tQy;TZ-gEM?Q9Mbw4jwq* zAkLZ*{|*}Pca0A^gGi~N575_gK5AH=(P-Le2_Qr5e(&L~m3}}zYy!ire z59{6a4}zqnByX-^&buQ)DOtqnj`g0ug1mx-xxLx=zFvD?2TeE}1M@DKj9bRRGl@(%W1#cEPtU!Vx1ni+!6Trzs}0lm3Uk$+ZNO|bpre}Gq;>(fr)gw!?zQ_f zf(RaBjr-M!)IlhXDSBJo4Tr5<)N&|af|VdxtRHjsiUVSOCVnZOF%CgRvk+$}T07n% zA^VPwPOID68q?#Cdol(n@Xbf0i;KG0 z{z6F;?`&|cTk^RDo2NBNj6>te4*E;fa~GLDd0>o`JA)3DHN`XIL2jwuLBONQ4fz8o zYQ-ZImVH@&VM1A*$)8OQ42dRRmF>*$jH~126vv?ebnYB!dx{WSo;}PE;a~QHw|(TF zZuE~=G9z_||Iw>z?^vjGZ-3nU(D2^Y^5KEp`q`nh=`Yc{o9*z&@6pHB3YJ-S4|Ja# zQku^W7T>Sz-xwMf!rLjZx}463#*od)Jg)#w9JcLGtoEk#5l_q&yMy!4Y+AMeHREgJ z?jI14hc{ko$#z!IUxptpG;)(xN@70$ng#9;R(VeZ_7Kx_$368-m>*p3-UTpi7eeoZ zO4`6wn5sgGGdnOhQ$;P;Jq3e@+U-kC4yRCSNF4g-Rg#yy77cH@gl(WyBw`!*+Ke1} zyO^Pzj|{l`|Kz%_w_IQMNDyh_A%cwO`ws7Q3YA@nuCpZvmL8E_f{Q|!sJ=z25DOIm z!ktInhmvUwMx3?@Q2*UV%tLI30ALFRrv8W%_RJKwmzLK3PIDz9AW6MLXU)X5a-Xbl zT{!5h>`S%)p7FGGPlvRiyex53n^MPhIR-_rnDu$ahK&TmrJ{{7bDXCC2ydC+p@?{% zqrL9sj*g*18}o=gA-J^8hbJqhHdEnjUXa7%jRB;Su`2t!!x{D<_jH&ypYPDw_2-HD z26d(y);J8`0efL(O94B`^04+Py!4M2Ws;1=$4$^3^@&)3Ojf7Toi}rtsN34&E4T~5P;d3- zNoYXa;O}DZ`p9la-4igWh@|yah76rhLQi7yle*Ib5blm^XYA~GgkKSIui3meAr$JTOPEEoe$~2|q~< z=#<*w>icLRhySH4ol$D1L!S2Y{P)NkZW2jWBWlNYTqmu(&$Dx;5*3T5&N2FFVSGI3 zsd;5Q7k>L2>+i`Irua}I74`}W{|a8%7^{U`pF)F;4=;F;)SsAX!I0fKPoz@jnB9o( zYM!|?C1BQ(TSm_{Xr#XRbCA(uPGE$IKv3l%)X+S2h6PkW(;hGde2t}(#HE%bA>bfD z%5nkH7e$?v5t3+RZOL@BCp1(P!(~tF3^YT+OUjHaH(^h+YMEbaFoH;oyRY1gM0QGy z3avl{X^6za>XE|zh@}{&EDpPK33CsX&vWjPcd=B6NY3#{mtI|P;g+{zNOh>*|%Yb#xoa{ z-s6&-022|{gN-2I?=5Q4%0Yj)rc$@_r9bmU$NhHp2)`GAf}Qd${6iO%fcPG3(xlGg z2J2!g4&5SRU{#QnrR*2R`K+(GQVPy5gtyEMtMocR8l&}>uhLk-vaG^ta?O>L948P+ zdA_3L*dF3#$djRFT+cV1J(N7k#7TefL2XS+4%b8XzWj>gT1%CEa}YWruVQYW`{PpL zP2(nYwD~VLovyMm%?JyMF6*`4lz(qyGV+7~GDX?3xxHeJC_WHAE+9!cSKsj?n~VvZvzRU+^RVAOcs&4szpIiKhrD<{h+Zf z{eY_?S-6bY#uZ@}4Y**j19iA2B#n0M_glTMZA-)!B>!4i>l9jQ)?&kWlmb0-c@)Qu z8}oTG`^NBN-_dPcagFr9^z}sQ?(@IKnGQ;XVyos$%q7&R#WCmiz_i(Fng&8t%sWg`+j#*IU3JLT=ihR3%UUk(GCT;ZODsWH`uqL;TkTC0JE|C5u+p#77R(H#{h zeu*g{9ua3Gk+c_j9=Nun%&F$(v$D%b?CjY~pwG^MqLj9@n2tKewB>zn43U|Obp5OG zVt0z3o;7(|e>kyd8MNl*rkRyqzD#PHvv6Hp^cZme#5z*WZ^PyFVqbnH_yyqkyrXj5QbALZbF+Mf&rV9`4N4I0(ZMx@q)^ zn3D6m@&Fr`H=~-PQ@~pT#N>8$nJH2s*@U`T5XV9<>P+6~YG;J0Y!8uU8V>);dlHH^ z3h~9v98=X0?wjw(T3pkkY;Y|`!(#3J?o??dp!5nS2uzj$WS1C&8y%x(`;*Z5Js_L- z{MNJ$x92=!(}t{F|h(!LgHRn;D z&!7FZUO~?p0}kHbL;u<&6kq6{O+sI>)Vg|JkwDX{H8t4*l~brwK-QDM?`vcIm7V^WSz z(cRh&cq}9)4)Jn)ikhiq_xkx=){%v*hd+OANNQV8v#OyYB9xS#UNf|&>{SI3?LmcN z+EgxNhHX%G;4*nTR~7Kj484uI{F>IUV;X__(Hm?CteZp695241pN-5F9RA z;?^O*WvG`)%o2yoxg+PP)L8uMzA+CXO#(^Dd)qq0u|o3Y29ZETaFnDn4xjZw7P_n% z)8Zr-6UVOh*sD#BB$no}>Km9fNk$0t_b^&jW0c*KmxGY;1gMDX>8@I2t#v{x9QI&L znVmy}?x0v$7p`z`2Lz0qJk(e*$fGxP;j65HAl!wBImCB-U((?qA)Ukdp%$f}&M-8d z@Hol>bJN!ecnfCyDG&tC6cs#-oo00?$UZR`VRMK-rCMgy>L89{iK<_*l7HR~i#fWF zR4~9yKm30E@!zr7!TJaM7L*%~J47!}mC5v61Y;=*-)zTF_Y1m%P(zG6O$Tg=Qb)hk znn9wkS4x+_Zf_(9R!*rV*_lF>c!nBtpB(o}G!tiRdZUrW6cwpL8f!Y6Xj5BW68j3h zn6}Og4R=_?t@5Tf>pr67Z}j_}T<{2{9tniJ2{aJk_h9$6zbe`=HOTx#=R1ZScQKgD zD=cg2ZVUhF%@J)*18(;=?~01M42JxgX;@==B!)I%@EDFR67NyJM!{gFxg@6dCCW@T zyyLMYbY|04fvehXHO_L8Bz3!Z7FE86bY~xl&gQdmobym>p-YhFv^wbw;%MVcnLar^ zUat?_@dhqgP97DxIa=+i;D|8n(sHLa;Yq3q^ECmQt#OLHd1m;AX8svO2=4GM_{yxtXyt$#wo<4a(2EhT7{y2Ze8w!7lcwt$d%!qmI0akfLtoGvYl6s%bDSP z6ENhsgF_}zSH7je5n*47$Wk`Xn3r1OSYX|4aVVM#`5905OnN5ub7zZ~hObzBZ++*- zp@n##K&-ZkGO9w8_ie)u!3ZRLyQ-`Oa-+Qb<9C5ekEnDvpH|oqe6mKoLTQ!@1$EW3 z+^|gfvNB7^oG7E;_CyhS3BX<+i)@Ca3|}Kctcp&8(KzYBdb>4w*GM%;wqSZK?}^!H z7|dXjjMUYPC))&lgV&%_b~+##6n!8FZ}6HzA_bqsJ0QbB%PAbXxPD2h+gVqyaUqxLM%CW@{S_=&1FKfjBi#1ha2yKKIn-p$rl1qWTZ8K3(;%U>&4P{1Q{quNvE+(w0y9ZZM+-JxtMgBO~XG zlK8)<#k!n~$xy871g?b51XXP2CxwZwEJk7cF5m;HL9q41n(8XKjs;&5-(hSw5g|~Y zehrDG)|vs)J>DbHwo@JLV&GwCaolu0sAzx4smBcrHszsuilc%TF$^L7u{-De7RRmz+hjt_@>T#K1EO3x;QpJC7Zd~$gbHI_Zhk!^ZbR`SaVuV3S!hM|T@ z8`NY*HhAV?1JXW(U2kk`m$yx;~za=%87D+8-o3=!TcPK(}p)AV4 zi@sa_C~HkQ*+2+-XSEe!Yjo$G!m$cfp#0I|Y)!@bV{Lw%?@oNlLvP9QNnjq)F(SMP zaZiIC`63%e{+cqkcLr*r(|WF#DwK~gN#6$sx6)o@!@DK?pD3jsW$`}IL~p?RC4%pz z@A0%^L1T}(FPUFf5gFL!ZcXQg#i{1)X^|0*{T&V@zzJyb zfuRF108;l6;?}u02YWU{l4OYtsjqoG)bdmX{^p? zf#HEqMUokYGYs^L55xve=S6|v{pg&Ibq{vd6~vfd7FlnayG!;z2CLP zBUycUr%HYkT1Lsv42%QkiynI4U^E1{9f@&6N?P)Y(PbLki&ENsxRq9bnM00QY{B7e zy~Q|coYL*1G_W#TioDP9sN7Jr(i^o_t2N|F37Hodw+g671-kMDjU*7bmu# zv&N+VU_=?R`DZRbt5(s&lIS`^ReXiGfO>Ag!~N2>b?Jp_OG=x=FL3A(YerA|>I@PS z%e!vf_sKWU7a+g((OLZDlm1nEKzHR(Vh+urXTiVV4Ns3s8i^5uNS|*-jSdmk{@Ir& zeNdWD#!x}a>SDG%k}TwX(S13}Od!%d+VA-kq;y)K*$9W|hl-bIu}Y|lkjY|Anx~CS zciQlO#{os4Ntv6II7aL;-O@P@5H494i?9sp$Z_u@;S68TNfh_yj;q33QHQJ~F`Xem z;6`PuahFT^1Y!;@lN6lvG4|mKN8k?jf#{J&-S}z-p<*cI#;7a0glMfC`h1~VwQ7(F zwGREaOj3=cas8`_bBw0JRCHr|dMDYgEML699zlD;^!jzFF0e|Qen9+KWn=OIn?l9< zP3SLxR%(ARK&K}5R@q4>R03aYV=$75JrrMtA+fg9ivl-C+smtw)?y=M&z6;hQ1Tz< z;PxesjVhT?uK6tpqvkAyyJiOI*d2EzTuC4)D$hFZ!2Dkmp;Ex2khq>_AIoBl6Cs-rkP;t>5`ULR%F z{rg)6hfjJv5~lMBs>=#TOJAZ3A{(%}7rW=o?-3h{|eKW*NWN$fh z8K`OR0#QCI`%a;6l_G=XQa=YCLd;Z-5^9uc;U+|-X=VBlRh)>Fb-sdNx)!T5-*bH? zGWLcf`vt9Q>u&BKO+1x0}E>8E_eFk_O}=lrP_HLN3dgjYnH^8c=#G_bl6ZD>@8Qt#}U~a~(x1KeLWe_;L3s(?Xz$TC~~Pi?KN>Jw*Fh=qSj3;+jl* zy95@C-Cw2(&rKJZ7#>1VPxR!n1#50gUIu8@C8IayNm^o2F7=7E{yD=*91P}H?hHhg zH#-Qn9#2NSY2#IFZy)_aGs*juu2m+sjvTUVjEDssrU%M;0#{gmfq*9EE&kGk!g0sl zD%-LRK_O$>2M*=-{qVP>>Xt$N&-cLFJ7HS=rvc5XnCIGI6??-ccjSkUB0hmygRJb| z_e940OD|LA(H#tYCJrIt=_xn*TXlntsq#=p*Q$cGAW>1fcR#^kkn`yh@l{@RL$^Z) z;xU6NB*I__XqqV;lJvw!@J`)a-0G>AI}Is^Hnjgc7w0CItJAgF-DqHJq4izfAUgBs zp;8(*803&9rNYSh68+-V2zImMa(XGyLF}W1U##){+maBX`iIARsyJij0AKr3@NL^n z=)5rkNgP}Alq8LY>twVyZwwvE5q7vps$lNa0lx?9l zwK#ty@@$Az+GW?WHa;nHbd5!^?m`9Wd|zb8GB)(-tlyI6hPJq@^L_HaY7z_>eU8I@h+M@seBbhm)j}+o8h$F)471RrM2k+vxlpAFY=R;8gYM?wh<@>&ckkoLh)6-8pex+a z`a$9&EuyE+miVm-#Jb*(5SO~Mo_Bs?b$?-a?TgbPNw>*lzcagbxaaAWneND#S!Zou z_v;+Ej@q10$+gLoKNz_@xqhc^Zm$^3lr4avJ6Emop~l|fofge~Z-=M~CS*P;gInhT zwvU=i)f+9$f3dh)_FmIQqWVx@tgwxhN8nx_s9O_X`nJ$N&Yr3|47H%r^xGVYS9*Mf z8(dk{x(O^!WNI+p_?7mm+S6$C+Ji<5=`{slrf2EQxywxU`$$fN`B?4!%90I*N&|`x z@-M~5isZlKo5n(D&c7s6Zhw~;e1La7;4k}&XNLJNvFMm=ZjAGBc<&68Bd)G@s;r+@ z;mP;CxEVi{+cjQv@ol_>hyPCQgVz2Z-k2lV;!rH!odYf}PIrp-if@Gp#mboGM)wc9 zF~$04wtl^ep!I7-3`Se(Xr4L#Qn5A(NpWY&YvIM;GE4?e1EF_4Q`3W^bq~vBvD?*G zGm&|Ib|+(|Ji4V@@aaT0;ZvFx!-emlFc0vRIuhjuXV&z7+nN`AqJ!d<)|b5Qa){Br zT+PoyCMs!MzX)p(egomVuLY=CIDV=ka-f-!O?R)4xllm2(SA!HhZzd%fwcXub~w2Q z$1f-<59vl8(%s~XxT#SXjllYoX_Z5IC*$6DaItmmE%Qi*!WA?&@}hQD#_Vo`@4_8?^D1uxoF28_U8+~3G6iyVloXugM55aSw}^OXPLA6s zzUip~jZ$EffOt5E|Nf^zrN=4GZtHq%F17;?Ii9e46>i2iMEqOd>L7C5+TOAD zfbTRaY~uX6(UDP^cwhiuf9oysW8_y5&fn-YobW)M@`w(~V(v*+-$B~AL+HwHoy(OSm?wa!z%Fc{9|QZ$A)t0Yn%%^Jh0CkJ2Sm zR3A4L4!8=n$y*lg`BX7^T?VdM{GV2yP}s^W0Ck$qYh~N5Hy|3tZ&;u_iBMwE<x=SpBu?ZDa z0K_Yc4LrRNBzX~;f6WDEe8huJD6c(Fz`(TMqv z5_NVE2D@oxpvCxkXZo_W^>!E1n-|qQ9=84mdkjsC;*!tcc5_fbw9b%!<4#B3O~K*4 z#tcT?;(_3rqH38`@wLoA_5K@XqpU?CspawZG(0!(FS~9=g`J~KxYId>0EuKd*W4y|twfzxd5qU4uR9P55c<~zZSglGPV1B%ZM2nD z`1mzK9FP}vjA+rRb?9aymS(SxvCc-jg zT731e0hN}2?9NRY*vc9?{K=OJ|CKKlm~7uN{>bi}Z-j32KR3$QJ(y??VaT04%Z{fY zFOHsoN9vjOF$UjMKMyqv4I&tr3fYF4?xVns7;M!y8)C>v4Ivs&&yuNwb~K-J8s1CU z**Jr+Y%eE0-XBKsF8>H}BhR+C%q6f{w!kPir^a*zQy;IOls5bm&Yt+DZ=kHmRZoOXYinSQ(oUQ{Z zMM}%(+YyuiG!Ewh5Az4FJx50I_9gciTBkchcoZ(gL`0CXp#4G(lo3CoLR-jSC)r8X z#p=s93sHmkB(`mByxwBQPMJUobfwJyLh58?vb>i7>@OT1kUYK;n_K(gC@#Tb7Ve`K zS_-X#NkaEdBnQB~2#iMHFmY&tv*pn|E~Aq9{}a>~pwl8T< zsJ+ELm`u+TwllmU>&kx&s(+JDuqwja_7Si+wCS@iMT)}U0}S8ywYdG8zP)CWQ7{sN z2m0YTlNvbudQg`+$LlE%w2KZ(V`ldyU3>8otjq(^{%H8EH|+Xv@iAZSe>$2{LjQ(& ze?s~ni{TH4^UNXpPuJ43wNR%)K?wa%Qru;yyn*ZrOs?UI<@w*Ku~2=F$PC_1{xWSg@1!q+Y952e``vvxKYOZ*+>Ma3v`HY&$Q~uURlnuVFkXk~jBeZpEggH`vkg2N$H7|u$473SQV)mm{ z$jLNL*)Jm4e&x?gZmbRKn9eg4X|{_7<1m*%oCF?SeWDMWw?0yl>xBOXqyLu;*B{ex z^*xqn(!Kdo{)^ZFla6o@Az5)e|B~{W8rtZx$FRl&S0ABG`4Xk@ zo@=&FL=im(VtRpUH)Waj#!i1J;w}0NCgSLWldh%9RLJ0KwJ}iuROWmf$RK^N*yEj`&kU9QMz<(zo!*~js^Xj@7D$E)b+0HK~q1PAZ{y6E-AM&x5G=qXEboK8u| zVOFb2u2Ns_nrNMO<-g0RQ%Ua|9z;6t^al&UXU}W)>ho1z`0{fz^e-fQ1uUkVJ9Eic z8`wK**H8s(xsu6h!CqOO9phLarA+(6|L}B@Ru48k7lJ`t*)}49uk3fFTMA0snV>3& z|2B{0@w2B6MJodlU0Kznh$SrNven&zXsbE;GO|bjV*a~kvJNWaCjNKIrPIEh^0MdR zraDIfD&&3t?W@TCZ5e_5&UUK&9P#UciTTDqGHB%Yepl^v8ua-U|1#%13V8o0o0qY}3a8F%~?b zU=ds#RxF+ZJIcO4%AV*>U(sxMwD5h-OU|}h%j)wLHygS{CYPVbE8<=Lj%i-xOpq5| zI@5jPPFZT&2+=p2e>_9-%l()~`eqa`*C-Ps?MpL4K~HjIA>7d-_X)V~DzhN(>L_2o z&yrcGqfBQI0-$1LA~g7bIMJok-&U-m@uE5t1Dx9xlrZsN1Fdf1^;QP!htuMG-PBC? z3@V)jr7hStU%Thzy`AfkveEwMk6ZoUFC+>HpJpi5Q@-(O-7aF}y^ycl_P&Lre za0~19EH0?vhdL{2H67_9vcM7%9;26S#ay?;u4{6*Y`vth23g85CyUBjH8?Z5vT9g+ z%n#dh21FOpdQe&g&dn-U?W53;wWUpR-;n;zSMcKF8Ja22CWw^Y6}GD@`jd_Nh?k!9fW?iL1lOKBV3;wPfhLBac0Cag1%xsMjc;;ZAwSF3k>cSg*wg+}Jk@buR~;=CLftuf z?JXM*z({6KUi*{PlQgs+zKr2-k#TW6wBm1bN!@t@;JcxNrrH>Ucc_4c&4QOi;<2v z(Y__P+FK;t&WXW6ykN`2-B$D`cA9;v)JJn=a1?P3&%5t+&+g#Ref9bcF@rhLM30g zB{<;}cF_kdMkgC}-L(-Ho!8EGs8zQn;~O{3{9<`P*VC}SdvFI8G1ni|zlyycV)l$K zjjOL-E>`HS9u@tsH)MX@Y2J=8K(tFz&gV81Lz&t44ryS%zD>0&q=&^o&Sht+6az5-0sw?B4ubj(@zmSoA}ET8UT}-AIpM zrK<-6sPu^b_4f=!=xF|JOh5R>`AqyhQo{Bi1Fa;h%NM8Vi|TSpjz&{J+^f&<=H^j7 zGZ4bPsfY%lL=4T?I`kl5ZmA2p)&yk?q9_r6~r3M=ZIa4Nr zYzDvrv1MC=_4p&lMve2fske+`P;FJmT}Yd+c}n(EAKs7Je{z{>V~jU*^B4!5jChY? z<$Y6@-`iXqP9T1@9zKjY#c0O%h5y_&957#5gBI}bGvhd|a(e1fK91Gk)EGNU4tMaX zbH96Ny9>3$Q9{Yn+h07zruF>B1v8QVjinGLb)(2*b4P9*QSnOJ%+H`n{T;_0G5JYZ zkYAQhWU{EXJcVWlC0Oz(&U}s2`O8AnMfvB!?w5^|9Sr$7UaJ+jxCzm!%GOwS85x>> zJ=<#O!RqnKiJ=l()7GqzdFr+S<3g&Ean;Ym1Jp94!`*J#h;MmiC1GW~fiY%mMlK$J zX%tumq^LN`4)zu$vs%ake1))!CL->nJk zAxy`&nujT#g1NKCc$faNggi46U``DdA#Gz zr5vGn0o~n*;!m!T%|ZZCb&rLLn2xaoiMZZQ~YpTw1-UL-!}TBqp82?SwVk!%y%$WOTU?4nbH5?U^gNHYfU zNQ@L7iD9k*1`nJ=e%Pmco=}Cgd827AW0escqz;=3tFudM{3@Zkt!ON%A;Wl1_WR`B zqmD6j1A0hARa{6F-Y4&OHqn98bHN?=7eiRliQ`^hdXHF1Aj)?y^82n8QPA>n5XlJBVr z=KPS=`e4T!nfX<>3qYL}^x-+of^rZA1+Vk&CU6!f*!@o?Oktg03!IH%Z+aPHi&>aR ziExn0Vl8NzU0k>o%GSJD9+;f!();?G&Q`8)JW?LX`y^TnMw$53{B-6TjTmw`*E=}P zm8s+DkGy8f_jMnTs7j3;&NxrzF_a$RFJiM}L2#G377zBh`Uh^%k?8Ch>H+d#PDXpP zUKdvD?Wqys{QGl2!7O^&os5yU`rCepD_XEGcgus&lr8&q+Wj(S1M2KiVtc8)b?@bx z*gMjbJhrnU76z=8^6gr+DbNMhZz}p25<2@iskISig;;@`rgL(!@pn|f3XwlFP~jg1 z?r@6FfuuGcP=gZwF-8h0opcf4nqX!^ac~~#8%IzDSh|wYYTjXGT(M;g?~@&7ViKYT z&fa?6cYH&gEvGf($7_4zN!Zra6eU4wc-0w+#V-deUO$eKrT=b?P8FYWkv|snTXce3 z^oGy-D{f#aVu+N_x~gk%w3qB1wJAm@ki5l6wDu0F!?oGC37g02eJD+oZG? zj4qT!U!}9eUwb5&SDp#O2MhOlMUV=wCH8MsPGw(I3tg6>55}E5dCelS@C%|lOJMU_ zHdxSFF?E!q>S>^9)`wOa-J29IdCW}K;H8l{50HHJ?FOal4ln8H+mqsL8q zB7u&a-)l(eIP@VIint7EP(nUhIQx%RJ;2tlnW=l&5Y1sdH$O2yQq}?T1FuF;#-2xs zUMBW^Vt|?-uf)jQZIP2CJiPWgx0pSYw*{ZRIdy3(F04@;A5KK5Pi8q1Yk{1+rnY9X zbfozIxMab>0lbS^%$CuKsL$@VA0?gdZOUqZ#8mFXYc~<(%Q#ePl^Pvjl?b-^xbtb4 zZiu4xcSRk&VU*CXWtG6deSfYL0X7gTAg~EHDb@Iv& zM0+6FdTjpOToMT{eAdU&UcZ=_t@^&htkHS}6M3COqimu$N(tu}@*Ol+;f-*7qMnr^`0YOunMV#7K5>8|-@mD!pJu_cyg z+(c=v97SiFox4pvDZYl5C!^%Y4ffk{uO<4kh_dW~R#ouYZFL+obV?F`>~QKk29!AUt;+6Q(z1<4x`I3x7XdVWHla z3dw+7BZ8pFVu4cE#uyA%wSRV$$QY{2QvObs{NN(Y&x+KdDBlV*K))-NIMq>`EUZx; zHp-l!SPZ4J1 z)=rSbSPRzTR$Av&9Rk~;!*I~)H{gbl6f#x2c=r>ZYE1GS|t-V&;B*p+Bu4Trc!`ZMCBKnds zuQ?*V!z30j01fD=hf zkPg>5%1Q`tCDa^E^%40ytf1YQ!pJ$YrPB)pkopq1I=Y`QO2C*XynlDbX{ zrINH>_8oggLQ76)+$WsRJ)WG@%vFxRxK`Z0o2b08Y@7z~PJ%y7D8P4R^&6d;qcsux zaX@Y|Ygd=RXRNGkz1Pnf_n#AOb%7{jZAk7)G`5vPt#P5&8t1e&U>$Zjpc4`3#*Fm` z5_Ks9<_Jse4&+S{CH=9{Nh=v{Cw}-EhYd7c1iwyeg@h7r&~}(ozlmspW_KX&70H9a zCglyM8aDIfGD&NJ@-n|Qz!ZYZfJ^zv1AIya84RmYJU=h-LcWsV!_$W{a;Je zS0KdHs7TnXyn~A)i{^`pHu$lceypR{twR5GtN8Pxh}cqg;QaHaP3Ig-u}$TQshp>B zoXciB|DslbhBb+(egVg73mS^*poE`q;jfwuO&gA$9K(;NPorn}6eV<#gKfA9F#i&j zyCQNHsnlG%`(`AFe(5U<))7~~%SySvz;cf5^TbCW@0;BowmHz-*Tn4xH#-YeWN!15 zu5_Z8xY!V$GrLWz$978Bn;VBat(O6ZTOYXPQlOFBG{J#!V_Ud7$2y(aKpGfYMLJ`6 zQh3UHFub3K(vQ$@cUl!$Mr{j(%nK;0UxgP3r#mfCi$mk;h^7bcfneyYIq-DZp!Pgj zk7#@Rc3Qth=1vleAkN`w0ut`BURT9JF4jon+KbuET9p)?ywc|&P)fu9X6?zB+H&=X zwpd?NWWJ-Z4*C3v^3D`7A)3|Yu_N;?_? zO{6#O*Ngxm2Fm&!+kk^_{1gztzHd$@FLhNv$fZ>q!rd-if|^I@7Wl_ZGQWNlMQ8p* zybC|n_OrNH!N>KGs!!M|`-I40FY$^js2OUgO@|WI=MT=Kq-VtPq`GP9z3{w~>|VQ=PNX5|?{xGrS9i98?rfEC@32^9HHt^u&W&%r zc-)N&7J?>h=Ji(WX<%1ciy%`hV#EQ&SerLTZA;{8^J_;qP{uLefDW8Aw--xLQ;mL} zym;cfeAkYDQlup6c(o%EPeROqffrA&lSkd03!ZU#SYSe0~ueQw42d;NKpJJF!QR$$eC0p8ttD()mWsTF)DD-5|z!t-+k z_F|`Ja%~SPBLK7KCp?fObcT4AtJyBJ$>L|JR?N2WDRI1yNJ{3l-m?&d+ZdjUow##K)ummeNgAuA*jq&t={Ea8vNd_9Scmx-7oS{RZ`oc|FY) zhoDJ~M)KLJ&VU%CDJ9WoMQFU?idtD)8pvx~^&wyjE_|O{@99Qg6=vN$macC2={*)j z146^PsI^1cM$l56N?26%-DG_81oyEND8p4_=T-cF;7z2fxj*(LTtMn8S`M8I4QTScmBzMO^xMz z;9RpXbis|?3n32}GH9#Wt?UE%;ifWGRnim8yMZ*jxTjIMYv`So~NSfXTxS zsMP9Jcgh|oj(;r$Q!*4vTwKOKpw-r-hW>YdzU;bPo;LLwMjBGmjO^L&50L5Km2eVm zJg5sozbG#&y?6%LD<$lE3*3gsB#QU$z2xkqx^Qy;zs}AwEXr>0+bGJ=2r5WRE8QK^ z4N6H#hs4m`9n#V*ASDQbboWpLNDZAsmvj&BfcJjhd+)7#zt4MpnB$n4FYCHkYyHo4 z{uXNjk0y!nND@uQ;$D9cg56704xOn%_nUUeIsLiIj&*!R!1_IQ!g=C(gXoqrqzrpB zWtP7PF!ml?09+O6tvIV>xb6q?NJo3?@P0Q#YGLZ&c-Zg(J&( z4pUSiue#Jr9hY$I;9?I#fcz!aDyNr8E5!7j|4QYGguw2#ZV_seqWEn+g{Hvkz7k10 zUYO!@26wD{t*@^dUbbc=%d~;)&n(k-ij5-`l!VejiP#kDoF+uXvgO=oWBgUuE+O~7 zM|Yg+EP}TsU0#?o=L9{_W2lUc#Th&iZ5EWmE3@83*BK;g5pATv$HDh2EsEYAbs67< zVa`P0@Na(S>m^JCj6L}SZMmsM%_ODaQ(7u6XILTGvPd$LMRV}%9}6Wfa|HD_Yhx>XIct z3p=F(v*|9sMd>pQzgoj3*`u@c3MwVDXK+j+>}~O_9{HBy%U}lBn$zq)ZHC&vOpS7b z>~$|_cxQK3CCjTUMZySCS&{|!V+^hx2f1?E(% zQpBqG+q1NoqR9lQT)o#jzWJ_J4%{!p1fl8b?|B#Az_>48eh6w-IC^ushbSv$Xmum1 zOAeS(01Ej(e)|ow@QHa^f=sVaEnK;}==QFpa&zFwXz)klwhRr&v*6GaU`-Ny11!`9 zcO)D=78=m%*i5H6<0xel;bVqIWL1>vKJ{h-oNq{PYc@m=s^!1dj=}1ec>Yy_U$&Vs zqELhF5$W4|pvO-8?N?MDgt7iK=ZoT(mJf!_&qnx13&}Vv0$z85gm+uHIR|e-;(vhp zOb%+4ky`$QG&IdZ60g~K1;%4ffT>FPYRJOAf;As3DZ#0&seQu&1gYAl;d)cy>AgR# zaGkDpO6flg99vc;S7M)HHaz8Q0?(Xl^>C3f&Pnfd=G5M_23ejncY?P-GL22`8xX;C zjFEYA=!WTgXEhYrL!Iyp9Pz_C7I}SDqxFH@PgQ;ROBH z=_yKV9fYRBf>opP^dvVdWloAnG`|MjM|c&nJ0J0Y%JNSG3?HYB&huFS;YBCY=lT2D63m2k z?WhEOf-G=If%V4*?nv4TBvb+_SJEP>};7h0s z-s%9VVixcw>B{szn)D9)$2T#7#Tl%r;g=EzXGu~{J6B0Y!SO%!2ia2};k&CNo!MgKcClpEt>VuT>2ist+Z4?O(&y zRc18XgD;Iz=u+vCx;Q)ixXulOMj_Xf>a)1D-ddGK8C!-n+dp&EH8_0ewcpF+3Y`a$%p0LnAohgF>(T6^Z>uGyctxjK zQx#}Fhjv9*&}AU<7~{DdFk=0s{~&3%T~WQA;{Cd(ACPZ^@r>CTh@*g5x@>v=a=Cg^ zd4PhlgDBtm)MnGwGwSOT`YeVG)+H>5hDNe6fAkOKVL$gdx(|-Kd{D6<1FzkZCT>X9 zS})rR*D5o#xuPC6#tEkKBoi?)7myN#_=3N(Cgg$NL-Ae>L7iQk56m8Z)lnaAFEFSUP}#kA9B#%7 z={to9TYey>_>9q*k40W{zg~+m5hVy7nhx6acyiuq!8pjUhA}#`w&W!HHOKg_5S@k% zG}ci(Qa_F`G&x@yQ5oJ&l?E9>BK6^(j~dK8J*7Mk-$(fh7AuBIx^uE6wx|1R~Gdk0MJs#FXr zynK8nT8(+nX&Jf{O4D^vVDXS;L#=Jffouk?+>629gH5+|yK^GT(51nFXIhzlbPEO` zu}tad+Slqm(X!8r`MCY*`ns`}>74I`n4t~XQlwze)xC&6 z<@#G>2SkDa>;;jYhrB07FHC9{UH?_+O*?~=+oCdeSDWxi3_Hl^=DUPPVE(lcnHoPG zHmhR(8ROb80meKZG8lSo#W*KwFwC-zN&2PA zTt>B2i51BETDxFossxD-RshY7XTOAtv>=88Ldw1mZnU}!`>R?LNlF`lZ zc`=H2n!@9*ky`GsIHt8SfeYq`8AfuEwCo!<4^GEUa=8U!z-;sSt`1F?K-bZ=KGlw< zS~eE}djzcGNFymD`b)l_E|+fSv$iJD-vlDu>+m}|iE0Bz^yL*it`%3$ zF!YB$(YQJ>Lw9FeO=I!C@f;Qxos$DKQjV6APcL3W+zyyF1;Kp+a+bPR5z^M%wxxVQ zOt_h^G*3trsx^IGl>G$Q;sc`AeoodM?y0`G8@BPWzemyf{SK?q-JSq(#Gdqh_PwvA z0c>*g`VO9lq(_5Z@c%{t{=kuqnMaZBK*(!^_-0Bf8i;4#H@yX>m|hV!IG{CLAs6Vx zKf2XOKKz%ZF>zcGb&mPMJ!Fv?FWQhxB)4FVW+~NS-aE8)dGByz2z~KjS@+JKAxVTV zjepRMXSi!!qV!@4vK|npGhpS7PpIc{Q3Ep@62ONlDFwK<+B)F$Nsi{yJtW2#XA3>(RD* zRv{gAE=^=~jH;cgJJnqq$n7YUYktKx@b`A1^pHBlUthpqA$0Ir?;ls96o8-`V?ZVc z`+G8L1+3@uc`+ge|014*OFa_zvNt)^8fs}(6Dkn@e{|AiokM#nKNk=!ccocgjP|25 zU(i?X!&m;QIn-t3KU{&AznYN$Li_Q(G(ZzHV!x={CZ*;B8b8)Jf^6(AdZsOaWpJCC zYOPoBOedmBZkiJpU9oKtr=R$-ZZ_ztnK+b|^*-_*SDY`Rb-q3aqSi3xcw=Sso_7x@ zC!{WW(^hhWBmon@b1lgC2jxdR9iY|^hFcsB={6oNe~pbGiG5N`WJzNQo#fy`Lr6?7 z_79fgb9tZ@GawMNl`dQf$XKoY0eqo(NVX@JJc#Q~c+0)8{MA5(g~pG+TpPx8D3Kko zliQK*FWHt-OKpcO5#Ke#X3l)-Y%T+SWS#c#d_sw<%;gHyF?Fvr)y1VJb3?O;zG(Lx zM(%cB@8jthJ$1tc8)ggg&H%GmAp!!Qy5VG@qu-VqZj1D_vy2 z2Vg=`fS*pXC4E^XU#LtM@aYw)wm9d{a1g~I}AX_^B z1X%K!=Y%{bI3en8**APCliX5XQ!dqy+?ecsITu-LPL}Cm^FYfNt<>jHc!i-c7R;*3 z@eLecrz^5`2F&NYJ@Fpu=vS=6kC`rQ68niZqFzrT`|>puOP&BGm}+~aMO`_vG zv`&;C2Lc6qoF1yw0BvhCP~K0}qku$RPFoGT0-37&J|`EgV?GI=PhVHendkPtd>%7v zboj&rC!E0+E62hOK+pNEN7b)!e*6j!?6oo>*QfWZnpwlkWUVR8MogTFr@O0&H=ek0 zWAx%oePpD7y#h@WDhYIddQp!|s_Rd$YmHuT7BM8C`Y-fZolzfWoBaPkpDieZk_-@x z*qPa_GlSEW@nuS57&~=oMYQ{9t9)aLjX)mCGd%>x$9PD%VZ!2Gf3>#qHdrAiDimV2 zR!6tso9Rq{$2)A{_5_Qnc;Om;-Y36>8{{D(tE@b)Vyf6pU75%EoKT2-nPEUh*6ES( z16_mW5~*ivtgXy8?pi0ZB#EJYC_%Xm2?Ml-K8w7)c^jo=PB$7G{uG(TbndT;wAcE# zE$s?Lq#Sk86VtbIe6XdY9EG|E$Ogf$`j*|~@E9TIbf?hoccMy+mMI;Vb_r9GF*qAi z?s3s4hhG+QgzLEuDH=~EQ;|l=JzFNV$!O`G^2uZHl+rpzDT07v%Z1|o%K+W9wH<)< zgQ+@|1Ol-Nly=wWffV_G{~^u!NwDfsP4D7Nrreht-bHLdqujh$+Y9fF+VybAJfHsp z=j^&b10Psapm`U(O?g7hiM%(ILfgDrDg4#UGger_63&#`<#<+o-`!g7sIsAT9F6$( z!hmVmT`y2Ehfm5%jHH_A1ij!+cPTmEpxH&yF*W(ZO;wq^o&I;AcfWUhPZQZ9;*0=0 zdwXEdp82x9_t+A8k3~Egcd+Ybs`v{)Q+0Hnm%<_`u>|RtIF8DUe0f%6YezD_jh{R&+C5Oz-<%H3*r{KYTLdXO+s~s#u`ET$TQ7eyyJ?;2 z8l*qFD89^VsG2DNHQrdP!2WTwcV64@%wQkov+>@dL($U^E~*JOW$82c`QcyrEK0xm zy}Meg9D8t6h!zD7Z+pQ#&{a+E)64)mxoZ9Szrd! zK7A>JBCWkjmh=rxO=%TV=SHYy#yMtR&f(x@RP43v+IQ+JTVDBRifc>sN=<2?llAte zLM3)j|0p8)=azIz=myYns`70Wx%_LAC=zWBih4pzZ+eKD$fIIli+bUxy1@UF z$~s(EJZPjtRoiAjIxB&C7GH1~(;#C~US=RyXjI2aAP-207DTgXin1CR%JgITqx+JT zH@b%fBv;}!b8dvlK74^`s& zj7Wh4OqP=m#CY5<`m5d`tABaAJc=!L*QEGJ_yYaF<^S#{lyGlq4#_}Bf_id7zyp>s(uZz5Zgvs|F92Oh#EsU47r0cH}(pL?QZ~i9To^)|49pf&UHuR=I%L7eHu8L!22d>QaM`igRuNZ)4PStIPK6wqo zjxq!STlSUDDf5QFZhzkJXv(D4SiZ~()H+|^f8fDD=8(j{Vsz$2E&E@IO1CYzv7<&X zS8OmHgy)WiVs(muD50R|(rUC?%&W66y8%4~X{IJPkJCIy)~qh_r{X<@TNMS&Yj*-B zFCzoZ_KnlgT5GQV64rw7vLDV*F{~3!qHeX4hVW_Q4%RyBs-uve@cZ)_9~`GaCezhI zsGi5AI1(G->RePy-#xPu!CNs!OUA@N>~15dKs3QN+#@Am4`HF$_Fg}J4aB^0$022q zZGU)$6C3olU4#Fud)DJ{#pDUfVv6_AEf47l$TPlZ+ZK zOI-<`oKY)3!~^3><9iI<+gcIWj9!*}Nymvf@z`$BB1uHyEm%URd3aSS3y>fO1I z8=63?tF{>lLkSM}`vBg#x#&${B=Je{voivtb2r0RD;bN%DL(g*7Fccd^~#>9|5Mr< zU+tzZ4gV#jR@V~{4o|A|?yjRp*`?iXiL;kKIXJ1cJT;96}Uu+K3=r3IngF;0F&*Kh~+UB?+3o4YKz zLd*Pz{8tf?;q5&d%ma70id%~EZmDHSIsBt#ta*zyj>Hb!5S{v{ zsNM*((Gd9M8G|hT<{1+&h;($kz39ZG%R;fAy?W}8wkx|bA(&_@&2ckSFCf*V-1aJgt*rpwF@EnG{g_4+E?O<= z-@J4E=8jo*@~VxyrAt0|mVbXJ0+wc86jJe7E?mfIIScUp{AE6>euDqixBX}>VA6lq zjUtb@{&oN0AbkHIO;XCS$j_>A^6u#t0`1s3`Gc2WK8e+R1GzsY)P<&VTq~8vg)&>P zcgTEBKH=Ns;XWzsJ3mqtI3o9#PcLm2c7=)sE1t2(rG}kGCpnm`r}vGTf?KneQzV3KHj{^c-mi4y67>oR@0p->b2(D%0QCS`xxw@9O*TDyGl z_3NnO+P-lIa$N+zB3Y^b3>itON03t{Dur3pI|phR!Y_fx^KxQ3-^m> zuZh#@IU2ib{~mS^pu{l9yY2V8dlpy-oZ~rWuC90hvdLpj9puRDAn$HW$MRO*|AxC}OK*l%l;_o(@{T0H;18yfH`V0p z9bRfn{+?#l2}8rAsEk9OwN#w){ybcVN5v{H?(E_3HXlL;^vIR)T^30Re4_OA0?rH= ztljVU4ZD{5x0(6TyZGpT!`D3;_X@7m5N(RNYUcNgV!TM1a${-1r9kgrMVd$xm-e83 zNmQzx_raykd$%y@jZg|BquOe%lsmu;35ipLZ^HfS>ZU5!-opIHyAbVCm{41lQsx#~ RHp1;CEv_I|BBJN_e*iMK9G(CG literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/image/static_drivable_area_after_expansion.png b/planning/behavior_path_planner/image/static_drivable_area_after_expansion.png new file mode 100644 index 0000000000000000000000000000000000000000..c01ca440072b558ba37e9f9dacb5d569f9358308 GIT binary patch literal 151054 zcmXtDQRg0Y3T-~8%7J;Kq;j=q`Nz%W7H^-6zLSnkpcqJog=>6 z_kF+pLkzgt&hx&m7rohqT>j6aewCo16eyb+QVKtTRFjC4$d}?E{9m1lE4q~zt=T% zk#mB*b9wLRK(G7W9{97sgYOj||3*s#FYjh{IIqBFS}{HFX~t*4R~zA>e6O}j6Q?(m zqd*{f&|7&KU61U&c5jd8y(vQXv5J?&HZJwdlqjpgH?#{B?2m%F#^CL5pI~RpV}vme zb|=2Rj5AN|X^{=+3dKg+31yjf$UlDkm>5%L)iN>tPM^S*a`pB1If`MSRKX@Ll^Iu; zx`V>&J6@N{(o!Bh3D*+E&`Zy=IjS5HJyX|jH)o!^*-kKP>#%pA&Xu^PCZR&9cC7D5 z*FJdIn5szdX?J0gUg}n+2Xy7T*w4bRUn%bH?o^S8CVc~gFkke=<4N3~i(+t5sfX+F z!p=@Q4e?{_q+Iu|M>8!E)@qzw?DFakv4w{mhV35&mtUWSYNAe%PT2>NH0O}J-gCny zJIIu^_XCoAKhW)BjPLVS=9q#_zn7EK)7{w`B^4Ed`=f5U7njk5*SS7V;-2siQlT;_ zD>y2D`YkRmpIz|JNrl%JS`)%nj{R3;#4V2Ls#_04vn740THO!fzt|U8a<0xG5S94c z1Kwmxy2HK^RZR<`?Vmq?22@mVfTV#77#SOf?5uS7iZwfIh<&#pj){qpMKj&x*r6}> zk37WZnjPsfGc)ZrQqW3b2bU}Uo$DPlv$IyaGgYsBZv-YOsF!SAU0nx;hA=@0^G;g- zo5{RaA|mWA*@o2y-<#|gexG|yEH94{qBAwvr1}yTibK*%Y&39vPI9WoUf;2Vlej~PyIUSK#BKv=aYH&0)D_h zHgwRp@CbY#l(KlTF^mDCp`lsa*9l;BQ~9LE4)_1v@+Bp#kxhhNwxL!U5+FZxa+aht z^F%yJx$fu5Uueok3ri%mUQgQ#S=KIxH1LJ7fk8jlFn+}+J}gcKg4zWt0*2v2qWl*3 z5toCNPC8C~gvHD{SbUeK_uCLh|BZMZ*6w0YeMxa?|Dz<2?{a3yA*uu@4h{||fRt7J zRr3~Dd{);?pIbMU9N~2;aXlhB$-lYJ`1-lLg9EoXEm4J!UhI5HvLGgKF^YvuN<%zI zz_=gVEmv-1A|{_Nj3ZBUqT>;#;a%9ogcdx+Idb~9R1O>~54D|FuZf?Bb=wdI8SCe8wGqIXBqMN5@E<{LVs=Tiv zi9hid9m=q^HA}ns26n~L>GT~Kq=*%u3}e`M&1-xzAP zS5*=6v>kn3KV-qj!oqrNJN(4$!tZocn6)Yo5wdcqaf6l-Vi@L=w70i6?DX@+^s@R- z%=`4(=dH{@WF*0d1jHp34l7gE)@tC0?ONSq9qm+HF!``@Lv~a!BM}sbBYS}5>EKNP z3|qgosMb99H!i2gd|G?CtN_E{agJUSTSrwRN+b_0`D25%J_fkm8qn^N$@pc@#jzCXD^*P^iNF0LNuVv zm8{Up%CyRdyjda$IiJP~2Q`&%_AbqNC0j7g})-%{zZz-}W1ST60#Cjt^Q| zB%mJR7;shthI5u~-|+5vK}SdK!kD+0S2}bZV%=uOqo}C(+2?0RB_UI%0(*XgMo%m*K4(%AEP-DZn}vnD)7=@tW|}6p z;QKmuWt$0G5P!&)<{wet^JxQCoKF_b_f3tB%nDK%r^hRewg#4BmLM^2M+b*g+R{gR zTj*aZJSiQ=n)+FYpRsY%9+J05KO+9dvhVG^q}(I<9Y=r+Set*QoNZELP|iil!zOf~ z-Qf6$HtWq7JV_m53h{l`(*h2v%HlW_Y`$IM&$@V-pCWhBP zOs|wpq~b!MjkHAbwFMYE^skd*z-`FqwccRsJ`_oQN%#6x3REJV#`UMh;J$5JyViqOuVA^bdv` zY%oYoWpgw6_4T!E1Pv|v-KZJa+c!Epsy!<0q#|Yz{2bj~4g#p7AL+i%>5aYaJt?P0 z-&vx{vaJzvE;b$~ahP=??@Kw4vFhq%o`kJWUn5QOo(9vvi*Lh2Lz-r^KpP{Y*>Ab3 z5R%6FM6I@&>FFTQ$mnP}WtaN9rV@^xx@X{VaH*}At!-uI`QEu#;Q%x;W<~sG^PxH+ zLq9(WlYwdbqL7t7#<+wGiT4Tm4v-BW^mCKyRIquI{*D^*t<&jtP>&1NInWZ*SQlkm zR~>jCwx=Ozp4E;l5DG6!uaNv#J4e(D$7dzJ%av9bu$dk5=;zk5EkXveLM+H<-I0n~ zBh7n%s57X)!RQqFgP>|}NRQPibUM=4EMcS)@SiKXj89^QFbY8-SZ^>Q_lP1DLS|VY z8>A37o?P$lCrEP(54*JPcg0=-b){Jnag^8WQ$boz|AgB; zEU4?N3|yR_^O8jJ`7qjFI6yK!iMVCRyX)zZspmRtO4fgi#gQnFI&p$_a- zR5(kXn;I8&3dnI^GLlZ`$Pjfio!AN4!8dxFnj)np`e?2>B#gjR37cW!5}T;O7S=Y- zR(dhYCuu|pfi-&i#HjGJ>)x3PkuzdOM5pMqkq${l#^NIPLr!u8LX%VW1GvFC$Ou{e z($tDQ6J+XKN=w=C{EN!Ak#Cn^RIoTwH;_B>VwCkovgux7cB$!@XG1&i&B6ky;t+IGwt&232fnNyx;x8NyAG+wQ zg6{6_>d6WLn_F7vElhS{D=-y`sIGoipcCaGWS*X~zEO9+w`T{3=x0mPc$OH!$g{q* zwo)@OF;P%ZNc;J9)Jjgz&Q^{;w$Fg_Ya*uGgiv#HHYy|9c8RMo?8#{$((|1)$V@KvPHX=`#Ov-tfu`U(~9PJ1S5{H{dzMib|HdX{4#jjM?+QBV(=-t z;*t9IZzZOl8!1rVTFhY|TbM)p`OMdO=MP!p9ewL@QU_%*fVN`o8Cp3KPh$6AVQTmF z^&J=)f!<3-jd^Uy2mVj>rhmN8pywPILn;ffvBXc87juXyX<52|!ER+6P^wT6Oo%tV z%~NGV&#U{%(;hr*f_d$FWt^MM~OWTwi3_*$|D8rp=G2Wn@%>;t$^uWS>CS zwX>Ore|1PQHA(!8t*he|3`%A6PFCWAZ}yGk<1Q)^YoxFHwuIWR#r9EXGF$ zaOMw~{{t4(?ix*_G=1X(Y9D<7-G(n zg#*s0=Q=F%vP@0;}VLobF zl%BsbdW&j3$8q@*ze;>J^P&rj=wqV{Myj=M+a35_mYZ$V0( zXZd!iOp-Z7{y;X&msP^!D1Rr-Zmw2_f_K(5>BAwe&sOFTckJlt#>o+eK}) zJ#7C^lHhg7j;h7PtZj1>HYSGB#hW^~)>Q?PQ)#GL@%^LrI~M1Y7@L!91#A5HD`)C8 z8Ag@TBWbs74b)hQYC+IWi5c4#XI3C%{&1!HmpL8<^xzukaJiitl&(y%zyLXXjG`80 z+Y1XTE26LTaOKz;P%d0mgodvWwETA~fd-}g7w`NMa*t3toCy#022;8vf!o-Lyb z`J+~87&htY$}wRpf59PD{p<2er#~owfalK=ROJE*KaZR*D}9MZWN!>%!m1>Fu4=tp z0+KFbTq5NeImsKEn$|iW(4EsO3MBR7)G3~pqHe{}WR^mI@Oje&QXyUsNqM&~>eVNB z$(Fa0e@UuHc~~jmbWn^A{{BrrDRLmb54?9JjB66Y%e!l)HS!X4a7{L-)*Oc9VcImAjwi|{nHf0kt@>K0A|h3k|{nh z-iVqTHq-T})f_V@F$!R_dkGn5EU_^cnn2`q0{7N>HvvzyF{^@zQ?B>t&*1p?TjKl1 zG8+03^kB&2SA|@3cb@faqMlH8my@B$nesfT`eWU(lyeX95?5F5c=EDj=zqchy_k>9VdAI^5UXmqn{kp>BLF%TM_tuIZpa>4dLXvq4?rjbCL~# zoTo@>OCPT^F+y&4Q9q<7m!gn_1Pv|`ZBO=aj7XYyF0pfQS4t*E(N{uOs_u>Msi;ef z>7VuKA36whM%~MyRVU6D6T1b2%l?pNB51GRQa03mszQ)eX5Mwi0OIH)jBcG7vG#@ zY;8G>jEtsMYQF7oY#wS~t+?&h+5m@LEV}*$^f*LNI#Pi(zf5ncm)G7qwT&LR@&yKAe zEVXJG8V+Q?R7q&(kY&YTr=J}2oZpgR6uY}_A9mTu;#gM z3~rlu+ieDyKi_wvI|GJ8MqKlx55oMPT&@Z7ijKyg-XGEzcUgbvgq-KeIs6EEV@@{M z@pjNSx?n+r0bOy}?R@Hd=61XaoGfkrgmt^>i_00~y*M9i2N(Xt)=z`m|9EG|mR#ynY@+pc9>ApdpYc;e(_O4Sw zK>@U>LVo(Uh^=)CTvb)IBM1N$3t)&-T`4^3gv^+~#^%S!H>>{aq|8* zFzlyq#|l|_8)LEg!=@%}R_Ws}0~9arOSX0QIH~)u#JXd2^lS6?_q-vKPn>CBYmH^amIy3~D86aO=d z{jJT>tdPG6gfrHpIOEBx<6L3`(d9=C8YKR!+okO6DkQq8Iqfg3lvrHR;O}Yj9e=e- z#-c*)3PQTMJ@yP-G&6?A5?z(}L#j?qb|(szGU{RM^X`cv^xFEHH^UXetUO^5y7=ev z8vx1(@I=O+`-qzjaGR=Vsb}EAq3(|6FBa6V#fZMVP1yL?Qxn5jkz2wFsrchjW_;Kd z5PEMljUo;I-(47+O;A_{2dd8cX57MyFNa+&)wN1JbhMIM$WGIL7LML#7%m<2m?fmR zzt($=zMVZP-@p)XeHn4%J%2)o7kAFM>+jg#I(|>9;JIz+e(j9`sy9Uw?<~hnMMfnw zS&|}mq{8+tS001jn788;8$Zyni=6s-e0#u3r?v^>6eNXEKS=%Y`Hg;a=`Y=0l3jVw zJ9pR_o_)E5@zvx_O$%mWXFH{J9vVNCx<-0Fva@%CT>rbUFCITX|H!&U=)r-*Was$s*h?QZq*rg9M%+^ z`E$3bICl~gQ&UAx>&n$EX}E1UCBOue|-^f%cJ1RGVeozzPH% zv|pOBKqfA!;yN}r;c!T#JN~mAr8ru$Wo{nBnX@>*v%(TLNpbP$?Cd#L1IKWoBMN-}=jz2$gn&mdYi9=T+E!d-)Alcf8Taj~(M`}2)E zhrs$8cepE%Z(^t&-n}MUR9xCijI^B{yPT|m@^<+>u*_f1z)u^Sn~f6#B96)dSYQd= z{G22G`U$A)^wEUmGn#Bw2}hce3#mW=mV%_0=ROs^jNwfVTIt z6nZH^2&}~;)}tKx;qNK77n>dPL|Nvy!vBuebJ;$3M7y2RYA6tp+&=-x45$CxYC#nD z+5uDVrmvV-=lP6r%h|E4e0JzBjb~&Fi}lt-Y2w3QkFp5~Ypb?b0AAm+pAEZ3qtPuh zQk9b7ejPjgJSgF@4-2X;<`7r5x0v`(eZe$1TFsh#mh6cxpiHY>HjcF8uD#5s%0qov zxsSm)<^BBZ;8uY|N@T=;_?B^uD)D5xe_RT0^zK^p%U-lag>G(#*Plg#JhZfxT}Wl1!5)m&66NO z=)0_eQ4p}c2hHv(yrPf?oD{$&`3j&f5_2=!_WPD!NRt0X&Ixcbaw zMD0m=UU3L(g4xI1n;Za*2mg3ClIut4{G;?$-R{coA&xG)%iVN|^V#MG%CMX;oZsDZljc2Bfh!EY=g&s488dp;A6$izD`I&hJ40s{6Q=Dp={JI){Pio| zb4SL5i1KoFIAocLJGma#ZdS96LL%HgF~079fjb~&8P3R7Jg^f1d3l{3ezBi_$sf%J zC;J-#vFIq`44fH6PG$LBVWhZ`LpF-_+PfJd}_AdlCsGQDY#9O zx<8IHxdBmWOQ-G+RebJpYKL3Poz8h7^`X#-_0#L%o|?0D)}1^1^}ZO@{oQxMtn)$& zXXnm&Xp^bKEFt^Io2Amho!L~e`yGSMiu;Fkx(AP`^X-K-h!m7YEI)veCF6}|RSLL& zMoX7_J%ha7)=71UWfH>T6+Sk#o&k&hr&mK6YT&O-hA4pE`6-|XMz)*o9~gJ?4rn4Gq&7erl-z8I69W4*X68MX;1}E zReQk}ZdNLPI)~x~^`VA!gT;xoIKKHtJ{{Hdi`~o5#?!3YEs&|Z*MW|45UcG)&}TNH z>ZF6?CB!U!Qd3joHz1Sjx2(BnRR$=Ag@uLmDBlJ~Z|v1%Y2j?=(a39)_or5L_^t8# z|6zp3n~si-;%Pi#=q05@2jLP~@-gE|j&r4^zI^oRFli)b-&F;(7j7vug-axytz+q z{T=#GE6gJELkE62DmNke*R|?l`}9Ml24j5scq8(kfj&q95SpHz9&ZnqD_Z~63I9kq z3fOYwET4tP*W&{dXOiw=j~B{g-9`74zVi1sQdW6 zi}PBqXQIA-V%zTGMFB~#*Cj3&t!{)9_IpoF^TxwCYuflWomr=K_Bwv>TPxNj*7)D; z^5$LN`MJ2dK9(34T#k`UGxK7fpPw(dcUzAU?i(=m-fsj20KQAg$J-HW$sdbu;xC$= zsu3%P{WDd@g)V;kw&ptim)AZVgDr0RMvbF%_eWtP_MBcGFgl+jnW>qXioD%=6Rf}h zFO7#ktWsK1{s3T_dH~)sN6&lS4V zf^6XqFWnB82|*v45YHmaD%alU$yy`fF2iGZg1;aeQOw`iknb>l$H+Op8b*FjDJvY} z+hESDdUL>}6!&}Y3Nno$kV#$oCX_!aMp~;NV`w~qCfO=vkBNnC=z?W8v)TgiYAL9w zWYyH{LR+5|JbuE2p0@7C+zaOFYA(^a(m+@>*e?iinSKLH2R|Xz5_*Ra#L^x{Ck}R;c(Yxd_(3~%*PCWlRv(Z9fOSR8s*x)&x-(_V zAN>C;00JertwJtFs9bj@BVdRICg2()fbqH@hpNolsnX2-Jg4GlqQfD@*>z;R#&vC& zfL45U9z}i}|Er~?Z>mfA-$aYuxf>FXpQ2NZ9kd>5;>`fLop&=;Y6*QfrhCx3L-)l{e*y%z)#>Kw zh_CBY>$d%-1(3AFkIAjm)k34zO?2M|fY*w*R0$r80cZJ22)B5n^Oxdkobwn@=j(2W&2g7R=zKamCIyIu$j-=Hn+ z0L!#IEK<-{dVz^PlLfva{U~#&8 zFViqWw1P{gRKDJiwfytgnEI3d2r*xAzuN(6kN+)GC5gS_Z<2F_1q8Zw&n*G4$HqYL z6LudXf!1LA)=sd@(-B=NO1@t43-9gOrS}XL2;OS0bY(}USpC2Qwv!58%-|nL&yrSO z_L&Zjp0C0?r~C1fXvX62wsArtC4}dPGe2G!oH#cF)Xg9mB((lHF8}v1?yK5+HxH>h zOqR?0?pps`e~+hl<6lbGr0~d>USQ9p1%gs|60kr+q33Hc3$=JOm!a4Hxdv@oDsVnEM~+bkXw2F zX7*_G%0tJ^H5QRL@wA`6zm%Eh1{tW!z2lSypo5EmcLlxswGxLP@dV_)>{)u_-?>6} zE)4p5cd>vWzex{tT@fQu_Kho%I70|0}0K0Lw7+p#8b*mOFzT*O@qxrf)=aQW^6{nb2;cmnoK7s~Ejw9J%?=cLk3{ z8xi@n?*MT|5=9kq$CW%v-ey1iyb^GSRz=xo%qyG<7-#%5ie71?(i2_xJE!gzBr1gZ zPbP&%3@r*`?FwoohnH}O*_T{Gx88y#n4=-*EVdCgGuP|v#UoZyU?r1*i$QrbWx(Po zMmfL~zkiTJSh4-`Ye3b_qq{lenjC)@Y05s!Kb{QyD`E$DH5}xX%upCENA%DbXZrjD z_M;A+(BE-9a@UKuURPNv_lSG{t1q^%uG&v|T^=}~_lM0Gpp1+RLnIrYS-Hy2tBamd zPyi~)oA|%+a#S?rb;s(h;UztT=Nc1I2Uea ze9-Zio!BppZ{0BGy{+dwZtg#n*1zJaroE&56&A;^HRP{&;2QI0kX@#4e%G=(tlzH{ zFm_>(cbnGi*2941Xcwg zw-XC!R9!v2@^#J%U;cD^%laTO!Qc;_$G6GgmyIvro@1GM(j=3>X6kXXT{^uY?6_=q z9m~LPI6}%A$y!$Fqi<*t0_V$F-usvic{l z3bjb&I=)-H?2tB>t~e4b&wx{@p{E{edC9X8Yx%5a*G4NF=kb8VdUWK^BENtkn+KCN z7JjzxZ&IDi5c!7w zcc(Yj@TtgSjny|O3~FCN!C4RTh=+o^C(;Mk0lIH=(YXITmo_uYT~~vt-#x!W)!~C> zo4$E@j$Fp@LCa^}7w)c|Po{`8FhU!h7{3?lh(s;@C$&hNvs#?3Qxf8&xbx@Fi?%Iu zO!s5_qCeb<9v@Uw9_P`3Ob*fyzx{Gvy}MPR`1Vlc%Kf}=Z%~5bZj|-a?d0fyu`6?^ zzZ=e@14*Ltj_`-S7v@0(EXE+v_XHBveQ&T%jb!MN{LhBHIvvd$D8QpW%v1n_im$H( z1U(-uK!TbFs$4713Ct}2j2=+JaU&BPFs5=FE4D`1e?$WlVs2S9gegaP#!lT#eQFE2 zYzkx!{w)+|7;m5bwO`uHj6R3};&RckvDz+C<#!(6`TfC{ab@)lIRnRC%B9O;@oEj} zfgFBHs}IAm+x4FrSy<7pQ=9|KRCE)AP&W!GK1@`|Ja+J|e?ig+w4ZD*KM~32uB?gk z?ddjHv-U=J`p{UmJ7ejq@9RAtMJ+R>Q;Ww=lu8mB7zu6Z83oO=PNvSA z*24*bVi95@g{4@X5>qAn$4FJopNBg6x~NI zK%_~Ml6&Hls!-JT_>0lA|8LI-CaMaeMXs8z)uwO zM(!os7@HvD!^n-YjG0bKxLd*Lz{H!Mi|fZ_D5QFqoO1n;b`Dzk3x9$w=Cn%VNQ@IQ z$P#?WuWr|UAU3q3q@+~mwm)Cixm_cJ&HiOPc6ymqpE*h)hav0lrRqxt>L-s1$2jV{ zWnZsM?odPmXa*Y0s!6dU<7M-tzVx!NfMrdm6}YLC#~*FNtvZAkJ#c;*m_2qszCNW3 z-5Oi~k3an*nwomyd+J;u>|z@M0U0)a zNO`A^oNV%hLVS$eKj3AcCV8`TL8tui#twCL2PkRu*}Ini--l?iJ*QRWAHe0-2$9*T^J-3A*4X+jXIxztCmClo5hAC4+{=jT+qG(gbe zMFN#v(=9b%QP?96=wYtLnaYH0AZb=DL9h-np&}BFsvD9>zysWHaL2a-XMnV51>0F! zSw-*3mYV=*!BUwlEj85$KK_AUvfum$BXrkMDYEp5NY-KZmH&$ERZhzU?URQ+4i869 zoR2L9_o;UsV)2PO(LayaJ)|CYbNa+7pLTVwyr@sp{wY8s~woB0 z+40S3I1^|rs?!O-czf&TKXu2nW45+$E$$aFeVWoM1ex`(cwGpgTSvviLggJhK2{`g zsQ2LG=LNHtNUtVk6a1kgVzV=Klci9&jbF>rZ8BxCl}+C}H*ga)n0d`QEyl~qCS-op zm7H8`sB6fo;3fh>$*`k}>j9o0KY~lsb*Tw&e1|G#l_%Ep8sH{*iN22@kHDYGOnIfQ zi)M7up5qxmRXU4pIy-aWE{GRI$A9+u!|)*AkXOdF;31=DNe-IFnz^egul`=HQ#$n! z<&cL1ZtBxv%p`*q*I}GP1NN3qk>-(XGcL56Y1PO~Tzvl`K*if~8qfYZ6J$6UNzh=QZ zP3Yrag_rLNHk3ZLOxB*;C{zl!2)7m!oQvVJ&|s6O#+`cmp`y2Vzl2NQ=NUW z7VRa0=rgnBQG`X4xwyM$-K)h()6-{rKqaCK-8K;p4Dj$#~3|4TTHXc{Kf$v=7vWt}=|;Hh^i-233gNbfAiTa2(Ni0{@Y z#Z=hPK~3wz;>sata2Ah;h4Ro2Lsr|H8HE^2ZD`t<5u4a&5Be;d)SM05N3_-nWJncx zoq-{iO!htN_^(t#l&z>nyy4k!#haD4Sv0na z0u-J2iTI}(9r$~q*Egm(y}_4P;W;Ty!GmOD{RVK zDb?}&NCJ6!byEMVMM%zJi3IwrB+G#>nUb3N$50CA^oowkhzj5C!~}`)f5K)1k_0iA zBGdEpk?6xtDGq*!#t0HlYV^HgN|!zANQ~?k+C$V#XtoS)}kZbs!^)(s8Z|iFMJOCgA|{IW&npA~b`L zkcfzh)w<(Xl&Wl;LF#8#LpI*Gkug+^2d0IMvcWYn7?DGz$jWl<=<+?TPb9XY{Op_y z*YP5Ox?&tq?h5g{qObSzVpPb8%@A2Lo#g-0?lhmhvptS(grJcs4?vPTBlXoxP=RW^ zos#PpyN=%sXKZ}ho@1De!+*e!E1b>QU09IWPTu*ZgqA>BCO&&Z8J2|bBK6hKMCc*M zf0ckj%+p3%9dkMmJ7^IBfnbHGXkqi$o*HbX+ElJ?2-*$U#^aZek#G0C>stZ>0v10) z33m?n_xEi+e26rz!GkbOP0jTAz*9&v>$d;9E%q+I5hIvzIr=RFCMW-~drpe|Au z>Elk!?wL@50dLw=9+mexNAq6%5qjcRgI{)Q{G>%?n%9lT4CnB{6Gu+!+l$Rs70C=@-gs67+{+` zKC1*JD`fvyS93SbG@Q0^hYa5D@@Y1yF(I-$T2<2o3akpUF?(DFk?BR@moHFT3p&t< zVU}_BWpfzm$>6uQCT^);!v!TmlZ#(PhDZjAx7I+DK7fh5B6rQ%Hn=>_v_+^QxVDtE zL`^Q_GL%v+5lI<7Q>m{~+rP+TLrIswqMphl+E8{Q*!soAdFK5n$B(4XWraTn3)8}G z1%jq;Q7{6+C;yefZW>U?$`AUF-`|AyX8KaEjrVsFiUzFQ}wYqc^p1y&ewSm{_g5jPimLP)qelEJSf1w{WqYnOBY z*anQR1?@hscJ+FA9E~qlZ-|JYnO1aW1+&f75w05S+L+8W|9t_!TTq6QWMrjwmiF|NWUjAw&Vhh(fZeXM;do#!Xxw#@P6* zF{nu-m@Zv|gsg-Cu zZR2jk!Bp3$w}j`N5r7R}cd|rlazFU~37kjvu&xty;Ns!nfi3r76m~Sl)>iCba;IU| zcF3=AHIU?vb>ITNos_)Yuc7TtZT)aOvEoaZ=dsfK%C~^>Ve-Mdjq-*ia)|#p=fU)I z&7om*_NcqnAPxHCl1}q_rc!5E6^IQ<70d7{MFG;wPc|4KnI01l+>q!PQ`pRUf zhSlxf>sT7GlKb@U5qawk$#o@jtGc%z;ii;+SoJZ*SIBTv4CLq>dJN*gY_u#xBc2xa2P+c~VbbS1Y%e-Sz zUwxrt>9wK6ZqAjy?qLSfmyaY~%|#Ot2@N_~P*d)ky)Yh6dqF_n>@X+t|-bs4;7b=fKFpkBON%sv!?6b}@%bx2+I#Drp ziE=CU6yg=QeZh|Otkn$P^q|d0Fh?siIzB=bz3R;z@>X-BR0o+KWnmhfbd{OZ2`z*b zJb&2>sn&%wF=}dRcD*Q-Vrq1CwAH1w!V&*dXLpj#IGkdAKh~R%i6d{9oCIm%sX^O=?Hr`qE+dQ1Q!ww-Pb82ptdReFXu!8~oT9laSQy z2bqm;sxEFG$5Gw}zZVV{buR+xMj%x7r@|In$v?q6 z$3N)Jt~!6DKhKiejuc4F$qPMR6%qe*_;~N?9kHvyTprnA>laz$KEphFaUfAqP{63S zWw(+Q`mLd7%`)i8w#UumpU~tNqF0EyZ@KByY5bdY<~xMG`aOHUPCpQ5y7KShF#fUI zPSpPMXCr;+-;RT0M%1SmwyKVCa(bGuh8g+@z3McYw|e_KhzK*C&S2l?#zzuJVOWgk zO4!)i{uoSRo$j<>Zlg3X^JMmWK(8=ya&p4k6mVTVXKf%Eac*v`qTFxJbJ-VI3y<{v z5sBV0))GBOx%MT{crP0EpWkngfCz@iNqq7m`JzFxlOnyVP9DC6rpC(la5 zgfxjPOV#3 zQ_~L|L7d{C`zJW;?4lFM_We&6t-bQTIjk!}VdF`mSk_}@4_n9EO9yxplZ%UX?4@&= zT1^OAu37&t3qiI@X5AI#2DKHZ4D`?YKCY8d+-?<9+Zmdc;i|_{$dADl-#?w>iK-G56kHu-&C}i2XScQ!xDdCM>J5GRze(Y2 zn!z;|IB?KF)6m2wQxLEN#x3kzD5{(N%*|S!Q)VQ%E)^$C#trxMU|;Mngw4+z>FVn% zqMEg5C_x?PRgUjIe$-s@DVk*xEgRl#9T@Q`id>0c*-5z0aR}pMii>A7gtbk|AkgoIfd1ht$7*{krUt zutJmLBYfO=K~4Gv7Ec#sqLR2gB@qKmse&DnF21h=ZPAYRXB-RL2qc?WJ@!cd1G0Gi z8UgQZqH}EKvO?fgnjS$>%Hw~V>Y}1m@3qtZ4XE?N-t5IEldwm67)@Jo<6A!flerEy z{0#6tu6#PmgwC8<)-q2{PSRaK6R0|b{ExaqxzIdn5~R2-2aqe*cltNX)V>SasXseE zhvd=?V-C6h;>+U+jh_zcWqG*WlEMPXeu8wbk5=FWxl^$y zZvFJN!*^!hjd%Z1IMBMP&O%SI>} zGy@E=yu&JZSt$a`4cmvW_^DA}iT}frSdyT~OYbtFz+=K`Y-|Ks_A7YCwqMNK?m&>e zy}e&ghB)gSmPA1$)ZTzaP-i`!TXqPMx$v$g1;}whZT!P?^NOn+n*s-h9HQaEB+IJg z{mJ^zJ9E7J11zHdG!-6${)rd-(uKF zbS)*sfhKi>#a^-_O+2OFkpt<-f0@?OL`-CkGKW$|V=!;8;Gmfftn+Vg>pe9Ij4@o9 zU)vsqgn<|{vf%%6*uyDdw^q!?p4Ab8bI%+jHi3AEl2-~}AMiS~V9{0dVk%j`{MG{j z-W++sF624LT}pX)Lyd?1N=z(j+-H;jUsz!%z0y=i(*Y!NE*Kd`WnPzCiwbhy1l@1+`Vu+J{R0TV-}-faJN_GpOB=9qXpr~bE&eWdc(%yn^#5l82q1%x#P?ay5^u{V zKV-AbD5E4LfLr%!8@#1>BJCzih?6Mz*7{3TCs%&0IlghyD9tf_g6(I!tfDtg>l2hj zv+tCLGS#B@a4G&B&|O;aEG6v4?3wJ?8!@F#Hzf@*)m)SU|6z*L$*{3rDYs+9>P`N8 zco^3jT&FYeKb=wsI0^K1kA~R8`9ct6OOhI?Rg@kB`ueqS^VjSXcB!Zj#mx;30*adh z6HLHwhV`$1*E{TtG%m%{B#{7)FlLVTp1xCP;Azb+2|vFy=)57z_1axcl&GNL0BzX{J~;Y`<13m2nZVJEv<}PtRU-=j!*@aOdxMZ}fAYaC@^!>} z^Z5gq2c>IOCkD|nLu$5%xd%Qfii1IuUduP~E@2460UTzImBt!?ki{RTPL zE8yq-%xsNbQw_`a#|}xYEDgKuiIO9#t4admEX})Mc@0+&)|1{{1;%2lHNp&6Q&(=h zI=3>QsM#TY;@R-S0g`D)-g|OUCBQ_y&Er(2stsUlR`b*P)#4M4is;@R8k5QrTS(>bUJMXUG*e*M-qn~_z|n<@WJjMB7lOvJ zur=DOEvzkQv2i2u{#!4?A=hGDfuKc+X<;Dd=>nsXS5d%N-VYcO-WfzSG#p&U@W@^A zr_DIXUGc+ai~m7Cn=QZ6%EL`jg(%-0f5fb-rGoih(DLZSf*^?*9`jviBl5}c2G56% zAJ^Lb*>)u?<|mh48sL;|=wwKpg)ZfjpAITa)Z>Cu_xa}aH9+uYN*qWv6V%vDQ`I*# zlwAXD1is`9qxk|*u-M=*FMi?Yk7%%4Bz}$FKha?Up)B8weT$FA&gZng1*YhawNk&B zDZ0|bH_n@AEgJTR;cLbm-%{OGSPU{gKo`3lS30qxz?Qmak-%Z#B}i6CkU3!YV}Hx_ zjXax-^uIPLi-Wz%e+8vfcyP{z?%3o@T0io&MSdyX2V#X5cg56=I`uT4=cpV$;yjaZ z{He3&8&r1R+>FF&-aH4Z>Zbf|*njzOS}hH3dGbZOY~u0WtQhZ>wCw69-*{%05)UCH zPwNXgA03Q{rr3=!u03p%b`y&uWqvhZ*On*c{aFf#Sdu1 zfpLmAG}!xQ@qg^|)3{zmMeAw!-GIQW%<}2zU%#HTY=MJ}l9l7RGKY~I9ud%mm_ z`Re6?WcS?gP@VI^{NjfB_3G4VD>|k4^W})LO5&yV$)mr7wXYjl)xi^OaerfI>KMi1D|zmc1K{oy!3WgGeU*FK?7?9$k4#aKq7Zj6^2 zLt?4=|5lI6z&D-!kdl*9`}{xK*@^xqQAA$rZnxl-yM{$;3p=Ytwv6Wj9UL$FEcXu# z*uAA-dz^PfUiQCfgfuWI=VJaRNFZP|WHo0rw- zzk7gn3uCs7N7#JhsI0clGi&`ZFYXtPQd=;VK0cGJk^xsO8QZI1b&Q3By5InfS z-+P!R?@WEZqt^)`v#&N_qB%a}6g|$PM>ve@S*4I`tAx?@;(G;HceX>dGFB ztrCa;8gg{^Ni#=o#1=Q4i(fxcLVv`)V*a!iLm8iFB1n%uAS6YhwU7<~Vq8c_NN^H^ z7eCQhRbU>r%>0VlL?V(#Xv>}Dag|JW6+j@vDU8dutDyl8K;-yFbZ>p^Ka0}U zGFt$>aK2dQPoy`%kLn%XKV4q*VQ?Or&ks{Wm_~mB6JzxZW+o;#5KlJePCVkU+!vCy zbB>)T!9Q8MJ*Z?)Nu&w5c?n5#oGXc@ch7ZHu*?zSWemGynhK=~mzfQbVZH3t6JgF) zZigq2I5q)1*^4-nkRFr zCcM*-;H&^;`+XsC;`En}ArtN7+0a-3Mb*MbobW8v1(nH3sAswi2V2~_>rnc>lw1wN zZ7y5q3{b}k=D&8j?JJ>UOghQ605G1*CG*$;zjMIK8FRRUEb<__*V5SP;qSrh6zj58D20hU!GH{{7oZJ(k7Q=^wqNDI}(kG!uU7SR>6bIJ*6rM77Zv@?? z*SqCf&@pY^9_F;#A)E$g^=s!CS}@+n35@wg>cSDJB5;Jj#&`C=jS{9LCT{kTzdA=n zC4ZcYC8rPxaOBd=-z0-igGLfBDIH8>|cXc5X%L9Y}7)`_qRCf^S=>fQvWe zS|l?gd-J>3%O4oS?q?3rbK~yfxv1>%TC?3qbQ+eag%Nvz$ zdwrGmpNy$u@#T0Do|{Cy9D6!{vKirFK_hLs0#}qWXfQC3Ua0>%bE(;dTKFapV+*Lz zyMeuL{_qkY2$-jvw|3T7o}YrO#>%<`@bQaIm=R8f!7b-z@r8ji%#C(R0IyZWHL_IgPS>YOLHMt_B+T zC53qC3z`?b>|MPq z2z3F|1sKrX2uVpSZ36*b(Qj)yzMhe5?Op&31Q5&wU^$mWk#L`JKlY|;#-V4H9Ws2+ zI*W*#z8Bd@h%GBCYlfDvT{4L!yJs@27<<3USy)P*m@baC0Ti%Ks5W$ZanV|bL$$}i z=7ao53LIQ=b`!2sW7ju&ZB5+)cSGh)B6Y2crC3+kn8KuqnP0D}ui&H)Y7JmTEgrrz z)_Doc-lv;%+uj{c;Prd>?BnBeF-YRH3FHAP^8OYpX3V8@n0zkHKK(X_Ujb9Oui{V4 z(f;6BPGV?Sdt8KXW!H*Dsc+cv(VEUDO%5N}+!S4AW)Ya9w6hB3ot^y5E z>3pJsgOd}aAXYd+y+mpGE`!+PJ|vz}K)9zdSs_y>QfZB73&5BGQ>afsx;!8Lo!;tl zyEmt++kTxTkHbp;Ts9eC1_$QWI<4Osf@B7MX&d`%zO*&kUjh!WfR|%q&O?iq#TBFU z-c39C%dxJUZeYP~rnBvvm-^z1Je^Ri7)2O%v9%sh;R30nq3$UaOg=uNo14tLT1L~1+- zCkxm#L;lC52rQ@(k?bU>rV0hp3%&)0PXG|h>+xTTs-9j1K-W-ER;K1+!2|5@1|r`M zza@(>O&I?GRE67nTRZuzsV?~QPR@dUySRdKEfQENPx8?qbUFH z&JMr}g#kbEi9Bfkm4TJjYUbNrX1%R6jI@BSw4#FZxgCJr0fu4WbwAGS`*cH`SXeLP zsBcc>@975Oadp9$`YT@@%Uf414>|#*zFFac%!oUPx7j5K(`9WmnMIvRh?ZJsQ9w(j z|BIyP2AT4c)iIb1{D_0!(QeL`0kS5gBhzo3(FOEYAXHf;ymA;N%^jx#O-$YkSfaIuQuY>a_~j>1Vb+#frT)5-0RL_|Lz zJEAU>`cjw!e60Y=YmCVBzl;zWlU9e|X$k;6nW)f|m8V8W|Bzc>k6TbsP|Uyj_Ebj$ zi~?ZY08~!%>&mgqcK^HjGl%G8YTl+4c)>gIxc6gkBN`%lVaXlE84YZ%C-pDWoyR9D z4Wsqdf@vAdJK8`7{zd%d;>KIW(9nU&sa`3~a)|7l_xFjQomgX4_ySj*(G}cqkAnN?e@JCMB6QmeMCMwe#RV=600O@@UMnAMoDKn+?+7 z2C6N@!^6YW?3i5owHw73dDsjdom$hN}r^%;IxH z`tM!`VZu=`F_Ca_HSoI9_@I}8%}xN-EJ87Zo06LP?PFb*7tBT=9S*m{J*GxA8KkaX zC)Um%J>tl8r?02_!!aYE=8g+1z(-vj2QWZxD!KJ#;RoWElPSr*u{0ms_3|0pn250e zs7h}MV62B8qc*n)ci<4wj*4U`B^Ylpb%@kLjWF!=pOGyjvqF3_5L?Y9b zORNKni_)~Oj*n3FUe_2-ZpZ`{9H94ebGsD=E_-9>0JNyz@65wm>P49E-R|BVWQZuQ zi+pIDtLim5Ni*iJ!RteIk`kPA+x|;w9wmi{$YX3;MU_!ZfwTa#r2!!9*{@!&|Ne6t zbje%}+U1+%xI^EC9@L0Uh}git6yq2)wsuU|V-Ad=jcKN*?ls)m_CLTy zg1~vdE|$Ab&BzsIh>tRGx~g^$Ub&v`(aNX$JVVE_^zY%`bpzFR#8{<7MqzG3Y122n5(AZ@yYc zdjj@7jbxCjG4?6W_&qyGC`MPARv;lEFOK*a|2KUE)~;vQ_G80yF)J(lpwB;ha%~qA zxht2VfLyz&2R;}dXJ==rX|z)>6g_qPcJSW5KmIyDI94!C3)pQ6nqo6EGZ)*DY#fKo zfYmp*VB=3JVz(QDFoJs2P@<`(qv%N*eXuG+{{>1B4663l6*<@+C{ zsf6e57ufp38)^vfwew8dNnE{>1cqV2(UDhT-HECp$Zr{M<%2!Okj%;g8BUnsCbkP_ znJz7*m$WW7O^;RxVXEfHeuB>%OM0+y{|8!3b2V;Z9wkl^NDi&q!=KE;mxNVd47Pog#;{eiZJ;9E=IDoFQhWuwaU6yVn8FcB^nT_J?sx4pdts}ZD&T{Z97GE4 zNj=e7PTODxGg~B+0U{is)yR>oE;Whfhy_zvO5%JYnnX4yu(Z&}62L@2nc$@%8z5ko zjCWb32}Hp7;7sPr=P!H;IML3!U;(S=0^`q(RF>XnIiuW8R`H{wWBn7>*{1PDaOZ+V zabR3R5rG*0>PsP>V!Bzy@MYUB0wL?A(Z)Lap!zu}2+}t6A zw?PpR0|zHxg!Q@=CSs<{-Zxeo=!W!#E_3VQ0&84!W zAL7)yI09AZhs>7vI`2h2>RA;fm>FzS292$RS%W0Ua3;CJKZ!&`ojeo;Ukut7V&5V! zWvk;hzIy!hFtW8}oL*gx&72sQNtp|JsoAX?hm#=sqYBZshL2t z+U5+0IL;2R&{bY1ssPbTDLU!7rl-o6V>Pks3 z;IUKH)eVQSJTeP6*$8JOrZ3@d8DBawe_qwd4L$K>0l>W50|SkP_U(4Wn^B2~RR5!p zqX&DYE#J|OL@xv|DJZ5}Zw@9nNWNEH1_H?^mMN8h`klq=UalP$uzn{QM5Qt|t4x+J z{^`+%w&XkoPnDb7Bbh-xN|SEXv$8wA1wd@R2mb;4T>Pom0z+%H21k^T8`dJJoEz@J zaT8t+LkDhj{)>8(v#W5*Fv*RIc7TW3X`&0mQ{(30(I=i(Y{(0NXOJSt zC#cJMi!708jJoXAv$K0_nKWY=Zfo41hN|R#6;$HCz`k4iPAf~}j;WWGzMG#-u%BVl zU{tVKF#E|M5u}g>Fm(Zh*WD_x`+)P|k1Thb9Y5g2=9%8#1?JHeM%i~lWU)TZ9rPEV zGL9Su!50NB5y%HcMa5>=>k|;%sanSY#Kr%LNx=N{_w?F=5-{@4Ki+|IFUaWu=4o-p zZ9-DvqyicxodasfI`ggtd`sF_M=6wV3~{;j9vw}yWer4RPxB(`|4Zfh67dJ|VZy$c z!os^-&IsU7=)4LMq64T(L|_^+Hi;9l|BL>k_bFFrd#^badmOpP^sD2o`=4HDIj6zPWeMn3U1EV_akg^rAlpLfIm9lS*2d{Z> z)1~OYM1S2Zga)>eYc12tN2IxfN0gLfyR(v$JxX511|g6%w)D_HTf;Lu-ns;&^n25g zmClWG>&^f&T`j;w={9cHZbB-aeQYr=YuSa%JJZT5_PpUvn7BG@$ z3Oi)Km~aOIZ3{gM%K$))K}ACYutQ-0YY~@^k8jLUOj1Ohp293EuZC;+^!gz2Fp#8y z6dfrpog*@_<=rpwI_DC&^=Coc6lO7J8^T$)yJbnBS<^OfLHs}_IJDM@g$mSA=i{NP z4jXqz^A(qal*cm{N+|!)x1(Z+kP(67&rFU151lZgM2$;N)cg^2MTgFyO?TJQDf>^sfDV7$Wwi zk@Kv0IsN@prfDSG(IXNH5e9F^R%ss_|ny) zzje&O!;uyE^FDW9o{4T%tSs+xY;XYD4P0C_mDO=PzOJrrYE~A|{R8qg5V9T|8;d&4 zOsniVo5M7yIsh#K$ytC;G%)l5U1GHxU*UNh%Y4iQGB%E^ zs&b5qS|T^4G&8utbWwy(GBV0dPn#M*_1FL#sM%7ds(=+(a4}apAfU=rA8JQRh{6%u zwR+mSYhj<HA5W592qyhoN{;gCppm>oIdWXh2LVjt>IJCi0WR-${EEy z@86laa&nsMfD1AG{S6KHArNI#TYwZmCnEB`$Akb0S=l*|XFccekP@8J*_qG_z~Q9_ zQrMCW8}~?QKH$2s0P-B!vgZj8pD24E;Fy}^X`Cq&(Y_%wNgDfT>RJCPEi!77Z_PtyFSVQjxWV>Rp11-D6DXJE8|dqxcQA+i?sd=zFm|h* zhzM!C+b>q6rbDA=80)jA$2K7+OY0t@arTfi*o(%xvF`LnbBjyP2C(NNQ}go zOHn;NZ%!VsjnQGkTya%M7Y#)P+rxk6li93<$niIsUec11LOR!lPrR%`i!x8Hqb1iw zq;$iyCQ;h12B0$oL8+XUKOU{4;TLw^VZU+k{?`}UW;Q~=l$uHi0qptBd&;|J5lRe?5{~dc8l6n$F%5uU{XWdaJPP#m>!d zB|nmFS6WsndD`lJAn4A>s)ir-$qL|2VWA*6_r2#?y6ZW5ovu0tJ`9k=6*3%wI3wZX z`gEZ^+}pQtCib$jSWsyGJH3$9q#tePodD6b0Iv7wLG?*k={Dujj~8HRoc#Tm;P*en zf!vXInB?qCJ}-;MbwD-Eonv8XNn~ZiMEHGzB679w1UkZY|##!cwN9_CJco zg@tx+_gJRP=hf9^{F0f8*F$^L-k&_#g!>~%NL5-AB?qm4VUK2Z!i0j^T-0<@{>OuL{O6Tv0POmBA3Qt;sO0NcREv0eZXS-(O7S&-J^0Q-^ zWZ98DZ87W*Gco}tM3gMB{71FKzJJpUtqws>M)YzLb;)Pjy6R=}fku9p12T$=10+s5 zDQXHpER?m-CMRD)7{lv(=hND`)@b+PWMkcI8H=g??OF(m|6|w5UxTsVVuYOZWg`)Q zwHW|$He~KP1wQFp`&T@|mVNIxrK+xtE*8DI-oR756aKx8xocy^I}>H0e`h0T4yo1F z6(C_4*;#M%-5F{*?r`r&vR89gFO#zz%_!G6DsFdg;y$)uDqEAdbYuum(A?eS56|Sq zh~|o*)+dtXq#pm1Nw*;$L?PP#@~yw*Hc!`eE}074UJ{e2D;nT$FJ#6xiVh#U*FEbp#iwu+l|@ zYVUOEi0gprS;=DRjg^(&kr7ne2n0k9d+g0iA60rSQ%~gDI_X7z{%tpiKKn&l%XN@yKYO54aYVYg5e0nJxAF#@^oP;CasTZm9F^k%+0g`;SaUXM5(L=x9mxwzM=;X0|SA zIlfedPc^MR!Sc`^YH6uIaxCU<*Tw%jE9Ot~e1=`)4wICe{+zhB7=kCu$`ED_-Qz2V z8d?u{3l6yA@D3VJwg3kvc$pcj`{KQDgzecb*K)xd$ZV%+YwW9wQ@e8OnsxJ(zFGVF zPZc#$`-$1y!OM&A(Qkdu==-wxw2KxV_bE9uGheJB+3YNkAbxY3VAjA=eW&|;hco9k z&Jm!Kn4qDbeCK_FvbB`}d9ZvF%f5W>!U{D|cS2=$W2|2DWn2$B-D*zD~UOeL$@KvCm_pIzGgeeCsPDMvl| zJx)rCJm5b2f&vWh^Zz(#e$#!EJnktt$c9maz!)_+a66iE$wrWYmkByfF@C9TS3Ex^ zwM+KZW1@Tl-toXQucEc@g0)zUHDW2Js6tNWU;nbM@MiS6f;44P1SWX(DEPC-DrASm zsr|=!zn$w1OE~? zsyG`c%#XF&&bU$|9|%pGdkOW(B0-x)s5$!xq?iDk%4; zvGoqn|D+a@dx!-`xH9m*8=4$ASc@9QBAf9b@M$iG^VR|!c;2U^_rFZ$Ey0RO1`Su9pOr>q;b)L2d?-DzqMw@Vrugp+ud4w8ZrBbf^5|giH>FVO!09PIlYw03QQBLxFV%DCD=j~^_gn+Ph z3aAbc+tu?-D#~GQoU>EBasLDre9!3hF~#`xpYdQd3|ft5mje+Bksf!_>I!|glJ2;+ zz@w?jhaqRUT$1BGI9L2VP(IRd+5oMX~ z``o1Wn0Y&_9Dwb4_V-6V{Vuy~^eo)MqJmXJ(YC3A`^+iJH~BgJK8uDdJD zQeZ0Wi`ko|4`2e zd`8#v#K_XX{TOU>`S08cKGZ}d`lB3+W-)uMwR_i3a+Il2`dnUNhLQ*lVvN3J#mJvR z%`t|~q+HysI_=yp8q+-xvv*KSG%&$J><`#+OQ2YjSx_BF5-t7<9o5G2&1lx)IjoHAK-ie zXhof4lq>8my9aSGjXUN$q_YMSAG3OD%^??y)vpa@m8kgnKepX~^9=yu^3Iff$HB^& z{I_-eR8w0!Eg`7#G%Pmq;pll1jj?ATJkg!(5%cxAJ07~_W!7w!@cR0Z2NX;xQ37S{$hc{6h zIO;(y0+C51z-xiJ^ksF0R=bs9d>{MV6wfu!*}km%KGxYq-!CpMUW&A@80_3Yic&~M z_A^?Do>T4@RiSOhh*MQy&GW^qv#0-_?&^%kj$yi-YEAlTT9NuqRpt(-+}E%)QD3LF z?}ymWBGAAseON77*gOf2-jm~kdZn;H9GHq*!%m%0Jsh}G;&|<{x-1$$?>;lwM9b(J z5q?Rsrc+CnHZC*o(B?7~$s>b_QV!jiBpul;oOYX)*@m;>wQCs5R=<@;yzZQk{@c9r zV`?_uTq8d?WY?5ZGCqLrx4#m|YP4Cu{!UP3mHZ3*e(;Cn+QDGIUG`5>h8`S07+e)z zzgmV`@L=DX`Bwju)7|@9V5Oij- zk=~Bq@hEn4Z~fmn;taG_&v#C+#)B%s8cd;uv8s0tjB8EnJ{8B8b|K~BH@D)l`k+w# z#cK2DB_}3zAz-O8*QA&F0&j_62mHfdbJOUDEI5Dz+yQ|FBmWNsuovAYh7u~MOi(g0 ztd_eTNsLV7WJ2ccw9}qFdoM0NPh<&%3N)S9W7Wd>`k3KKF|rvIo&>{j7BS;74nG>h zRz$cvV0{pr)XT-;(2SM>FD{?ChQ;mbE<(u`14mnRTAwn1#B^ER z)65mQ5&XyxULCi!P&bkL^G%Poi=^u3oQDSECtA4f>gN%s`UdmDX9%c963iI%E`YJh@EbaHwchq7Wc%Wy1uTNWj>GR=yYDkZqOWDh>NkuDl6R>O{X5nvGwp(c|`>ov{ulhjisF4eq#D z)afS5)nE3_bWY!c`A!RA1c(`Z&4EG*;1`9GXjJ&hS?sY4+@qZ1l~0jQl0FwZ zL~GUE4u&~?5K>xD4&m=1aHi_AUVnYCfvX^aX3*=&R+~%(+b46wp8hKB%6E)+RrV)C zPQ_|9xL-s#+qUvP%axjXW>gwk(HtPpEI0;uPffGb;-MndW{jt=44AXq7pc+Y_%!jhJsyr6KSk7z|zW+^{6(-5@^9KbSMVqzoCof7u6pA*8 zkvY#!nC{H$k_@h0#vTb)Z@`9l(Fui^Mee33t%O90H{Z!-oLcC=%!>~Z;Xwy?3^DE`g#<9Pbbk3nsiq526AluY@XT@5RQ`9% zbk*|=(|dq78eKS!NGsxfmf#Dyj>&)vlDnY~pvF0GHLm0}mfe9pXe(2sjG7A3ZFRNr z&)u{j-+rA)8$r!>>-bSwiOU-Ds(->r)?ab^UKw^xcl@K`N%vh}j}PHaQ?K^+_1_Az)Z@KIeE_JT5QJAqjB%lo-0~A3G4CNr z(TPW)#;DbDE59e zbh~MkW!m$kPO>wy4)JH@r71i0kDZM%8}PcG(v*H7GGRUGfp-z7#87xJ&>5Z$3t;;C z$r9O8x;Dux)#uDvyq+p)MYvioRWNL?4_6}~%tJ>=+y7ABxEGiJ|Cb7lJCR&;_2<>r zN9I&ZM!n6{$#RT^KznSS%Wr2|DXlgCfr!|B?@o06?&@*|fQRCtSH?Juk)f@riRZ!% zx?E@Nax_==n`0E+cEubH!_Pr)y08Y%&WFh^=9cr{7El6ZutK>+{HyQB|f(+H16A4EPMf znm?oErc|HGpop#1u=?FCyDhW_-;!F!KN0FlLj8=lF4s=+0e-ht@3k{e<@9rv;tiI( zE2m%c$0O6!1h6z~+G_VuHnZ0d;Vzg?duWpm=C?DH*WSRjx8V0wZ)BY;or5*budUG* zKPOagK)Q&Z?&+x_$)gtiVcxby1sE)^!T#^5NjBb2J^m$}zd8;{oF@^H`ZXsr7difg zWlFliQZ{sH*qRPp-rV-XZ;z}jI)H+nJX3t+d5k13j*n(4fCbQ3O&uH*_eENRTb0In zG1SiWl9J=P# zpBSNGr*(h6GdE_fEXJF^=_2rz5G&P}5DQo`6}L^1%G4A6ekoRsK#1ofL4?T2P#hXI z8>4_MrieyXxM0pMvaUFNl&8LG4Pc*eLPFo+bVAeH$@{Ik-px5qe|r{mmeZXU^(Kp; zCo4o?%fAS&8X}dr;9bbKdm}<~1Pw-RsR9knJ%#qr*)bY&=B)UX1>RW)T0Q=b4=~&} zpPfaKq`E*1zJT7$1`$&>)c!b5Sv_8TvkD*+wzPH- z2&A@k1#~cr-4NL7mfKG3vEq_*0XM9MR;m8NrKKawp{I*cnF6&8{(xFGuSnc>U3MNH zHloB>GAZnVzL>IDTi>xdot*TmV?T;3QKzFE)cPhQQE2Qy((=~pRVvuT7veb<{|Z!K z@5MAHotW~9G?n=NePnEeHcvxk_>OILZTTgH1e}VpOqhB5P>@a?8f!j zM^NVA5>*>~-B)?k&HeAFfmCRh-}NWi7Fq_EUlrQKf#pF*W6zc{pri#$*Wf|c3!k1w;O35+Y*`y99^8wbjzh?t@R0OwGEq%a?MX0+l0N=5 zqvi8?SW}Cz3}P0CsYc`mPD?k78z_;RQypUO+KB%6Ly$Nep(d@?>a>z}uveJC1Bp3z zBb-oR>>yb%?fsnH21v&Zlg}Bh--FItE_aRFNtIIW``*TfH z9i)hP<`LS^YJ1iGSzs5k-T0`3(e`nPfyDYDueZ^)z?xieN@9epnDh}twgck>v@Gms zA!Z;sG(B_vj?(9CthrE_TR9fP>bV_QzX%U)dIsZ0{og!O0AHsnU8_NYA_HC%<0B_ z=a&1mYaW?;U>ZZigIMAxx6Z~pJ*qcwTA8=}ep>XMAf!mBQlT>0NS_fq$~R;>#&3n^ z0oB$b%30Zvs}4L+@vZDzPHe3Zxj`$3&QD4BY^hkJMkyp)ThL;hz^O=s#=3GUHC^iw zq`v&``9F^miX4m@nK4taryF21;@+_N7%SI7j9fDtCiw6dbmC)@TZ*)Dbhoy@^hw_s z@mi@Olmb-!!GDZ3l9CQ?B3k@D`0}~9k0Ft&Jrjc0P1hztG@W{)inYyqC~=xb%)eHg zmm;485Tio;o#n94tfJ0~d>HV_HS$j=LCBh_5V7wU;3Ba?xf&dXRhF?ZmgyP?Rx~>S zA~X{QOF#01-%G?8&{{be{SR>0IDO5nu3dIHjh?XIErIRq*@S&Z{46+#k*B$4et~W; z)PK*rPKWItT%6TC~BEk`1Jk zg;HMu#){w_sMsh_{`)l?Y5o%^D|qx-(qS?-TbnzuRT;;~!+j7I^GZxekpi@mqLraAASR{>GPO~`T z;|5nmBDs(@tGv11(I!Jg??n|yX~D6_wNUR7oI7*XEEpzbL*jzOzGg~?ZZ;xAtuoA! zj2kJ{Fr_!I&$_H&sVTa=09udKP;c$@>N|AJRjcCGFsijJE@RWXU6cS-HS5W`OXu48 zzwM4Mam%`0fU$#1ie*l?2PmBmuuL@axB6BiQ~&xz&P~YpA!O)h(5%YPM~ziIzNFbg zD*QPOgs+JH-hEkgeWfU?-0Qo2pQ!EmAhO|!Ms`HYST>kHvm-jEd+LTc#1n@=Vxo{A zE%~f-T*KFM6;S`jQsZjdocxuZyNTQ7`i@0iAOGqX@^r7*jUdYIDl!rCPAKx8^4QLi zueRc;&S0A6Vr+7v<+q%FQ13reaf$y#h2d}XQbWsxPlIC|6K$pa9siEZlHHUxHk9F{ zzH4@NoAi6bf9zpWE0NHWgX-%X(hQdw)9lg~JR(QCl>PB?izQ3%t4}UH7_PN95;e)| zI3@p|C@@0~wqE;!${>Hs7sgnDjHrdpXG_{-G{exi0B@&QQcBxP#V*3p57#Zj95$ZV z0{_z%8Ll=LqYTtw3%*Q6TV1_>)Aqim3HcOlAb1X<_isP`T*Ganm8Nf7oH9ze|8gQJ z!|(-W`Wx?8j?HZbp0GZi3-E68W&8W1Jfqa9P~?q&3nS7CC}%aPj>Lq z=z$+o&wHK7E+Za=0!9xZq|z_z5A_wlAlzMOa1TnG@A`In)OJAneyzo8j91K)q0Ts#89zD@838wgO`l(s`;Xj)efzC{1(>O* zGpVtMp>p8~qI_oj(H%^`D_M_DWmSBfk;G7Vf=ntnNbHo9i?SN}i`O_zW2EsX{%1P*Jf9ye>J@0k*AZ77?NN6d4^%ddtSb_RQfLLlLZp#wi@jR zLW8QkoCac*(pa{p)o8Uc|2jpcW!%UCVt4iN&wT7ZWO#ovEslArsO81mYAuI%=T=;J z;Y4W+=q{c2DT&|pDE*%oU?S5ZcMh!}S0DaVcb`-(LMbLZ`O1u>lS)4IcK;~VazBpD0;gonHS+5EOVwCVnMxuG}8pv;`VH$TqY`8fy4(jx9Jct49oPMGOsk)Ylyf8)tQ{XfB(w--+k=K(56RufKd} z)G*U}%Hod$x98DX+;%>N{yw7NU;;*aok|*&Ks)UW2MvC@f+1A9?EQ zh+ouv0d9-V+VSh-Z4^uJyE5;}e)FnbK$QEGrq%BIXb7qT)px)|->H#{czlGrc#Xbq zc@SYP46^x`b8rsB?8wX6SB_1@Qxqoi$bX_dz?7V;Z5%JiS%ZG0QM>#6_3F_N6+`mq zZ{RaayU;V?FdfF#0i`hSW*pV`IZMd!N0uobVdCzi-`;Ti_|DYxk}L=nGZ=U973u`w zAWz_Zq43N*3OeiLwolBvT7vj}_;Ky*>dHdid++|X=qr~D1%GyKGo;6o)kHsxcDR60T zn}Qh*FiVh5LM?Gs>@sU}Kazba3I2%oRMTiqHfBvpqodYUy9A^q22nM8q$PQdL>b3` zfTIpDOwGl9&%FENeu&{YZ=Ys3ng5gSoB>uSX&R%$378(NVz8p&Ps^zR2KL-fpng1G=L10H- zeLdIE>~;MVOdza5_myppX>-tO-xpjy1?CTOe|<*$s5k)!*Lk-c>5!A-eewlv^Qz5> zvtdK-``9>X-?AGr3BkJ83pPIfQF+S(uDflH2M3YgPLj65Dl~Vib~e`3Z^mntbYX0}4+ASa8yvHJnOds%om5ha)U3eA`b--}_96Le(a% zpgJN`k1i)CF`b&0js(}t@-V6#DM?acDJUxQyt3k=>NE#9`+t+|%ThqnUJqFO^6;52P2$V{W9qA8;(DL2 z7q{Y8Z1G~-QYh}O#oa0HR@~iPi@W>c4yCYIp%k~`#a)ZO_w!AD$(!sSyU9&9xiil* zGiT165sF^?g`>J+H=b-k;pOZ(q=wotJEDkRu#^pK#Q#qLy7V zu*CnG=dC@w0AL%3xs0_VLl^v6DuJ;Z>sUt6y}q>eJ#tYz^YIG2f9zq3d2SEF1gY;V z=d?SvvFslS>NJ~7jxDS#VVgq2A- z0@Qv}g{nzp7f=OyJ3A;M+idxy{oeJ0N@nIgwe9>Z;S_;TuU4P1YjO9?d})l9OQe>I z!VW}!je})m%8*S{(34Sf5BIQTxl(E2R*r|8(EjOX438ir6mmlj%{fBL$2c0l8);pe zobyKKPrr_@s-0^Yi?xYJ19_so=D%Bp>lXxdj%piu79J>l;_Tk84~SW$`RHo`&VCeK zzyy`a?@m4AEOCR%HUtxlg|Ul*!uEL}m0dL;`TUAjbznd_N&poxYk|hl@oKK4!3iNs z0$w`h6RI@L=PB8mP`kp!!9Rw3Yzqk&rcxuS{doIh=1rd4H}Y{;5654p4wCD{aUXPN zBLz%IQXoNmHU;@|R*kK~+#a!Juw?gde6LaO%)Cm}h-zK7rv2YF#Z}Ut&<|_Zp&4#3 z*yMNDeFfhw4YJQml>amjn!Y2J9f3bKRnQpIMLPVp;r6Ud%{LynZ<~ywy{xtD2xwRi zE#n!VXI4(N_kvwWs{46vyFh~><$M930c6TR*AGG7`9eatzMY^2PVDM&w#-SpEgfVI=`KU!A!wI~QQYCdgqI`joazmL-!xPX0=d`VG+^nI%us1{g zk+le`{<7SuT~QvYwj{fXuoQ5~^DOkOYxL>*wcZp$k;pG-R29Cs?2@`1-1_9=dU23M z_1C2!I}-$&3a@Qqf;bL4dp%-Id@=_1o_>6+tNX?EF;?sW8^}OJeFjWbq#m&hPUMexP&kfK>gRuP8BhxnI z66WfLP5rx?FX6L%$2Y%_HR32};tpVkbVQuzzuypDMxsw22<$0M6zkVoip$gCMV?Y( z+!!W~?=@r;Ti(GfqADEb{Bb<5V4V!9z*iuM|8d}4E}HY|bHiJ4^a^;F_QU8P1BR!a zm8nXUUfPzsrAJ#5R+{wRa8aa$3)>c@w08Xg(x{5rrcX4?gQp+e?lhm*BGPsa<-r7yS6waQ_NAfYacGoGG&*Q~>@pJd*s znGNtbem!l5Q$&l@RpwQ^eh5N0TqrTM9(|Y`Heur_Q|#Y#=EC=Q9}AG&r6w6E-fGZW z2IgtFK$z>(QM0Hwhs9o0?4x#Q(`vQ~QB5@Rv=#m|-236EvZ(_5yRj=_gXQ3B)CS1) zD5Kz8TrGmPbIAOhq{C^Lx}X#rc@2prO$TExq5+fW^etb3eVEO>Z%sD}u(-(w?$psE zKPyhoA1)W|B^JJhOdGat z4CwFO3}@b$5$v~7pNZ89`idD|vS=bV7L`LeitCNBWWiRC2i)N@2ZzTS88G5}TxtYF zsAVzpc3a{FtB$oLWwjfgoyKDfD&Tn~Bgnw_i>qQow5svmj7hJ-)fNqA@iR>mvKLC) z&6*y4?rr5kNTeEAV4Lmm)VPdgQ}9hX-y8E#l@KcR>rt_GOdIqTOkqDB z?sjs>nIm||@jVH3GQaPaRkr!doV;a?$C<^_FT33yX$5TZH;CtxD`$!E^=aE$_Gf^Q z!bgzlPz~cb6+I*D^ywc)oC2I?NZ79((UHq z=wN@yY<}}G@+zQSNYc>|uji#Seti)7(z><0S&CQwuzwJY{|w%++lQVoiD(=q#^hNeTLmu?Ch z^<%$`@ZtT9ZSWX=XvqU20VSF4>huj0*dM zq?{hSGzcAQDMear*QiL93K|bl(PZQ|+ac|dkQRehju3*+JDLqr70#n#vp``^m#-@} z6)9u2h-C$cFaAL>NRntVSK(bl%$-R9QfnIMC(`dN7#VV4w#rjfZIR zrAYxP2}VukO-fOxiv8@yhjFh>=NG=DfT$m$e}U}8Xq$b$tPDI&Z|-xkG}^jix^}if zkudwU2*JLHn*Am*ZRcm)5E*cv6e(9MG*JBT$_*nZKz?8fg~SMJ>P-ikR1;9>DsuJd9I-u9m zsywp!GK|iidD|&IYfIYTE*_E9%G1>*{jR$f+-K93OVFen`G)zbO0R5QL5Md1N{f5c zu#_lQ?hJSkC=j;CRl_7t&+JwCB@R^se8r40-QC$MMPmlXHw}a#xC9WyO_4a)q;Vam zR>mC8?dj4gAJ$>PdrNaf*0ika_sVuz{<)=^Tl@vb{VU401ii?O>O{OCd-zHTB6J*U1v zf@$U3%rIA@u}{#gqIOyd%YkWk`P{|t3VFpEfKRSu8i!2yD{S!$aWcI}Y%at1ytY;D z5~^GPT&FbOqILIDRI|jt%FJ_u1>#pUDXh+U*EA(4{mu-|yTF7cO^l(aD@o=Udto&rfK9W$*L#y!fhh(p6ICDh{kp)~6MsMAByMdw zTQ+Y=g>$;E1}LUQ4of!z>j|p+3j;0Re+HE?-FxceLu_fl`+GgX($VjMyT{f6LW}At!ABW}@IzCl<DwL{3Wb3VJ<$t#htc)!fyL6N!c+_0PyR8ZBp`lj|M z>iRaRu`S)9NSSfNXWeIJcJGAWL%HfVyRT$Kk<6!(_A_LD{$tJo);_;XaiznNk~U0X zjQi(_A4~~*cHj**f3G1DuaZbE_=FqmgrD*PzVNS3zlK??&8?csQnWBAz|I9n896y4<7KvNrja^_`w`z>&~W`VcE2WIaE6 zXPT~~emjayl~UU`+9CgN2L1ePAEXsxnyh6cd4GgF>nz%Wfh5kDhG}EyanO`v1ir$? z;A;`);tK~D`=xr^nUkCe7vr`$YEzsES3kB=%4ag@uA-t(mYt5bQmE2B*AC+!d{vsw_U_$3 zz|9t}^B!FIa?6A=h=^pL50Hz_#%I||JQONS+tndk507U@4;(aRI?Kq{dsU;OwC4}L z;je17nn{YK%YXWO?y$;YG43?9x{y_~v?)XW%KGJI)*7je z-c}{#5zZ@aWqC za<>UH#5TC2!;~jrQ$XmUF=2CLHfi{71>n)Lt_NTQyn3t;uXTAebjo3eOHo@qD2RMd6kVZlL}EMZ{I4;=mjDXU z!<#s^%n3(2yvMvp07#VDI-kHwJrf5~#vSt&N9%@ruZGUrTd|OJKV_I>n{pW_G}}l{ zHHaO#q{o`kG|(4bIi9O;X9j&|8>L>I2GjhrbwJqk^>P|CknEwJs05?=>iFw}aob8` zqh&8#;$aH$yWs7S^rrM>=zUHceHbNzV8eCPgMmEfvH%(=+vm*@vB{%4KhgR5XmE!% z9>32@!)TxZ@^Q;^epbfAl9Ma>ZV%-4$sCe13GYl^F^mD45B#-@qZqE_lKEQMNW=0s z;163`-3)PCaMswjj3V*ov6#-{pV71L1>DiknHyfHPW=nSn&p(6X`<1q39vNJ48L?J z>I`Eg3d-_MnkNEiu+pjUg00e5uBnyeAJGAuK5?fdt*aMJIT z=vfa}-p>kd`xC}$RbpzyYOv+n((G0D9X-rq+hiE$5bakuC(n7hqE7*lnyKd^A91Lb zDsRkmrjBY?+By$3XI^)=d1tFQ>zJ7gf%lGz9DM%x)R`af5=IOnFA3F%8uDij_P!WB z%A9?}46NGvUtZ{%`xE}x)Nhq4S4{%%or1kTRkjMuwnO}NhNlXc zJ2P6-WlDMAsCruDpu3!}l<5z*se7<@r8Q~FY0%n@#&K}Lnb3CWWznfs@p5C}!s(}~ zlcy-J@j32i&C2t|XDVI#5f?>?Q}mreJhOj7knIfVN6kQ3chSi!aO44D7|**yLN&cA zrB9K){uRc&0MesW|MlVN$v4}i$%sF?#b!zQqglo8+?>zfkBU(!&;IlVt#}Z19;Rq~ z?Y2Q zha79?%1b8kBO4c-Y?T%bX*AXsM!wJ)%gK%F%uh~TYo0qv(x00+$cc8j`)@znl%yhM z5keQ%efk*0<}31NKK%_fsns1kb?`Z-%~ky3?M(_!uneHsloH^Z<*5U3G{~waOqs-% zODj+4E3$|I(~)xrB)?kYTj~4LP$$OF!a{1bQV0egMat1x-#X7c~$)tWWTX|`X#Gj%w z0&|wAz=$vYHU*SCa~YYc^SKWBIT98hj_w4*E}yIr4l5&= z3IN=x@*ixZRb5h=QKr7=r#wA-*K49 z4Nk=>WC|xJzn(c&7tTs*9RFR7om zPu9REbYxYz%9UE*V0z7#AuXzF<~DRgV|UZc^^Mx&9sM5lfS{_T739gm8&W(<;tSjm z=l_Te`@c>-Tg{MLBc`(rnAQ$d`w`}<5;Ya5t>C6~{$=j=-@YDR_uNf;Ue9@}K-U0m zjlZ5p{?p+*%Apr#C7Bv+1zEoD(b`&xwuEXnPo^Er4v;%@@QQaDPWWC9udcEQJg$Dd zf5KqhIPNHCA3lv2|MjSySDeLS)*faZ ze+WCwfMtzDyTw~cChqgDMejXmR+x%q+W3zuF(>A$D?h4VRX^mcdd}t9`H!lh?=T^m zUYRP3$<2(THnA;#D_Mqfy9`IKT5ni+Fr9)=KQlwBV3sH1q-*)h6r+^B{aw8Dvwgn# zQyyvY&pyB!hfV7nh20hd7Q?IMUZs2PkrVpEF?ajs&yEQDl@XQhAgA5KE;GHufxl^! z@exX3I65%4w}71&3iAUT7#}2muH#yuyVF5LQE@`A{2NnuDu!@93U*(5dTC*uPwX{G zE7`K&kt_{5`I`T@Ieezc;#AS@extkX!P&6r{qpy3eD;H^qrLIw!%F&frO|g!$E4NW(jC9PV|17yY4P&)i0pVJ`=%b(W(PW|5F|EVV_u)2d^~ zzqvKE-~^S_E{NZ2+RJm0Q|s>Tjs@xx2^y11iJ1Mz@<=ZYjC7yqKWu`Z$;PxF#!Rm` z6F8IhG1mk}j{Jr9T7?!oE@kO;>hlfvWg1jRHQsxc6q{2YdNxlb-)5i$jbG+^;DL0RD8a%)0)?EU9eCuC2X;v!A>J&X{I|N zt2g=%#Q8X%Ah|z4W9q-taRFe0z(2&n9(G4|aG^@zx3f2G`x9UO$Ksz4E0nY#tR@*93)$Z& z#6#ToGpCl->FrChuXoe)LBcLdmiAMg4rRtJ${Z?}N%Lgrn!lparFTFCXS24dn!rl- zf67CSh?!r%31rPOn6LYs3A&i7>rIO?5lIpdcEcMir>u3x$UpLVy_mtKTIw?sCKHb( zSlYCWXBYev8Fp=u67s#tFRWJC|7RfJew7(QF~FTuid1X_Dy+T2r)@U>N5R+DmD(Zy!N~|Aw=?hcRMdk$nGZB!z z6S=%=p4PzSi$KiU8}8VB8C@66MIObW zN}ewqFmNv9tj+a$5SQ;n7yO^6Kh-9O3UCotFC;7+(Z5ceS2&}^e73-l$2jAZxd9&F zQs-&X=a(8Y5On?Ynh)T=_dR-Iw|~ai0fDT|y>8g@P)t3i0ZT2cH{bSfo?wWXL|#^9 z!t|L%w*&oG6Zv^wz|UXapXd4{9sRc({X5!x6OL0*0LU3ggS=WD%Pcr)bZ=xdS*Ub( z$BOogZ_~o)c9Rq}IHrGw%x+6I-{AwqaiV-0jV;J_4(uHQcmXkHO5&Tvcv13+hrsBe zT`EwumEB;Z+3Iw*AfgQYcVf&gHEgRt!^!EtB3JwxTXg-QrD@A^n3(ypXCadjF+bD= zhn8@1aQC_vh-ggWnR94QV)VE;(D3ZryL7hTi;`~uga1Wd|7(c99sY+^?Rr0r$lC~y zMzOD`-oiRgK=kciR3@;S{XZ_iuUm~}&OE%~K~wEDYa@_6UnXrzu`I+MBD!pI$6(D> zpr`;I(Bwms)NDvQ)$el>V6*rq&W4?zOU0)w-=Y9kNVW%#Z3QZl_>OF@xxTVJfR(3s zOx^nE>tarm(LZz)YuDE?C5WJze}+I-`$zw!eBkx@_ zXm;FEy&z*t0S3yjwCWe-x1hw8HR?xeB+l`mxvP2-UD$kzlE9Lyeq20T!ro^97rC%C z>+0Ys#_2#=M)yrLqWgC!xL#9MIHC3o zJy_Z4WhS&Sg-S-rWeyXdbZ`V*(?O0_*d!%uUSL@9~zblGiILMEEHgGi3@Hb zfw~Q$`Y!q{Gw*SlOCUyt9Ot4P*CL^wAG;H?aD<*HH-tAqDYqH!>qPqi2q4p29gO99Q45O)F~wzu5)4WCg2u*FTvRu304V% zz7>>Tsn7(53cpSukDx8^07CnJu11q|`x#LrH?ed+fsmrY>c)D=8JI)X{wr(q2tY>9 zYx_TJUrK{vPvh|50cr3y_kTkR(ir|~%fffl<&C`^103&ce@M?%jxv>j1ducl4|I$r zj6I*>Jbi`Q@6ft^TYleD6yQQ@f8ojRO&M8@ofo{+N&kWxVhgY{C>K)nId=P3(nbxL zzU00ogNgW1>h-|l~4@&EZef$DT*oB+U}lDtyM%*19)Td_(WC zB`LA<)m4EvEKPstnYd8Xs;&*Ncshs#{ekqN2u)`?o4KNOP<(sD?sVluXA|D+Vhxtrt;IEppIJSct>5MToarVw zap-n(BO&9$zT_m6b0Ksw1C(6xx>X5zN81a z^YCC{Bx-8lC3jj9RHoaw{Szd|w-rN`CM#Mu(y(NA&L_Y)LVtX0o-|IJ`2H_-2EiMz z;zgD-(MrZd7IZVl1|~c^5@V0HK-ykf#*S#2Q2Y^UY@JF`6#_fnRw{mTo@hlzFQg%T zxB(HI+hVRC`oJitKO+{>hYSp;YRFHE2zaDY8#J!bc(KO7t!Du)F784JxbmM-F12qc zeYOASNR1kXZwbA{uQhYzmSDy3OfrM82UPn-zk5Y~F0`|?#Q;>3Wh{RSrX+YD(8c;f z7o$V>9~vMhwi-~)(qE-{#KnPCRp}Zt>V|-Smr-Vl+J1Or|Gen1OkC;9Cbu_&{^2H! zBzRRobtguVVXQj6dhRP9Yf)GJ#xw&nwY>f7&6%NzO@Nyp=5*5AoDWxiLz?(dkX~Y* z+?#JnFkL*Zq_=~&@rnFDFXmvT(O?C9O``ZQXhU;R82*s3AqJC8O%)V#^jsW8ZKpgp5XNn2kW+BX zm5^jx+~Eg;Mvjmdfpl3o9Dl(goK7+v8HgXWa{HpRvDl6{N>ml_4z5A=CLiy1eI>~3 zD?DD}qq zn9)kZBO@Qpx`I!>W6?Bzp$i}W_$51d#zMSN`-g)UaaWqbYEI{xZ<80Ey|S9X)Uahk zyPF!f-=|-n&)>l;oUXe5Mt?9IgZT@kM!kCgjzVmUefq8Bf`A#I@iA(f0~nG&Gu9lA zLhY@%%c-PB+#k~UFBl0> z5-^l#lR1BD3s?)hKpI1HxOmJ~HapZ4yj-s-rm2Kh9V|BTr^gu~vv%^}Z_7v8{8_%{ z!*|7+NGCvLH<{EfRa@Fd+M@KHM8c9RL6ldcwq6KCwhnm)PM9zv1iS??iQPSAu|qpsG%kId-2s( z#m>=!m=1#=TfziV&;6V5V8%5023frMnIqINtV4A&3LkW8j7ZkU@9@()(GqoiH@>8$ z*kJ60FOs;$!-t55C3!OW5IREav?43jqlUyiO*>Q^1=MIw{}|1VXiZr)Sn2)+KbREu zoZ4Z}!4-e(?PwY;9hIr*uXmOP*Vo5X_q!4^{SgvVAkz~eFO)x}96VYSnVXk4e6rG( z{U`egJE8d`54}q~olyK`tSlD8WB(wM^7~sz$@%FyZM()*(f-|_a{!Wy9eisKhwrDW z2KoL!f3Wnq$mlWvZuJTyKy3S|^^t=>l#w8GWjDNtapc(S@X`Y#E|efZu9RE#Tffyl-S4jwcdc90EkR+>z=0o}gBcAXKp`v0PfYq}e!jFGy` z&;44KzjZNK^KyO|!f7w*4jo^ZCQ{LM^&oT=6*O3f3?2*%FZN*}-3)d< z2=$e~*K+zYA+q)>4Y25%j}@mA)Vt=bF+&w8@?qNv!toisFA-&}*ldgc!APL}oYs0R z*KBV^OgeaX{a)XOmv)~=WM43YS58bFeRYIC`JJZkX1QVi*{d+?ZRvXz9D_Ck*Y^vC zGcQM*4T)PQS4fyfJ{OV>ezIWs@27McVF!^@zL%fwvjgt47`?-t19R_8Av2)KMO=PXgjVY9yJxFm`7x3I~T2485zauf_uL~&hs$Y5;xM&j46nw-+^j~H(a}@$M<{ddmVQ>3rw#A zC2?2eMo5Fq#lB<)dNPVtO3=r+q(!)7AW8XG+7k|LGa?qBJJg8E2?QTBGO63+x%^{X z{XhmC64)95kt;IL$$p=F#+1R^aOo;wL@xk^sp2XJ+O#NEtekKas0WVkib=v(?ZQ{h zq3bI$L~D?x+Q4*M?^Gj5(zsB3p4`#Oo$TijG}Mp=hjnzqQK5Qlt%m<GIT&ch(tm(JR~}oHj6#P7lpj0r1d>5B^tAgaxT(I3snLvD zV}W}@!^Lb8#nL!JTLW0Fo8)dqx)2(I*zc@f=Z?X`VIJ|%LN*{FKy^`7JLpY8=c|ED zR({L#8NmSJsa+jcZ?%n@VGAb(0!e@Dr>LPZyef|psT+=)@>wzX2!L_%xkbN^5B(3X z5?)O9&Dx>&PF?yUMMC_S6Lvr8ZZK9zQ9K}1)e51j9wC_SCZJa*PsfB~Zmx{+!V6g| z%i~ubU;fC(7BnFFnJSXT(Ear{w`r-|9U#lSACas%lSEL)%zoKE*TFkfB+D7?OT2Py5xYC%--BuRV8BIXptkh&J?`}s9N;IrsM~d%e z)S^wm5)|Wn#c35BO-)_;bbX+W>wmz9ugdZf?c{EC^n|K@CwrUr!v>(8aK0Q%_@j0s zNil1IPu}%Wy`k)@VGZX>D_)(P%oiFZPaHwbKophl;^yN3cy+=u-m&fcSrR`?K!y{{ zAp?acVYlI|<NH5S zYxQ2gU4bXqNwb&vKtDcpYP9tvJIDo2x+4JhJ}&w1iWlljJdzThMjAz`)1E# ze~Q%nsutfx;+Y6j&rcbpOV6lbK-ZyC#r4rvooy^wUqDRovghs^FG+2I+6PVvmMU{7 zvaGzX2u1vr^RB5qC5U15`2wKaC*jm`(HO4@O3DkgBo{KXRVTZy*`=~|`d5V3RK3jN zh2>JYyr6WhJWVV3=?KQsL6o_O`e*7bzECrvq~TZwSrsLss0`5#eUKNf+}3jS zGiRxjoz7;}?l&z)PSBn33sHfF-K>LN_Kg+-@(n=n`NI)%<2+D-SwFpTTb{aS{tei= z#6FyMqSQ-)_omWAc*Ld2`4kwVKNX4aiP?4Joo_|_%GaM zOF_nr@QdT;4`b*5d{N;U)5jADsoVmHq3XlAK6edWT?i4h=%Xk7vr#&4{>6im5xWM1 zqMKuqQ|&8MVoGV;+pa1^Mco-tDwV_Zk~T2B0DVRfW5pLTa5hT(GHUCw9-~*2c3qkC z`oZA&^Op&SXP!FB$C)yg^9omVj4{HsYSqU-sT?sYV>Abcx&4TznTdU4k-r-ZmfC9L znoB5z#jW00(fVsxMH#){T(Kw@e=!UQfaB?Tm~YK7OUYC)@0rzVjy}`=P)V_+R}gBBO86y-WZvpUn3uYaftnW#@}RQ zm@cjBV_%b^wZRf7te2sD9{{rav<_B9B&KB2vZCI+(9xaH|Cq7kW{>_sVOGEJ;9Fcs zTI7)2%TqcO-ZKsS7RvV-vu*dhXpv&pd@qYip4bezBTYY&&bH`ESypZyOM|(+-0qGG zE@T+!88NJoQsBR*9`7tOR+)^RTrEIpnXE~-6ZEnH8`ifSXz$O(^|ZL+%VS`C=Q?!D z?&yDGQBt-ht2K5gTAf#`F;T4Ds=7+nTB z5l~c*hHD<84&~(K3K^1HE7w8)0%jiYU+~+7OBYhH_ex}d(3M&NYMA5sz?lFqlqGM2L*aD%yh-eYA{-k8skoR2ZUOvSiMAnpqYj}DB@he276kG<*pkHj2M0v6T>$_tLe{fXoLX1&X z!DtTkWB`h)!J}M9m^2!((O`~y&h)rbgP3g)ToVe%qf*I-iynT&X%-~40&YWb*COQV z!fudt;xljpfYc2MsvS7G{!=H8AMNaczJ-z3f5BBQaCd4<#}*nc8bLLTiRMTL>ZF{d z$fFrZ1pLQ;XzX6#bL3FDMniPpV`r;5Bo-KEVB`hjb4rTZ2?VN^MnCE?9UmXlbhTl$ z(FPh%U?*S)HboYiydil6+i;PD*u{`9k__ttRnSmg|# zyBwhVV2$`eRWbNlbIrk>Cu-?-o9t9vFLEK-DrzbLloE z(S8W%4x!a%uU4J_@kXHvD;;!5bsDLqhN7wgrHK*~?23HXQkkB!#zZ`NqBgL-dZFqX z`5DGjvBQZ0D05nb9lMDNnwfR3gxnJ8sC%^9|0b)Js7>Pp#JoNGzsE^UT*9JK93(oljmO@Tw~}eCt99*wT1v zi+?!4ZHInNR*Z7qFStFotwnx^-_*+j32Wfg+{|qmpf||--_gL#qTn4g42cwmqNsFH zB>C4$M5t9774~J4`P2DZe1YFdKn`k;IQ=!v>Qc8^E*q)x+U8S~=k{LE*{gB(+G{w| z6QV!Dr+fPGWvqg$t1fqnf@gy+BFE=|c~$tHx`Uf}_0AFq_AVp=e(zQSZ?WvX`*Bmb zvR=1|jb)UJ#-5-dr-=_zi&D#UaUvc67#FeKE={TnR+t>pN+~lD*Gz>vGtd%%)`%q2 z$$+Zlkap#em`0JcJW++RG5!>OEZe%d7UHVMaFSD&!n@I}#X@R8h^9lpLW0s2N0W}Z zp!Eh4m+GQLbA(nFn<^ih-gGj$qiK|)KgyA|`l5|T;oi$*jlBI{{8ec2w2Vp#M#^dW zc1aeExvZ%kp6oO@9QNlz zSAV6+`HAeFDd5F}9H5d9i&1JWp;933A`$=u6$Jrn+wWJ_k_U!a%^w^G1$A5CXtZ41(FyG7w_@{M0-uHwZ)Osdu8MGj}lT2Y5c~u%FIR+N7@b>S$ zx^nU$1~sYsZw2z~e|3%hM82KUo{Mr&^TD3=AP0m++KinX@03*~GOyILvXcGdlMa1b z4SFI{z_ZpuZ!65yC)PcfnIT8;WRQ5F&fqL(uwbFEay!dvb%Cz9HRV&^afV^Q8vgyk z;*>ng_}Br$u^*ss*3MIsgFm9lJUAG)KLjELM@aDm0_2?sVF$kx%u?s zlNL8*^10lFoCv!=aCP>L2Y3~XZZ^P2^n8qOVA^S;BYaYCphI?_`6;I%C#lB3V0Y5g zcJ> zvc12zF+a>V`~U>#)10~}?|<3joM^CB5x!I8J8g0h@E9Z;>%3Y0I(6~#c$QzuMu9e| z$A3sBi8K-{w0GEUP*-IRXzzZg^Gn|!et)WD^aZMJ=3|*LT59g_=Os|LQsRh5iG~P) z3LFE6SF9s_?11NUDyb_SF&m2`Pn{y2fK}`JZjQN7g8WnNz(>TlRM44kr2+>N5@en5 z(;Nrtsj1Xx(u1MNY!Wge9B@#vA0SQkW8qZ>enHr9EvDG!$HoUbhU~7-z9yK~VA`+} zeNIsssxSha`0&owX)b-Fk9sO4JSJcFKKS@NHkXu`w~D;|U}ei|0#`!#_$|F5JO(Q! zEm^KI2p8S-Te37Zca#Ke34U@YTLR)(D*t8-y|Eky7Hn&tt5yvf*tkTK6`3+>miQZe z%U79ar{MuS`U^f~nh7f_0cXyO9V6wqZZGqG0295wd#z20n;;0%ACKUV#UFMLSIej0 zy6{88fu&9hM|rVUDSGc;)HT>P$H8#V17%M_>1tCIw#dG>_l5N+ef6NZ&mX=Rd7s4Q{_NXU&7}msyX_j07}hp_6Y!T!jNSgebiSbo!M0b5mwcdgq)K zb~H|xKTRdd(DC@%4bTvN^wf=8mYRHms%6Hi+Q18Mj`R%6?fLUC6Y!l>##X1vg;iJE z(uxyn$?X>AD^2b23A3c3S9%6NVxOupUhhe(^lAzUz2oM8>K6D69Cu5;1!0ASXmeG)? zXB=SKS6;K=HD#NR=&Vq(y~$0u)PJLBn~Rab`U~CTY#aq{Vddtg7tNFP0G@(xd@)spY>}wTIAz&yJ#+!Vgap0Q@&6oEpcQ1wzM9PzH|6!t|!7w<=be}yV?j2*4!4C^mmotZf-$T-w+@4UA^vwEncU9Ymes8gN!OVYuHw)&gRVSxLv=}eZ<|$aR zOCB}T?tOvKZ6)UZeRz5!ALWpN-@?oejSg5%} zO2nHG5=KGpzP{7sTSxP=z|~E_EsDlTRBSmCX$=_W|DcP;p@5M$ug4HNsDg(k+q6_d zPp>K$YHyQPl)IqWdi6{9gU*to#Y%iuY-)1aKU;P4LVR>j6B=3O-0vk)F{Dru8Undr z1R98VB{v4*sE0Rv?{KgpWJ}dPTd>cPDVUU0MA4L`nz56-qbH}JP~k=Y@>V6@EN^Lo zE+vL7>y9|7Mf{RYQjh+*FixXM{0LR$Sh`At=vrh`RAj!kAbkeS8*Y5JYm521YWt3B zwrBh~k4CYbtaHU}JGyG)%L*@K9_g}3;xFBAHk4h&E{P9=haJ+h{)?R95Eoea(cRAUPWEym5T<2C><}lV|_i z?9KJoOtQRY#JFaJYiyr?Jeu&iMdESm{8?=RJwY*6Mm2D-ikBTz$0d?SgYw%*F{|R8 zsqv!l*u^AhRCF!mm)`Tp@qul$yP)$V#kn8E&WYz2N$M6)Q`R3RJ*59C=gO4xUIw~~ zj-nw?A^gHh{^VOH=dU9SYhLho4|Zm-Q$N6e?CPS!i%Qy!9>P~tRBUhP{$BiZ6Q)O# z)Q|YVuy;c8Z3nAsY})HR@&39W5yqSovs-JZ~u5x(KEA965>UE*HIxBIM7yH}kQS zxlZ-#{4eX`Kjk!GQJt0>QvB0#+jS9~a+>E8<9Iws3EH7?7sPQXXWOC1&A7TW_;V7H zA5vhEkQ`#^$Gy0ZkQ~ySqixpoo4?K{Xr!f*b3TFKacUG#kABEDd3I|93R`nirg+US zGu`@Z6J*!FHrOSR^{Yy}39bljHi)a)p0jr0$2DHuav!4qdQ&H%q3JzEqVP%ki@Om& zqT5M@X`Yp~4n5?Z0AOEObM%XSNw4Qj|FevUyG zW2708&Xiti15*0XeBF-=_T_c_le5;o{G3>jCV#F#m8xq_WA3*`Z7L3OWVP1Fq5f3P zM8LUVOgJ~ky+^%K50Yd{tKZM-YcL@{+@mziltgNU1_;iwH0k(|E+u9tvehtqJi2- zp+0;=DB)usQDQNj@)FXcheRz9bi5zG<$1FtThT@9`o*+XYtMyxW9>Z3-dmOMjzO%G zn9a2)w_ZKHGS?p{ajUBbkXSF%q|1yt>@052!MqxRB(Vej)0ul#R^;sYoz&0p^w$At8?o&oiCJND3RFPyq-+8ZL$9EkU zpZ%2ppHxqbK?`~-Q#T1rJ^ix9vq76TIWz0u%Fn&4Kahg}=LfO1J8!P^njkY4QGEe^ zemB%*RCl#72;l>YDzTR)M|B+q&R^C0N4&c9zupiDT7YpIFmD>{9_CIW|9VFWU;Z@q z%Wkuppx0uvGN=XxSUHO9scBeC@KVSMIAi^cACv${FcW`9fA5idC*j8XG(K_I3ck3r z8b-G00;t|4oRg?z5_3bp@+7Qod|;+h_f1iqqlzuZZ~h=@Wa7U8O%QiUuOOdXC(J>* z5fflP+;Q7YR#j-^q>nb6@ChdmowQCfytvoRcT;LztFig?5(^;zVVLs`**i_Kx&d(V zMgC-i&YP|Q@V|B;tcWS-Xz}ci#SBp8>h>$=x|vKamXeFAj`O8Zg1Oy|+XsWH%02ND z4rc1GBHVMRO*;4f<$UJa8XL|X%=X^r{+h7s^JVbA;0>iv0sQRm*Cz9Qf$c0$_CxD2 zW)ki=hGUWoF^ma*-_PMe>gKqq^BdrQu5=V>dBIz*+KI?t7Ta&Vm z5#^6$`2aPVvnIzZR>ykJ zenI3NL7-pD^%75@0R;As6j+OY)t*7KoXdEuZG-T?)+Uwk#KJsUkhI#Y;rroI@8we} zEA;G|vvLxY6;*VK7u@0AJ?jQ!&!a~Mf$z>xi?Hb9_TA-e;8;3ukRAOlmAxYm~6_nWeOHFX&bnU&^sN3bwO7T$y2Ev zUsygVV=B1_K=PYt#)69hJV%2P#Q?ux*j;#>N6e(|z*!ItTyvD5k=Nz7yS=@IJ8L#j z6$}2xs!?>uq++84WDq^+sM9s?IIQ@!o}JKvEorA!&is0|6laCjc3cqIqF!nSx=AHZ z>}mn|Yy$i8{P|K<6O3VGRtE=LoIR*TVmmNU^6HO$L1(KcgM#Zr`+L{u7n@%DIutKU zU#hYXsHNVtYFX1FXyL0XB_@D;Z2+59$m6e36wS}x5WAR{5=fg#AnCVUOgrlRFFS)v z`71^r7emgxp?hv^dss{$R>w(953or)_xb@Xa+vwNSNM47IcT*#DL_zOX_ z;P(@#XsO8XOW%)FOBeSWQqt$8aygdtd|MRjLfcE(w>o-=oY6T>ru^K&0~4};8ISyL z5cMDSk6a%=n+9@iJp6dL=t1)xcA-e`Y*~Ll{JBd1bS+ps;ZgaTYSM5ML9a9@RqCl; zONd);h6TYfob=Sb)bY+1n0FsdAN3}(a}hA%@bFLudSqfQ{`VFKk&n=*&2Zq+MFOW^ zJ(5$V*9RFqr>x_Ur=yHdjOEFwk3iZ+m5_5IZcUq2(=3~7m=SB_l6<{dB|!>*vFfo( zM3RWq8s_dzK6hD8#uzVGL*5ZvbeJB5*W(n~KRBn>3`=c&0V@K&@i=4@sLv{EUA0zK zXq^+3>N{B}wNa`32zg6{`&=!}CanzI*vfbG>f$#|#zRFYB@Eq-zN#jiB;CF#|GYJ5 zT|vSN6t|r)2IL(R%k&b1g?ikOUnS061#6LM)cfuEE(o;GZNM4#uZoSLO1^VjhcCUD zBdUgrvaabh!Y!53b-qtuRq&nHb?oQ4O=*yFpC{*f`GN9rKP&BG&;xIq?I6<^6D5?K z@_ZPT-2Vdqus(_~O8V7U8q=HQszf4cvUeF1)tat)!|Kq);iA^7W9$omuu;|fViS5I z2feE%mh=h?^ac)Cx7`xZds=c5ilym=@X@v#4lE-CNI$gUGuU>m z<7V}jXG*+#?}Xn7u~nDVQ7pzWqOPtcCw@aJ6mV`Ce|{?M-TvUWw-nlU+4?dL=p2_L(lj zO0<4oy;Dg*ekmC`Dcfz^O8wMaz)ZOa z29d>$lR3`hc64Y}E?Be%5i) z^G&O(Xkf_~q~dG4$DA?}zg45&Y%ST;+vmxznwBrh0V27Q2;z(p*aa?~zl+SWA&ArRZ=saZ5?T z#F;Z9xFQ`v@-W`Y+fL^{j94O6P4&tx;L;p=0^6={49|*m1B4W!MW!(qS~#fO zG!?M~)ZTrVC8q9ES7i_?yOX&LK8#NHWkpeM#5&q|l^!;|EK66)*QWu9co# z4GRJiU%%n9Mj>^D!P@GHON2n@uDz30qF=}ql6^h*lRXmjjWLE70|fW@oOQijl+{SD zsk(CM9^`Tf{F<6dBXboo(NJ6KwnuEza%U1)-fm(Jx}o_p#ogpDJ!w*pAb!YR;&}b~ zF3C!dm2_ot&>NhY`Aoy-U#r4*q}^JA*INr&fdhBMsZ51#@9*~tFj2dkqIcdNk^ZAN z`o-GB+v}T~;k!3}0%kp{xDJHny1d?Rck-f4G`^uj(+^jA=FhGIU2?|9$-GUej}JW% zRhhfbm|0|ABrV$dyT=$+4M6({Q=}N1JcT_KEnk0meIykbW+f@s)ys$+>Nsf8z_0+N zRr1 zVd{wTjbz>#I8D|#V7vt1V>FdL{wiQ_O?3_+tJcJhulCWpY|dfxEGnpaJ}#= z*v89Pj}!MSl4jr0#U=@rilQq}0i@b|`66%6;&R}W%j<)DwM%4*w9RoB5FPYZLEq}V zLmbq5v;cFC`xCsvqcPnn;s?{u4;^IMn8vCt*)>d+B5~1vEt7DTOxyI>i&tvcJ^!i` zK$%AHnCcS=H&*I8a7BXr=}_-A7y;;A-y4ajgq)2D2ATnmC=n1$6AU{^vpv38FJV+R)e0%;&bEK@OyTx@29UZr=7wJ!?VbU z$U>-b%I2$9?HJT%o>}Q(myx&Kr`ur94N=rHc`ukTN(S>!hK?!A#mX}bc-N0Dsy!Vo z<^@<}I_?|CTkwn3#q9fyjOv>*vj0@^fB)-J{ygJrM4oz`Eg1hPT^dzZf$DeSijTxi zMsYF29M9qZv@dv7Jf18ZEm`sX}O!){?@8ttj zXr-KFu3VRS>nPdR_A1g6A8-u-BpVTXb=&2*EU^odc(hO6&g~XCf$2lir-#e?4Pc?nrSCA#pYuv0kX8SYXyt@8-V6Mj>{)Vqm7qnVh0(9Unh?^b)FYd5WParku-VpRV>bH%y8A1c0j$VSt8|JR}JT)=)b1LpIx2)(?<9# zwMh)gAxqI!apUSB_(ah98E*dm=4LdWo3p8*@j>gRUNwa-l<$yopqZS7ub+8vmSpi#ZmUlk5M{t{$X}S0W3XN zz6>$=_6h3o;yg6c7RZ0a@0#N)58Tq0tNM!Ay{dBk2D-G5kMHcW0zb{oJYl<40k++G z@3v|9F|%I0@%a@*EQM9HYQyxjvSqnV3C!BWMX^Ja=s!j*H#iZ%*2_b0r*F?MEE^0Sw?0|`HLm`q?Vy06J|B*a@uLz@WEO|0aEmK4z@h!uGT|NM znkEO;jkzu#rXHV8QodK0#?%?zQV3n<fh@T;?rcRlfxZ`vQ8Y|vkJ`Uhx3ZwfcC?o zweR&Y_Lg=gDQ#8E{k~TkUwX~)Z$g&rc4)&$1vK3p6tUl!Ds~rkwT7q#_oy`m$u6n9 zn~*-^N1;%Rn|h~Zeta#p7-3GawqD0yh;D`M2&X#v*}kju$zRw@avyJrWq7fXfX+*w z2_OVjr2mOQ13kN2TA3R}buNQ9dV>I3Zg9?ZZzD2}XYTzRyuGVEJIl-9RLV#mzzeSF zSrZE%h4&dYeH@QJXjO>)di7ZQi+)Aph_yO1i*}8Ed2<3j;_^e$k8t_bD=8%zk2WZD zENKEEZQ6v$kL9CP5^!zvmG|pE{iv?~nA~{c-lnvkk)=XfH)&Me$HZQp^M?x6Fh{bE z4hOZ$^zdvZl&6&E>U6Z`c$n6ll{rB;N!=5Prntsy+lpi8y?hpH{$(ZlMO4 zjZ!Z(kb<3sjCpzce-^(|=1>=32A;D>rpYqKKPDd}dZs0xFCJH-Qm&g1Phn(Y;l?(k z1IxmAnzCEIsfH!J%1|CGSE?}StXB<{y2yMnm`vu&8F^EwC}31mjErUEQa3O%{L;{j z|GF|gN*8f>mvW(lm|LcgN}VyEsZo3BsVh;iuyg1t3(RRkm#TnZI!%>(pv$H1Tz@^_ zc968nmBBY`iQ%(PF13Fn zTtKx?rW1Js_6qVtczul^0qZpG%`4)jhwjGK_jQR!JR5<}UIZ=>@SYfa_h?)8%NS2X z$yh7|h3!d4uXrFAx0yO8yhzd!47#k9_bJZJ)%;oy0gs!yP^O65q@}JGR@Xy> z1WevBSA5*7Xg+cTKUoy3#%yDX4s!{sO|h+3dbm0=7}l_70TnBzh>iJ+8%^-3{_$04 z)->lkeQhk{J6Gg6e5;H7e2UaUFQgI`B*@K&HMJwS;naivfx|&ogvXP`$o!Nib<}ys zp~I?5@Mpmuu}IzMf<-)j#;iTHsdl-@u+=mUn2Yn@)G#ymk{1@dJMnk#NkHj$Mat(d zbimooFX3z!Ma1vO3f_MmtisrU%I@ISOj3OA!hD=CH7SINNB%Wa-eFcN1n| ziIp4^@2w$-3CQd*6#MTTCwE2rJ!o+ryIl{JkPDa~&5`_FO?`N8b2e}2@AE9AHx(!N zz9RTF<#9={*vAu}4@|!td$L33L9Yo^gl zNXR~C)>LDt6u1Q0-)bFPfKsz1(<)tm0$;kRTgY#KhjO2IKrFstYT3S{-Q$1o1 z0x8a!Uze&;N9M0W^T!{ z>|6kPh~h2t3$BzZ7-ZJb!OynqZ7LaV0ttTe8!-tP8S>5S0;9vlCS>Q`$S6O*Va#+q z3I6?UK=8`54HlWeUzoQ^&jH@2X|P*)OC;yb?< zSh;xj39Hj+(=oLP?AcCcO?neJ;kUYSiSfyuhKn6~9vRXk48{zghG!2bI$Q>3-Wt-d zI=Z4-)<7K%2NiP;6Rke$|M360^F0aZV#?oOSi4SO&u`3qjSi!b$ur@daS|C)wu5e&{csr8(hl%4V8Z<95Zmg zl7_SJ@2`e8F(e5;bb>D~7c{UNN-5O;2U+TWrC*0y?84iL{+;es1?<93X(MlnxxRt@Q!6lTs%7s zDT`uG!Xi*1?1W*DWYgnYV+w3_l%QA5gMG1Orq}mi0F(zLa`@V`sir(04O(g$ZO?bQ zck3Z+Pb0a3+7{;RdwDNXkL0`yJCybsKik3TGP9QMqeTrrt}wckvJ6Cx6hq1@J;3zx zf`q9bU};jz8+O|`b&5Z>V}QwAeOj;hDUoT)MZZ(@ufIG`Tvw(@Y$5@UjyTkz2C!m$ z3Ew4Xx+lP6JDIJqj4UFqiZ}U$5N*yCQ9FuG=AF z=ZqX(2x(YNY0CPzH%C(SJ~_rN+@Vdr%LRiVlsP<#X2$a=${>;41Q(26WMp7zc%#QJrc$AsukT!I>Z^7*jsK1PkWZ%JTKMiWO39K!sUqvcWv6G` zUSjT+ETsHh&av>-9@i04oW>6H(Kh3=QuOCt0J$V@too{+E#2R46Nrpwnb~-id(=rp zG`akS%)Kt^&rHfFa5+CgFCDmilbWkrzI{h<(Om+#3}|8r*H4>YXk(F@(dp8^@|3Qz zRDXA2G$-vN0SVIJMsg`tIv6s&g$?n`nK{=R6_uoT^xO__IheFU9_ghnU1^o(T1!{$ zwSA!53(BdI^kq*dZpzs@er!J(9%7Z`o<7V}0sqITgo2_+#F;UjPevdCiF+5degQkNOP6{R}aZ;D_ zm_v9cCN1yQjpFHeAm=iA$U74vxiHXD>(r`UOu4vC1*s8-z5pEM%q_a}Mg!}Nzo8g= zr+oYB9G3;X`GZV;0}lvbEzYgqh-^V5Vg9Q~DdZdUsaW^&4Z3R0m-N`@?$M7CAvo*R zQj!qdad(Ae6-A`}B} zf5|oE5@U&RH)4yQyZqOP>A7~_9H@f~x$sy@wBA1b`o94-hF@(vyV{OSaNK+RR-dMS zvEBOsP(B<3T`L`D2r%lp*>3SW8+W~OLRqky4obYc$e0ohf)*F&5Npa)U zz7oUKjlb>!Pd`w`a+b~U>hf0C%@asF53w_qe-kw8{MFYrwehe#%NU?^@0lN|O)Sq- z@mn6}Lgpc$j|8eqvk9J;r(2`TJ;COF&!KD$d8=A_ zA>4RJLKiFD1c*wOHaXYb&5TycMqV0Hbr>%t&}?{=Jh160glSnUXTOv4OH9s(bc^)Y zY+yNk(k^`IZq{CV4m9=0IQ{Ixji>=OJPymboAY|GP$53!L#6S1R#2NKXwKf=#-4V8Vfp%|^RfeGYH6Et4 z5Qfdej$-EQo)cM8X2JI0pTe*|AsB%Tq1~0I8o!CbzT?`#BEA7=&ItO@FXngfqO!|6 z^ndI~<9*xkc;-*0UmYB23qOqMkmz5uolKpDoA?iyp%u+Uy%~Ki|it zE)hz7-foFLzmUU1jx6$G)QGCk_e@#@Z(3RaOCUNTDM4081TL$@EGxNu9#0 z$GpS4tKlQ2gR@SzqqOv&O4X3~sWsu)g~|Tl4rC5xpf2jN*?nZRNm@-VZtlPL!mQN# z&G8L)xj@f+hEc^_nLeK`FOBLJRr%%he{yz+~Jcl$X zjMcnvpB|H0Dan}x{QDHeuG&;dj)1+oai=d=C8VTl8P&tYal=E&mtzj^jJ)?;bVDZR5cVt2$N+b<<)hXWyiCCDLc@Q#sCUiQ;jjzZ%r(h$Vj8C7d9f8G1=R2 zvfhG-$D}Q1Bh6=HB$c^a9k7YvIhXi_ThsUioeXMH)?eZPD-VgapR%yb*r&HL$v8!c zE6e5D(>RB#T@#1*)mwN^aV+RqE2H~fICE9juGAKAAs|ePt(?VrW~$#cqxmW-Hf?MG z)`i=Q)|Rw<{jW0`O`BWKIu_^O#p9~C)Tcj9SEN?1Rs&>+slQLXm47>VTQn=6j;ovGY&GKM`{zf~WDY(xOE5Ts5YVUcJrKTHr8Vs)O1_d3+H9r(w=R9CRd%$@hhRm zknJsNhd2ANf?d5Bxrbk4+tgJT?V_Li#PrdBq${HP*l%Lu{@NVPw{}rJqOnIHsU2N) z7ShnXJSvft$&q;|!`O}aPJyVqMAZ`ifzPBPX1!GrZ4%z6)pYDnSb6!#2<}%y@fr`k$47OP$id!hKKmp3`}@G;BW#u9o+Xa zT7-2u#13U!gq>uADn*-l9@{>2lNnc6SJyrG<`!-w5bkL0JuiU>e46tRZFui681S{% zXNNFh;qJ5!zA>#6Q5r&(cwvm-W<{Fd-t4Heh6-jQSws?n5c{lfG9*@PB%ZbrxglRL zPe^FS(Bz10iAA`b3Q?4Th?+{^+f_qDp5A3D6ExmW3Kk2x=l^2F>+Bv0GqTagQjtUi zfLn2`7?~_U*9wZ4hVp|-(E)njVkQzVi9)T3LgD2N#x25Z^(j=i$a}s4(;xfn5sHlu z7hHxkBI5mKdWgZt^~!kzp{br}l%uD-!UtDX%?cSJ;17R^{2sl#1YpM%pK(^AKjSV% zD;pfsseH)jSJos=&G3zne_N5pzdB)0f$r`{)PbwtaETK<>Jv zZwtcCc$oaC4HzCxPCxWjR>>*xCe>A{`}d-;W430ITQMc~_t~j=uh|=nSrt5IZM(Rp z3vUv;(QK(#!@OnvrYyUoW+jl!#jt18Ht!M{*WKB{`+5Fg@u2evrxVm$x1gzCTnQP- z9Gy$>+SI<#so9(P3Hlom&n1r;ji;&LW6pugwojk~D7c?iz4lGq0HRmhT@g3uCN5SI zG-3|AcOBHHFyGk8!%Z| zfD=c&pMLEz83Mt8o|egqyb@Fd5Lh{Te|q|A$Bh|9c(x0!Y=C*s-6~|2$E1SG*)nCQsOCF0Jk-{_l3AaIajUTi-1A!87u)RtmvhQ z>N8Bpb(XHoMm6|~te#!fdPg28?9zR;ZTRryayCs*Y4eq=HLxgXDhc|hE!zlO4__NQ z>7D4#JNS&gUwiXDO$(R+0ocl|JeG7pI8oMv>y1C+x^Fa$Iju!HWajSEQr<{gH97n? zw2*kuF#dvTjy}Te2mHow`h*T6`kSz&T2+U?`6DtzJ!>pl^!#6w|}-P&<| z1y(j#3m{MTt6av5kJDopL9oz9Z7McJoi~qP_8Ga%^oxAt<)SIr<<=5@&rM&DzxGv;;wJ)v7wG3I;M-?6_QmZou$z$@9eu(l%s$bkOvfku zw<9c|;xm+S&xt;l(}_k!_g$ReRk*th#r!eL9dhlHHxJ=TutLJ4917Wqj`39_EyHbh z)-4;>8gCc&FKyo#Fw3QRS^Mv!WRi0k*vxa;L=?Z6kqaWfO3p%~ixDUn!JL&d3e2wO zjbD)SU#AwtI)(<=226fz=`^WV&$LPI>LPrKhwUxq4RxGKp~3quePFOV=i}^?A3sc} zDJy`Hi3HhOB+d3KQe-r>#HlhHGGT6aV<1Cj-yorrlhoeLzD{o7w1j zd%Rr28UWT|tMeE+Iik%r_rM)WzN7&;s5m$Eo4UP$!zbRh1}PjqVq!dcfd1QOiyMi? zs~~S0BM{k}HKN%%`mV!uBenhe_46HZYq2=fH}U})wA6GblNsr5Qn&s4o>-kNYq>ce zX}JTm^Bc9nh1pe*YFGl9&Z4MGdS0~~H2CPBZCgvQtCc$Z%v%OjnULo7eRo6V1$xMP zG;05RNhCgajs{S@lzjdM7lXd1UUYRIo_5TEt*1uuUmqQ)? ze*KA`&ED$7g?4fgvdWqM^*}yTx#(Ts4W5Jq?s!L6ek}O;_oev+`J%*w>?&>Lyl)(< z#5DYV(ZkFysN_cX_E4m z>E3=~ZNoc!Z-}Cz5S{x5BfvjNGapl$ot6!4?VBP%xg8jE(EVYZ zvpLH+M}2K3(w$lC$>o{irubQPJVVZ-AD9_?a6Dk{pmfx)j8~8Kr+RU!!V?sB7q4|` zNr{1>iH)VPvzk#?HNyvdnDm`g&p0K zi^3V^8SiexQtIhlf!TF4y%o>~bfT-NflP8qS`)VVMm-8MpaR0UaU1|G&XpG08NeZG<8`)C8iGoKKZBo4ez zkAv7i)ReI*a4#cJAIO~3;)T)dj^4g*$oA7-#cg&e60@j7uTm~7Za7^;+wG)~YnEbQ zFU~gve17nNYIdE9P+UsFidROIYGlu#w6wei(@^CG8o_vo@I^}`TMXH<=&mzaBzh3{ z_q71vci9hoj{7TQu&q6WjKy-BRanl<)M3iU>S8awHTRKQkD^=diYyKNPbiJAPNn;G zkGDSG(9`lo>7EfTLs{411TrC83u95jIdyg1xRWjD< z$HSYEEe)atBJWm4cpMRFq8}Bx`?vTi#>R{^-|*Ipd`!;bp2W4b7EDZi`~8viX(Na8 z_2Rhb(vKhIHVh-G@L?WfiuqTh77hh}9vUuXujF9-qx<#nVOqzYHC&q|q~wGUgOgG2 z=;yrsz zpKK|~`SfFQQi6^y@Tdqh=BxW&3kcOBy(Y{1B<1vopei+$G)TZu{HM;FB<;76#HsLs&T4$+kg$#JeQY_rd(BsBY)6+olIJ_ z$qs;7m8AV3Z*z=?L84H{+kVQw-PRFR=&n(qqX4eghz*p`4ocA*=c*_Sl3o8El&VM8 zwOlPM`uZKIT{ye5CQrtQO_HDEuVgAkp*Vip$MOc>^{_5@!wV-J3?wW#qf_*%mFk&f z7OcTEbx-Q`_PQ-3Z6sf{9P#ySApM6o^1Hj$8VbHT@6+@W)E0>4)$FuegJUPDfOrK5 zwM}mYMFF*w^gr!4y*T*F(i;H(S7`lCuVJSFl1bzcz0ysC>4@$;K)fl@8lHk6X1 zf|ll-gdIbi-%R9?!u5WaJYpW&!|G}`X+{ti50do&Ta|#VCO~l?%+#B3X#3$Fd#w{d zKZJpZL8}zz3n5+yRiZ*yLV;TpJs#V~(8DbsKq^=pzy7aaPuV7R2L@E!pHXxmG-2NR~T-O-4pWKe8UQ+|VE_ z910l9h8AmKMm9q%aZtJ4Qs_*3B>@k;im=4%-zUQ{+TbMR>6ynnY4OX@W+*+xps8wR zn-ReKL|jT-*MpXzF1x*`uS?MQ1=}oB^8e(R^?(6$hQ6;K|Gw zbTOzQzi|!y-5!F3XhXegSM96%-T~Zb{IU6dnSTVu9{hVlI)|^n0RvX7v>fTr-{@b& z<(vXc^a}^N)8MRD2KfjdmLu*kgSpoW69!dA`am@e4cpi9k5vbi)V6GfSfrYn$J8TQ zUj^j5GAvU6Dtz%3{fohrddqeW@oetk$4A>idMe4XI&JY1 z%Wa_#n^#>(sh8A~uS@?Sax|knuPU! zXP=?`WY4_^nVPSptZ)rOf&=u%gNh0t;wAUbxg~z@D+0zpms#NfW%@H_^~n z{X@r)aOZNPK4=lMTT(^(g2He1DhIP=q@6^1+xMx3z!YR z|Kyw$c)O6LehqU{57~~T9?T!e^*!X($uz_o*%G2)SzdSTUL)hH0Khl)siBiSW=1B) zR>+}%`#)s*dMg!SdHsar#(|Taf7CsrB5Lt%J>m94eGY-+)X+r$g|B5ZzY_o7QJM+> z0qR)=CLH2-r+mL_7pp$AW0WGu%Mmj0^R99=HXX0hDmQNP5YuRmgm&D7iUFq6;v};@ z@{WthjMKGaotjLm3s0K_Mmd{RjoB?6DVKDW#H~%A7w8q^%G{QFW^0ZgiA$(+OS|~W zV)!PBiuhDauL{I6WXi+jf-MWno{k5?I`zWK*t1qr$iq*9a3k1JK*US7(AmY*_{Mjj z!>EBwW*g0}98GV^Kt23=tfQU>88|~*(w5gFtoG~%h&ASv#oDDFP5W)9N4!aDeSQqj zzu_lM9x;&U#4;ue5eAXo$9S0g+Xp{VmHQPVhuoP9wf;Q8>5EJ!zwngcV%zjeFl&{o zT%vJ!8c<%YpIYDzgZW|S1I+at@s-{-+UBZ0 z#|Lb7yB+6RFWrNQ;s&a6f>hhfrk^!+4J{QWW`sL1Y^y=(`)gu!C9i1`DM7E8$7qhFGJT<{lp;K z!TDG;Q%A1D1f6o`AWQ#@vA{1SKp%gMfU{H>Mo?dv{a@sgYudKBB7Qcl@9Vypalc;t z?7ci##QTJt%8P}D1f#Q6E1C)1y_ipxr^}_uN%;B`%Y#61v}1oSP7mhOHUE%WELab) zjH-SEca^azY{n)%9u`DP5vEEri_Q;sKx3wppp7^FS0-nZgKYs}A2YNuG5#RrAio;f zfaTLNFA0UuT`#^BufSbx9qjS9JjPu@ye=Wo^PUtcs@K8%%vOjNoY19LOHK5w?8r>o z_dU7-RnPJv_UfnWYS6RK#O-pzCF6jk?c{FFI7|!e!)YGfu$RqRnfx<#AAun*rUG5= z9ZrPy|Hba*BzAF_%aR7%{i?|wVJdy()(V-%_6N2$CO8ZRExn2+G|HxLUR%i}lRUgr zEZ?aNV+7e`4!_h|&_c>Kv>9GfyjLokO!elB=C*X%HPYAMt{^c-i`(WtRjRDcu0dpe z(5D%KU>Zi1Gq+rMwR#a}(~s(#HWJ)9jlvKkbxr#drLhf#MAmn7a->FNM(f-eUA1*^ zCqFUqA+*E8B7{|e_{g9Km!phTrFHdtFC`Z5Ql5rt%<~52(}h68W+i@xp^;1P=)_{V z-z1-w4Y`rR&)Y2$v8l$iY!VW`>$s+N44X+kVN>bJtGcX5$QxF$!70Qzb|+ zmIRl+=1jEA?0PJATqurc3j@sKtZb)fjvFSB{;i1AS$)F1Md0*`XsqF>pe&bK}v}Bmch}hU+(&QOok($jAS9faJDx3rtI)&2iJf z5L|s8RMWjZ_Q?@<^$cemls4lEcTbR&!!@J}-u#+3&}c#FyMTab`hG?+=Pkg4m45$A zCFFAwrOByJSoz!4!^D_2Ti(=9k4yzF(3!q@8mC=xWiH$13dt5Ta{L4f#5L6PktoM8 zBwF3tE6x6dN>cWCtCF(ZFe7}%p>6N7Mk25mX>8_agpR~+F5W0H`)`!!TrkDG8zZ8V zIX0O%AgBJMEM(|ovxTyRWYK~1;amNxmE2>2z;<*{y78F{5G)qoGfulvQ#(ShlljQ} zmaFEB%QzU|i&;6A-R3&}ZiIq(OxS0T!rGflP=kM$mUoxbCn9s#-`^4FtRJebI&>?v zS;%)93()4W4>A%~Ni)CcK-4Wyi==3@RE8B<7Wir|z3~MCY`LcG^>=#>ZQJs;MDNLP zvi^VUTP@tQUf^ASC0HN&KP^BMg)0Tv)6F4UfKQfs1ca)AL^8{Ii?26Y@w5$sDY?_Qe+k8JM_18)rvmP?DwOH-%e4N2mPC=;IKB2Y%YnU_XEi(5YZQf zU9`E>Nr{DI$f)Sj#5k&;`W^>F8q;}OVKuW-<-Cto7sV!t7XGs%&|2BFLzCTbU;Izq zMT?){S2f^}rr*z7L!B7*Ro6|#%NqLvxTsV(sFHtge2(?^X|f8IaD;Q{87gMMN-fxw zdF&%AI23quxTWd{<#c2ByxtuOY{&2q`gCK{kz zivLBr<!w!0stK;|}Era!|lP6#H^V@{%x6Kz5A9;nFaweS10&@>Ny4R}LcItzk3gbG|;ZU*}|d^zW##a^eENg-<<9DhP-u3Cu<`5JnNI{h0&&6X*J-)Z{E_+oKm$ zSQ;$ZLXpi3y?w@qsd5m&7hpCY)l@hF)&8PUZ_8F5?)ren5NCa)O`%8|f9e;Jk|ysS zH;*hue?bj^9$_MU7{lZDY`2DLQl2*4K?eWK;IZf-$BIh~C)UUs)isaOH9ka}%95}l zS^|u75w9hN+GNUtm?(I&FXWoecq??PgKpb}S_TGSJHQdBfY!3UF_hJ#ZO^Sdz5|Nc znvAv*lE6_hxUpCZen2PDK*z?8uidY<0jQr6KOA{517xrBqX*~0BWc;ZbIbDGO+;{< zve3YqZZE%C`&jX`04kM$Wwj$==m;oJOZvP_-%%GrgZI_T<*BC!J^NEj8=H9BnXU<} zXd{|`?xY#?Z;3`bm~hzM8W{8}1xM8`m%qpVA*|dmi(Upj(|^``kV_ElMzHxto1>j| zPJqjfD;8hziO#H~+ic1Y?c!dI)u42JNkIYm&p2O2UTWc3U>l$$wL=uWg4u|NABkoT zI?daMD+F!}=N<%>>Zwwz(9ebgIX!ziCrJUP5aIJ+u zEQ$?U-(!8})5#t@wp70+w@J9VGZZ1=GD+3g`I$d2rRQ8_y0vfJ|G<%9Z1J??^C`363iD`alf*2Fk;8u+B?+2W?Nf_V{+@djQ5uEJQe1=164`yBs>cGXr$ zcv!1}j8iIv59{3^*_AI2S70U9d1H9kTq>#I;B~N>(WudshHn1;p#Nzx>1sS=-f!#? z68Y~5#R9(uf4$!{zDL2Nxs5Z(`Lj`Mx3zCzH^mLnjQ_JRkSg*jCw;$L{)Lpod{bj9 z(Jz?y@#LAvX|npesL08Za1cF>{V+iF z<&(S8cc+T38A(51nmyf>V30`(z{4V560>5QH&6BjgOA8-Jvg3LKZ$Gy0DmR3#^<_6 z^<6B!c#~3R0mV%GD!ZCW@SMy#Zj1Y!fl}M~ z!~C@v)NK>A$M~dRp=$Wp&d%R>^*I;F+v~wSn@_O6n(c|e_q$EP^No7#IYU!@={8!^ zi9eC@TJrB3&sumJ$0N4I%gUm58o9IyelN^m0hs*$9{?yp*S^dA$Udj2=v&n{dcwZ0 z#@EP&bKI=n>;Zh^e#&2UqS)Q`ASmaS(=lt8e^TM}Fn6p|d2^q6bJ^1^>r~W80!i$H zaNI7ZASds?ReghRRo~#(XJ04NnC`qkEbpw2iCsTqwT?P<}2=Xcg4HN>yFRdA%!RDgaAL@IO(LLdXinPeiTIBQ@3=1y7P3zJ}u#3 zb>%|VG5(JmO6#aoN7-?^Y;|fByv#%=Db)Lq@vYf0LbX=K5C-XV8Z$eG5sSk_h8L&POhgPsGKDOc z5Va~Y9=F`Dw$s(=lnsHH$Rg``>wTwl)^^1@|F#{nhU4!xq!prqG!pH$QbIE5C2cl*C$T4jvy; zDK+^?>u=cm{NG>#8J2m>CMM8iumjfqOycdVHTl>nI}VM@kp%ERgno~I*ZP`wK3!Xm ziD@06=SdCcd=?FI#TKpy|qhPTA8c z6pC`oxW)8bj?KdzlEQM_I^mN$Z{{Gq8vi1>aIOPmbJ=O`?%(Z$l3sceT{2E!XFFw8 z>-?y>W}WME)U;;krox$_>-8JyU+?q<-RnPSzYKHAy8El!9qX=hm|HeCk>%hd&q`#4 z*|6o5{ZZwI%EykMb@I|UCV)@loYm=+Et`tTe4k+DBl*CbvghKccEDEB)=j1zPIx)7 z$fjubUv~~ym%G*3*X{7d@9p+pC(SAAmJQ`c$xr`NtOieKr4zVANL&P-xjngWZFk*3Jqs~dwWFlf9%Z{9}(HPBElW;Tw1~ghVqVZS&4ydNX5%p1kf8%x}spR2Rs@HLR z^f`Bj)UN|xjHCZLL2NEN%|ZUK^VuL*?0JC>o$}MybmaJTxBtx>-(-7!o5kJ5j$?L^ zYu3&sYww>yb^2-ltmXVl2NZsiq4a5`+Ws)`soH;axujLwA9sFZ9qs#Z9-d`PALNcb zi_3K)on~XJe|h}4T%RwLKJVW4#esgfu|bac5}7YmGF5?C z5N^^S@}8b$xm3#zbM?BVV_*5vlM2;Uw~3!+_p_ay^$yJ`tLlioeEBl>@89ox-^(c* z_nn{2th>67 zzOU(?>FGHz2L_iwhQt}@qG(bQ*Rm*qp|Gq!c0-}XuEX@M|1ozrV(mY6^_L@jg=mG2 z@NQ^n30_LJD4LQ@Eg{a3GyxC*!5IJq=Ioj2nLetoy06UrBde;jva_n*tE$)44fMAo zqw9F}-pkCFud?3feSdEkNE%i9+}ykWfZ*gbnx+$&oaO1bAFCE-r&=gb8A>oRF@a`) zWdOPkL4U*j8jVH4fQqgW@IyErr&`Hk1bk>Zqzfft+j$s{vXsv8czu(p$uMJBL`Fub zM8W6tHJq@GFveODOSdblX#p&))JRjcEGpFu_$u7Fd!3b)T*Hy-)2Ap|D>kszb^9|8 z=c=XE!yAL2VM^?-C2PBA;rPNL;}heUK)8Agsv**W59~al;f8Hms}>u+`m7-eWSX3^ zrfFdiL^lKE3njKUv*fZcGCD$Fw8*=!EK&K?GWSA1Y`9(P?pOEbcEh@zvK98OCwt_S z71yA{Y4#e9_6x>8;9pe#W!L44N(%C59%)76YY#x}T(RxK6CVT(By_h!s>6|cx$f$4 z_QLuFKJ!ca=yhw*-zkGuKi8C%IhJ*&Y`6fS+W(pFeT>jb z!Vbbx-%OgH*EZe#nBB)y&pyTd4$97<+W4q|4-84Sqa<_WH){DstTwi{t z@v@h@Rkkjo{eL^B?2!(K1|9iACPeh0LAR&|^o`3dvUVG!Up7Ly0uR*ULdL*?@*+GNee#85=P_|degfH$!-9TAkm#NJ9 zuo7uS)i0N8H|e~}e|+XLiSZHE^F{KBDUJnAG&I(CGW=+5lX9g@wYnR9T+=i(4VIT5 z5gnT(GCqk<*O(cK@I=&CH<;E!2Ga;RZ0Q#GEV88>re8=ju_M&6iA6DA#RN2;iKT1A6A41$Fx8qjw`y7x3I*0T zHqeWsJmKc@`AF5Nqb;Ni>ZK3ZLPyMq)5B0gV?#XV|yH2UNCmhP-M{M4_aO! zjh)ZyVT%u{oagU1jsK3{tNwvd+ICVEWkAJR$VWQdk~!DE{G-3a_$zxIWp34hp2&oX zS!Ow*>*RyWR;b2$bPM=@gH$H|;RS1&H35z`xr-s+D>!xLmTR`FNBSFXKY zt)(eB(pSLush{HOJGXea+5Q+zBqmth7F(ZiP>w98HX@sQplmC(TQBx;*ud)f>E|2px?gZoX7E{dEyGqo7UZC;Gd=8YC}$^>eZqH^pBVZ?6QidgfDh$zrq=-$Wt`!6TY*Jb(P)9=Ca(~zRms0eL&o~3gZ2$O#dq?6?uB8 z4rSZPeIA||J;Qsc_c04q$d%BuRdm3b4N#rc(P9RtVvF3Y*4kZ%P{Mh1fmP;gb`dCPHzx3--nAm`09T{b2dYT{JxZW|X zQ!;RF(4a?D2eqEPz~ffuN!7lJ=37rEl3sNGRRM9?eNvrgA|7XaY@D07kKlMG8K+O5 z{wG^o0xK&6&ph)Cj~_o4N_*nO39=J8!V~RhDkg$)idC^6>2Cezvb;yn%B4Fel1L|; zRyfa{jn0WA%a__GSNY*Wn$^h#VmoWx)1wSqWdgw<(NGY--^WHahgl2rt7#gBt~24+ zDV9t4s%7G4iC8&@RVkC-N|84Ltgo+8$Y;r9GNiK^GP&CSY?@*qLbaTuP|TAr7s%!^ zZ0~I24+h8;vg~Awq;okkC4-G>mhEDJtxS=0E|0ENuwt-dSftZADpiX@p+v=ufd<85 zmU1}_1x{7N;CQq5`M@3)Vs;)A} zd3NPk)AiX(`GOr{adUpN+O-Kv1JvK%aGUW~Yb&y(yz*-a|Z(x|9*S7lOaz5Mi z+%RodtZv$QIp5P4PjIuiNxIPfIAn|2w(mQ&Ex44*L}EfJUs0Voc7_M}hg9@x+jRfU z_-DDOU*vS?3?bcKPGq~X#T&Wr^Ivk`;BMs}>t+hD;ooXztzC8pUg=Vr6TTA+`|LKn z>R%yU>b{@3Te-(ZCdFJ}9)Mxr2npict=#LWo-)T-CT%+)3vfPgj*uQ=v$83)4^e-F zNn;AI_dQ?9HQI|?v#}ZBW8Eq3^pIWV6P2@EiagbL{X3a&^Lpv~o}W22y2wV}I~*~< zwz)x4AH}cv_q-Q3;zac*0FNuXgJ7evVIJg{gn(?T@_T82tt6ADXxeo%#ofw1-YmRH zf;gL%&Bk?9E|>9DeN6kNN$3gk=^Q(z*g&yp|0mN=iuS82`d+XnUT)z@apA1qm^?czIFL3XEZ})&s z%}h-b8;W_>p;+46!7nZ>3Y~*+DAdR^9*Z~f@+#-jg-figt;klrNutNFo=zma*Z%iX zHmGU8GUfM@XDApX8i}&8*}M-kQ`5rvil!B9XR_rx+hRY;Z&kKZr)=aWq6}Z@pHtQy zI;xdZR)xz{Cap~QGHc0-N`-S5VCAV#65M{w_czNt{S%idWw!BQkxVAgiUl66t&>9| zQZ7&pgwZs(apMN@L>xmm2*wj=nvS9C7}YXbE!1y4Y%tLfRPtDc3E?o6N`|soCU03( zDp_(B&;ot}0TZ9Ef~i?xST&ceWHm*fZrb=Iuykpve(Hqd_LP5t3kd{B%9A;T5$L7L;N9~s%hFT zTGMv9X0inyJzmBi4Ax+3fGaP&Ku{mSFk=7|^c_mtb_0@DYtGw>S;e$0^2H*Rs!2AJ zWpjI*a3o475~6BaB!|Y)eGxJhll5wfQn|#CG0yN%kq2*Yu^n1t`NzK7aKAc35xc_` z*FzJZ)-Ljnb$!qKmMg6VEGTfK%7iFAa!>8A4uexx#ahHN?d<2bK27Y^#GdfP&>=*z z+qLWXW|j%jd~{9pSD*jSpKm&sw=Un}(c~j;jNKS`L;#Vrb*HRozB2u<==Gx_?DUZi zruMu4xv+kL%U`+Ncs?~T$>Y_%Kh)h$*;!_ZXyLZ)_cQvZ`MUX+d)v7M!IJHc4Hs%* zjPnq=F+n^#OeLGKov-B@u=RTEaLNWsU{oCMyPUH7<(^V4FQ@DizOw)=*NbfxqF9yo z+YvRakMmUEytGqRr0hEIthap;$EJ$?ZkDv49d#nGZwAXykFw zU6Z|rFBT1FFLOKfXyM-Kh40TtEZv z+Rrs#3=7+lrfC{_Ev#@NF+{ndkt-A_m3A<63*E4=tRj_ag{oPiS}9T}X2@hRWU|}r zq&HYgt@2HT4neA)&3WXC5pu&YisN5?4(&;TSGSth9U_@ z#*>625ez*}&NSIE(iDmXbX{XIFi!E7$>ZZ6uzL2@hO5=-gtZ*6nXdQNS#5gXa@5J4 zS4x2+brtbzV$kj>Q5_~nR4YBLT_Qn(A6Rcom#;#t_DN^`Cv6ufO2!itS7J4tH)^OM8c9b~||`^rUuC__`Er7b^0Uk?1vX`5Tv;o{ubz zF#qm6!{K3mF!2N7@>E0w5J_8i%8KSI)BlQIKQejBIGR=Te+RYy?Iq9s?5p?tJ7FR> z!Th`Pjpv!Hx6{b&lwE&o9seCa>$g(O1&@)5?fu-%8i@5e&c135u2yNdW&LYW%xtyU z4eQ~Wbvk8@ipTpdr>qM1l-oJgPNFWaPU-Ug0u{Z=6TY)NH}fn{n@@8(bcVUWe8UwB zyUy6Fg=;Ncj$Z1An`S>9QBU}vX52SL!WbfM*poEhEVPblAY1m`$~_Xq301;?m}^$W z{(GhKTL0GTT(@${wmaABW{P|z*Ki9zJ^3^nnN-KN)QfZKS7(2fSUFCqTxvLe*UePV zZm@!t^K{Fen>kB0Z~ro@J7otAWMTi>PrLH(R_?J~+9p+8$Bz%t8pki9M~UcB0=WQw zd?fTlM+a?cN30K0<#KJ?uLiN{s1JyM6|?^n0g^xrFtA~40JK`5f|-&Yw>xh#Q4UnNB*Dj*UIG9B zAOJ~3K~&o*DEh)sG?3(S&2ITK#fb!={y@w4%c4uj_^51m!OPfTzXEet+(zUWF3ND<-79`bqKbT zSH1e-aut<(Kf68l-AaYaRVL3tDxJx+bjtRkULC1kx^V77+v}^Fd}ZChJwe%aKo**z ztcn};-zrV_9YE@Hr-Y%Zaq6NFRMnyhD2sJ!GN80q$%Zo?G9bLO!Dc9i_4ppQ-nl_6 z6d`%+I9scai3Wl^T3e%3C{Qew*hyz7=d);m5UHw0AQYxpDp4v|C{`+@3k3?LGDfw+ zPN__;Tqa*Ckt>&}REq2r%49R!WYe1rhYDnKX@+7$_yfM(b!c^M*Bx7btd$zCX%1*R zG!!EkG6)0=R#&$%d^W^&hvBs$WbLoEW~^ouDOZbRvRN|O9kzEiSzb<&-3nkCc{1q| zp-_w}WrCp)k!Xa8i3vtVNAU-O6t^N+xi}$nhU})r#@Y@mk5@^p?C|K}V^$wzSXtWP z{s(KU+}mdPc8b))ESrz=UV()h=||6>e?hr0@AEYq)v$_vzag)dfhP4weB zch|pF*j!cp-$Ctvd&zT<=UOK0aW|mZ4Q1U51_D&8yCHKo=Qnxx@w-$rRkrmV=A(1m zUAxDr{37#XbHdl8ue$4OZ9v(AA7d-f1Z7W5o+Z7LY7J$pd!g*mQ%~}ZCGU`@{gNn< zh5m%|OzKIVi$BkkVLLQ&yp-?+vG+^&rD1GcG6Sl;ES=LzGN9onMt%w^I$*=nXzf_I zp{&e=X0P(^R_>9n(OmtE!ADs7c2 zNuxRHSSFKggz9}g93^sv!7GlyhCocBA#EZBWj$Y=Mt-9lNfJVol- zYoFe0S{eAL;(M|mQURr9fowa#S`P=DxtD1RSe>DMH;pEz-XyLayjXIxjm!xuaC8##;r@kXU{!XrsZB=mA69Op-o zIVxt6Lb*hxYNF4b!C%M_oR}iFwSkU>6%3PJUtzOYAy=*vkH@K?69@*tvM{VFx~5@b zQL(BJ3}IFBRICaZ*suA0Wb#>_J{4y*waWP9I7T=^FgAv6rmze^hkP+dzG8hy_^cd@@4IZzo^6*Xu-3sIL`v^zE1OfpnrfG+B_W95a15MZP`FwWx zVojr3tx~C)lu9N1Lk6P@5emg3$>=eLMn=e3MG6!tmP$lRQw-;4V5`7;^H;e$^`9GX zwc`3;->M#)`*mkp=YMA?WM%Qs4~SHRW0c8LCLFJ5zA|~%_4C?i0QgVV*QGvpm~~;Iu+p527)eZv1VVLh^2FFnD@pk4MiGJi=RVI74XbtqAa6D>wO-%ILA zVtR}*-?-=d^$^GREBAY@$53d9Ou;oU=MhfW3N$|lY=DXlSe?%&;uDQE72By@pPmio z*beNrYtc4&YIKoACd%7C{7&QRvjSA22HI?RPkPZ1zk}%0KR*94()o1P;fs&dEEVC% zMI{q<*_qZI8n|6p;C3N_RfNrz(V#=L?w2}+Fa9W~T?k{R+-;&=8+qXqFYv8zf2(62 zGGTL7h1mV5wDp4^nb75}l!(Wh!WWC?*=>mPPEt{RzuM%XSX0*P%hn6ZDp?;^L7uW{ zMWt#j*>>8AjIt9PVr?Tu9v@&48XYIMy^Zeou~IV0S{hpwFoGfSz98e{#>Bu$|3f_zkwUH_^2!Lt%qlsm#aEMoH(=OwUdeiUz4KXkuw#88&>y2b!+g z?>W|!wKULl`*E=Z)oK-g$d9IJXnGk*s9sCP))-EcG4ym7KS!V znQeT2gFwi#;bbk1sX=NrOE?rKlP$2iy3We-7NvqtF<&Jd8p1-yAMg_nhtV|K(rXZ+ zzz$W@c6AiWC3K%gxm?CSWH5FzidBhWgkl&`jl7k^Eb8|DEXNp6j`CpkI`1dH)&x}D zP}aRZY<*kQF7jS&E!kF3whm)Op{xpca-{uLeE@$DP&P?|EyNr>qHWEct{r%d4Gndi z=~Rbtm8mkXjPCCM=Z9Kt*4S;Crd2vgIYEyb$b#L5j$c2q2h6%918QaZO3~}$iuMVf z(4P>3vMSbnJ?j5II#RKgw@AABwOU^{vy<+P-Q!QE{*?KlIhM+`LHF9Cc>Xy*{&^c3 zCP@%w$Qxd}p=|AcD=6zPH?J96hqAt^@0FS19XM&;10m?%(d+to7Q>nzHTkf&T2X`#5GM()`y)|COb5 z?;y`h?zXcFWy}2G*6%7Q^RTRi>6NY(ly!s3Io}*WOF#>fkhTt7-LTd1S{<&!Uf?Pi zRHA3Op{%U5%`(-sB6`%I0{A?D>_OMZ=Rd|$YKceL$5K$b8~E3+w5rxT|FFmjS?hpR z2CjbCr3!SYSPRn&KDL6gDnN@0wJKi}w6@cJtuuO9)-zSneg_Q-56iK4YG!&GfaOO= zAia~6LRssQ#j(#ESCaQf#VM-_v24Y(3;L)Iu9;yCIJC8o9;7)NIIFu2wNkvjJtPyLzit zDyBtd+lOgtq*jYWhaom5+!_kkfG5e;h6x%f{7j}5e*Ha2Xj=nLYP*Ga-_`q z^apH2-rM7Bbpq9PP_~s*wiV!YhDPp(R5*fUK!b|%Rk*BFfJzY^W~Xc&yh3N!tCzMG z>|b}O*%Xf^cW*4Zal{VVQKuqLnY8=eVF<;NP47ud*`wB^B*gw5_Sg69#`xeiS6@l)ZKSCV#Gf zm9z0P{HXB0eeKt7c>J?|{Ksu5+xDD@K-sbj!qy&-3{8+rahU^4PpUuW{#E0V{V7;Fq$0g`#|ww7<``honq9O@O;m9%1!_|rA}F= zoRAX40BJ932V~owzh0oM8(_2ov$F8ySoT;0$kyH7r=K{@SFis?Bb|yi`Go&zjwNPE zr8jF(b{-qb?oXRJOls$pZKXP(wZj@m2n9nFiiJJt>X3FRQG>Jrm>8O1HM82%-3mZa zJjwuw_rWrG*3))^vh{1?WAo4R>e6d%(~U$&+NSA7q7K_$oqrew=N2j6-)$5NfxUS*>Npg~ z%E;X;9&3{y$idIUruD!mX0<|gbPlUr#21d@3kETwaWq}S!lG=LU|5u>Qr0Xglqr<5 z7=DwT+z$RAR4W@8ehnjN;tTr8S`my;6ic(H=sJ$eho&srj%p1Ji=4X<})R&smK%Rt=wqPah`0 z2vsXbp;#cAERiX$VFaoK;}y!e7@?R>p;%;ldz%M0(?o}cC>0C>BpDt}fTj@&hiWj` zmRW&(sYtm}VS8%}f7l>hUdJETm>fUB%Jv;b#wWpVq9rtPCvIX6uQQ`va|H zu1RKD=V41ITmSqRvplM$>jY(w28uuY`VIZ>v2LyN1M6*}bFB&+4p4ba&XEpI~&aK*|8_FKF z-y?ZxkQ0(*(t4HO3d*)}&fdCwi?5kqqnfUQ0rP=5viU5j;s%kQZa;|MsHX+Nq77o} zP&Sf>@cmsV>jbgR$4ySzx;wT7ls%|w=Z3AT4q~^=-FSc-kxdH5VAnko1#qIyKj;kL z+5uT`LfImJxb=Hd^^}o2&;4@EcH@w(t6xspx}5vGUD@I*nLm~Kyc6s?KmXZ_zt{w2 zWh8p8oo?BXW^gWKKlXyMgLc%ZXumRgI(~`Lqf*QFV|vW7Z(<> zEPE{dForMg6)N>3lx#P37z7NH0n#ek+D8EZ_FJbyy(Q-`qPW=LMaOQx~b;?BFP=yH^812=D_DAnbT8Sla@iMH5)Yw!I!$ptd<5 z`)kkZ|LdWQ4acT?ysm*|)SRK34Je(?(mIsXn5D!+^upf)E5ufMn~nV2M90%EuxW=q z&gD%iRRdorgjG#qYC1mO5Ss48L~nAgnm|!|)Bv6(vts8}4N$I@sOWjDMA{Rgy4|o9 z*L!Z~YdfcG{qtT<*?KxB^i?GlEp1?RSta?W6T!2P}|ChlR`u&KJ)QtO^rj6RfTaL?jSQ*Y7+Z8V`9(|A7$vtGC

    T;P6X4RBv{0VGK!9RtcS4;n z3GUv#+cA@N&RI8UaG&z!#pOQdtHa78cB15L<(>$L8$Ubl)td_7F?&3}x$3 zQrr0za@7y0=sHH?&8D;-CTcXRb?QUuC2?UR=yxR&n`DE#P1#rnpoBnoBg-xDH}EjqT}7EpHh z)+r*l#?h)^n4s6Us{J2^&@9mH6+0T6USDCuf@E@(>6v4^a_a|D$3aG|+^wqhw(o83 zYY)2qe7``UQz{)%B0x403^QVm)}So>+0LJ^Y3_C2sdhega?Q%Pyz1)3AzN3!ow9Yg z_qSc$L>$GvIAz@uIoI`L8w>>a((1qIn5T+sqMJ6+mEx}FL-vi1HRO2BIh2*tIJv#R z`3Hl8vIkvtDBF#y+hzQ@BDw~K0j3E>-9R6=*OgTTTKnDqe|-L9Sf<6R4?2flR~wGPVFx}W2pUeGF$NU$yF0258?bWU~B=sV4!0_&9!BvJU*PHw=I2*-r$IypMdqZP4{x;K7wgeJx51LrP@yf@RBd&bJb67+08mc92*^Fy^Hci z)DM`b`*bRK@6W{J_6=OW-Kh1vMe>z#!;X!OvA(|E^x9U7{xF$LwtUYi(e`uXl-*~k z2ooWyBOu;h_4b z{Wvja?pgn})q1c_=;{Qjy*OpvXAul$|wDeXWUI!tTHei)%dD=6DZ&XB^e>uv=( zhpSt4@Cxc(ul>-VUD7JnEmm<&4C*>l>5`R^bB$UNQ0tcSy5N|_!pH)zr@r5KspFc+ zt-vgF?(Exr)J@c44JU>QFWlN%QjZzZWW7wEcW;=9fw2+OMlyKPL47(N^%b zpHNmrPT+m$oU&a&R;RT3xO7HiCOXY>wsueB7;`&WIl(z=7s}4f9OM3S_Y*?AB$KCT z|G!`TbWc!rDML7H16d6l%1#U&<8EmUJ-+w*?+M@89&4*cPoI8@w>}U*22(yY4lWTz zV?$)qoq-I%#K;7z8?D>gsL%clJ~T8$rW53;y}h3xtCcJ4qo6t<5rHDQZ*OFmZro$C zlBpwr?lTx29wxQ9*%I7{YIL`UI93Yf zw&~oG0cGxdogmD498WDSa`Tq=J&{>%w!wJ8qh2MGXD}F~SRCwfB;85`q^VXrpw|rm zmeu6sBr7Ye;r*i)YrwYC?CdNLA2$Dfjz*(|LZLnT)Tw-DJwyzmAh*1#s6-8_{g8J4 z{CP{o&enIL6O>f}3S~6Ng|v^fzv@@}dGd*i`2Bv~_~DyM!c_eDe>=@~{$Udsp15Q+ zAgB|H&IK=Uw|JwG)&!z8IBYr6#f@3AGxys<**fqYt*s^N1&Rj=WslT<$qe-WufG3< z|D*DM0?p1=Xa=r{a9nsT*H$z7+`ttCU{Xyg;K`9b+;Rfh$Cn@RA20m5(C0)!VXyGd z3)F5cY<0ZG=4a;sSXoU9w(MRY@O4Z~g73KFs z-9lMw+his^%_Hjp%prfU=Q11O=e1sAQn*VN}YJ5 zRC=>zK29k6X8sNCmOt=x%kGEz0cQKTR;?RvzgM&U+FH*GgiwwDPAt)Q$b zmw3I*mU4pDA=i7+4qw38+LyhP4|Om#bOL07QUHIkx4!tGtCvYRL(v$~$lmp6J2{sM zg*=<+S^qEIOGoKH7^tQ)zZn(Vp%?svc2Q~4^O zS~u*fpLwd-r^BR$g#`fa+&O&fK+8(B{j^GVaJQ-$^@DWo9^|K$Rnt!OwQ(LuJYg{{U!jk;RFUf2tKrTYaBm@DJRZIwq)`UpW`6>8_)cSG4$1F&`7 zx_pbjPJErSYYU`GYiw6HsaBwJ!jCrJJcwWK_xALEE+|`f%uc=c9CHsY2o03C8c_Fw zvZ90U2f+>7PW^_m2Tk+7Q;ZrD(w}oe*(Ki{-rxEWOO^KD%})5%$%&STCD=|2hFGkn zy%4(40Ft*0w|HD>cBF)YAqvI4gN;+ZsXdUhlXI(`oNK?PD!bnsqa&jo*OjX)91N2$ z=3Bl$>KkqBYrW3y*S0Io6PCtD##r0f9Zm zP>ggYO(vHi(`F5`$?-{6*2F?Q&dtto|KWWq<@V4inMks=E#|A%E z)8zB5uL-B(u^2lw&{ZrJ*ht;O?+0J4nV1%o%Mgi-6N@*89Cf?94wBBEJ4Jxci7r^Kk94#+TPij<|XlwYIAY-^KRg~-x@Ta ztE(L-bHkdrFNXhK^SUEmkfzmu_DFJ=`PsQ9C>t9Z;{JH^0IL^leK__&Nr+uheb|BG zVbwti2kUgnUi;j&13fuFRzIu#Gys2XeRI!yoq(=0%y?bBgd6Xdye4CNzQafl=QGsfyU(_nz|i zS@rU#SEd`+uZSM$54k?`UGxCx0Gb_saoji0&ZXV&zNYi*l4gQl2BQT20{DvHFM{u3 zh}b*FdfKo3a>|N^)09ysD4YtV2>C+*%udbl@UaaQ>){l=6d#JSlM!=?jEs!1(dQ70 zb@6ItfbTep2Mtas7f^?)>cn1 zoaTc&A2gnCY&^hkg60EFgT+&4_|ZG>Gd6aDvQ}Z#KT5Jgf9X7jxAM1GE_=KCMiL`z zY>Qo!vT0|I&2arj`|sJrM1rq9{F+dn3&{oUY;|@6U6{PUjg`Ikr&`*vM(bv6{nk~- zYj5{^w&0Ntl2m{~6)wSU;bTAa!V533w6wHu;Y1Ic_7hgQ%lgG%{6+raFZ#QLgJ?Zf z07aR!Dz38+i_V`vF9c-=t%K129yw)QQn5y=3iu~ePni(SD&YBHgODO>w@-uI-$5U1 z73GWOY5tnYOn8>%{4SJf1%9W`O!Kg6r|SfH4+7Nl0w`{1(l21*6~gp<^a-{nws}4G z25>N3t%C%(GHbcYz{f#@%8#1*y^d_Z*6np(?+M~;cZ%g#lN%&m3O`A;Q00d8&YrYq zQ)k$zbRN_d0d-DC{aSkcK)_p-I%r@+uUl3Q`Iy~ka)i`Yi?-I~FBNx){Pgw)ne+;N zKj=Cn;=^ogZc-}2-0|}aCx^Rsif40KGTG*9$_sv0+c>Tk=4+vzmIf2*sgoP57mW>% z5%33l%HyD2d$z*V0atI3vFiA*ZmljA;SjsYb1T}}xi#0!5#;~?AOJ~3K~!(dv$M0) zF>Q1xN;cD5h{a@f@Ap>Qa%*4TiCBWM$uVx-yhSQ109E_6oY`WycJGpJKW5<9?Q1Se zJ?v)d$pfWoft^YU=)BxPzjdvAt#5f$Kise%HGp`~q{8K@qF-z0a&<%5qkgrugrICMUtq1EtPH3W4e=|ZLBp#f^`=3u zMSP@>j@r3=oetiaS}11`C+}(P6oIwf!AURBS_d04PKj1&-R`nc-w4-7o55;3(E9V* zX8`z5*4KsVaiqhiS!PMDi@~&M-xQB3VgpF69CdDYrj$#sLs~DFrm=Q0 zc%J{YwTD<%mOua|CT3V&U8Y)vY84WRd4j=E*JY+NX|~e65tmborvSKltM%j@nE`wi zl7SLV`H%Y>PFc4^U9PEUN;pjCXmpfRwsYSRi^fQ2J5NyYN*l?H06qY={LOVbF*(oO z6}#^(1$Nte(VwU2&o!RUWp6BUPPxIy1zbsS*QAb_7beH{?xe~tuz;CC1n+uZ{*j%^U)UaBUY6V=MIsOc9ef6!b@@%CeNOCYGdR}Di zsa3#hnGm4|5uT`mvL6+-YNskDKYaY-ALo1D`<_tRK|5lPq)z+clsyP8*M2yvl{;l; z7H07W#6vpuRF(qxCIkOu9H}ZCu}9iJserue7l6R7OLf3i0RJX&&txjvSLjN4CB2c!IOHd>vs9Q4d&*>8M3ddSkzu=!6 z{JGc7?1$=k_7ebh4x6Y}DxFTfK*LyUh;({y=tq^|2%XSK1ys9q=@L6TJ3=>$@pzo2 z`OffmBs{`KUhMjrj8C$%)7*!p7P5T7Ld~@;oP}Px2S<_BV82JK1gKZvk*M_nn^e^8&JmS*@U~3aRK*WfTsF zh1Z9zOVlargs`pNcfWTSoU)6tMdl~w`R1+m_iWudTxB$9c%Wh}KUMoQ=wo%Hy^?_! zy|y(kC_8A-EK|OyWPs+NuL%|Ve^51O_$R7CJ7=AF9+vRM2SE)et7`UvD3txE!pGC6 z&+L1dPH5CkS{dh_Xr5D3Q=Vx>2cJhrM@b2~X=Z0;cqkB#OO=L`Nj6=x{6|JdTBQDH zDUlR|PxUsq?ctUf9T_22b6m7?*>9va2m}I@9B^u4e4JH}FO6t4N;bPY;8t%x&T}SO z?^Y673#_j2r4WzO{hR5Xyp!x${?ivOvGnjh8(VVjn0^AlL4+;b@Ab|GvyZ)(*)O2z z1Z5$Ah(fs_lxH%WWGgS`P%E7-5%?fL@_MpSrWb^Z`C_C6!utYD1*dpie7pw=dPx)> zwSs?M;O`ru?aOt>P@ZAUoVn5f1>42GRX>J>-5R& zlZv+1uKd7#2;R2C7lZAR&7A=AM02`U`>UI~P&S&af!Qp~|KL+3Uh8d5SrMn~Vbxpy zx45o}wFwzVolM$Z98pfq7z>TZouF$c$w1jbsvT@m1x-~$*%u=(^6|NkH{453K;#8$ zy&QdBP*xQ@uebGGC~I&vx7S@gKXHtu)dxa(e%OF4>@So(OsWH1Q7GHCZIF^uHX8s@oe8g<&h4iRDfogw4zXJ&@RD)(9RFL zQ??%=g`JWGYJ;3qp~Cqsql3_X54*Z)zt2AVEN{H=M$7jH9Zp|GyXbbJg7$?kd_kF0 zHX4mm)~gtP!}I-aL53*6kb#GtTxs1%2DA*?z0|9`_O;dVcfM{`s>Ft3q%+=w-|qKB z^6VyUKO~ZGt9|u?Kck}~q*7w_jKyN4)13iAD>s;zrl+QOBiX;eQt>YK(|Y<9Rw7Gf1+u>Ir&W`@MOQ?-><*%>nwh?wierGZ}CUZ z{?Wdbz2Evxev@~2hi~(3Wo5{KIvI(!3mN#QD(#UDpR{f8Z9~zorVd@)7M861D(rd0KIrVI2XJvJLymd47+k$o_ zvrq#_3mXsh(mZmB2G6)+mYR}^iVR4H!*%Mqb|TcMt`IK8U%oo4UA3c5fb>=aiwO+x z_0d3^!Mf}8g;%|LaWbjL&lV`*<8om`3%NVf3Tm7ydw&m;91G^8?p=y7w5a+~*Nl`B zUcU72jESgeD9;ujKGzT&8ThF1eR6blPPfGyD}!prlVI}K2O{;>j8Uw8M!=G8@tB1)<^8wP8aIdY=>{6lbg zuH?Gl1&f+7jgK3-X047?WDah8N*rdQ@$Z7pGnV*AE<5?%hhEI>7?U8gz#FVdrHqUY zbM*USq<`ac5Hxgg0OJ3mby}}eUXirR4?!u$~<&2%ZTibaE0fK4^y6L}tP0=5=fZTvR6=JBtCtLb(% zS;jZ6{M1sNDutv%Cu8cyect1)K1|D3@84T)4wdWxu@eXyc^#r#KAA5w#!Lj~_k}wPl1;SGD?u@!nN3{liq%g*5cJz`ZSi%X5D zt&d&PZ4HGs|M<}pkFeUst~AZR<2mj7b&DA}f&dC1zV>{akyCbOaLPq_|ImWof68O$ z@@3agQOuUi7UcA+aNQfS9cM4?ds1xm&KdE!gn99#{iJL7_SSdj8yHRo48A`1q%xSv zw-C%$AaVE*ol^QFlFG6iZHD=tQVY?I6J;z~VYmo%-Efc9WWkQV1iiUQWqc%(yV-?M z9Q#^YO4?pi`(j{n0OHa4so9R|H{hOS4D$nDHmL;^-PZ7jW8-4#vl&b{(BNDor)_5E}d5k-U{XwmGzonXs_ZaJtxmxJNP~P6N=5zNlc2u<=KNTwp zR6}EESMhpHz8Z;^Ks9u>pM=Ui-NA1cVP;%D+PN~cxw~&|JPZxqo9YDd4 zfw8rIC2kQMan>Ia!}AS@FxRMhO}>jgf3$iVA0L}-Zm~y?B*cXO<(NpWL4wwka(U?0MWQNU|Zp(3Dqj$u$=lk=<=R z%{O#38K7ha(fW*UwSHAvt&(&((~F#=_MXn2%dYDDtkYRU9atCnFvHd?F|U{Vli#Y= zG=hUPQ*1+1@cq(>$1_Aa=w;8 zB<-Sd=!b9#KIafp$KB@t>-vK;t}AslI4VlC{sz_e!ZQ0_=8*>Z2IV+DbE_(g#rTf9 zgYr@m`ekT7>@Uy95FAxu{Nkj4xpPX-c0MGog~KLTC9_qVo+0JAT%AJZ7cKZ&u2Rj; zY=U!YtwsJG+yT=;>ZmXfHjg%FuQ|V8qs5k&Gf|2Lvtrs3tz$OFE>YwIggwwp9?NpS z)EnI(p^~4xpQ^}9WC>l4A!MP#@vQiW&p6kcvf^I{C>2YvrwVXKn%&)D?v3*-f{cc~MW zm7su)f~mFQv!0!thj%7^7c8bv=xt|?^9~yw=57JS758xMWB?e>`!eJNWD+di2e~i& z^3_`FgLiy?!^|L_6@Ij4ELV=8Ph4YTW7l_0?TKKk{#9%&JNzWOqxZuHk4FqZAI)aG z^F^}K0iBW5XT0<`ILuug`=*s^c2Zu)%dK6hh(BCo&q^uC$(NeXwdR*sj!I3Oiq^zP z@9|YmRy$dsrQjy^saeTl>ak$iZQV-Q%6|hpc@ipR_T2^kv%aK=-2GjY=D_WMw8aI= zNfg$dlGT6k2rtmFbU4(!*Oxt@qt3maagR#EvG*W6oC@C^0^G7 z4A)~&FOu$8gUtlH*)(%rBpAuEKPx8ZP6+Zo)(h4A^1kQs*C(`I|8H*!uaHAP?WWwp zY&3+-09csY_pl0ILdZ_0ZWjMiFuXP)g)apeOODwHMm^CJdp#ItH0QA8@aVnYO#aaR z+ITa%&}4H!Ty$2plv>h*LAZjIhjJKAZ(@UOHW&ie*ft#g9@%x+{in7+7|H@+QM_k} z+Mkd%f%4RMnE2*qLnzGNFIAu@8YDxj6c^+2H!gmZq|$ueIWqMGZ<*l+AOE8R?Oja3QF*6O000} z_gM>S=J*i4;s=&b<{6CXjOa64Zzv$-m-c#JS%890ydT(m$o~QYMK_sf1^L$^P&p6_ z5{j+hwO3{PXi~)mYJ-3N?)osW8FZCtE>Gutb}Kl^p83+5kHzC;^t+Yv@p_fL))3g+*`vvQ=>bip0sG`rhuysoHL;JO2WSxXY4!*Vh z1W{P-)uv|T)tm`SyakqCEsxrXT=(VLJ-1*8Gv}Lr|5ECjJUMFnF1$7{|Lpc?*rj>I zVtn)qi9>k>TKM~}oWs01>J+ycu)NfR7CQHh0W-b*pkmiG)gutY?F{X0 zdx~cuHS^pP^NN=DC)^~~Hvh&-Cy6q?Mm-jv>qcNcqn@*y}X>BmB0jk)$wE2L2HmcK32LRSI0dJ5Fh z*Pdoy=fz#&`JW^6@SbzBHwN!80eaa6;_1JY@6Vidx*j?%{S`a=<(8nez`0QC9@x{m zDlgdCT5k0K<~rmzFpJeIJ`k{(Y~6fYzj;7KU4&Oxv#sMt8z*r30bWem{*!xphtwtD zk+{QK_!9+&Ja>)lI!95nv)WU44s+6yV~vXBm8pEZywdDD2%0yJ<6hT?dim#8i$y?N z@;`wkm!SrpiJ+rK#5HsJ#q#joLu>8>f7jy{hY!N<%}~Rd@|-T8AH2Z}a^6T18-Ds^ zNpw*f^?kMB4am{-QM5ht1a-aspwpgt#`hE{db)wa5bdhHKSk8xTdeflRN!woVQk>_ zxZ4C>Ap5^QQBzLWeW$Qt;yAkUieUIp)5yHvFk_~@d3*u zrF>7AUBJ-A+}f>|bj|1VnB^Co;~R6aE~cV^PWBT+2k(g_`ph9nXUuU*Ym%R!f-_d0O9a zdHgv`eJr-gDb=MlTBZGKNYwNqG?uYn8f^u$5a;{zu0>GaS;j***T`V6U9jfjUu&tO ztGYJ2*(?D6(f3a3vv{G@c*EXriK zV;1w%%7b5F;MX@!-wC?$`r@$Txe7;I3j-x~(;6l(@^_x^eehJ;x%zhyJ7={xR(h%O zy!r!6(oW@4tveeimH|VBGv~F7=w`lTc>3?%2u#X<>(b#J9wGOL0v`Ty{BfF{! zISyWf?DD$p1dR_ey$viLB9@k0gRz~YBn--{@9byJKk=0HF5kX01EpnB&F4J;4?#@K zq4*iVo$7QQ?>Y?Go8N6}f1>vV;1o51;POqO%+ZOGWw0oCR%_d*ThcllDfyg<{Ospds1t zLKk3D7`AYsqP28*%<|4!rLxb-s*|1$$xfSbslUv4#o^VJ*ZR5Dez|+@)BkFOe;>Xf z@q=%+=dSB&%1KG0r3+atwt*utm0MTZ?)kj?KIPu;l%66aO!|t+9~a*L%*Aux1KoZu zMK)i&KwNz8r@H%y92{tM$^Cr;y1RDlZ^jFFh<_TohVQ!fkovL9hTEw+tDSRQ5_^yF z5qf1}c2?+`*oaZJY`5aPp!iJ;)|I_3+Z9Z-sz z$pezD+pICDo7~IYr7PLD9Q_lnbSQ@tNRIJO?bIh+Z(ozz3)T&H3JP)(`8j44j)=qU z$oX&B1gQt9P2H04)ZUXDKEvLXrXy#H5wzhMLADiGv%*Q8Aw^83p>?jMcWh@CGOeuF<<$GkC*V=LJ{Oj0N=*^XM69P(xVBcfMnxxQ%hC>7*UR_Q0(#ZmkC>@ujoPEqnb%!qoar&D z0_hu^yRIz-gwN@WP;okLh!=|!)#h1URCC{0lNL6TkEANB8=}SsXhUFdAK`SMj($)R3fZQjlXgbS97IoA7SvTrvv4UB*2yf(`H@m{k4|~3g+pfdi=Udr zK{P)OzVZBICe2)_YaDRKcJg9~HS0ap7(3(hsjWM7q1e^!pP0dysd8Mbg3?))_}W}h zfM=*lD#J?bUdTiM(_#ov&uEYYHIg;l%gF`o8gHVunKYUd7roiPFeJq862wW_lxtTi zDeL`Mfss_oFD@pscSH4qx{g0rVbmDh89e@+rIOtWDh$M6<~GctK|=cZYZUq+{y#g! zWbxHL;sQU}+;Q$m0@G~>oY;6r9#_}eB=;uI~%?!f8DM@606Sb#IbR?vEj{4 zKmhP^%~lz$WYIx4e`wY~dXo`<^*PBKqKM9c|FBALoFNI2%h_atoiGo`7|e*ijXidQ z18kbPe^0CBmtgThrN;Hg5nJ-jHayO^mocwN;=1trVmL|eUM?2%?Jn3b1Eyy;XbL2m zI|*if_Y$|6C%sF(p;mhWRhfYhi1Z35DOEZB!=>Z0)`(1>AYg|6p%di_}Nd2jQW^wg2Uqk;9lC(htPg)6APW`)`Knj z!1c9`ao@*k6w;t~Kt}SbXVFXl5d#u-6|GS5uqV7>aWy8pfo=4Z@evT;-2z4m#m`dz(Olz@%ZtPSE}0M(^BXr6w)G_yX_ zTlqiCNO|4A{kT|ZxM~ZB`{!Io`i4I8AmAO0d9e*3C=Z*SqsBla2k2E!&3vVxPWZ|) z@X;4cJTq;sb>4EWb{U|gS~_sV8=6Mqi1W zH~q+H)Rp?Otx&}(=PM=Z^=4WT&dzkimkL9F=6-xFDR!cn_XD)p!lU!}M`Sy8I&oZ` zw%;PW{cl!$!l_;UV>B-8IyT6P*;103JpL)OsPp;J*kz8=k^l3tN0G+D8zyDrjN{U`(!aoK&0qHO%Hx%)S2KhX$ zp}S7{BrZXhych4b$1a)Si;$pSQ803QOeZi+gvj4GMOo zN^-`;wCP#@UoF5{)~k@tL8i1CF;V@P6P zj^9#aCZs&$OkSpyWJ>JdC1KM3_=!*1d(I&9%R69l8q&-u7G7>ysh&}EI~HSPC1}RY zG^3oQo0DHyCqr57O)OXROruC_k{TT%N%TGv|A{FE-jiMYz+3J5O@W6>&w{y1sc=s(B1^YNmkK}(;Wq{f_*Qn1413T^P2Gv1!AtU7Aa zY|8U2W{yg@BK4cFTJu)Sin1N+%fEW_qV^2pSv4Nb*!X0v;x>h8V)z_!>i=5Q@bSZx z595gpE{9j=H-o9>kHnOdhiivj4)P8y>NigkA=@0W|FU|Tt$rGsq?=_>lj&RmvtN4P zqiAXFnOG}mYAIK)OY90+S6hqkE~Tat@V&e$dnmz^@>0AykV$bwOEXuAY;K5uk{6ZM`nWl_dhy=(<2uU zxlWDY&jBhB>%ID50^UaQ)!QZ&tQ0Ot9S_e;S|)BfoQL zN~F7WXh!Ev=P1&het9zzw>cJKnMfu}@6Qz#d};Aa;`TNEK#lE_n22c$=$2g)H1Lmw zjd(c=ye^NAeY%ZqNUq3H57Ske_}8HH~xxt??Dho@U<_z}cN{Y>v z&5w1@gH)XqZB!a$w|8~9=zoT_LuNTS9kV<61lNxZl5AW{wsVrT<6mlBRMm!3B!Y=? zGF5s}lnWWq>_T9ISoSNJw>j%w)j_+FKD)@ysvj@VRJF8#s>vqLdt%tg$Vf|&K{urX zbI{z(OnS*hW>(s-bo_aI^Yg=`s`pmqX43F&9LB(~f~copqz^22TkR( z!fX>kmC!B?|JP+_K6azFUz@w@d)<|lxDrjj@bXFPmX4148)GeH8Z}jX4&?Bj%zZm_ zVzHNS-T2^UDSc}Xf%)m;;}m3;Drpy_|M!v!-W(%652U*O0JfbJu8`B4JHI~R>FW;t zM^49Rj18V`J{Yw}Iyw>ogVaKtC>U1*Pf>V(qc~8c$VYwqO#>;laFS-F?{+)fHKe-- z(ByqB7JqMhC!8d!Bt?inv09CgQ^t_|UbF*C#i#by=G0c1_C6bv)1@g=!|F-jr4eTd zM?w&oHUUhCARjQgZv}$saq2h7yp293z-EFcD*4L4^LC*+H+_{M9to3feKH%L>p7(R z{GsU@7}^qSeJ6t_RK!{v{|%b#)xOdKLWvMDIb0#n7Ho2*SV{Y8gRfXhc$pq07h1;t zeBJI;y~Qja^w2&%&Yn6FrDAHY@7ZWC8Z=C>E2~vF5Rh7;tc0*ZU?o}GX#o=}o#gt)X@@&?5i7M?sp5-B2VJM&Z;sNQdD!*Otk(rB65lfN|rSMWq< zQBZWo?d^SneUifi3Riv&J$UBD{l#h+GJgLlk<3^2@=28CNw*z}@AifUWt@75g$7EZ zDwH*3J%Dr)mpd>O7)r@t>_D=|CwYVsNuImU;%q7H6J!@w>Wp-aG9ZOkx_d8CbgStuuFbt4F!#l%nLcaa;Lo<-Di3^0i3-ji2jqkL>Sy5 z$y5sSRyjI(i_QYrwSAk#Aa#7QlC7-o5dGiG>pmtx$^S3$^8j(^fupDPqNc z5{l*@5RkqFe2m+#j);n$QNB6?5v+hH167k?1wo4i1D2F~A69NsV^6?vh9UX9%G@Xd zrp)H>p5me!9*#3tsLr*bA!=@rG6JOKnQZ+szHcz(&zwq2w3F@SGtcnJanUM66pk)N1` z!8SR;PpNY5K34NihR)b=LQOwdjZ99+o6=pO)j>e4u(2hR-lVMv^t2?{#K<#|*o(ag zPZfD;{Ji+MnI|r>dMUDc1WeIT)kK*8ePQsmnEz%KCDU+4s&>Mm_D@#(cGL3rU%E{5 z(Xy{8eVg|wgGrwP*ohiKhZfR2`!!{jzRKm-V2xmEz6@Ny4yly{vpz7{$`IE0@)EGp zov@v^IJepWbLJl7l%oW*#lP`1mu?w1*wl})z;D@lSzbc zEES3z1qNxylH-%DBzcn<_8KxH_`Sv1a3~S^vN9|g9i&0GG-PBm1Mx1Ugn&qoS<8B`L|d+sDYM-pv8pa8jKSNhS3hW43=--Q|EaOE*?^p_f*Y{{61 zShkmU_(+y%Vb76GJmLSViuA5j1}+cNCWMtI##=*R^138EnZpnm;n01fk%_|FF`KcR z->p!OCHL;tlqrLx*U(GXb|c$!zTs{c$13w63oT@4em-flv&AwpF5RK#<-oFEe5wHlq+H-xl6@g z8Ka?4ea$n$Lwb%oE;NbGb9eLqqjafG5@+pB{L8Y{M&ovSac@`Gk2ahxs?PA~B1c}D z?CFu`Ag;1G+}*iDXt#?PS}6vYQ76Y+YOb_6kpyp!P?ge8)!-WaQ~Sf*o)ml^0&9K3 zr7k81FL?`DbU2XetTs-{s;(*P$1jaNh?6%x$`z1*1r)j=?~v_f?7TG;V?a_u8JC4x zKpVG;pk5jR+YcC~bY^bx)R?*)4@*K>lF@ew+VG<-+c>RH8@u{r;-T5#F23j!kBG&;P zrJOBAQtbRR3N7UwTn;q%;VY3P@vqZa0zC0n&*5Y=Wng;#hbn2_(y&ol-vURbee#n& zk!9mH9GlAzA1Yt8p3(Wr;cECoYo5Ebkz+-ad7G<1CKzM zHl7yc%2rgeRw)WAfiOJ-C;0%Ijg$A?%Z=%B4MT?~R~eGgX;9gPMSTuyn~^0g_-~z5 z0u!TYs8u6Wh!;vt9;TLQuRaU+(q@;0!xCWy*$8Ty`?Bi=;?Wx+PHeR zF=aYNcKjZ}~l!$OWlPmqbUK3+j2ZqHK^=4S{J&vap2a z9j`?uZ^>m>ey8Lg*7x8gn)o68k$Rri9dHr03y!gIGhuJ)D#(~B={@zw8m%8eW)E!c@S+}l+6!?z;xNd~YrNTW$1E3B(926IeTH4stq3?kXpH38^%|zur7Vrinuw7Y7mA)>WPmU5PgB)zg z_~EQEi}RA379)~m7a$Mh$E5Y=u{y%TqGmWAwe^3R-n7uHd z6JV;y^b%>_yP49S{{FY0*Uynu=}*%2-6x^%sPCwh%Vq|?m*$_(nc&nR9$RKkdTK>g zWf>8_rHUDuVdTLimgkGS_X{vk}jBwrc zH7Ee-f{upT@99pAQk>A^qzpLx)X>yaB6Z4$pDy>2rXu+uuij>iGbuBDS=1g3a`O>BR#e<;qLUgrpPx1?=dZ-%U>g2v7@bT4ZIueMJ&$Mh(4&lh%1P4V zdbz6>csU_scQwYGxhA+R!WigY;KaiM`(3g_V|DjF2}aC8=Q8b1u9?XP9uJz>dwqdB zbBI}qM<_f2R<_CS(iT?NzTD=)cZv+2)huP0f!W)P4J9$4A67Byu-v2i`MN@ZMh?Rk z*Pn~g)Z*;I4%!Qb0tu3J^n^;Q_2w623+m!7@8;3a-Z2V<3|D?-G{%xQ4-tO(=%NLR zMEM__jB``=96wNeKYA^d-qhTPfhHYB(_3hGHOWp!2JJQeC$6UUJmknfhOYQPaZW%@ zBs5++G234M^SCeCS0DB0*GQwA6Z#}Wk1sFQDEh~z6GodSB?Jh-LYM~sLnd5gMx_f0 z4BI@Voh6h)&Jw(+^K<5)b1Q3W97(WJVKNPnwpwAuUB17 zN*|4E>fR5?kBpg-0Dc$H?NLh1l*y(BtFk*m&ueXc1JK-U`?Z*4=q!f`@;vqIxcy`w zZWqf1Sg5OuQbS|tTg&X{l39~_S-lB|Ntx%=QPve0<$j1dO8=rN+er2^8cz8HxN@{{ zwlA)E9v4SK}`_K70PSIn^t0m^s_fB!|z z*$N)W>SGP9l|+8RmKE+~I0*nqcBMutym)71_1JXF4?@MzYCF#5!?L;CM3~iSU2pw7 zMP{9tb$}s|hlfplu5^U`lkU#ao~-OJE0%;GZ%ydxe=odcs+^``nIbbds>~A*Y9qq0 z6_E$izjlM^?A;mEVg6W7m{6ixSSBmEIjp)VrpDfm*n znMWLxPQOlWXx_anop~xH$)=K71ru^Ac~G2mngZV>Dg$2{85z+^HTzNDR|P8rTpJ=w zTg~fkrFbeN2tJbl5@(kY;wdr=)s&(#aqqs^*f5CP{>2zxvR9?S@P%Ecdhjouu9%I1%sagjIQ))rAo<03q;w}WU z4w9iJxGVj=7FM@p@jSO2v@LNFDP5p=eFGGv_07(b*5?GCMVm-!X+g`gmX4%_CN(}wAC1;DdMEvJ~{=` z(jw82Mw@se!1PG_-}eCC38!UrB!MC}_Dt?-s#~150(d8BYUiTQ&fKPWY18&Bm6Y(P zAgKqYtg{tj_5c&JVf-L~5s!rzyu+Bu*lb@zup`eoP?MVMAZp}9 z=x!uV&a@~XWptzyO_xHGel&*HY+EbF#ueQDl<|sfSKGTXt*m-+ea=~Opl*)ZcyP1W ze5&z{nj~u!M^kIIpk;9MF?-1;k*20WS-O_B)-+f-)3u3E|GtnU^fNzy6cy@rK+#FP zrd+Rpat1+O9HHc+vb?YmwZCuwpP`{k^0@Ga#CKxlv$P|ay3|%dBEX~`?Jm*kn|Cgkm)C~L8gssq+5D+d-A1yXb_@f-ed{4uv* z?3le(MlWU?ot4#l&c?=O>+IY=KcBW`L7lo!v^{sZ5M_8KYAJA$BM|iIx5x)kdH_S8 zNL}V6|I6WApjR-#e)+EFuc^J2EsTQrq^+#5aDxMOCMorXo_HvM|fn zN{U*iX6ji%p(B&nnXzR2^I2qdWQX-{prHgnbTvja2NG{c9O@Smk(5!6a~&*Be)T=+yz#W6Q=NAKpUE`RFLZ-Mfi6N9W`=vo zj@=m2Dktknr1}?6Nv!znyh!)0kt|g`y(kF526yikFL}meFssn}_ZF3Izh<=wjP-s# z{-gFu*3!@*0*+ExbJ%w^<;nQk(TJ#_=kyD3u>7Ate{7K>+K1mtE6|}N?cx>}^S{sPP@5YVw5w`ug^yTEC@D26_Sl;R1>yOe#Np;@T#8wNnBM!V4dc*= zYX@Z*(|&jvxze*cL?Ph$%(?kL0o`n0h1R|J-8WltZEn9244eXkUkC-K-6kE?klk}m z(w%M9)4zqi|IFv*k90ZMrSqACK1E+V_Jm^GQk|giw;e1$U|!zWx(2A(`xMmWW6b0T z5R`I~Es`Ml&q!w^!^r93^OiUt%x5RlwM+vG|G# zeQqAFy!MCZ4b9Cz*CxT=`=2Ja8#30Bz+rF+5`9Ki*3GyQxd8?S2+V&%H2t;c-ryOa zrW9c4OJZOC2epy`1?Yar(A;oC z(}O07~siAc#huUAz zahjWcVEt{i82Bi_3;u`0hog{KFItvQ(%Im1Vr)n*KdK5*mP~$2;>_`uT;NA(AueyG z2ED~q9xX?Ms=E4<(t1o1XR>S0!%*OSySddp-Ym36@L1AO_t^gvBH@p^HPF?SeQy&D z1_S=k?ycWoVUl%#dQ@_(Bz1;bJRy3M%@`$M*k9(KmfO5=Pr6Yez3Z-o1eH%&m=10p z>Kx|SKW8s((Z)P8!VxTNDF4sNwENU5ihS=gThVWo&Rb5p4-|PPYV;x#2D{X$a3(&52D9}@Afs1hsI#P+ceSi6jI)=mlExaBwb(ehdAp2G@F4Kg(f8pkPFgFe2X>}F(S?d` z&B5vWFSrHu=syO=`!qgu>6Qr@8x%Nn3Qc{wpPDZ|0%*lLxHgJ=fSW7q!sV8I_p7No$ zjNK+~tl4XnJFD>+D#;{(sZ;Re_-hbbB<@I->`n~;0NmEzUYz^wZy;~CIW|=X(%!9= zH7cDn0VDOkG}6C1(liYxiFl!VX?SmRa^H-Ds)z(+(>53S2xNHevbaZsC?aQw1O&Vo2wK8g|Kf-MR z zuOslOzK>Xco!XnG{TXVh?j00F0f7B9lQc+_-t(UmCgj({Z}&2kx5E^ho;wOQUcpFj z1B1D_ZvmAVJ#{!*>^)lM$jgXAVlOXaUm<5r&9?Ol*S_O1M+khuYhz}T804}1GtFY-sPg5|R#|)uPEUQ-^gBCf`2Ne)Q<^9)SQE1*xFRYb^j2O)C8J3I$R_5LP6?xo|0V>AtjOv|N1l@Bga>aC|Bi>N_E|?aO(jRC?z`Cp6)eisKWqg zQvt(iu>a|Ko9r# z<4a4?aJc+(yAM9VqW~qOx2GrM*k|&{;AEkc+)K#)0PKiS4DvhlV!ob}*V8`z!<1<3 z?R^}vWCXxwo&gOhV3Ga(v{lt-xFns5pSOS-eEucef5%vz)eiHN48YFOklsbgEdEm#0S2!n8+Ie#BstbdT&BGe9&K-H`%gfl7f+d~iK-E#{+DbAkbN{- zNjNxcwGk|Y$W&MmVpMjvmf&vIYW!TD?}NHIUYUw)aFV8d8``%g24I{GpF}R9*T7oN z52Vp%?(UPCyfciI01ztPI?~Lp_aI8k&J=U2qnMb-NlDcvEEp)V)s-p7uo~qA5V45t zkwK^~>qL21YisCC<7QcdrKF_LOOBMd9 z2<*3vHNbb=6Zy4RZsGcM*9?cRCAO((U22bM5SkxTS$IHuZHcm@= zK)=<8S3#i)tNK$u854_{ogez|-`ypOEF+v|7^m<+bIDweLqQ$~z@@$S_c#?5 z%&La!FKqPQ$Wthfl+;B_zptV%r_jvj z_JsuG2#VA8^wX*qda5uL?*Dm;xgiRI!derHqe_(~kg1B|mpsLp)NLgtPrchIJUl$k zxwh+Uh&N=o87yW??)JeL@+o@Yw8VlE0l}NnY5K7t8?apZzsnZ~QS7r*vV>J4LH!;l z9djA%x>sR*(Da$S&s!>P@JMEV+0DH-6-4|C{?tj>`u=X4g9K2?z1?NvpnEGSOpKw|0E5743Nh+)=Hzo&sHh~cn-x%H@-sW z=GvS0Sg%A;Kf*ZA1u0asmj4vnI_I1X<4_vR%+K30Pfbq7kQqNSbv`D=c{Ol<|F)#$ zibAFeNDrzh2ejXC4p)5Qq4+iJdHRL+=vBxw_^|w6@6=xFdO8B?^;2_rkRE!@r=Jy~ z`@AYZY0euSU~zLx%?FZz{FpyRdV0X03(9e2t16GI4gVi#xAJ;a zBo`lG5i>J0ietu4#?n+5wW1QBs%nVw_@5RUOt5#V4MSmjdwWik#VxPBQ!#)=g03xx zj7=9ZzhU<#z6Fm=v-pCacNCD!LB>(EpfWa%uUfvOyhAjXM44+a(|Ulda}|S+Ff9$DVo(vY5 z?#Udj20$AP&Cu1M?owwkg0se?J4PXO^zU-34?%nc0nW%rf<_*md%KrGBHfQ5mi{7J zBO<@sunLst5Rn!9pX=wCsZteOh76{D4k-cB!UIdC?B5s@nf?&Og<%HOiKNis1Ddtg<41n{VRvLP?inEVYdQM}m z6YC(c&GR>Qe04D{XyswNrJbPXX^M_`i;oLoy~me7qgVt{-+(K$cckHd9X-4-1RH>} z&uMk6tmuGJ1*IV|I^9DT05Ek0JrIf{4bBe(bas{*+T-rpQwE~bomA4O*&C53dz>*r zKp#=S-P37Rnn9+SF>Sy^5Apm2YbQ%FQ7Jb8n0Bp45e61u`w(w=i+UtRDBAr4fPK*& zWj6L_5DhqhnBEeM5E#uCjF^~E>+>yY=6`Eu9R8sLg+B1}c~9_J-;^lU^tZ!ujnZ#M!^%CCwO!zo zppyW*=DrFCA%UR^2jYzw9p3mujNcCmHcBS?ZRqV3jI7H@Cic2My>0REcJzF#rpQTu z6XBAQ(o-l02#e2oxu<%v<5Vk1uy5tKUs_T}2OSN%1x%gN0YZ>MQ(^j1(`MN=*!?17gOIb@0vn$a z6D<(n!EX+dunXqOg?O`Pbb38h;tNo8_!gc%J{V}VhY?R?gCLRJf;mQZ{m!J z|E72o8=aByc6xf+)YdjKW@piEyqc*JdNU7z)BK_i)viZXW1Q86R zm6l#Wk?v5I?(PO@q*Fjeq`O;|r8^d+5k+AE>7@h&sinK)4DbJ(^T7{Zav?mk&&>V1 zYuMChDpK>1@Ml{n?M?=!*!ZmtJ^MQA zY}Dk&wB?XrJZx`0`$|C{zol!GS@pR#{#C({Cwm;)z;^v4?o_G4tnqDLi$5nB*$M_m zNJuxU=VZ-S66sf%hRw1i+ot~hBH%(Evaa(IHGPMtwE)svZI0{{;cs~*B_-#7sVB*4 z78XSIsc*aGFTKM5*VXl!gp7>7p*HH{$LEgD73KkAA5Yhb@b7;Bea7De+BDteE#t!=gFM@_%bJhh%fFWH4PS15w^!pO$?z)W;TN!~khz#t6U zj=3m-Vaumf44kz<dd=83ML5u9micU?3f-aXJQhcOzP>C2oPA zE9{U-a$%HnT~UqK)K#bEDl0RnI(-7%rtwkoG&fJnuJyJO|832`)X)KSUlb1=unB>h z5f&o{3tP(s%Ebhkd{+OCDiCs7yS0aX1;t__=MnxmGsk{Ym#VGnUW35&1pI5H* z@fJ!EG^^lrjem*b9rV$?~o2(N0$a?#tmap@h7g!_}7k0wHzj4_L+Ez}*$;iPG_1B2^r%>N8T?ZUo4NC(S z%t^THI%35cT;(^&P7%#~zi6oPDRjoPjsJc!0ldz=gNn2)CMrAAa{hF-Dc{(Tm0C?u zQaX_ZM%}G-QiU52ZM20+9rm*1;Bh40@AQb<5bm9kz!|0|jN97U`mA0H1G*;*gx{*Q zmVTxlE9tnZs*3X)=933^6Jeszw})QzzACRg)CAdlzDyL_8g}17IV`)9R6CbS&nOH# z)vo)gs>T+UgR}Cd3}#B|{hC@0jH*V`_@7;C|HW$Pt+>9v#&&xN zv2Tt)X8&Ru+N19 z9x4$oZ{4PY@{I@`+E`yt`1NB;q>=bhT=DSGSQ50S)ST1Xl`sSBxc#;1*s)jR{z2HMux!IviTXgVr2&(A;pZAmTDuTVF>$y(pV_leeF`6$ZD?5;=MCI`1ho ze@b&Tp$n5OLzHlfwQw!h0xO?h)$28sgq>9-DBLSBa@+I}hANF-+57h^WTKiYc#XBp zNT@g-9n5dP_M8oHQZ9=>!r^jxU~I}PoFxtzVl@=7HaP#c=fg|wLa%Ct#k+w!3>7H5 z8aRab9~EYFLEelN_DDS>*_hYkD1@*dArRW{5s25=!Ho-U+OQ?eJv&f*S6Z5Ivr}>G zHvVD!dsi10>fa3F5~ZvA(3<@zo@7OjKHdi9Mp)I)8Y1IwSIZYJg4E57VMJOn5lWRE zoW{*oPx#oagIS-?#x(HITQdFW7|fwCsMt{W=;h&|#e7%azFPjP??K_he1LfF<&DRL z6;kWB#<_V8KcJ3YzI+)c8O5IO%%ld@hip~3QQhes?x%?j6>{Sl#cduhiTbeh9fw6F zOVZRd*Zk1C+065L|FNI_l{yWb`b@!Ygpi$ymc~b%yFz%tYV;DTAhArQ&(F{@YT3e)DwQgQ% z;6ps&(4o(-c~VS2k+G_%YB;WY!!VJD@P2%@`~-GFb(m^UxCx0BJF7=FU^@zDG^FaU z!{$h8kOr@6BUOwGOtjYHYZBZua9{)!d%_VFN&n)HF0KHZ&>3={JPim-yQKAgHMmEG%vPq*+BiC@4~dN8jJvZ}ApIki%r(f5Xm8nCIsGLA zrY(t3+0Xt>B`iFc?2v{K8??Lw7rdkEVZ&U%%tJ^x8iMiU+$DKsl5Ijij57vj;iFJX`y5N zjCu?fz8Yu(0)l`2PaCG|%Fh+G=|7WdREUs;G2)l>{8HMM_od@ThL;8nWAcH2CA4N2 zJ|ODOvhYw{x3R_XWtc9yVztSKFQ&7`ReZbC=satY0OB@&mI*ehJsFSEk=M1a*Cl{O z_WRCB-_aHKt09f79Qfqe4)hL`6kM$c)A3l+DtvZ+n7StYq348N7{)++?vTkdi<^i6` zO*i1w)TZIrFXaMMuvXc?e;PyzkfVG`Rz)HZGNlfF)`w*j-rIl7ofC_Kn4a0n^eDvt zlo13QUqnR2QbR>4r$eDctl06B6xt|A1Yi32v1zGOxzf|;)G?Hll!=;@4)Jvwha7Y{ zNq^(DiQ^1BtuX)o9!qkjJl_97u}}_YuBv#0aKFs<6jktbM^N0wH_t&6ND-WvUleQIhqWEyGmO$zzxqXT*`3aZ13AL5*ZP<1% z@nOaf6CZj(;del=aan;w7)YV1p%WmL&S;Cdhjx)Z=^!>cvSJZ-i@=3F#E{NRFK5DH z>_}D0nIoYdepS%{oMQ{uD$S1rV7k1%7TsUJ6t`G~Tq~$Zl(f%WU7Vzk@b4Rytr0tk zngvYgz}?G$iR<$6ox+u7{0YfWi_Y+G)8QC^cgiJ7HaVpuY;(Q`-I@^j=07O?w74HD zw)dp@*gMZ5h`ej>WeQBu=#iJnE>sA@P&77NM_GFKvz)M|%tOi)C2r%hk&ekWMIIXONyc-_Ch zM$w(ouW&(o5BpY709Ff(pM*$*C64#Np!`wpHh2YaX^RKo57i32IoTi|X0^Ws7^5c@ z7#5Qe#yK9yHyf!z*Q-HyC3%>AkgH+L!g@Qo$U(Vy<(G;7TLgC|X;$sHs2-1cSZ{~p z=l`C+kak?mxF2MCkd>NXL>2Ula=fSrkWdGsyZ_?^d2~h`!4uDt`WDvdWj>XE7qEY zZVieF?gp_@1y3Z(dkz;qKH6K5RO>mO@eO5Kvro(oj7*C(Ex;qc* z?HpL^^lQT%8Y>s3*NzDsB?ZZT4iNsE&f@qImX$Ca#rfQVi8r+8ot%JQ3Sxyr^=3eM zGv2Vg+9GRj`v6{lX>c$L+_kO%3StMp`qL3a>*VAF<^%yoJg_Dr*(#OIb;%HqyQ&LVBQwzjLA zG{N`x6>^{ULS*SsSmKeOqaZL>Un|I=0QF3KM7bPR)PE1(g=Je_|Jk%^qFtDhtfKUF zxTvjy=jrSE+#FI^0GrHCuYDWImdz4oxBtRX8`u_w5~FB}f2uMoQWdb5eNsXewm>of zZl|}Ur1a)74OcKPDn*GUK@}$n z&eZyK-eNCb(n%bE*{hJ%8cgr?SE*LXP{C^BdA+ku{mm-q@45B>5eTA2XNkk11-VfV z!X>}a!&n2!z8dOE*Mu$GI0Y zAuht%CFHLypun^Ir-SzA;o%ccT@jkVj@(E|n|N?jh=q<9Fdyrb2wF}vQj<7o$2PWK1N3dX*J$?c9o5O}^GBb7F!W}>uCg*FeQZ2oytG9R?PY22NV4I2;8E*0 zAuPld&O@7J-dySU0cC{C_}lx)3{)*Q?n=36#>@5X6-1oI9 zu%)k1^bjR2{RMB-L+j)QjdK%0s+3V`_B`vGF;7h(jVN1a7VOi~23^)zJJllZVqxB@ zXJNnoH4Epzd*nCBNh-%!p0J6d!7>9;TVV_S)e@jqadltyic zIH!2X^hz>0eD=D@_kN4)Sd~jCZ2mZ+-7rXBos+&`Jdh)hjiu?9r43*#4`R!u3sL2c z{qxy2H%+@4H9H#(%mRRb!J{Qs6+0pU_P|`P`PQA!y6vDNxIjcSbdb0sRh|%w*8a~l^*u+-U(KL7 z8~GeyBtUlfTx>ORadCZ{We%zMO?vURpi&IT8>dr)fii_1ep`hHpo)vVR>^>RUs=#>~R{6Q17cL4d<5si=9M3=!@E|9@Tp`um+^)!u_9fWs8*%PKA_ z|Gq!MjY6T8Xl>GY&;Y~oam<>&29~}`qo#yI0YujDe6qy-`}ct|{|kwXKo9o!D~;Gh z9z5%x&z9k6k0|JtCLtkRxE>+ua<99`$&uFJyE7*?FesJx81!AI&%YAhiN%p=F3j0j z-`J?Bum5EBG7MOGKArtu6J}v%b^%w=Y|gfj7Zeoi`iKIXwW1rd9QOR_>DMNrE{e-_XB2AKWEQr3m(~s{cM2ezx~^z1M)D)!pZ9> zvfRbRCC)hk-s4J>HsrfDkQT|#&IaG_^R3Q;Z1LI3~I~&_gQXe{%p&L z{IgP&8;Ilp8+Mb1HPE0JL3v4`Q|%-lneoQjTIWEfKu8tZSF+~%w@!8Cjn8&=>1MK= zDP~BedO5n{i4B-gjreLS?k20ob+O1}=6EuJt!@l*xukO{1bN3s?`Zu$?=yXT*e+Mz z?|bR%?)ahK_eD?+QYCjr=JgLpc1~=VHTYwls%y`+SSa*nmeILj{18`I8V3JKWK0+` zc{I~cz1DX~5`ML8r>n?v1Pi%!(Vn5lFT>RWsetcsc6RpmsuyWf{HZJ@SHA=c_fUdNXnRK>LXQ@2rc>|Jp7mCDM89va-1MYP2piln>6L62@ z60#l(!%kG25}KG}|GX9k_8#?0n5Txv&6#V8keaAN)kL4?DLtuS1;{Ag9yuJ<`&T5j zE8kayj+mR%_{umO0&vSD)y>3o-NrPR7FUw3L)HvFlKg!tk&X?FIpg>8o=A`oKkRD} z54`+Jh3>%u(m^p(Pq5NVQ2cRfk#T{Fg6AQitcdSTfww4;MKu9VOvK0RW9>V=G(4|$ zUUds_Tg9j1<&BG`iwj^KI=vAliE3+{$ye4}xiICjXKjjY4%C#?-&b=3V!Gs>8I&2S z*P3)G_cS!rGmlNzWyIlhO81~H))6yu@p0huuqt*i$;)G```cZ?qPJMwk4?CwlILPX zk@MN(dp$veC_X%bF$W^+HgzU0Sw2-ceq()8F#i!n;5{;SQYv#PeByPrNDcCW$Zz zxY{f+%ZRspj32Bt+k3U{Lu1&>#@?)qs{e&?aX@Ze=DQ4Sw8I|e(|~j~vyg5TEns%H z_S*+RP}h>q!_BKr=4Ai^HUN9iKg>(hqgQU zCtVJd$tM=a?FAhhQ#Y?snai%%5dcnGL-3&o@4NKWIM_FR&wl z#6)g_u^oe|pd1fpm_RJaFs|rvuBRsR^tC=>7#|yJZDT{~?ORUZ*4E*5nUx;yw`fdqWGG1$XLVmG1j)WlEc{| zzyg&s8=Rk?FCjYibB@dq`KO2IQN6&p9I#F!NsqPWI=E*u)B}u}l0w=0UX_W)nc=`sRu3)~z%XD>4??<7W{c=f z%Nrj@K6chkPSwm29_^XCrAI|_H;ONSU+r%FZqJ*I3}9%zU>U}IPIAsZJ=ilXF*qGg zPbcXS_gke?<$;@Jh;8PJ^WD&?G_6Fq!A|E|8{Cp|V6O4dTkIlNOOroQXpskp{hZwR zBnFnkUdACEz(WHta0EpKiRDKY2?>W55}}*u&Vx#6)V;hB(=vy4EZ*iqrj!3~@UCLd zzLuT|V(%2LgwC_PPy`Pk?sR&8VrMQZA z>+L)Pmce`v@Q{*nK`JZ>=$cTHE6sig315bf*^zLlE`Q>2uEmwh$+j_&);={Le!dl? z`U!+PDivJK7U25Fs0M1*4~rUjh5!-kI`RJdq5(hCw!BuYUvc(Xb?eh_uTXCnKo5m- zX|yFNH;aQGiZ6zqaw!Op{Wf4#ZAtNKBaV`G#2DbIKP!p>VztjVq z%^F*+AQlDueOO>>xkZ$Tun>6Iv-tQLnC6b!WKbDH2Rj>^%R(2<8((}wW%b3^9>UMq zH#^qW?#J8Z`kt?XeW$#@!N5Iqen-`%oznQe>eATUc3VFn-g#d)dpeAUFx_%?lW`%V78F>);G%hg85wFA&bGG%z~ z{PaT~TyXha35#Ft-f^tp;F120wK<$Gs$M8sTb@n~g>Hk}O7(?fHK9odrxJP$^8k3T z6zm68H?Rv!*VEK*sxk-gH4zmkFBkP5X0(I6YF<`newGmTsJMLml#;X!!#_+QU3z5{ z8RuL}4{D~{^UNOh_|2~l^OOw0L1OV$d=YIeA5y_1DXgbQie@)U4(3yMJF-T-eNTOB6)9VXQOB$8T=tcS%oz8^2@NUBB3O$Or{PM82p@$KMt0xo3jM!-FK#u?t3o=?~s&ArqBrCLPH{cCmB{`?bkD0d}4^#WP%M*2CbAjFs$h%(kPk;t;<7G*% zfc|4y^y_NsBLMxzc~E-fcVr71`Up7Ctxf#31O z=0(X`;#eUB!k%GEDBq*;aNX$HjZYkUtf?G?EHqn*@nvh)zLUd##gaY_@cD$e$(N1g zE_(4h=|IGI%BVIuU2lvczS{m*J+vz(HufJ_=@dZrref|q9HOA%6&NVK9DoGNv%bE*#P_)Gz_ZDy8D35z4Q%QzAmeY;{w^KeTwYrOj#%#a zL4}_E!`$$zsEjYqIXIGjmCf(Sf@cqTb>DV_Gx9lq*X`~RYA_b6dKhPy>5OdxME}tN zd-j5)1rCrZ8&NhbmucSk0jy=^m6gnbkr0%S=mu^Ce+g=yK0ra|^r?PTcoA(GinFAF z-B0zEagMYy(qO!j5PAXSL3faBjS_BY=B?#+>1ZZDu}EId1}d{G5u{9pKh@Z(?ZuJ% zuz!j@s1+hi2Ul#puO)0EDPR$n73=;&6mTACk*Bcmj{jp%Fi{h4Ae3{R^^2$K|DA9( zlQ8gG2X)cX`5I!yFxdXP&^K$|k(JK(cz|E7zQFA?9SAAYOLW&1z|lf zdK^7#!wiG8)u%dbJ_{k_yO#%p8*kpnt+eD`F0o8bPXl6woLk1LG|yWVdH#inTfX0* zsW7Fd3(!utC%j!_8Kd=l&`m($@!>QT4NXcftgw*zHc0vH7+4^`8YSzQ%w2DT(-c$) zIr39tfUvN-N?R$Tbpb6CD~d6poSW$BB(t^VIPvfW2_A3=KB1yY!kY#f$k|((Se9oW zZ{?7MKtzsdGn_*;1rudZJ7qOGAUEZ4bn^FGu)IG(1?aR%f^#J2-hFT6Kh>k}*q!#6 znu+E73t@SP4=}ZyQsF{e0r8>`@{LhZZu;xE%=d6AP4;!o5op#sd_h`mW`Dg8h_5XOO zDzMQOt#|9Ywm8myD7bsw?W)^H4ov8CTRk8T<&K+1#87M%>Kd*=2E=13+Lu zn%u+fwEX@2cpdt@yu7e5fd4Q?jrG&UMAg9`9i$p@?fa&fu=k|@05jLQdcZVWbxTYD ze=Xd92aWy~9Z$Koxz4)dbV}!<@HM`OB3(a)HM(2g~OYe)|@Ti;0mNcwWM^rCzQLxqPQpTi#QJt|M;xt7&Iz+c}&syBB+N z8k=&G%RU)?l2q~7=>|Fzr1J!!uc;Xfc((@+A7b`wRMCtLN~b1~USS*%`>a$GKa5)o zk)dgNh;N+llCx*D>fL@o?da^hh%0gWp~SJ01K*2230^k1D&^_PhvBqZN7gSlsr4=Y z);{yqBfLTeHvTVEVX#&^sADhsE%4XfBY$D^H~^ymu=FgmODB?^)_0G!B3v&A0Y&cr zHNBy|p$Iymy?K$XsE9@IVFoq*`ESJ+Yd4u%dkv78d4^8hQW+eeVImQqwy)bIz< zA4X86`BFrrFUfBl|DuYyt)-=fF!qWPYMCf5+R>m zI*?&s_UQLrdg0^9HkgwHJQ^e9 zwXY9zln!4NMadu|yzs-BrCED2WqTnhinlRR^=Xn5DCY2$4g3GKT0K7~rW)=cy;AN5 zEq-7*?!0Fl(MA`)1i2;(9UUDxxk=GA^N{QI^YyaRxs&!^jEciSrEb1Uc_Bu^?~2+{ z+`3P5E*BH!-Ntk5Kdnf~=icc|H8~}kySSNCJpaQn-Fs`&WW6dLRqE7V!R}PWw$g-h z;3PE{GFk)CHi4dAKU_fF|25ig)>+_sbMU%fE5|eIAOSE>$0s*qμ7V5&=2|H5mHf^A#q6V?hxOxwIn{kQm9ug^D>oZxqc z@826%OQd(H3oSK173gBtUsk=wjsbMIFbGGWwCvBEz2 zb*%N;6%1XGV8WuI;LV{z#T?3Yg9 zv5%5=rlXQbv#se21B9g`BO`;pjbMzw2HQD%ZJ#D@HbPlPh-SB5{#hA|toFT3Sf_8P zbYg{VBCaS-5dga|Wnhig{A*0G?y&fjSm$ssU#h&ed@x-h2r(@Nh9U4$xPm0_84sHw z)5x{@T9X0)<9oNA7`N{xAe&rw|Gv77Yz|7?h{jNhd^T?J$}1_sqlv`@jO>0aS=YkL z|FuMb6M&1C_YSf-bJz;`F~0z~ z3i2tV-n1w-BNG#qI9EX`Kn&YB^B5OjOh|E%SvqSb7&mu(+N*IrbGLgT=Czq78hZY& z{gaSp1_P%_YZx$*Qi9nU^ltpEy&-YH(#bY+I_QaK0QB%Fzz@qpfq?b}tH=Fp0?fX^ z0RevgmnXU50bPomZP=ZDuXUOW!Kn^Xups`N5%dZdSkpnQR8l#bfIssgXw6Vi0G?Lw zyw*Q4O-&-r4rR&7q*~fcF&ilxD;V20y>Fq$CX_z@VIc?TV#-L{&q*;?ZrZ!`Nr&D42h(?rk z29W2@(=>|sE=(G;iRV{=94}rJZV?kZ1=W#iwab)U6zQ>RP6pAao!0w$B#d7l{1yX0 zD#l9z0UP-iozrmEIll49ydl$gCoBukY>V7Zc172larw zggjDwI9~SnLum@#Mu|xTYuP0_TeO}|SRwOu5IAmK0F?qRv0j3%TMWNc zv%TkfDLzN#E^o5c&>xG#lWdbo`YRc~MAG;QtISKJSGGUleIUKxSOVqu-TL}{7#Q{-18CLe$iF`mpz zf&2#5BV3Fx4Gm<09kdKf{8*kk(ns;X~^a`0~YaY>pt<y1 zWV`r{vc3C9Io~-n^!SC*SGseJuaaC7kuf8MPb7S;9=+LtmOit?=7TtpHNipMlNgdO z`FcD~PM--+1Yly#14dFk7!40Km&36U+~LvPU@#KYUw*k4M*(qw{zQ#wSvtR9yrID# z08)}p6Tvc%_FTu{YN7+RH^8ZrDosd5WbGOS`&4#p(m3u8=2LKClhB7g%OHJg&@tqC zaqLvcA8j=b=ZG}f1~f6a71%C&bbcPhBbZ0QD8Wq#nHd@RxU%x*-R?KsrGVwUhY?5K z|8}l(`=qp5-QW?tV}$|}7=Sx3LIh~#9I_^7D)PYf%6V!P>vtC^R$ zYxa0Gf7O&TqAz?X;Y`oHNuj3xM`1^~6LQ}n{b)4pwn4Czq{thZ$U<_pXL6UwVu>{}t=RKN-}^C%y=ou3j60nC zEvf8$7q)el+(f0P&n*#WJ@#hVVDST6j#v%%!JNv6nXS9;sl81N{`v;JspW>S`{jc^ zRY^j1`V7&*jkhat?1LHW!tTr0n0qCW17D(SacEGk;E$X3M}ZOTNRJ~Q(X`xL0Z$9{ zDcZ6vPHkS=5arcZFQRz}1p&u`_2E4eoC61H!`PE_Fo8cMT1yU!V}337rKVdA$mx6X zqIgs#f*qtLc;)qTSlNNgNQqG8!(IodGCAD~CnRsS!W3!4soz;i&-V9C!+`G1+N@2n z>S#oVz9XJu#sI{jrM*3Jgx{M!FRh|F;WFQmcoKzJUbfcso#WR(^d1=Pg4W*o3H29_ zn|?UeYBc{(#gyYbNksa2f9t{K@CRF54(TKXaU_J`IWRI@UhmvY)WaG6pBEqysa^|; z=+N*CBPU14ALr-CB{Fx?Q;P?%kp_< zNWTS>-xy>uiryF=mY@}{9M3vf{`qh2MV#?9+Gcm*sn?m&FPS5gR{fi(5~?z(r#%&{ zg!x`Kmve)d7_{0{-97~q^*8fIhChb8W0&S7N(Cc=YP8{F0-SJ%hr%Zd5<-R?cA5k? zidG~}@mmJp?H3DOElJyttOfZ`M=3r#zA!>0v%D*0OsLOUP29s19|_FCaQzg4wuwbWU+ga_#`P{8%-LjyPEA9rt1eJM)Q1p8gwG0#k5jq2o3lfCCc62`z&%$TM5rHu=_l^2fxn-3--K0 z{?jy1CiPW4Iy%zR)9abQ9duk&hdkUrB*B~>mBeL{iNkV=#(MSP7$*6?v(d>pP_SEl6fQYEdTzAK z>y`1dByl?4ibgivy0^9%*G?nplxTiOz%yvb!C?zAVcCyZ(X)ITK`SZuC(Hl$(G&OI zT)zZpCK>e~ruFJbaxSnbx4ZUmh8~0-=F~=qPM-cCcU^JetJSI7y_&f*eW9zYE&Gat zg)+aajuZNo5H$dlKA9OS75kLs0#?6j9aTeQ0`|AH0?!xQ&Le^5c%h;vaGdWfBga8 zvFyx2*X&38i_+fJPMDS_vpL0Tfo{sV2qq3trnTCn9l5_q>U8~h{Z#V)uV9z68tGtJj{=Teu*B!rZFJ%(o8u|uwq+j9v4-1~j?VnztE0^)w` zjEMZt3eVLz*M5aBaX<5HVt}xx$EaIh%0}Dz zCdJF|7`Ul8{u}TYfE^P5JAUY=Nr1!q-J(5w13(avD+`@Bk;r58lEXNS8^AtEzs9q|TeSvxyD8 z;_a6?Vet0WT=ceoUa~*V_1rVJ%eHK!NQl0Zs`sDO&;y=n7WcUOW~qzbIvA(k!or}u zdCq@FtbsRJORlIce=ZTbx4yRaWBi`eRSzC`)X@9+3iEcL@W$J_vBBYQ-2KKLKrs7( zsmd}i(8PC>&Suf$y-I?TfR?7{XS_yMUQ&(d>4w7E$H5HlaB&;^vfgtETtN-1nP;}j zQ%Xx+b3I&fxR$U#-h@tmj^L!PegJGF4N|n>nC)$Lp8*l3Bn18Oei%QAX zP3xuE!2a^*lywUunhY6~YI}v#<(AwOFShJ+e!Km*B5rI(aztOpY6Qghqzl40>IYF|@R|fA01K#J+Xx3gaFR`FP}8kWnX=|INyszfZiN zf%J^YvxmL(0dET9CEW3kso|$@y*T}xyF#|ESs_9m_I5C-X7LJ-B^3Xrd1lNzRgxQ5 zPEX@8r-|xBJQnWgb;in%KYLUTIYuU!XQ3G?f`oQxjBLgXQy1%;e}6w+-d3}KNx`#U zp=JPYDp(2Wb}z(Z$+Fq6-c`y5`>AZkcLwP*pP)CImYq-k1g#MWKVs71{`RugFnZBT#!*{phFDef19((UcjluOVLO3$$8YF&6vTde*&$@5_Wnv_)tr8C~}=PMwg+N#9aSCy&S;r{mWvieT`xgofAJJNPL$}vfdY=ru6?nL2#Lt^smHD7d^ zV@T?9MprLjcpoM|vRd8#alTK1rgnu_CTu1$WW1sLJ#_Wp-=5(9!GY$;2VCjGo($fz zRF%Inb;)?t*HGLHC|W>EEkpX-U|9#W&*ZXWZrC(d%6_JI$)%VHhS z4rL32KTV{irE%s=iffrx%d1C&299)#+)8(E$a2-1?>73H>&_%&;ScXmu2Ug(ZE8d^ zLNDqFj&1}F%A9_A3bQ=9N;98e!C7$~K={%24Ss9izh}}!=_t{NS}ACCXD^3u>U^4a zFQkMx7;Db%>KT((&K`*~P{pp8P3W0gQ0EN3kTXaez;@JkC7HN`N+tL>oxtk+X2K_- z7M zoP4A*#v*?G1A92A*c+>(!96R&LfbS)YZXu8eZ|6Os!LjDrX`@AtC!knPxT?A#&>^@g-9KsATl>f`fFCl%BiA%*P538wSEp2aI#cIg1gIn3J|MGoWAnf_;*_L+Zz!ZWb5f( z5#h|?LxlJ)#HC~{`#N%nTTb6jcCea?LR&6cV)iRG#+p9sj~k9dQ_Jg)e$PCvpi#5A z#G5DAs~SJNO~b_x$Y_beFslY7XMa0tRrJ%ny;=~?;LG0Bp3fxh?lm3_zc`yt^KKrO z>iZWay{Y*%Mr<;?61QH?7Q-iSbpY!7*m5&gM@HQsEqLc-=(mnndg`_N_2qZ(dbO}1 z6IM00f{~;a;5@42EiO+lcq>+enG3#I@8B^Rp^7>v#z7rA<#AU?z8p?LwW5`Exr ze?r$mr@unBLjF=jAQGrplEd`T7Zk$>uT+Qnl)hd55oMNXvrhZY%$lscb1VK61f5E0 z1eH#z{7Rep8xaQknExZ|Pz>GW1uqwX&*w&zyG{}`hHoE!w7)%Pp0^cJTy38QOPtx5?tL zK@)TP`GhwZOQ0ob`Bs}SwWzhnoUpvWJ@c)}pX*QjK5r5fY~^0_wO;1m&>3ewbq<&| zKbgjkh!mK(LMqs3I9P#FK^Olaq3<$k8kU~cq~GtLJzofdJZbpN{5xFhsT^1NEbv?WgqU7M0UvQ@if-a}_96m?n>( z|63U12yeNDfaV?5@^VS-HOjCGg1!N@n}VL}Bp7D)_V^&)d@CbjVgOeO!3X1ksGyQPp=#y1Pq@ZA(@IE%M1h(8%&DPg5<)^u?Y|^k%s8EAoBz!| z?%ew)>#~fz$k|%l^E*63S8=wwv$SnSlLA@)XEOT&v^OO+)#BYB5f?0s+Pd%TgbN{? zn_4zk)IrBKK`RPK=b~_bkIuboH+T1%*3B(QA8Em_SEbez>ax5%-cZytR@bdB^5Vww&gf?h4QTigtLU3BP@?pB=2AE;Lq>?h{=aL)7mm~Zp@ zhda2t`4fTge?-*kMp{wmbgflohRn~z@*>=|=v{NGnV0#6&3A*PcvnT(v%u>wW!Q%v z4O^06)cYyXdh=4=ARC)9PO0DIs|zNuj<=t4C5FAKtY{XFDJ>Nydg=gD7ud2fn+MYO z48y1P_6Yy9mK=+N(i}(A8j#_Y=>_aT_PhMMut7Cz0NRaw$_G0fooeX$wAGE9?}xsk0G1n)4bM! z#+Z$-eI>^?d++r-bl3IO5ok;|XsQ$QxA^Kk=$~6wRrM-J!YNnSqnJ>@S=1w}mZ7X6 z57*OE`>P`Bug4?+G9pi@CJYQHx|iVIyV1x=+(*2BQ5ADvQtx6+qQ@me;E9ZHJs(?p z!L|OIL$)EE7+>fpzFn5jH50N0P{h~0>M75`!8m*HgKGIf``rg5#039`rn7*Gy8FI9 zih`n`A}A>>rGO$elyuiHbcr-WNlGh73PU#o0z-E{wI@V;%v!{6tUJ*_=)hU6nDZU$~ zkEZA7YH+{rrV8AbWxEKVYqeWYj|1-Jz;3x@3;T!KcXj+xJYAYg3!q^N&J1@ee$c`J z?p*zjF7=mBq-=u-2_H`21(EEF_x*T9<9?{~g5$+IW7j9#>gr@rGQBZXh0i@x?!aas z){_Qt>A6l4)AWzL^-Z!%ckK%s-94O>6SeF^^Vy~oJK|S`@?AGmDgZYnfwqnY#8UvT z&pQu@yP?`b_w~wQ%c)>hTpZAZI>zph?6~7P>D#c6_ z-4Ba8Yw|uTai!N}Rx|(PpSMJRl{zion|}S|$kUl>bdIxH2)6tS;1uGbX)5M|KBVNz zr9bpDn7Q5qR3fgV(H1jSk4GM(0VBH_g(?^3+@vG#&K7sg9}R|DVZU5eh~nXVJYi0G z765!3JC|W@8%l8vD&?s*VI}C0_nfzwDr++E5Dhd*stWQhUL5OWS8l#XZvSxr8l2@u zG;Edf$Y%J%dZ=Fa5i{kzTUWO_%lr8fI?h!kdQhlx184s7WCmfIkLNYVgCEW^z0?_D z@{wO>!tv|3>~D^4Og=k@oPGx1ZbL?1=`xsaEheB2{Qk=7d>6SWA#j%Jrm(aUD3x`m1lVIFxZw_hG5VqA@<+ zWO7m)tgiE{$8%`090^m($V)4-{6*TapU)wFVZNK%+$Dx{h+r3SGc$5)>jH-pNB(@( zksC>jtx1xh_6%gO`33I5)SuYWM!{zVhjIZusj_@Yvr*~kDkZFixRmL~^zkAGjmAWn zyQG<*;R1tXaw?k2H?(o7lS4j>x2T~hl82!NVZ9Pn62_6v!J1@WbQ?TXC>CGm1>Mc{ zw6wR!$7wp>?KL)nzH?}Lig82AErIXK9|pC1y>kr;UpQaod)(^OgjJ+($d{eq@n#qI zxQOwZa3OR_V|^}qv6=e;JO0vZ=A|j?Grn&_&T>feh)@k_K>iHyKk5Jn}s>Sf0kdpr1UFl_f zKbF`^C0S1Jitn`T#}euC)!V-9Jd2utDnNB`ecgRa7h+;vbaPXZ zlcCVYr{I5h+IoCjT1Ez_Mx!sy!($0ISSl;3?!gPE<_U4%yIVPNx|5)#o(X&4;QX8S ztgSj!;MstVJTKVqmb%PN$?%}GUZiD0q1~VHmp#Sla^bIyI$4b5!3gZ+MNJrw$0{)w zm6o!M5!TRiu@)8#*?ax@s$H6!ZT;sH+i#|jvdk|2%r~(6W6{IvGcJ+fZ3(LE7mHk37yK_OBtq$G&p$Ibr=K)-YyFjf$=6iMI%jwP9b0?*V=q4uEu62MJ z17p8?hq-_;EI0~m1!VM)7B%pGR{i!|*pta5A$jRRTshj{&$j#n*z>`FK2}_FQfd$q zZqH;k@+x_j*8Jk9y|6CP&CyRZP*uJt%OZ`ju@7(F45iy^Xnba1r8I}=|L@xJ`(6qG z*{RIN$VV{Ot_MP%hHGnbFe68^CU`ub18^J2nY zuOwSgAt=VzmRG~Xy>nKv`bKUKtSfTRt_sCUOoM&iBv03jJ*Gv1?YzD3o*hjr9d0?? z{QhSLvVSngRL#@cTFtWtLc?|FVbda)$0i?-=HMX<`Q$G*r;AIJr)pNpSU<$xDXXys zaRz_>WNx`hgvZ7yH^;L+JDFLQ^6>K~S)?tkzfTI2?X}O5w8QwB#uhop=JuRt3>aCR z%t?P7x+rmSlvn+48ne|arv2gk_>q47u1LPEfdLcHNdP%D>G@1+^Y6)lqEU~i_f*n^ zr6MD&TNJk=#7RO(NArkCPlo3#o_n(5gE{4{R#{DQI8p#R8TYhk`ST5i-NL%M#L;>A zJ_-jmf0K76-njOc`%2YcO}@mG7&Dn`&|6>+H-F4|9^v3L^Vv7#@bgA&OP67|M98Aj zzMBh=3=Al1A%kQ7sneNbvAt?qwK{q#uc1#Sy#jMp(mOo2n-e|;+Wm_W(UoF884zSnl6I917-FPh1nW7WnF0i1fCZ2^pXKh1@99iJ2P1|2=%8s}wNG-4_0-@|p8&XD&6Z zMi)<BM2{~Y#I`Km zvYXpkT#Cq={p^+Vr+C7Up_Y(gW0(y06MMcTBH9~x4|LKFDhDs|%q^OG4@V~wmhy9z z-#Iu8#l)^Wzw+7R^L>1coAU7Ru#wY*r`rwcbqaV2f)aT)s-ojmhR&>c+{i!D8|Hj7 z1dp^Co_6mZVmGWF}F50)?O23eQ?0DzU@oK^w(7ySc@<1zIzPt z9O-Ckei>G?7oTTG_iw$heZEoj+E85`u-rm!4X=_2NDE&TX1CRBk8s@VmnRX}Qg5(% zZ+NyC@;JrQS6NvZ{gG-(!9oOjBS;C!&=ub1nmoYu_egE|RhVZ^WCdDCy`hI9DYidW zN-BGS3*C*O@TL6m{m}{=(j#1Apf<{fm3Ho*Uh9Dl&eU;&?@9Ttn?`WMw=#x*dHE8s z-95bra68jES4ehW;C^L1SHbzw)#Ys<`twq8KesjI<)@eb83vu|kVqA|V8mHGKQXe# zaB})GiS05n9(Ucb1L}7j6_5y~ ze65$wwM`d(_(xLD*G(hz$J0%fB^!vzX`-toEx2GFJO@CCk{^0Ow+Us`Z zwm3p&tNTx(nik78L$W$fUy2AeWs|<0mChw~rE;LXS_qcTR|5}R?1P9Fe+wL`r=ODf zoSPiIAQVGxZ_>}eDt_OR+d2L>&3l*M-@z$41}*)8txlF2)8}L?xP7*j(CZ_+b#$#6 ztALMcWPJA*{&i4_wsHE(eHEXTUKMMw z8{|df%0%$~S?(Uc#i|exs(5QBZJ~n~_BM_tE*J-KarXT)9?&!ip%Xskx@%9eB&MRnT+WID0Dp(1oDNvChnE;`U>wRFM_b}Dqu7JED{ zV}MlzfeVL!=e~lbgG9a&^_N5g8nGi$?9tq5jO*y)o#043{EP-dPp|zfns$&R#l0Q) zGxGV>Yq{J36d*@~^`n|C%kBIWJS)z(pD#HIcEWX7hq7KEyF?4UAt7BJ^SKrA){q1?<@X!VQ znsw{^cdm*-{@400n6*52?M|`pNcnSBIOo`yM)ta|GD3z;2QP1!#uZ2b{Z$u?-Q8I` zI<3AWQ@Y!S<78|ANnr$qT15k-{XOi!8oT!5aYW}UZc%@~pFtL%RYcFMu5%k`ytHfO zN$*uY(sR^|OXOiNpf_vtE4cAVyf2x-qS?B8`Um3O5=2xmD$p3DGSx}-O-EHgxmLS> zw*{$h>`~m=BliFy%mRGNlfi#n;f1(VkII*;uVlGJF84d*Hrh@AZHR!N4)BR|d`G*T zS|{bBDvV7!|IW!wF__iMH9F%3CA1Ro-``-1;+u)miy%V5QKkgLnfHA6Wv&Q)PZF*q zPG1XUoRK?9?d2C~jJg;kdoAY$bU$+Mu2vZz*Nhy=Q0wM)LeiJo+!%+*DKkSd54qWC&HtO;er2XbastPvdqhuxsO5^MHep4D1qBQKqAQc@dSzK<~LhH zsH=%d+bhDVoo91s39Mg1U!vJ$X{tE^$aV1_MY}SXA+5Uu#kxvLiZUB2C=wQS<}33c zVhRfPfD$wA!0$Rne!FQ;AuJ;Ny*KV;xrq#Vq248&Ieqp8`M+MH4Oa3y*5AbcPYV!< zh-7^DIzOHU|D=vkL|aY=6AZ%yiy%Cw@g6u^NDjRsl8J5A$hEh$#KGA=%$deGo0sf3 z6_0KQ3j2obRD2EHxD;Y%r&Jd81cMM)*WsP*SXa%_F%4sLbB?N%xL;`EIVW!~q3U%H z)x3QS*%zK0|QbI&+Y6gmj;eTAM8c}mw>=${0HM| zdU}BvjE>O9GQ{uSkHCktBL+Clb`u)kC{M>0Qd1RZ)SXuC5LgrX3e&4B&(E`RLeI$MLZx+5%KoA=}Bmecs8w zr)T!YE-oB9>foCW4}V4tYHF=TreA@4x3*t3lw{9ZEM`gy3ajMrW@TMy>m>c^>0z|C4*hWDWBdTf@>PVxTQ6o>%WZ3Gc)w0h@1jIHJA-VlTEU;f!?RK8At6z* zgS@=)s)mMNLPCE3+V=N%vz-~6&|<2dnbiJyapsSzu_FM%cAcZ6ZSKuwW$$K6va^|{ zRIRNhW@l5$I?sJ^XSOFuLw<8nq>F?ja&#N`+jj$K%pXAex!;C;f z$}+4yKuYLv(&Rd4?`*;fL8#o-ZP0eA%gf7K5iMe**WZDlmL)r|ShGZMlxx2jI#4Zl zT2m&GB)G=e0wer&;2qF=v+hk0j`Pr23bF;BovEp*`=_Q-O}K6w!UjzrMs)rUJiokb z$|8*|DdC_JaJ=R2?haTb*D)yomhed_8aU_`Fehp=kmj}DzkOgZ@Lq<5$Stp}Wo2gG z!TC3?XMdYQ&~gTt(%w5bJiK zVi8uHzJ8{3R!uD}YO`s?x(kCTI3`3^!o$5@Dkr9=bgutn2@JB_jywGeq{49%qd;A( zzu|?egXIohwt1&DfQR#LuF6gA3>L+`m-fC04h*<8wgQJFaqzKnEw$Fca?OH1@3@+V zBZp5uD#{jwg6sMt8fS_@JHX~DJE-82ehmO-B>u6uDA6fSbfSTYF-ebUVMe&;pmX<6 zdjp*HNAd?HSEh6h(m}3RCpNRBaD2O=*>kVDpv5h>#&B@7X*H>|A0l$#5w>k1lf~ov zcU(1ENbNHL>u+gVhogKynUE&D*D~Wp%MnE4il+wZomzCLt!YU3$fP!swxY;1>G6r# zQR7LcA|lB*Jvmt!vyfkG&}trSyU-#ZhM4bMUj9h@!(66-{Fjcgu`=;zbEc6n5zuQ> zQ&WpPZarBOy~tHrw7)v^3|T-<7ngFHxVzJbz-B6QsgC}7M~c@JmkeZ-ms3bcxRo_P zf_8R(lf1Y4cwDjt0w}Q67qcZ-@QD&eZ(bp>Gsz(kCqY5+0mVoq<$0BJ-@!D;u<$vha}i$G!FaFA z8a=&~_P=vXa$i!}PIv_b(sp&!)EEOSuivWm^FuIxlzw;Ts)N9#(5 zc|5+#_d!(wXvGdLWo5;hGn|H?txh%hcUv78zS$ylsVQuSHqYAFi{dU)1o6lMG2o`UE%}I*T_S#%< zt#Ie%4Fqi8UxK{@10WYtB~0^F{24pAckf;l zP565)!)L2h`)r)Dl%iYz*qME9yGJcYE3?5#fyiXVR3;ZUJR<9AplWO3JSUxR`*9(A zVPaZpN8fT-XYIK}`)53yoDTel{WEXvh*Wi{Zt#w)YDWg0wDSnPeUg%zR66`MHtxAS z{~=q?X`y_F>I{}1r7=JdJyf4lc$h@Aq#p8Q%sVqL@6NF0n~>OQ`j{?J>sDB_-c$b7 z*f+ze2uKJu>`>im&4Mk>YgbNDS=l;{y|(##_qa*GK)rQZ`l{>rWwVX&I9xum!c|Sq zSPY*od)J%Yy@1$EYD*nIZ`j1u!6Szam25y0yIy~A5XT7ZRs5urH8^{R9~)7RoNx=< z315FB__O!r&%UkBQ)=u{zp4J4zH|;AYm&R~ojfCfV$B2sZthqHaJ^g~<9{8sgc;pu0x|Pv3t0MhZ zM&S7#&Qh|p^`-(Tr@-2A#b3jH1ZNs68n)|<;4^vmZIHL2KjhcmY5CVwr_eMfKZ5)f zsg5b{zdVKy9oq(fM|t3AFp*vuJ`Kt&5ibzZ2QmWG12ZL2s77BnmubmBM20_Z(eDCpwBz&M@BVvPj%8T?UfpHo(R(hpTxtIvHp)q>{18T7S#K^B}N69VI zR2z|sYbIOf)byje>=Eu6ZHG)-=S2jfgF{=wNmr}VUmyp@M@fjq8|;3QNp3JLQ7b+5 zaecm$hK9*y^!-8hy@Xq9zx_snujCRfn*Jqck4}yn(}}Z@hN39=i@=u>K2fX_^`zH{d^q1hA_PUxM>M=ae#Y6L@Zu*1vgJ&S z@QgN$aCv*=1d#EQwe~bVrz7dn(}KcnfCh+%^Y0W}$~+w&7XIy9+4oA7+S9U8ib`c~ zie)0cRr9rf{@YiyJDy;}$6=(u|M{PF0iKwP5F+r}0s6l#cGl6V(*4_!^}xNFi9$)9 zT)L!=giWJxt}zn8=NU3iTvUR{$}rwL0mId$p$u=FcxreL^qYwiXuWs#axzc&^NI?- z+dFY_b;Y9yB8W?_7)|ba`_H2idKRtrxIQ!UCU7#XZ>bbpt==kyZLgTEkfoEUoOpS7 zKmy*BjYl8I>ue@O-sa6Rv9K_IB`UZ*r;QUJz#hDc+vsX{+0s&e!u<;WMQNkO*P(z2 z-}9w9r!|Cac%x#Fdr1=fjE9epIrTdLp~a5i;pabih8naLg8YjP0k9?9Ye#KKu?qL= z_JO)^+sPknqISEI28GB|)hLbHn`D1FNJ%lNf##MOoVo zTdr;cE7f~DyPq}4l-y4X&Tiw|n13R7ZWhS+rzGT77sn)|&K>11VL#@GHMPz*y~(qB zoIO%x)80S`S^Z^y-eLc(v5|7SwG}h^C`U$Xs784Y3hBQiBbiR{n(6d~jZUrK#_(qC z-&hWZk0muVHJQLd$`c-=EL)19n(xFcK2nbA2SE85ULX`>%I(sW^EGS6&&A$r;QUhW zgL!5FXcXPwu>1GZ!NL!?8(_4-IBfU9c$nMzi32lXUw&BsluZ+qoYEUgZw8__p&P8z zKVC|$gLpE#IWMxU*1Ec2(6=4T1IrG>0_SQ@PFYP00v$^5;swWhFVkDze3nF=ctv}^ zfn8~zl$G+0N4Gvc>7*jLtc%E^?#S9I`1%?I8Xfw8!HgZJC1IG?kOmg`)|T)-S1d*VYh1{*-2q#4M1og zR(eQho4g+bYy0(~;O;~^z>LfcZp{}8^!@+^`jfR?=rm5s7n`OGKmD_r(6Km;`w#A) zArKl-z1LwIsD^d`&;qH!(!N*b-^4(A&bXF&RNQSLoPUcq%A(@@kpd@qMI|F8>@)r8 z;JI2tXDjHQ!I}qXAyG5OtJ^6vVd3E!t^e_mdd}z$>Th*BEZ^cd!>xX)B}rXv6nBum zl=icz9pkbElrT8@3}zZRv)vA`z4bY?NR1&{ z!1VRVauZl7YkS3=W`1eNR!42ZE{xYCuI?-2b8biWUY1OEj0-C zZT%1DjgK(qv~yYJ4@55cd)V1`#^I$*B72RO^-?{K19usw9f4*9q%Yz?(*-+)vKAMA zbbeU;ZcGKKqWLcVO?K+rwMpY}YbJ>1@?Vf#dJ2Qt_3ra`wtlDt!+H6KlZ%^sNkHYk zfQHmiu#Tu|933{0EtU4`C?{bk#A{N(3%XLaq#=TsJH=7bZDQ9s}-<}jOg^s6v*+~{6yagh{} zOApDP6!AncpHII5F%F*rECo!&QB`pwBeLl+HIJS>t3Hyc?iH-glJ2o%Ak`TS-1#W< z@7?%qShh-T4I3qw3p8I*#Cn4$PDEoGx}Clxkl)k_tWJ)4Y-~0gklWPhOOP98A z{O#?a%U)yk-$Sh$<37}TK_mRs;25+n#Q44QO*hZ&=x!Zu ziX)!r;Hl&dikWS}v7&0+xOG*`9++9L1Fqv&&Xz>+0o}V?L`XxkOR_sqneousS$(LW z0qA=VZD25BLeFHtFM8?;lL+A)v-5A-hG{=1C%Hb2-f>{BqZ->h<&m+ZsDOZ%_jI=D z^gaQz&R~Re+$pBno%<18@9(C9%(bb5Yb~03t}@e|pCIeF33x1*tK5Jju$hwe=WK3L zWHtRAI>A@GpMT$|cJ_uiZvZbcfF094i&&a_5aQvaS9|cC%-8)TB|BDd$9LXG@1B}$ zb14|yGAxtyukOs53J{n3*1D>eb59G)Uo9SI!;8^GmR_FsS%Xz1}r5obT6C;smLVzI#?-S!;3m6riS3B z>oa*eGlAe9=i8k*iUzQ{C-OwHGK?R(P*q1#iT~JJA=@c!d8w>D)~YAA_Vy|v(Q&C3 z4d2xUC3K%NX5FeEw<3zDDbBN4uhSGfVP$8pES3>NilT>?iI;Q9eS)8G%6ghQ_H}dp zb~bR`HaayhYVjgpI32I8I>O$L%hSQdQ`?a0D|nbqbqi051H7Qo)*BmZwNC>3!=`;$!1pMtpu73fBQX2(7Jp)P32dJ3hPYE%ikQ zReV$PONt#}R^Pu*>cAS;-rimZg6;BOR;$GAxYR05*xX^evs==(e<#irs#dSn-NzH_ z6W;REdHo(SPYR8JWLwK1?B75EJ?}RBj6_<&P_X_KgvEq3N#G(;cnANCkB+LT1EL zFfHB6noF^72?20ciqh6g2oW{p3usZG+{eIAA>~u-R9#s3^#$elPWYXEKmnMjxM7F& zuTqln@FGGLUZ$|B`LQk5U6lnl09MceLe5u6!8A=&?X@A53Ox}SL_7qvO_JZ-WjLLdkL zEIU!BD?=fSgAvN!x+713ulf0@b7*|r%>yJ5(=G0v?4j=Hgz(Je(da>;ejrBTI(HWU zxJtgfc&maG5$4{S>&jArf7vY7dvL&88r$x=Bq-Hcuz4`LW*_fTI16^P|NPl1zNhNv zZKCJ6KD#mLj2FfA_2hu0KxY)gR#ai^cIBFm>H5WJYw;$cRKX(FwPp2=R)@hN-NetL;1Ssl)T4AW&c@X@B-m%^ zp^AJYGsf(asDkeec#yf6s&kyv2j*0}?8ws~T;&O?BX@wop=Sfc`Fo(CLJTH(7-^Ln zW*g)Yu3D_U65xG_ERGXI?wWb|!20S&Cy|>#-gqAj|tyz^_ z0puv!qpMLL@t~^}f^KG{XNFAxKH0@6HikgI0 zw(;mFO}$9-dOQH_5qdG1mX?NEv#|pUVX!vodI=p?Q*fM>ev}~YbkkgiPcR&yF};9B zsom)6zz7$oWe>T%=(%uan0W=Z5AdvmnM41UYt@e?{FLo>J7vA}uPI@&kW%Ox?$d5Y z>XnsSh%OzB4F#HLj0zG$02@GocR4ZrXyD=F!z6KCj=U~Loi&`!3#WgIY*^0Dns-Aj|xv?OE4Zt zKRi5)t!igm3Q9uzE#WY|6h*@!_$QrUL3})?H>ElYq6&b2d`v5y>QO%W8HUYPfJhg; zTPQK{o9ms<3^c6OaB+wf`M3M;9*Fe3Cd_rLi5%6(@{Tu;VOy>VD8Dnr-thdD7)KD| zJP;}!!;mLuncrCKGTvrkB6tN4lwW>f<~1fVH{UE^{RAh?^RGbXbgrh5{Qqv0N^W_- zRakhJ%EmEOgT?jkD01VVj|Z<0RZR|9O(4jQUZxjM>D4_Pz@0+5X3^vr@p6g0ey`94 z?&?ia9ncq22pw&4_$^LA2d~P0%S0a^TF@hGDn8Ec^hp2`-=HZV;8QqiQHwCE0*{ph zXyAhmxc$r_4WJ~3Nd8l~+E+=N$Zt5DuI5{aNuVMhWCD26_wU8^!nN6cBG%REGWsJC zyV1_XFk6KH1h>+|q|pptrzSXtq#q_L2otsDjZ?gVKZvThblg;DTT)+s4XE2zRw1*@ zK}cx|v4JEV9F@>I#n&VXloVhaqILN1X6@(nMV-n_Ya%>my*&&T&l9g z8zgZ$EC0O4agcQ3FD@Lf4rO@K#FjX3imP9D&%UF(xC>qkV;L5 zJ{qDds@zMskFx8n1afH#6P)EY9iJ}F?=)QX_4VC4ZF!uB-3C}MHBC*tMdRuBg3iv) z-@u6#=cR7Ey6=ZVW=AtJUa%CLeYqO*FT z6%1o+MXO5c(c~+6cV_5VW%bxlgKtJf>N8RK7mi4EKfkt|A54$Y7EmIvKWy0){1A)k z1;LT=eT(0r{_8 zfmb60wle88OJXgTiC}1dnXt=V41>}k|7hyEJKpSsY;`g?0?^MnHK)TmBin_%XDOC< z{zG>Of`yv{kg!+>G}32^ZC^aWEjuaM$_!{40^xT;lW*nIpD7OaD-ZzbwKum_@2nKA|Pf4#VkmKIPpm@AGiqTWQ4o!#gZ z`H?X)Q;Y@O4*8)bji3_o13RE%n9{rVqadD78dfMd@7~O8 z;!6d{62PhPcw*;d&{rfsTpol6ygGF`Ykb`FS5#E=I*0xb*8cg_1F)NOTQ%fZ#^Y(l zzNt2<6}d-15S<#$M7;r?%0OL#_EaaY;h^I zHPt8CMEfz9+pXc%#?J>x#!fI1B(vT9Fvwr-W2?uw0H z4SKC|1FJnwq#{)CU}|bADVR&M_+_EGPnbu=s%`}y9rhODAfe!KbxqBm>+P|C#uKCq z>>g-G8AYb=X5DlB@&adeqeZ-g?hKF$y_~kv4oZ++zt6?IeHTs!+=zEUYH0vC^f5W4 ze{wU>7L629mrZk;`^SClr#LPZ+J-M6m3!*t6w-Wc8v26 zm6w1Z&Zy#)jO&I z-$5En)(Vu*CN?(rA3rv!^FHI9ccGJ=eP`eso~PrV%F{+64C?Y<2PLD)i3grU4bpuL z2UbDAI02^Fzf^!^D&JlsF=PsqYv3Emv%9lwnGKe!Tr7!RWJy!oEe+zsS4oM zmIuKChasSW`s>)v>TB^o%9p)#qS7y?K-^8L~8y!TvnON5LsD#)L;a-dJJ7k(*yOk7Wc=QpQ?~0 zf~g%+_%_ZIeogjI zWgq0c+z>7d)YyP>I0S?t3JDy)uj!8fIbM$Px&BL_#!w&w?MPaX&fF9<=!TDnF9TYm z;5U~5Pk2QI!J947FlxaH;sy19xl=(=!HAGy*!yt~k8zH;onpP_wEVES(^yFv8GOJh ziaef^wRl0zL|l_GNmu}oE?hFf5Gh|r0oVf~v}w3Wx}}YcB%ss+GMg~`U-C*PyKa2S zdf9l)R@i48lKZj=(5b|O(->V1Q(H&J*BCdxKVxtMZhBMuxecXL zFN*<4NFqnFb1BFAa?m-&$U`&{46EW#w|6H`+5+%@t)j#ivlF`IFBtG{*h;>faY zAnq6Y#y}s63+yD$qqcW&liriWAZAa|2`yj#{y$=)ypFwrVOx_22 z=ZI&5hzf1$_=!((JnwA1_ZHYE?4Gw2F4ZSZT!swao!x4NQ}V#S& zoKo*gqTTK0DXwW@6?-*b5iX*6;85v!Q%{ zE?rr&d&6(;Vn(W;f-Cs0!LQAzHkmHl{C|SXz~GPovjBb2N;zAm@b^%JvRI}mA(`pl z$w{($O}3yt8ErMq4(>)UH{hiAw6tW|@#Q4eJ32Ko)CnojzMn9du0n6>5~dO`alS)u zI&wpp#%ACtr}+5nI6>{Yw!x5@SIxl7xkJGc7IwK^wc8D+qe?jPGgjbIB18Zo0b#?> zwuFr|D&;n|wS5U7leiJ!aNp-iB}o@lQt-NEUpJ}b78NNKHXZhM5)iy`PHa4=;E)7G z3fq{Xo6)E**6CDTB$*8AVHRlbh97KjWl7c`nTJ}#t_Jt2T@>YV2?}l&KwJ|E^0d-{ zP(u1h?_yxEwN$}|Ca-n@*#bH#p1hE9Rc3Rk(` zKbnK&oooHam<&*k!U;^^dT~B;s?-rCAB=BM(@39S*GC@An)Y+j74DXRby#+5mR|n` z1sxpU+Sx|i>gwWc?FE9pM?TsM_W8{T^Oof=wXfU;gC$fD9vNP$xSi}3E$E=?=TOBB z{zip8W;C3sGbt9A3adL=@dRb7I@!F&Wed?i^&cJ|(@0s8Dtz0MrOk}$hGPPt6)L0- zl6!e?qZ#-8Q0lieZfH>J)!rh}UnX|-`*_RP|=Eh`Bh;s5~F|cUf z-E{;bIqMkGN^qmoa);+jm5aixKa7W}d1gx3gXi0+t3)-cQS=lj`T zHOYeo$rd2DN(m)8 zqpJp2un3N>Fs}-4e-F^W^uB|HY=g-V-)w&>76&FX0mCW+SjXDrTNJ2RP~7>o!YzD^ z&7*a+`LMu?w2Km75N-@Kg-(ikFEDv@-Yn6FU9lyP=(9=k#DjJ|ON^titH%b9ffM@Q zMq%mcX$d(x$b%^2mZBARe`X#zBa21hJp~mc%gD<(}gPy)(--^t?DXN1vJw0s$Pp0@+ znUfqM?L<;ijU@3Ks03Jca5}{K__5RuT&~h3)||WmNqcd# zp0K*1BjNc0>M0Lqhl$q3J6fJ8K_*EV`dwD<9Mr`6XU9p)!sO5Ef*}a!V5&VCDV@v~ zIB8amsbsA)gn=Mzv>mdVw4agI#$Y&o@`b=^?W?mvZriA+3)TJb>VCO+kU$L7w-~+g z+4;x08PhMVUA5*35JH*>yY)$lD}gmDYBoN;gjtIr;eLJJ+PXTjrKP3MsX_PAqX??CvKR-lZRfs_>!IJ57cwvZ zba%@^8`B)Nb>aT|5$iX4Tjfx$tQ*qc)XkVi7{W~~i)GI%XGvl#ZiPH3mxGwXbPaBQn-dxVn z2cVk;8G_&E2rXl`r5*+RlJ_@|tD)$q5tz;B;@T z7kc?F@?BO|*76Q(g)4yi0&?t)PqtMrNJjNBH2M2ry0;10`2XYoR_P# zBmzP~*WjZ*F-yn&?(B1UK~A}GS+x+$dlf1LIUMoh|GSc<=v_hFoIfyRDj;5 zP*5Fh^JfJ?Ulcs{Th$)1%$z*pWQp%|3!E-l=YP0v!A?hqiDVc2;|chQD5>%n_)VcJ zI)z17;Mg>BqLOQ8zcr%t1bAo-)M-7#?cL_sSff+lRk?&F^8`b+yLsZGh9~#;3fY3b{Xu!>v&ZRckYVuP0uPn3o!vlr zc#p1aNgG!BU122isH{4o*>Ad}xR?;kZeV}hYGd1}mT>c3jF5|xT{qv_F;0nP+o>Q; zwzTCES7Z|ApKl3m$hg4)RUepfc8@k`tt?`HeqpQ`rEb0YcJwsk$cG<3d7(vy*q z4e_=-F2W`w1jp(x%)R?Jj%8hjq(ODcsh4>oP{m( z-+JICxLz*uTRPGjgcG<9avH1!oallQh3l2E{UWd!MGAp0N+wx^klc15i9+~9&SS$x zF4hl~w^@lpCJ(K=h;RT~yUzEj<+Z!**uiE=ibU>0qebbog_K=G3;`n^2LvjIUTA0Kn)vV|6TuR>@K@P<3sk+ z+6z6gVfqTU5@w%tAU)SxTW~C*1{VmKtZ~3gbP>`kC#)z72K3YNkHyil6Wpx$oAcFx zEzm`>tA=(Dxu*}7ShWtT17E)uHwI5glmFIP@&^eJQGUeetvp@?}Oipk5Qts&@tT_qIej*cebD4KiCra#GKc za`}s8P6hjNOsdXP&em{vdEGIWl28!R5TDVuhix&`F}noIRv}HD&X7{zyedd4n{eUy zb9ot+yY!NlW{3rOxKM0M%u0DE&1rBS*>*;|`IHO~9hX-r^3-Z6<8d80kv(C@I8&el zd9!RiJq1BKf@oq70K@*>_Ob(fHdF}2YBz#_XxC36ca@gSWfsikRPT~-q!0xm z(+G%?RIS*lAO47|f3bc{H3iG&UdaEnq?;{gB`4VYrrS=Mn6>w}S=LPiFh~U-nH>nO&0lopYCJ8Pm8ylPcU7a|1q_arWA^OkrK^MgKC~w#4Q`b-^ zQC1@8kVt7qRay+BirL%Sf7@vbW_k56Fe?!V>=P8_OGelhx!4?p)#o71h&4HPA3NLK z-CY~eqsGgm&I$@j*f_yPWw~^J!=uWC`OCLw$Hu1I<;0b%RjrsmL%EQaDCr^;ijj3g zopkj7)pXtARKEXTBvBm+QI1gd3>oJLS=rkm93&(&j)RabLfIpG9eZVFgzS}d>@EA4 z*_+?p=X?G9(LY^RSJ&-%p8NfN%`?8xKSFxi*kfzV*d`7qUlR-9|EVhbW}TE5YkU0J zPY=%$G4jMgN+8jM0- z(samb``@+p-@e*c8HX2G-uKonVx^`%R%}(Fr~%3LZ^A9`-3Q*~`yW0+PNEBFn$2=L zOm___CBBdt%a&!E1ih_YF*nFhOtuHk2G9;A86gx6`!h7MRlN!yO2~M-aEG#ptSoU3 zn*@i$@0seFn3(u{i*~yFTbreCl@Xt|dmFJ8{E(~LIEv)WbBDaT{EYhe={Js=I6E0btV0L{{eH7l&TPS4c6mu&=&(oxf!BK4I5?r^!z~ z_7;B!FarPvd~%R~k4frl3~(H21W?bZikKHYvHA+v#*z2)duEwu*@!zU>LS(3KY#to zgxY*Xd&pR%x36WYAPA*A5hx{G-H6P8uA^2b*L2dfeOz<42scL!Nyb!O$cbPSCUMQz z+v6nT`y(ss6wP5b`BB3V_)SE#qcR~N%jGLleI;F0BZIKL_)P~h;fK3moS?1gE5So? zT4HC2unDD*T_jLi@CvrKG3u62_bp$5#)u4{D*l()Ue8ilZd4MYk5~S!{vMyBMRxy|x`rpJq z-m=|x;J)RM^5o#bP+FgS$`G&TmmFQhn@W2llP>ccjE;94M4kkZefZ`xd>i+hFiNb) zR61;^)#LSZka~KG`7AFa_b{lZ!nCk2@8?hG;2^2IXp&pJdbXh49mCqopTFW%hJwQo zIP$rCrgfPPZmu3ynRe7zB*x|;_P`=(BJX)K4rdWzNc+--n^JV}&X9S|?jw?H}d`AnT<)=UMmIA(mLFl%f+8>7Jq@^}KPljG_QzQIvV_!Fdjf%tuV~VM$*J6two>o#-4+{3wk|q|K<8nC6FeAQAH21 zEcG`~)(Y4~y4V8svuI{GCeSInQbJ=2UIF+FEW#7;DD;`!l?0=SsXid)2^%Q9CH~u8 zp*78~Ij1X}IfNe-j1M^}%*lBHN^&=63r5=*){WsUDqmFQRIVIL9+u^$cDw{oHYkK9 zea#;c{%{BP>8YuK?2wsS+%s94gyH}x58ndZ@{uLg@W0CLkQazgaX+)N9>s9;{uvp8 zB0K;$r=C$7c|Jx~+8$z4X`ma|xY{AgRbf(Rirp?7NNbRrL^1PL;L6aB zugfLj^b+ayJKDbGhTUZ9*(lYaoz0OoIYu9EZ(zC=UOR(-r7Kru$1=q87|j3s$4p2vAldU>x?eXt0D>0n0>R(83Lu|%A-5C;m>1u?~fa|!24A@2G8XsS;$Qb$B zN`No{U+BNem#BT14!P#PKaINaf5 z=V!(jm9`<44MQtEC93vNlFZIM^e_&#=nQB#0B8b5S&a$Jg1cRZ>lmbjJcFG2!CGTi zmr~d46d2qyq9zmnDF>xhf$?>|+vu`1#-p&`-3YEhMZ+f_I9DD?mmQxA-K8;AbqHb= zoRJ6TVmnp!r`EGptmkQm6+lVl3BJ=!cS4mPy+v0JR!nq;YWi&q=NkYQF=#z!CQg0Q z)Xft76 ztA^M@&i486Wy^UB3NqAAZQ!>6a)Ev=IQ*8kP|?g( z)z^sWW_|eyy+*-~c>>2GPNH8@3rJ4UE6?DaQi=e7d2dZI{Os%h{I|}|&Rw%PR(AuA zVuLh(@rt!4hTUjSoKq-CD6$fuL=t^N=d{9j|0HpTHg{`giV~?)2@a&=cgm#{$|aiz zsTAY0=$3&RWZ%iNeo>ypqQR{_dbh6md9QoC95zwA@#Jsc2;K_}%TQ~6Ou6~GV2}d! z+e%qSzR>Dd7%@xJz->xh;Cg*rp_$8MwQs>x+|2h29zGgz<27PB7i^>dH1>(>9r(}P zL=W_U{fa@`@coq#Im4}0q2#f9>AhQkakQj`d~!O% z4GGFEGf`e=GOPN`4&)VB=G>aBkdTnmYN)K7Y@EUY3!(f)?33nr63i@vY}oCCWH9G- zI0$WsD#s6M;Uc5zU%^`oNtzNVuw=B@muw+Bnaxv~8A!(m4UQa6Sh8HCqfu_^;n|c! zAAp_`qAGmjhl=r=kV*OoMXRr>5{fE&U|jn_lC;s*hdx~xq%(B$Z; z5}L02=2!Nh{VWR5c`Q~kiX|K>X8*4RPz)}Ft{LVhffIG;I_FK!oOYZbD+8f|i&|~a zUOM*ghX95Or|$&?(b4qOgZ5kHm6dPaGDlN5`;5k`DCb-GGmxwJWjtU%y>(EpW!c&L z`?qk!=s%IhhYJT`*N0XO;g58wTzc%8oh&CuMq(&zHV!v3ttnsnZA{lT=X#diErrjO zd#KOe(wUYBdAMDZmY%&x+5DP=p_1we(m#_hRjvh%wAXVZt+Kb81=l zfBcF3g&G5`S)RyxghEPQN7Nh*j^c;Pg8r=W*vj<~`UmnX5=B6rTv-qI&g)&;Y_f70+kssWa~oI&F8bIhN2}`~j7bcwTvV z?30xgy1-8UFeoSpNh~`ohA;++pB1Lw%90bT9KZgoS`=IWyLVt;VtPboUyGAXkKYDZ zslZe_rm?SSY>-`6Mq;gbp8(i)o^R2*Z<;Ir@GY-zR9~3p$+=-8Bq!3Mk(|BusL^aN zT)HOW9(!1_2zy_cRQ9NQuTz3KQ0>V#IKblkEi`|05z402gt0XWL0v=8&)mkYm(K1u z!e|I_{7QaF^UnjLmOigelE^F|9tj4dacQPs&kTg)Sjj?8lc6`{g)mZZRT9izz5c+= zj4e>OfxwLljn*^ajRT?Eq@3Aq5k*Vv${h~FRjGyqh>@nEV(7~?&L2ClMOng#-F$o% z0y{Nq7f%&LMxvdRBPkJL!bO<~2lC81D^cBFmk(}yjURSY>EHP|t?_{Bz99Pn6O8AJ z7|2}2d(EFdptN>!O~>6X`(ducet=v{vUGNb9=Om>&(5w1%Xa4-=91L9@jdneAscIc zqqTyv6pAr7)iwvi1n9>tyh%dJ0$h@MJJ}i`W3sL^WTg}?3w&#D0cd(_?KvsxQOL^- zOeuXFiA6R&JEoYQcBCtH?t{NEa6dd17f(4BkCn>9C>sC_y_-3X?V2dNVB^yj!co0k zeeTT(5I(}m#dWe3E7cdlT#YDdoZ|lP92agzs$}13xfNHchVy!+-d^FY*{E(JaR6sS zF@~#*Zy&2%_eak-^G{4p0)E<<1`uPH!XpY`%d%k2^jb*f>l~1Scl8ht9X&QMij!jD zZOg`RtLR91Q$pQ>NYHnuM-El`0@wexlw>&+L?ag*vXVz~jQ|@dqLH4T-@ONS?Ad#I znAz0@)qf)>;ud?4x0@k0&m^ISW1aEG^8Qa8 zp2Hn2j^DeQNMvHwA${sktBlJnP!c1LYE2u=-#=*~S7p3Z%{3@+`^dAn7)3AM0K&vF zyD*wvZ)ne?!alQ7`nhD?6j5loT|^NKaBg~s4R@rjWYd~v>&X*MYj&twwF>2h4%VZ? zo;g}&JD&h4C?DeWD8#&(*AuZ}4b-+k`9ZEFsu;hhU46qrWOTn3DXrKq#&4EEz-OK| zuZNct9F6AcDlE-WUzCFb}nPe+Npx{ps{KpiQ7p-Xa2Z#rs8BHnG&%w@OPNJz7fA*nRj{ z&$E!RK$FCTKXGy7BUhfZU~G}`uT2=`{rhhKkB;&1S(|AaZ-lz%1)ZONoSj8@SA-PA z7JRzn8%F4ruM=s8E%Yx)xoBLkQxtiB4X6J^P)?r&_}q5p8VM#F?BUzge_gjCuHA;N zv_DPGB^TD%$@A)FK%lm2z80c9BFpJeiSn6)X9^+~+5Fy|#FS?Q0q1$oSs-U%JI*-N z>({b_MahM)6k#~qB|HDXiYIt7xke>3n;kwkr#4mKsZnu2q_|?!;!R8ze`!OF+RH{W zUse40kpU_MdFuA>-BM>sdZR-ap{|WpV4{*=MHfco253d8{ySNtX*Kn=Dbu>Nv}?`H z37`jqR1E|rhKMyYZ)K8(Mo5bU>@go)l#9nW0R!ue3GHyw7~0#f42z$ z$;I2bO-fK2KhA)?q!fW+r4GG6FFPh0H{o|&qG$Hl!WgfFdok?m4*`jJ5jml~R2@J| z#^mBL@3ntn2g4|glk26MYM6@wkZ@^xeGV5Y|`(fOdg=gy%1* z>Ss5{g=RkvR?v=u)i%?MV|RcUOTtQtJRAOI#{7o*u9vjsO$CG>>G=tO6j#SA0ENcH-T4xEyV$2^X#?9OB~7G9)IKnwAVRry@5`0 z#OA9*tqLML3hj*^rwrj|ke#qFumL)X||*Nq!zjZwi_rSI2s{k8S5xV^0mM9@8<&i&Dzb zb)jFNE|!Gf$#V>O)gZMH2$wAG<-fb6lgD9@ZGRG5DVZ@F#0-P1G$&=8w47#J=*x_6 zaq?eD4hW{L=mV0|c2$ZDH_>0dadF$eR0$E643Z*pv@%yQ0W$Pd_YEH(d{heXII>ND zrx}-XR{?TVwiI;@YLP}{s8B(9pVO}5*9a~ip7#BHbk_>hf@X6rYI$7Q`qCj`|auJX`rG?{{UB|^?RGuky(C(!AJ!t==XkxOuPHzezp)Is=+Gy&zqlTW^Lhn zg9w1LlyV{zDB(4jM2)J2RLSUZ-}AlOZ_UkH9W6sDRW>)ahLv@k6wGdeq~+oI&$$aaP(?V zldh<*(_C}lXP~J}dqs#ny@l`>?j?rqTK$X!G|w^2EKD&~!zn=H90%!DtY_q+_m9E0)yu=R2{2q|765 zqi)FSu4ggU9j|+#xt`%VxI$PtLI}P*b9p3)5w&4t*d)WO;r{i#vXGTZv}ac?p(5<@ zWktntU+{+9=Ho?%&UAG18S56C1Puwj2hU3)iL)!6P-H`Hk&2#Sj5XC;^4XWE?4ei) z6ZBCl9KOufctq`9(Jw%G<54F+62pGXM9V5_8E!D51E6_}Ih~<_#w<92i zJId!13n)-$sLRUAPt2FZUiO4n>JUQtS}ZiPU!1}SKP5e{88?!{1ta{BSg*|Pu^2W? z3`x#W3&I&dNZk_20ZCcyBo_Ej1{;^y4#7G9L-nG=5VR>1PS(~+THKgBgh&gYoSS>& zlZ6P0_LVSsNQ4F$7 z!b9Qc;djr1Ky1R&w!Fw}?k|gv4Y~A)$u%$A1hBbs-wCOZ5^#_Rs{|`mS0)YGS860@ zF2V=`43@|T(K-EpelpVLWOom+-VbKF> zO$~2I=m$zuh4|#FhPwRCz;)qC9h>u}-Fi-H6O$AH#?=;elf0I#C!=YkJDPdyF{hn$ zr{t#`=^m>otL=Hwr-g`gxfnggmd9*8gL8-WQW5a2i7{^Ko3CT01^kasUc40*5#e7+ zc32i8N;Jd*PCLX}eP6yttC}95=&{%RM%z;&x&vcE3A4bl5DAo9TDQ=a)qy zhPz7`;$k-4i@g!Ba=ob8Q|s99F3{i3wt^AYhhkt*gFU)@>x%&-j(ONINu>ogz)4<~ zpZ}GcWnqRl->11tezkZbM#s^F^M#E#D9m0wURhp#I3HBQ679pP@yf{_I*OKIdO=TD<0`UPsPZ5zhVgQ zrzc5SCy~JtFGeu;V`Z7xg-?wjRjV=)Ryr--#<5k^Ck=H^vs!e?g~Cd8^%*x2{7Z~o zWmFVWL?Pr7y6^YRMaRr|S&bN3=Ht{@g_tUP1iW)iyg{L$FALTrZBzLpW~*%*0F>NG{gHfHpWz5xz&}Y&2gvC zwEIo;udLoc z&3OBtw{>4=#%#T-?r7jVim&P**P#fO(PF2xqK5F$ihVvT5c-=t_w5R`l(eu0#u*3Q zIOc<&v8LNkZ0ri7hre?t8!63EYa%B|DTkT<( z-N?cNopbJ*`{v41FS<|$NEMlpnd=k4Kt`UP>FmUJgTI1$d^I>gl`bN3SjWH_vuTFHes>hf!yc_e> zFM48Frm538bOeg+_f(X1w9f4T^Z~&G4Ktw?W~#%Qc>;AdQ!CVG$X#g*@%lpf^iyP# zm;={7dTxx>e%K(S`sIj2DW@4~pI@>s9TJ0wONwyv#<`R8iikJ7sQl*0FyX$|Dof|? z2aKZx-y}4gGdloOv_ora%Zdo-kfgY&?Tyb7FL*2CXjEt2vzXAxI`#xE+m^%r5 z{IB~5v3_>ig{FfuADs%V6buJfucWJSQ}-SAbE6#Pt=5S_6Fl|a-mNk(RgxOkiDUc6i@PNlA(Eon{FIQya5x2|UzPZM>jM-=C#VdZY3MN;WPle}BfJ z3u74*K}@3lqIZrkiY+yUE#UH0Z#@W3VJy6S#cWrt34TZK*>lV`n;lFdzC%w%o?(uH zG6(`+0Ibam{o6Rr~UFVJd1g3O{^2IYk;N0cxkudAR6^3 zo!L?Fjf%&81b3wjNd@>X2Z@YS?_bLjOwH=fyqr%irK6_Ksnr^cHcI5H$V_OqDdyr7 zP#vn8w?@evxTyCjW5k$xhW2aryS0+!+%h=0HnKIlvQ?6r=&p|2{bz+C)$xMc=!3Nc z3j63>#Ylzo&hH>S!`|$7$-uj{D^Fmr9R`06>x_@G<*mQbA3K)99{4k`{S5w1-#<%}(F_##;1l(@S$z<9Z-gm{+gLfZzAsZ;w_TMu zq5O-oU9LFff^0W^WDiGZe1qkY=Q2I8Wi>vSMV)_ zq^K{+6vl$c($iXX3-Du)m7p9t9ZgeX1qRQQDNps3U{ugrnaxrsuMVb3#<}WLpB;%7 z4NPVtblkeLF~cGvEKFU^+r^u0sIM&5eKv0&Q&cm5ooPg%5cb zH_Wt+8i_YFbeL@}#B0-9!+C*N`=eOszpPP5M@patXX&KCkv88w`S_?p?+(bA3KU3M z=}VCnOCiEL-*RrSy1AD`K=f3M*Lz|x`xV3L--(HbB%km*-R(h?#3ON!DfD)pLdW63 zLApk6y54k4mx9Sd&>$WfOvQtb2MnhEfRgBdQ~cSUu9amUrN8;Fkb7~@rJ%6z&%e5` zMUh{&wIGEPKXo*)GDHw6hN`-J;9_yz{lZ;2rK~tvrid%RvT)*V@-A)*_fplF)XB-| zZ`FB~{NeihpCRF~FQ4vWZ-$UU+t()8wMVr}{=U0bXj9nMx4vQ|tK&?iLXJBAyP8Y3WVXkwHne)1($Gra)>2aev3pX5hPh9rQ zh3pTExYI?-6zqg3&zk40PX z_$son?cHVvsup}aPoboi<@@M^JB2YkRY+_iJhX;f2c-rIgMw_u6?_e8|FtZ6M=#JvA` zdBe5F?R!mSQ0Udsf?Tz1h!{&sgXf>ZjH}`h?vMt);5GP5KPToXef(aEC?uf50d(lqc{_tq`%(H+gj(4@AnR z7eDnI(XOjletAMx`NL{#Z0y%cil-q6&FZl)U)EDE)Z#s8)M^$1a%V6e<9SVxJAefk zr0ewS?c?_aP672ch&x(XiZ!b20;xKUfsN$Hg9qXkq_EqM=vtaR#jTHRHm0aiHUp+k zW@SF(2|X7(f8&flx?~Sv9ZXHH18~)fMC9qy*Hc64OZgVSUNpGeke%KBfeQ5Tp_`p8 zFCF=mPePltH=kNYH!J_U5Fc=vHrP0r&$>6<%31JR|8URw`~8ATQNzDMQHj?7^5>0MEyep$}afPi136+b`kPOo^`t3R&;>4p6r_8?a1kdd<`n- zo}p6WR=k#4SQg~V<%-oNB4^8No}Yiro)FE9uMqHK#`RW3e3J0>cbF*p1?$CxAiWCz z29Mp*tXZSFzf*Pgg&K{gO;RS8|IF4;0#YKIf&1`yqpYuBXXX?=n!eP)eJ)f}o3Ncs z`2jgox4s8VUdMl%N!J^?57O@Ci=U>@8JCq>d^P$d4ScH0`}@ySQpCQ3OlUo`Br*4g zczXVnZ1D2~ z88Ab*!BEUF>&mzA{7Bvqzf9rZqI? z6=&()QoK4tBnzhUQ^J;;*4fA~amBV%biVI){`Kn-y>w{YN>xfshVqzcThid^+S%Z9 zikumi^$4O65hs6t{|>%fi=H=^uWL=5_Ut(-EqnaF-U8(#U;0>qqxxgTE+YNe>fF53 z=FHETydTWfICy;bpO(Lhh6~$k8sV35S}YW&T@QgAUp2*+;Syn z&`(P0=VEd(aoatS&7f{6io*8wYkGLU&}z?7L{p%k1cPbr37EK^-uq#Ha~yS|_@2gE zx6c!H=pigfS7s<4-_*6F!+Aex;w1R{c2>7C|& z_7l6w7{iahhd)h`v#6x%6+RpdFIuD`G^Q>sNO3P05FiBshiz2=W#knS3IHBwWR+bb zyUv$wW9m03RH?i+v}Jmm%w?!B4a}|USEP6D3_HTuzh*gQx$$)BIosNXd|l~0<<>^uiL_1E^4^*x&t}xtOb!N`4KC%unQtZ;;h&S0Amtk(t%2Rw*bX*n{SE=z9 zmP@eeTc{|DOBh-|Rxms&O!eW& z^@^Xc`94=A7qYOWMV;Yr4xOTR2D#ObyH9+fDqQ+I2DY<9$_#Xy$ml;kqdv-p9TD%DlO?lBBzT%e> z#-`sH5BP7nwIpG(*Q=)d10v{M7ue>8wXT`Apfhn)B+ENSR>E{811@DVwQc;Ydq-Y0 zE~+IzZ%lQZ^@;t^7rRwZR5TK}!MeI@G+yw`eG7b)4M)}gJt$7PN}HOV|1w&eu08jg z2XAGc>xCR~!heg0L`0L7l%DxOn=0U@4g$n>289O)()~I4c?iNJSMsqW?x7zteJklBKlIdv%@~;a|iI=#xikuSt zsO_mKC_wK<_NSg{8`hw6|I~)=s4kWi7mp7HA%(y<8mR+ygX6hh))@&u5J=)C5|VzU z?s;)>fw$rIv!=8jq+|Kee=Z=>jLX|mhuDrc;hNgyb?!weFhTDg6&-tpDsxlW3B0iU z@3H8#f85DrP3=FUy6x~Ps*0X%AOf9%ZC{*R;uaxEU(7VNkYX@3z&6Rupgxewx#4#) z^c|&(S)7aAa0}sOT9+b(N;{0ijB3S!X)!6ul`4^&FOr*{jW5!lT+LAww-}wDq)Chj z>HJ|+RIn_eb1A>#flL-Zd@Ou+34G0wTl7nE1PG#`JCrn~iC1~S?&0DpZ|=WijzFj0 zvtv%zF=u;MdJi3*KTnr(DRov$e~LPpf%AfmBPhm~YixYn;`q7C?)3`2!asXJvf#g+ zw0SY{VR>7eC)*}4YIy1D()a8Dlm}M}AMf_Y9*87+uiQ_GIxB)ti2Oa?aS)xXxKZf| z8tMB{c1N14T&YX1gS9K;J!u#k>g#9zPPaZDX>}bYdi%cjjjLRe6jbd>J| zqHCFQdNzBNOabYbN#{{q@Gcl7MoJ5{i-i;Gx)N*bS;Wr44bFTBoU~K) zH|3nAYAT88;Ee4SK}P0e784?f&L51MQ7scy19}1b($>tH3vWWuS!ku*^Si>jD#&1_({9b7L+VP>i ztu1lcG-@~N(Zt=SIKt6ao}hRXs@}qhC^-!7drR-ekzMe|_eJPrn9b7S{C%(P)8?aj zQ}8+B^cr@K+gi^s~mgj<#-QsLt6DZNdA`n6qFIPdl!) zT;nn^Gc!rO7=32DyFI%4hMK1JJ8d)|>9Og(#~#glK7(cyE-n}u(rFbh%^-WaP&2qQ zYzuqtX*zvX<2TKdY!&hNw$%M@U8-Yxxak|GcRAr|>37ROzSW(@@UL>axEji*?+qwrzo?qp@Qn{na znkeZ~mMEOWuD+&`MWMzeMhGmI4?DK&CF%TCAiCm7v`HNm%VAbM#_OH;QH8K4yd2G+ z!kkM!XFhsl7cMV@J>}Q!s6R)MsU{cTJq_h`Gv3&7Q44w8eUt_dsh=g358MK~k2K0) zS(GwW9BrEEA@jOk<%c5`$}J3Gh;*fpL5c=z7+bqC z>}~=kseAoC;>Ysxa{QEk{Mr>_8S(rUvo* zh6|^`_g<6U3YxE6F4+!$I9kCGo(h>7QsP4V{F*!_0^;)q6_+3>KjBo|u}^o%fL>Qj z_JBsv_cJT)J>0-jBctZ9n*gLb5sAG=B(}oyxUc?DbMc&;hlgfQm5VAVx#rckgj5<; znYvDB*t>?PlUGB+s!4Q@{$=?C?`e@?o#jWi_0ESx!Z+-S$iua&I7yH<(X$pyHMg3m zT%?%75LM{=_3~tcZMlku%EpeRur(%J`tR$A(PG28AVBUYDJu)S>UdktfWy~!$&&b0 z-IhWDy_G{X(CvNeBY8B^kPpik8o64;okT!DV2Gq*xfYvjKjpS|FGhg^Wu2D=V^Md+ zB4m#&&&E{^ZLL?qd=B>9FMMUpmLOR3UZycm^&Umb#`#D7w8b~P>+^zR*QrJ;)?QW+ zb35m1$X8JMe%cH_JcRRdfK_i=&c(MqK%IMVmq0pO)5%zgYmik^&&fck&??ETCey6W z(I)Cs?_qBxqKLR&9#;-7M6GW(b@4z>s?>A$nj611KAG@*5fvL1vo}>gn=4q6M((Vj zU>^?<0G_@Nqqqwa#v!{T3BB2CjNzzlGzI z*WGpN$b(E0gOl}L%dQ5t5XrQ=@_4ZdObfKx^()bQ3^{J?FPRByF;Pk_H^;W#MeosH z>U44qJTfg+r@8{AeA&^eqG~W0%;Gl3`U`6R5h)+bI>u@hzS~mBTBkybE5wg1O1kh7 zkos~C;&`k|g-2Qm`bouZc%OKvtMdS5gR=P&2g@SNh}vHn9$sE7&*y1BzL1?-SC{m& zp0}0mx;HsnB3dafF>xqMca){u)A7RhcGrPZUI@+($Q2#}*C6$S2aUin`SqGv6~*fj z7A)+BK3xJzo+8+iDW{FgQx$vjV`5%v4W!?(vM7KEO~6En+>%yqc|Q~=x09scV+R%M z|CCu{qGYny>z}VvoUX?Duh<%B#Ag;yo%Bt7*L|ji)Yl$|b~|dvOP7&AsA}B~xOD+= z>(beA`r=iDN98Nd`Dy1_n^X6O-+{tY)#F`}HQr&29yHjARRwlUFAYK6O1fG1^7Wtm zcdVv>m-YN&+f&HD=k#w6sGR`s;6uSZWLSlWDk30nm`K>EV4QNRzaKB|n`4Q_VwGY{ zb8A7BqPD+lalwltp{;$#7S8YMZ8`ys3(XxztJC+7j)acZMMPA;;3&fksBh(Lxgo|r z8x8|;Pmzd-NXhpq4xL5MixM$f=dEv@do222U7V_ad{eNjS$#-Zs-$^wYZa|bl$ZQ| z7?M$Z6m_VZxw{Pqxw%tk9rOMKhea#TAmC0SZP8e)zc`#cu&a>@vvjwIvOcR89&VNG z)ErqizNV=+{M?|*&Kv#Wap46WxkUC8Ct$iF?}^Oa!wR3McM_EJhLqNqw`OggB94O z7|M=Jj5J%mn!fnX9NU>U6&M(pK=IU; zh|%+hL4`7p2R(TMktghUgrj8@q>VBMrQMG>F8!M{1P3^~#_pcQOU)3GWNR_;j&P;D0MHcZ) zpRK)bx|5@L(aEji9`$K`xw^Pod#b$e_wQ#>vB8rF@^oaq#_I{IvT#$1jwRDIk>OHw zbsJ|05gsKs=2b*}P<-3d+q`gip8FwChduw0DlVP1rJui!Hy&Mytbbe#kNq3v+8-U5 z)0}gpn0XJ}Pc&Wn$)4Q-!d*+HBM0U3Mdv!7 zsPk4LuTuQzTa7kS%CfRD5Z}OG6re;TH*Yw=bj1@nQIxs{DDS+zb2gkeDrsg65`b6h qHoIG8s#u2m>r1Sau1zFBdqv9G!DSlMy?%fPe&l6Tq>Ch9`}`lTVw++B literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/image/static_drivable_area_before_expansion.png b/planning/behavior_path_planner/image/static_drivable_area_before_expansion.png new file mode 100644 index 0000000000000000000000000000000000000000..4f78f12bb16a2c62ca59b662515e1751b5d221b2 GIT binary patch literal 146681 zcmY&=bzGBS_cw@$pnwbzB_t%IL^`FUkpUwoB}hou1`?wLVJJu=-HegaB_ZA2Fi@J2 zB0b{0eV*U*$Gbm>oBMM!u5+Dpoo^hFT3}^T5?T^GJUmiW6$J<$9+4Fu9zM<8JHVB+ zxeNi|(`|QoRo%P5%lEEj81VgLn4%#}$JrX@Y3^o)XXE7TXvORP&dtio$^E@EY@eV- z8n{W&R@V^r%FW6gX6x+4q-*O4JQjEfybusvtFPkcUr!C=7g|ruV*%g?#5 zDOeT5n0^w@<9%f4kiWhT@R=DO?-$3M9;IcS>1Ev|8%p)TEsob}F72ngyQ!(EmA2n0 zH@yGyW0kdf*>sy zHy6J&KRBkkQkbKv#PQXB(c+19b;fA4_G?Y>eBa`szccgQXV>lXizgz+&AyM7Bk7s9 zCLCk^d@q)lt*NMVXZi*PjDNPt%bSz0jm*v>YidOBT7S2Pj$$w+x;M=T+)P8nJ}Zcr zUd%<-)?c?Jc6Yv(oSK?i%=_qBLqmhqS_H0JY7ck1e~Ouoj3nEctt3k1Gh>e^$20*e zAwoq%Lx8u}jB~o&v5{$CSV$dn%{DFzZ1OqHE-WNzYHG^m*PE^VK6muFqC#YK{b4Rb zT1F;tc2=D;Lv=@Hb84#=K|TBky%87Ak2v^A^d~mMGPEVt76=30gFaIeo`>xjm%SOk zGH%W@5C~BonXTcQ%i%v)`~EUY7vdE%62H7OXMu`;y~)O|%s{ik5>z zix?WHMGDE`Sxs(y<9|9#r<)*5Ff{q4RpNp-s z=}kql7L}IX!Aq6#PhUtkb16lm%T>|zG`dak)bW;Sgdw6kEd1%RQ0QYWF0PS>j(;a> za*G)Xf_dIL+k-P7RNxK!v0m~Fz2U@9Yp#gXWT+{VBb@aAmYT}CT{UMpGd*;?g$^zT z(`C=p%PHyU>Sor~PREYK9<=Pj*g^d(26}q&hxH_8%EF^}@hB-NEm^*L-{4g>dw6=T ztoFv@1q`N$`tjCO!H+EK0&dIXtXI0 z?;r|cs-+dUyu2Pa%zDD8yD8L_Ra5hjT-3RHO7~Ip_{2o-PuiY)wlUyjD z?yk{*kSDvixR9UM-QU{!IqZM!zO+Po@6QLRs+!ba*88!su``u6nq3#Y)*Tk*Us@Pp zlofG*wt!nPo=Xh!&Z)nxoJZdaJ-rLn!v$GeVw>21_HM3wiH&$^(5JYtT8T&18FG!f z34+4uH|Gitp3<=k94q#d=>h>X8(Jr#PCbD$7HVmPxz8t#d9C(P0Ew_OQ~t`!Y~WXM zi$vNjGFS4EZlh(b_PJ{N-U?9e9FWgF61!Sv28^3Ht}qA}x|{iib#CK9{9glS2Z8J5 zBs07^xp17Vky?VFzoY&9kC4_%)xx2!Pf8VFYCrI!6h)`)1h5&j54GNd^~JA^rK6*J zg=o5|j&a`wNk^v?$48meI%yo9o}VM*?n2W<6w2M7&aJkE++&4kx82l?do6b$SN9nh z7^P6un`rI`w2PFoxyl>L>VscIIQza+dO&2l?X0P(sdPl?^5n)Q-HUx8 za;CL^v9YnSdS8cN@h@V(>C{f<)k+(>JJO=1^5dIJSNeE!$CkF_%wQVH zVK6}&+FrZ@0ylzTL1+B% zLLDiPa8Nl=G4&qG{iD>@!{Z^I%kEsY7RO877cTJ;w+K3y>-ip<5|NgG_vh~?J_~n`F&SFzaE?>%%K63^T zzihQIF>W+1GC}?s87VowN<=E0AXIlHw=}O$O<`8;!LqgZM_&dyIs&{OM~#VE+S+nY z+)2bvUPYM3Gv%_u)D)AjrADvfC(}qnDcP29r$J5YB+R_G*y0isefm_-H0g0!raG>! zg5b0Y4wKJn>)OU1AL&PT{e60qiD!TRHV0)Dv~vh3?~91cq25ia!fLCle;=;(uhODH zehJVi?uMD|`;|K|< z4QFRQshD*9!GVU6nWwp!d`X*YSR(J3$*ErFb()!_q!+Ka(kv+2ZXin=Wo&>meMC#! zc6GYMH%CK#7nlC4^@si)gwlDnbKluFD_Gv-`Wfx%qL1_8O+)bve`#>;71o}3b7 zu=&rclD4#*Mf3QB57Qcu@`XCw@gC20bat@D6aQ9!I_cDuB{}LTcl9XSXfq{Dx;2ts zJgB~29O4MYkXsEIsxMGB>~=>D^7U}|D|5_cqb=8FW**f)q5c0>-^uOj>gpLcH^Fx) z8qjD?z(qqDm)#vAd=!E@#j|01O3Mmv(>|JZ{xpT`h%jWj7cM%}JDbNNqNOYFH7I*R zD7)dxS#%aCK&;FuDy#=Uy?#1zBK{)w3$Sl>vd6zLh4Q72{c&?>%FPYtQSV&q?;qB! z-L&8^u6H8@dV;X-m4f18-6<6CgjM&pRQ6e7kiGCUJ2}1BFVz7x`k3E)oI=7P;z|Rz zS{Gj9AO0;gK|)&)QHIm|^&3y-H9Q;7W5pii%cC+JES+{~S6-L@R$-N|IR;uMPXABp z6kjJ!mTs<3?b&`7oDQL6u55p&pM~;=c1JS&EqU5Q@8Zz&VQ~v@Bi$use|8osB3hg>naQ|3S|bUj-63Gqa_+5GAmt)}#OZkdPxH7NB#e9LdCShf%Bl1=UH z?a#QlSo|}x1q)KSRGMS+qbu~!G$>c^V6^qkUs>EjgG+Sh#F12uvlX*!a?)zNh34{} zi$27-_zxp)mU;@TY#=06s6IC9HK8yImkwi9fFEv9=;#E)^n5TnMdGOeer82bjcXsW zE53kD-FAtVVt#)5Ga8Myyj`Mj^h~+zHuH0QFb;H@yZ2EEbRkgvP?J5@AMb^@II_g3 z)^4eQ@X|~sF{=9G#LM3sFMra@*_J%*$46zzRWLk47{7UA5&OmTuG?8#>cy6PC`BzE{?TWXq85Sa3LWfoHrRsCW}?3Ely1(KkOjJ;Zi7; z@qJ?8un@{FwTGYs;LfIQncD{$T!@%=CT~o`u|3$+tzSVm%7VQGg6-e?9Eo(i@=xq=qIa_#fko3YyAyEB!evM*j5 zc+&PbbSukTXk$$9WX*_R`<2?iJT-nVwwoR%(O$CXQ5qf}dzbJc5Qyd-ZHvK}13kD+ z@Mv|J8E;^K( zAx{K5@ul5X@8U&49{Diq>=R>%Bv^MsU+Jnv=^3XfnLza<*uvyFXTQTto4kdsQin5S zz9u9*RQ8(8t)ub+hwMEwLLT$&5NOMZFrlwK^PS$iFeA>K9UKNk!kNdB+bSlvt*l7v zYAiEMr;t(cGk99nSr(;F=jZ3u3!mPz{8U0W8h$71{^qdpyD0AoS6xi={Eu(r(sb3v zoG+%ZIw&xkI?Vd!bZc@{_CD~QBl#*h6V{M2{@6LYTRy>={SjO>BIbv>@L>{v}l3?Mh~MMZXU}q zRqsLTgZWHCGz&3<+Tq81uYO&k$TQmPlszlu-~E-bo56E|!Vsk(;WqS=S&n40${mbz z`W~albytxK-De$+(0+c*S-izNDbQB~Eqp)fdxA28w>UZ=;nU z`-VLNZ9IfY-o+9GN>&i{tdV8(dSpaP;Oc`&X4MZW(m~Rm;i9gE*MTKpjDm}UuL@OA zTZvJGN4O&ZKCul}P%?LoK0ZqS{`qosVS{T=wakmZi$_K#<24I#*sgnNE4~d)`%f%F z$r-`dH$RCOS^W*#ZcZu~x%nHNFv+X?clhryJr?fYLUCzrtQDDEaY1eJchFiF=6eJ- z`@MX{CwYJ0#;snbCFTAlC?((Vq%U#b^UQd&W(Yx$V&D8cHo3elet9w7VqN{4X1&?9 zwEtVi_lw6JPlBWgU_|69ve|Jg)N%Hwe}{(3%?dSC4qi8$_O^f8W8y zXb~4oE$WuUZtA!+k+}kuL^QD+cBTHewTg*)$oyr}_US)R$LjB?W}bRzVsTWs7iLH{ z%5A<48g@nwFc#ibjE67RMH$|(_LZts^HJ14rLgjzK52Y_j`(#^4bhZOXwbK5`~43E zup;jkMC=^hE4_Iec?m0w?Hhf(n!dTS^ZMH9iTV)YxvS=z-EPN$HYr~d9UX#ScLE1T zIio#>`5GD8^fADHexrno%PJ5B%iI0onW?`Q-eVxo%x?6B{k?FV`l42DXQGnM<7U|9vzb9Tz{NJH^nHyP}W}!+}!x%$qk=KMfUqa>`b0doFfT zmuzfSJq9rV|Y zI~cS*+Zd<&F9i>BQaal7aql$E7ho=l>#+Ch5t3;~aTXDUZ_B2&6c#cU@6(TSavUKd$iG&PjG% z>x*xdxIZ)dRmTw;e)U>IBdeg`nHElI-dcs;FCl2s51_?j{+a^(39B_6cLbJ3nsBWo zB;3J6ckq0FJtQI|8s!T!c`RI5R74S>M9>r~5rKy4TX_(-hn5dD9(#*BN-*4&_S~aa zQ`^zm^9h`54&Kjo`;jwR(352!e+U%#vjH3FS222sGS?#p30N2p_aCs_sMqzS*V?X| z9CUo?`lMEJ?)>abOig`!+N6kKevrX4V-!sekeF{&Uyz-jW|1RQY6PEWp8Wmw^P}34 zA#?P(%JP+VA4ebSz|atTzpu*etWMh=}WLWE=vrH z#r8I2o7F8$g7{E}Q2SXlI4S(1!CSdve!JrAUo& z1Df?0FBOQKLx!K58^{P?K&~^e_Ab6=Ep&YVnaWa4u}ZUwqNp&cUED+&^;rb?-F({h zNy$0)_VF=MZGGX3?dnoG^eoxj+q;7Y@SsV>%E!WR4-fVX9j>R5_wL>6tw;sY#NB=O zDxoko+>mGek=_nXk_*#hCxO z_ML@aWP!AlI+VO_*JsctYSWAQ`hGQncuCc2J)m)~;WI`V`BBN#GHR<46eSeKbAZGJ1OCp zG&noyoA8{>;SNPrRTbWMO>-W(9s;Rsq4zkTm9k_2op6`yL#*I6jygNxQNY}v5K|L;JnU-s=Kp^rf>F8G|cx#_Lp9e6YO9bX#mPeg%u>`d-eiI z6~kTi)G%ke?6MXQZ_=Pq7394G-x#J7`;z`5c~oGLL0ODdJ=^otY^z;Mv;^mfiG_-V zPG3|tsM7jS{L4wx+hf5U7Hd*NB=nb(+B+_B`!t$bdjq}fP6smyGU%4mQb31vgp>a> z6&yej-}E{S_xrz)xu3BAC343SOT#r6fs)|;Z{M(B-(C%$~4dO7-DxA!_8 zeyQ8k0s#Kc6V247?iNluie@rrKgshiZvu&)sGR#xP)$06JugSU`U#!m8W)dCv~ezu4bpm`1be?CU}+ix8~J%b{GAiMHRe!px*Sd493) zWd;-@D81xEsJu#IpT)TqqN8SX<0T51HDHV~eyOQ#Gvv7+nBBCnPexpu;|N{6z3 zXXU2K(Mn9F0OUfx2AycMReSL5(e1?d>B;H0-ZD1vDE7FAK_++AbKfT%y2G6N&;d>r zfh7NpRDhj@CgG?+yIj$KGT!0967JWqr@ou&jk=y zdHE}AXRL)HdY4l%@dy4*mJ#n~!^26Y-$Mm;&yPG4k(b~3tj*;SN@n*=G=7)xe6LWi$mJB{i9+mg_=Hb;in&{FBwk{c zu1w}^0Es5?xe4UWu<)i_hR=Qz4N&Vi{e3pGLdRCGm-()5;eGemon!rd7D(c84jbACPyknS~Eq1?DUJ_PaZ?r!gJiFPSa zdV75?`pvH04*xP!P^*oieZ+3DBjXwD-# zy7r6XEs8zs0`?a>JJYlb_eKDzwND%=usb>DIX>=NV3eUl&t&PVH+wSUtb`P3|vt-YDm-n4|sU z=4xLv7BTFz7<-8;HEBFpJZ+|F^xS7Zog9{4;gC63#Z#F&_@b2a0XM&t9_OL|Z*ZNN?Q^?Ww-Fe6Ow6=fO9?+ONKhylV{5wpb!WO-Bm{6PB^M-g`6M@yi zOF%Zf7YZkO@|WMG?G71sxeEtgglDMDqj!%}}=kFooBdqeh4)6<{$0`Coc-BMP@cYgXR zl#FfuvPW53-f4bhMfqf={9W(T$6{)a-Ns|&m>I?=CW(a0Ur1P3F<~-o2)cZbkpaoH z%`NV*{ML#Gw<}G^oE8ZLv*9HmTVEeE{YHZd{j{dmi%gGY~JW3EY{W+pJDZze$8 zF5w>XWdsnTlarG;pP4~$(-9=S(Qh}VL9+w%!86EU*F|RdX__{e9tRNI>Z&)kM<^7E zBcwP|DaZEotBDX(En?`+c{}6vi*uYhU(@Zk^(|)SeFkHeE!W3o95>ekg2TV;&2Y42 zPoy5H>CS%jzg)4L&$!yLiOulebI(w>1+krj7^$;L=dlTAe7HZ&;ldY`*ZfT(HGF=I6 z>g^UVdZVu-C7V3lvso1V9~_Qy z0sEQTO+_8lfRrFM%8~bsL!YM~&=R2mGUfyC?zlPwWTL6;7a=c@sq&rC@k}Iah6psw z4TSP%)1=aQFfkfaKuEk<;>r$m#WJ$+Dt|%KSjsPhDrypZT&z=OXjrx`6k~g;_W*9b zSv9VXvDBaR(^AO|(?^d>rF(d<yDQ z#A4grhhGxC_3~{BgA(I@7wZvxq;Y&|jl&T^SgdzpwAz(->A955dw4|h@yh0#e zs+a9mm^EAx6`Ek5qud06g&`CdD=~xo6fMlcC9#xWhcZ~^`e&q>fds@nt06iZ1Q^WgNBob7a)wxQ+1g}eK$jf@lcPX zd6==V=vIT@2__XLR&pvev13-@k2teQ?~|fX5{`BbZLO_%Ztm`}f3pNa%FR?}fON7Y z&Un3iKxA_@;-&R`hlfFKZdg~VEO2{cW-?OvZDiC-_jTjGrBuj6_dP+Rh816$wY-O& zUARJ!l@FHZDRvxbd~|O+^_$M<9W=1mRhrh|YJ27PMRrTRva+YYH(rp#JmK)X2TQn< z-S&*D*$hs{d5r|4$e*cwGu|qlOx9_zgoJn&2%Rc2dGdH~?i3gI140)gmr?6+0%FbM zM=>@q7=L1Z$75g;f-`v2lN8wH=0PTQ1#i=n0Sx)Jp?wN0nCC>*B z(mAO|K2#DWxjqO+y^g7nVEh81&<26!Y7~O8;FpO=I_iMy(Cm&|tmOqNxs+oF7G-RD z+CgoBg zwucp;r@N>_iwi$F%`|t@>E6REUohE-5J?1qx2?#gEx#ofKk6 z)CCI91v|kR7aw1KoC5cN!);|Q=}!Wk1o`jb(TO^-GSEkDa&)2w2aV*ldwu7asaxy2 zif5-ed5xrRuhcFU2WFm@VZMFa&tN)@fdY-}-0Z!zrl@&+px^_tuC}S^-W(BfgKFcY z!KoyAsGSjlQ%JhY8DnC1HI1%pX_0|GZ@mYqDV1d6(IGFxu6x1q+vDd@(@iMeXz?!% z!<_tJr;)4T+M4}u&4w1*S>W(J7@kv4LYNi?y#b5ifRIZJy-KocPfGR^i}^Cc zH4B~0uvwM~F9BK?gba2hS$Q#Mkf%df{1=tIe!qK4oP$?ydge&|TF=0Mz@==KI+&{J zBf#Tw=~80iT%{1}LR>{$qw~}KY7Dy*(xGwreQJ}4_z|>wj{ND?`FFGM3PL}JHv6Z> zLGQoE!owql_mD5{LM2tsu%CtiRx1BN1rZs&O6*|5fUw_Ot&(q{>G*xO=wxrG=($Qr z^z~yy_B71hSMIbHe2?7U8~9K26%2c0qAT@baQN?o-|f9O`wR8s@puLy0AP%}nLkH* zNNdZDN`iLE7Yasla`>O0Om#o%%JBxd*UZnNg()YK=S$qIv+<@F{gbuQ_?+RXdt4Yatj?W zM9>*iQHYc$mN6j#C27KKbS7WsgLl>Gn}4-N$5qRVdPSo@CwJs-g45!8IfBGSG=#Pz z58=1Ep}F#&;qQr|7=SsvDmJcPDilvaM7Ni%GsB zE(C`=teA52Ee-Shk_=v}qr_z`(MUvwEV5ilj4o;uQGP#h%ed|)h#hz!&yuP)a9SNO?!@=Zrz5CXd z%SU-nUZFkrLO|dE>~)&R*EMqwg_B1}2?z*^{ltHAT0C^&ur2}Y00mH{GwI23O__-0 zWeeYJqop>0llt?IYML`>%9l{AlRzw$k!DDGlCiO|H83s@NQg< zPfo6VYnvfK3duDvOgf1B{$xI4Wr2uS%Qmry>&X}H6$KBy80S1aIc66vpDr`vgY@h5 zv7^1)n>kpgxG>dKY)rqWtq!-0TKI~l`~dnlt9kMIASB~7_|y8QxVdtDKx+<3uK3n) zP58$h5b4U@H-=Vk1}Rb{5Z)Zc&d!>+*KmbRK#9{bGE$FB0KA$nPZtQ7UaC!z%{HJN z&bnp2=ZsojDATB)O*GhNog=^uVlGUoK}JX@(#HA0&CiH$B}KOIh;PF00DU|#+Zs@; zqCal;{Dhk=5haW}pB^1C(MDJRKbxtrQa=QYXH<+ABcb#yMcx|la2NPR^PYwYN!_qh z8epVCy`PG3U_RC@o&-E>&EzbbCtGZ{>|o0EYCEchA2i2IEaX|#j77bk|G6$qi5i}G zwcL=?p;x>Gz`9^r`D0}< zi`KAI+o5&%!k(RWw@brQLfmea30=OA#i}t|pYG1nJlj11Tn~4Mh;;lug@)qaK4nY| zo4vlqAJ*;CZ}Q8r9!~dqTpbN5wncYd)L6rsk9i|2rs^X)EdWy>xhdjU55Q2DKyJ}# zzC5PFdpn%|a;C{gbSVAh_AGh(lb}7~xmmrLRpjK<#|wonZ?(xBcTFwquZ+E88KW=> zY9DOj?lc%h;sR5C2dx%q;S0kp{b2*4U(TER)jMm<}BVnL`#Ma0Fw2zN-5 z#cZ*%-hZakOG#FILRqz5oCX$EdB6)gwne-1Djr&6mH3GobT}YceSTl*#baI{qj0iF zCy1eiMtog96WT>jR#DBEI2$a_q0A>7Uq$5>^)Xq6G+^!h?B9)H0zCaP(=-7a0J8<$ z_j<0Kp-%{7oESl5Cy`+I-f;QCw;Sjql;T^s?*pbNG}7ZnY)dHnT~ljBRJ>S0*4Pw) zM@E4{4cL+Y8G5CC9|1nJKp1UQ-SBj6?Ys7_wT}X*uMF<-q*$46I*;f^E96A|2S?NW z0ESVeV==v*g#<9|>5M(1W6jDqp0;0rp<-i4dgTD#jM*ChE#Q~6-THz)@i{-V8hAbY z3$OzBGIE^#algzLs3Aa2ISA1zE`}?{C9bbv2gH<=@3^c%7){TP`5@WW|7cbAwTOCQ zk$QjuIcQwEA_GpNDu!WHx;F_>wZsq?RU04ZP9DHCM}|ssdt#H49v4F^yL5&Yny1C; zO62@}xzVSuG15sSo9q&-Q?kgHaLi*5nDWt<^n;Y$UuUc!d|}Y6g4jrtzS>S~Xc9~E zM~7LRXld5Hq-I0W^9{>KsfhxG#e0b$VuEF$?Xt@ z-~uP*SDja}ybA77L*xL(IfSB-&JA&i}gcQWp3?$J+8h4 z5|UAV5s`H+PXKV}>SMx!9F67^V!G!kN_s!nMO}%fqrFYXFf7|u_*SUxtsL`8~qIL z`BIZ-B9rjX*(!#_TJs0+FVu#%S zjNr9KU!8yi<(OrZ)$d_dvgJaNp0-wDw4U8a1*z@YI& zx&o`+gzi5!fhkF=?Jl9&u>$qdJRF%_Wnk(G$Sf0_{`v_mt-Q821(Y!}WAi)q2W$%z z{(1MxfD1+`4<2F2)4<%s8y4k#Ai{ntJTa*o86;MHvia!A6R?pdOgR^8e8cIMo?Cny zu-Ve9q*9F_SV9RfwzRC^H`aD>_ECfBuS1-aSFEK**?;o@(m1=Qs9w$fZDOLR2JOsw zc5w;xDn;nCl?M>h++>Q7URyJkKE0qz9c{)00@3W8?Cc;`BD@vkA4^?_{i3E)+b@He zbA%jy`aTM^p(a!hsVm@EKhBudR7>V_acRoZkp$kaZy6t^z~oJ6Aa{{|iw>IJtd?~{|`BIksd&cSn! zBJwFJ^j&WQ*d zUQ^jyrzKu^xvqlww_h`Sp~aFezXI$hc$68L+%s>xeElXI27S)F6E}7iNOVo}@L}Ng zbfW*A()(|%JswV%5=@uh0#pjTvF^?f0Kx9T162p4n1}!J&SfLb^Oj*v`M&=R?!#XF z2BaB~%lGU307_-+8!d(ug7YjyHaHZL_m6Ux>tj#0&{15H>$foqp+hg_IOW5_zpMU! z0ka065)B#5UA|%0K;Gt2XjNV-yA@of^`EyLp5#5Ibn9Owj7^ewT3y5t471LE{4xrZrWcm`!%8VmO^2PX%lU$+iJcJ4jdKcwgy;wE8^WX zCI)LVIg>*_h5Bv@k3E{6n##}R_W;1CqbiQ{7KTp|1b~6Vu{5yY=EXb!aXLE{eSZ-! z;^7sWG>Yu*Tkp(ObD!@67KC0$x({1H$dRx^a_CX1i8Gx>Pikr-O*T~SE>6_Ra*nG>Znw+>1q0GKGF@zhe)4W&Oo z6^p|K5KjBVp$~vFyHw=0$&KCxt7*qhk|1KWX5bkwH*i3b zGe`v6_q1PvzJI@M+#nUu$@bQdpJ-duL2YrvIc<_-k}S`cxbk zX;>8;yw|YgUOz(Z&}u6>zOSm9=Cs24-#B^v{4>smRdUOe%v8FSM4KDyxXnihD6{7F z4fRjS+Kee-^SKI9bjmglO53C3;K`3LQDEXG!O#TURP)RZ>#Ag?e#v4`W}rNAt4Kbm$HUo?{&JOt9z8`ZlZhiVp^Uz?T1tg(KSH2&!EV>w`BKe>!0nw8L#4d2X?4|?DHc)Pvuy_u(k2KDxS z%hi0#Z{UD`Zu;Rj;g^UA=7*ozHs&Sv0VgY7z~$v-+=VX}KRqM+bfoY*>xxI8?`?4k z0nT6wlUM#;aXrSe)z$y9ZoZZ;&u<5qQ_{h9(`vbD79KF(m!BeMCHv~F*bh*_v$IK{ zEnCrbDivd$8SR=o;_q|$MQqAlg7`iDIn+#$V{%5Q%T@sq|r`IGN$zN}dY(-=YkQ zSsyY1hS8zV6PMa$s@Vv@8s>Uq*_Z!~x?$UIv($CvlX~Lw^NaM3Ep8x-Cw|9f_T0`M zFixz(5uOf0`#$CA@-!|s5SCHQ6m?*(3eN?8+Padp3+!>nt!7L$HbFCO8lsHhmT z6JK|ol9j*%Jh)x$jJ!dVQJ_TF%f0ef|p7zZW()%ow7+xDf%ud$|*ak;f7hR zDwsjMNRlph?*#s&`4^K>_GO?8fj4aa>wm(elZL(#Kgr3@z6^I&!9sTT%cGS6>ReVN@B6k^yvjyOUkLUmd?^LU8SY z)x=2}Y%Xs$o(Ze#P^J2SG_}D>7n*bD5n)bFPE7`#?HByFIFot&9^;nV=e#D1{;M#-Gay!!xXrLi|Rq5fw?z|o%3`tu`^;~JYU%U}9r z`))V$2NhEVyr{TNW0m5qb^HCz&DMXdX7s04w+4%kj|Oy&TJ#M!CFQ4x3okkBtBMm% zKOQ81`}Vyg)Q$+y6i{NPJ}fsKNJ>=;51{Tvx>*CT!Y#ObFQVqSrA$>V5Qq&`eQD`) z0BVSZ&@a_GXK;&iYpYKU4wvT(?CmqETszV5_Xld*pOo%;Mz_2&;b!#SWL}eiUnqdL zf1dx{;Fpq0J*gjO4t4lrCbnxsIa=(V5lujSQk3#Of6pJlRS=xegxBv}hDi-7wS`!q zjpT4ybT6q`KN+01v9SkFm!(|B8d8eYfYV+f172`uNWXU3Q4WraHw@6NCEYZeNIk;( zJ+o1dE4iJ;d90OSI00L{O~{!qW1cYzak zp@Phr;eb>IS*4qHQs|~7>I5Ng|0`MY4gk2Z7hT$(pVzK*v+A>f3k%!2fsZXYXW4>U zi)xC`lZ$OXb81)6k07w}ctRlVFO=s1q zzaGE>kDT`VH)%vK_SVQ=AHG_=)XrflY>n&z`jNBR8Y2tkepmh|{lhYGjC3J5 zlHMR82#~CmQyd%|j!HyT2J2qS<%0%2P8)|1N@Or1FRh>D|5R!&7)14DBe-yq!?EfxWqbU7r$i5NCz>-M{s1y%qBR7dg{gT)tKm5dAi& z4n~A&<-JOXY0)QL-q&2PmMDq9N-e;^8GPk((VIk5xac6R-4z|*=ToM$@n@ymal21V z>W4UBS&MW~BT~dT95!-xVubQ16b4yUCvFsow1>Jk^Wch`|~ zW_GpSeFKvI_fCO5VK+zg%=_tGl-lh=g~!_w9dZ=Nc7MRoKA%|VwF%RZJ7G@1&5K&cX>w|N7GYagL)R9U>hr$5_4TKQ$+CM;I?)8?mNKBfz8KGgH_u)Tes* zFdKLp2Y7KN*We`w-q=`&cmyZPQRc+Hv+eShwT-oobWSN}s!dbJg{EUhWj^-AOzc{Q zI(4Jtp8=&|x{2(c-^}$_EB@tSVoOKXtIz|?zMrVZ#@}I?j7!8)GeQiu`2b+L2%yQ6WIjN4 z2zmP?;+TPLiA-n@C4V=bukqf_P9A9ct~dOzITX9Z>dZy`Jbo4H0hkIn&4KxvwuJ?H zQ{O+GtrGi-)%Um$opV*oN=rJI$3Xc!OMtRv?$`qKOnl8}EVQ(=F(PzG1s9xS?TSR{ zQxNjIpMLFw$HvY7^8%DAy?gca993LAP;Pk}Z*`rQnS-ci`><`&cXf@=yfb_|uq!t+ z^WVrvUF5dmH?zCB+_A0Y!jU%*K6h%Fm_!(udahPH7vO?E%m!lkl;Z1+Hiy9E2m3Phq>m3{Y3chDC4O2N8nQ!Hml0JR<^u2>aM?ANI zN(Gh5?$!2sZuaOiU?lJ|wgN=M{U@7EI8fJRjy(4L-FxOWWjJfnezXpL8s8M)AE4%Y zBlqBBMrXI8rG?R`#z78{kS=gI6DxRG3uuMIwanGQ&DSDTq0cR>4R8a_PJs_UlGZxQ z>giDf|C_+|;AVE(@OD6X$0HGE!&2J_t+q{jhgbK3A*sk*z`PvwsKX1$h96_N@Dlpa_xbWcXKOQGU2kTh zD|9#gev?%MQtEOrt+W(KM-d;SQv%koR7PN z0%y7uZs<>q#h|CUxbuu*fH=ABWyR&mIyogp`o&v(?8CTOl8n*Z z;OqG4sJOlK=gZ5h1?VWSRj_eze7%I{y;Gd{V{CH*?lR^t-!0z7`cuQ z*&wzmAXoMK@$>p7a#}dydVVxZ>Dr-RpN{N}KbeUH4TO*1Zy*pkPx0YFePEQu0hW@U z{?*0?<6i=XuF!9wBUvi!ZnWOvM5+PHxq;jL6+V4Td}@GOogYfE{B8gMGL8RDDpnq| zv~y<t;|&Mrx|^V>tGW)P zWPEXUc4im91lq(&m{?QZ^Jw5fiADG)0m)`5QKO33^DgJA1H=34y%+GhbGLgTCnpa% z0E=19m-n_hAD!3vi5MT*g+`AK8;D7_JiUW8-dcl~8#NvzbODiC=vc`hgCNYWNY&&c zLUl=PIG>bMk8dF@p?IWXq;3|WTO7ZnZBC3 zy4#$Mx<#Bs+CM&Ib0_%>m{%FnZGBE>&?ypKf|8s2dh^N?ayH=?KBYB<@UPCqX%}Ax6R#>ADVD* z*0cYeP3*xoRml8h!}>>nutEV2pU<3}*xG5O)_XTq-a^ouG6M#;z*J|cV=n1q2HA!z zi*Z}JoqbIU%Vo67OZFck=sV-vBtQ@)xCFCrP4lMwL)wz%4VC@z4j$6~+Tkd`tf1lV<+ zw-gZdt#_L(p1Dr|Bo8#$E?&sXbhT6vcvs9i!_Ky|g_<{29;-(xQ#M2{EPPp}D%?_| zkRt5?Q>9=nJ-gH+y}L89t5P5cgEvNFc6K(Ond0H$;l7s@Dmt||v*6$9NJSt&vUYsd z{O+{t6$&JPknWGQ*v38vjCo;JmSZ`c`8)=MLXSGp)J{SO+>7&>lkP($bSCGMGCL@X z%SldKk3Q+PyJEa~!&CbOak3hG+MPjvfDc*Q0bbJnBSW1)D+q+wtn;LaBh~@+o#b@ z(?Ihqv|lgy5245Zw~5D-3*FH#iXz# zr)RK?2zKrUI;=~FOC?RsB(XlgD^dR!yc)BPt@R-VBJOF2UKCXj7owrUUH;Th%mQ%0 zM>2pp6jh}W9jNEj*jNMg9;=C(wHjk2xNqBi5ezP<6O<7!320kPZTeIHe*oLOD=yA^ z??)DGLh~zwPC!KiAze!AjSWWKk&!w+etwa45%IuIbREz<0d$G>`nuZL^unMN&?7{L zVq02hg}gwYrVtby^!;(2>%9I1a;Ni)3z%!Esz$g9-emi$`6n4PW9Yf$zf1V?US_Dr z$QqxRxbN>@f7TAn9c0b@Mr$JbhfBD3NE!3&JQ2xG4>^5sUM)YVjUn2(QDzye$*B)S+`Tip$~KK`3AEaxkG z6`_}L@iXI7J&hk;Lp`d09Vq$Ww5~S*K@Q(F=iFm!Mdvwxkujh!W7SoZ%`Mxk;Uu`u z!!_wVt=c({@geX?)hBSOi92fXd^>A9Q_yXmhzi5|BfVcLKq=+>yp2v`7!#$-XW6w9 zTw79Np^}fUPPf};lPysR_`ct@v@lsoYjs&4!3D%O_n^3NhvD|1)HLP-Sx6z{QvrCJ9Xcg>l}Shz6|rV;@}C|tSPC8j?! zlG7(Jw^rr1Aic6lA_A+ACyX)&(FS7LF5u z*;rrG`3dCcC~IyN9=ppBy)eD;cL(6&78=e#1C8a{yTwJoXbtE_?yMB=+Hhy*d@*Z9 zm6SN6Q1BF&U#x8k$xn)$XCLEVS^wKvdg0{eT!v<*=|taRg;hw}*uej%M_2>%pnWd( zJsqG6xivGJ&bk3eREojIdd}!&``7}^S~x3Y0)d4XQH5$MMS2I*jyWh_!}_|&hIA?Z z36V)g#@OMZ!@O`?M4b9uiHJUb#^aX6yOvQuGCuN-EEX2jM#sO9vOVsKleX0#b6r}4 z>Q`rTHQaqerFnoUQ)8@bJ^ki4^Kgs7NO9$ViVu|!`i*T>D+7ujjyr8hnCPrl-T!!h zKB}3vxbC+U9JOxKYkS}*Lsgn5Ydhojais6A8ZDk0)OvLm^iE3LtEuOV>g+@Tasi;l zwWFf|(5klh@PNFtx4$p)y(1c+<1fV>-xDarlkP+GZX`ZSk~P4<%o3f@NM;;Bf?e*0 z`TpgJCBKB8=T&NQ^?%h{1+fJ zp^SMC{G4{&>BlD~#!mZ}LJOt7^zu^ygv#>%-gXmT45rG_t;Z=!fC^Vn z*e$LolQgm-zM5~(3j+qamutmWY&wPXZ%wvAfYm)gJz-$<#>NAfl3gG2J-)k&_*5J^B@uu5l*WxApHh%(N6Z=+}wB{m-7H61T@+cSIJs_i!X=p!UsM+KFRoByIix# zjP&zG-vjeyOyCRzP_KP`eOB|}5Ra*IY2afiV|M=_gn$s%ALp8;OiC;p4u9MMuKfDO zMg*`=OpLt_CQu}}VPUe#sVW?2D?$-KPp_t_X$-)CgZ6KKN>Td;2EGGW`)Vf@80e4b z-rnB%Rv4@M?R4nPCnQ!n+Lh^%g!qJ<{B~mdzP2F$szXRzSzej4vNHU)hwR|#Ruc(( z`_H&|c+w|T0Ij#Zy$uF~&(k@IZg_w&96r7hTtvU>$+Gm=DF>aBv%|O9 z&3wmyYV#8TA1c|7z_v4+{sLJ|w$Gb--D17X;GC`0@~nn>&W#nmr50azff%2XU%;~VHp&~Yx@^U3@H@(yNBx{wJ|KMU8 z?TxcDhMeN~H<#N|V}q418D^0g;3vM%pLf6SM?^RS(P-V**UXJJ5r%el)D@%TF5eTc z2=B6w>N5Z&_1Sl+b9H5T@IRJOsu=wKneBV2#8KRjK%B(jGui})w{5Xq^w@JI>dG+|kVe!WH7H)oCo<_J>j=!$e zonv@hs^>h*LgOjA$k9eeBY+AF-M?EuFKYYDPuTA`{@QnYrfG%}OLV_Cqby2kGI|hJ za$^Xue>e_E5VC3>eeQz*j|=DYa(fq~*Y30ydC;%(arLYFs(%(azJ`iU6ym&gAb$&_fCx`_pR+ z-NB80G1~d~hVJ6eI%@1^U`y_gb}IEM)1Mud(U?ZF^&X98Z!q8=c@GrqJy3pca?Z)h zI$chOR_O3-6eKAi9^k@}k^B#l+dnjQ6|U21Yj5H10jFtx542*(iZbSlASoTj`$dzZCiIW|XotN< zpMeQ_qbE#KN#7H-rR7&B@y4U`Hyilm*3>XQQP0g`~n8&rC;t>X|L~# z6uW$Lgzjhj?Q&ISU??k1EOXNX4)Aq_LUSmKKH z94=M=+cfBa@RrI{z3NrN%O;S2!u3GtX!3?Ce z2yl}U*&uN$385fLpRutq6T%)_@2BOL$400S+`rfynd7E^?6L3@Gk}Bw85I9eSzvDl zG#%N%*$6nN8xKlWo!=bL;RipP{nHC8g$p zmz0iFz^`q8ppK0@zWk!Ahu?dB4M$7&ADt=;74?S3yX*Bu;No()t8aI>Dq0m0z{d^k z&dZBdmKvO!U2B5k9jYrT;FDOhFr-Bmrc|O_pD6~?qptTmgY2H zrbX($p4cE^X`WmdL-W4@FU(sHU;kGox-3RDn5N%;9t%5s4PKaE%`&Hmb_m8pqIddMNNNE zyVGV6%?v_a1zmOAt;v?!elMDCFF91x)WG3w#GRQ316XEk?M!fBYbqgjd_3T(NN)sK zKAum z)Wp-`0|d(k03pMGf(H#CnSgkkk28u22F_2^>1H2r(k)dcg>QhMJ^p!{qi}-^)8u}` zlasVb$3isOc}I*e>mESCK+;8blb%}$<=g=}U?qbyVTrF)ctE5b89k(iAWk)|84BYE zz)U@F)50W!QX)b^l}-^3A!DYl=IZ3j*OwP)zwpY(mpGf(fYQ2}n$OY$|Kc!AiXODA zpY^sfeDfR&4){E7O0NnPWQR+4&bYXkYM@?idCaqO#kbRdej2ck=r-F?u$(voB7n<> z1>jdAk9i`L2XA-gWdzcNT|NRT>OXZzXj_YZNEl?qAWyrA8-ZRL8t}S}$Qu6%F`Pn1 z;jB@+=WgxEJ`h0A3#1LjTH;r?OH=_n#Xm?Cz@nQ^8kYxP_F~IR+_n_7+}10gL@q16 zUHt$0RDU4+m>c`y*LE(vt$toqvX&5?~q@Ntlg~_%Ne4T4*!{ zG!?D=+CQFVTFcU*4kjgcsi#kJcY+W`>b~7=vR7VGkK@nQC$fU7)Zd|wH>Ox4T&vG> zJX}-MYs}6N0HMeT?nk(?RLz3f zj0^zg?v=$GZ1Bb1!(+2!05hOuxby*h_C4T{_XUoc@dlNEEQp}N&ug>R2e&NbaZ5*U zKyD^JGQJRWjtW7y0psc`;?ANoTC5pZ*IhhLp<~qRt#E`W(>#&<$S@{Xr7#V^PKjP<~EY_KM z9id_6QRO9PwqtN5p<0#=-IYI`b&>6lX8~iw{2;gVY7zX*yxiW9ioK;G4M&cf98p4 zcf;~;1^~Z|mzQBui{AKkIegR?L3GiBrFj1cMaRdeHTA`9j=^MoFIu+j9Rv2Z6%_)u zEoBW2+#y1v#t9|nxhH2p zFz|{+r7e(wGFA;n`YytkZ&g_Ns>1f3```_;sl$Z%F#p`1StldHB&v;N!HrvToUsAb zOlV@F`rorIDN0j6VoaX*r-1D1pIpO<8nQZI)741I&0raTL1Ia30lODesiuOccLztW zRvUiRjsVm70y$hNyKt{ZT?z4A)qo2eC~?u9b4DD)d&PGQOc-uI>cnpJ17_ATdW5Nf zSmBaoAK4*O%8~r?l!d7fc^n#7H%g(fpoE1bT`hmCZBCU4DxwNTkik}I(Mn&cQF=J5 z+581%BljHkrb+soFplNWmA%cBuwEyQD3J4*ZS3fbp@2T9FT&rXhG%H*4(~@=AlW{l zks7sTkqTSUGVophaU`}+}v5AZ|G*Fo}R594X}uiF(aS<{xhSw!!erL3@zT)vkK z1WtD>h6;Jy!og*_A2N&zX}#;Gr3pT@YN1mTQ;#pJaU)Tp>{zA&< zH9&K4pVsw2WB}tl2ck6a4eq<~VqfP)v9m+OU?8GB zJUpx}b>l-U*8?%bX{eQxsDXx-M0pspfgI}CT1?9uK;?OAvQszzXen6bEIIs00~zK0 zamrb#d!V|+N`A9=dt5h;@Z}ONFGD_g7ZzToUPQ!Dw*94nFW_@Razd~mC%ODksv&y) zBDUxeXh?=)I#+O2N-Nk}_Vs_Y03n?!)Q3lgj3S8$R!(>yc_@D+`(_eU9_u{L1 zEfzV;bM2?dj*P2#2A-2mu+ree39nbBDct4Fm4oSKvE!y8wQ&uV#5c1bJu@>pjY{1V zjcNKADIlDu2;(g#C^ z8%1>78`!%v;zMg6qa)+FuzcgWM@)*-+Bqp~XdwH0mrA-;G8sCWew&-kWx_Uu#)n)f zUQ~XrS3`_g@yT3Ye*gvOCpP3jsZwHYYui6FgB_BMnyRq)DRAs4;z)0I3!*%uflaGQ z*;*jDldrHdP%0NU(0iM@>%0@-$~YN6c!1#tidN=%D&T%Bap&8SZq!w!{ide{4-7qO zuDh&i#jlIFM{^nyCh1j6Qfrg2)lqOpsqvP!)Aaaj=83wfH z_U9X-w|Bl0LkPbzn@)bKt}AC{bh8l7{WPFV^d-+PkC!)**`up+7Lj^_9`(q~h;mg! zVGe2qcv^?zL;Qdh=-rz)upugwh~Vn3Vq#h0Kf+I2^e*L*-+G^&1sx$HCr88Us}rG( zv5-rq7^#ins>d+$`{j9YDgH!lW6A?`8oP?lgoM2b)P@U9C2p#$(kpkZg6(x~=J1^7 zrH?X6Q&cKQmq*b9EPcO1DF;vajG7;8DNDw{wjVLWS@r*1`SFDPwuC9IB03olDA6qE)v`?HAL;ZA;T#v4=W&e-p^GU5#9n&@ihOjKE91?@ z)DW6I2q1F>)RU2KD|`Sj888`R{>vh!epegfITIn*KA-=qLt{vA>A;B+Qi7qJ#%3<>pnh90?Y!1qG8|^KsIyw>ibeh>BO<%MOPR`M&L=fPv z6RrAqWalV-N}Pmw$b)8ERwcStP$z@Dv<#&3xeR!yE*_+o=O6DKQjUzV zLgaT0lvYTzNG&-S%6!%0eu7N2MBU)`=sJ+YFE1(O6qc~&H7>0o)?Du-+tCW)hCy1s z(ZXqYbq%h8#2ASzN;o&_S~Z?kQB0&{jC^?rvt1(8+=)`z?d>1q;!Z&*Nh^%3OmuOQ zYFa#eM+;mtRXx8Z$ZNd3LDQpf>LyyW6q%YhV9ES?{JiPYp#MJ3s3lNlO6hr5?H~%| ztE*}U-#e9NscWhHY)?H2rK9m0NhJ4D$oCa6U3vlok?n~KcZ2A2{) z8jsb>XwP(`>+g4m!v`+2{z$Y4@SXH|RPG&&MQx9-$_z4}CeDWjHckdq)xY*fTk2M)p z)<&J*Q)=KmYQC`j#{VPb+9Ri$Pf4WYZJ=l{bNozB*TpAIt?&FiC9SfU47d#ZsJ;<0 z6Ut8(e-WQ!yiG69|1Fx=9RW#1l^Qog#sF}{ev$xYop&=^DGRDQV1Ol^C z2fAY1HPy8x6rMEjZyF-X(bKV`ZcuM_=&PzRXr(2@X(ga3gX~S8%Ss~2g$on0S()j7 z&AJ(Z$ZEV;V=Hq#Q+AS*(@ikkZBEh#Yig&Avax{6Eb#sAYF7Z#;bP)FBOc`x%* z*-$cG`CGJ+OYzXScz1vj$5-E(B^A}s^Xbe~PBPQt?OG}kh^dq-0&(uOqdytUqACtX?B-E*!;RmmK0ezw(KP)oxHLK$X ziVbz!xS)56)XLdgSF@VZfzrcL(;Ib`MU}EyYsKN)@E`qzmOnbMw$F!_?B#lnX^g0D z4UG+4V6_-TpR3m1+xEBLt6t7DxP?mnp3hM191=FhQlyV#mQsX=PDs(i2xyh=L{ zXTO9FSZ7Tw^|7&SX+aO6I)v*ZNNTZ&Ag{PwU+_6!yc#Cx)EjdtES{oA?%k$G(Ty0BqxG%w%90E zeT9Kq1P#`*0zFqqVM_@oPTAPpUZ(X52QLc74S17W@jqJ;+O)Jc8Gz&pJ1wnayrtia zS9`rUIX$`i=!Rb-Gki!6n-RJ18tkXEv?!FeQ_AdK0yqKjQ;xsYYRwoa7mm;>(}_g} z{DFRYJCGLw@~{piEJe!?)W<^2JQ6cm25ZV$fPQOS={y{#M#Bvtnh zH*d)W<;V%BM@NmHU+1}13bn!1XFq2JdHo(O%Y{i6W_1+rE(%$N&)&e_p(Mo`o}Qwf z9@%G!R!%K%N@71Q(NQJkAduuAPuEku5|rF6{ zu3HVxH-Bj-EUPYAWc}1cWh~KRn4$KL3y1flG)4K6$jhrxxxZ;ngalWzOKr3v*#EZo z5o%6{2{+dsA?T?<-6Xcv_m5aEE-|Ks~0|Myloa0DT6CLc36IwbTf*5l@pV z=qZUNpcY9=Hz_^l@AG{e%){oqlU-A@2&T4V{PQdE$J6RgcF{Mo3Rk(EHqT9DL4K+}Yuw7bkgaOn1h zrJ)Y&6ie?BsK^7tab^egSJx=S)Y_E3eTu35V}xF_%Y9v;K7Xh$Ck`IGej&jRTu2QG z)WTb#Z{idfyIi`RfE<#+1P*RX`bK6rkBE#Eu-R+Oa5yB>j^;_6*3o;ndc`$P(G-ZV z!}=D+!&c2g5|Ov|tAtKfi{eiLm-Cm{7-K}0a%$Zrf<^pD6t;Ems8&EY((FS8w+o`w zi&rJ&WM(tkwLj}V&=pOn$-rz4lK1Xjx2L@fH>gd5KTU!OF1sy`K)e=67G{$?ayo63 zBfWd^I9pnOoGU(8(*_D#BKmT$Bkswkr%h&UiCbTKEn4H61tvW0Cih{pPbymK zC4VyxJ3uVPI*H$1z242rR1{pw%+``vTWETZ77~V*HH_H3b@y0=WAb@%n`;x9X40Rb zvC(?r=7yGI!6k?9W1_9Lw8n4a>E_q;X!U}F^99hBDM6O^L{GAGR(YQ zOyA&a9b{L&+`=<>LTq$tY`)ug`2{>)5aJ}|*K1G0fu?bGlgFqJ%z8RT4||utcvGNz zGxrvB5XfN?fk+nZH4Ox)aq>)*D~ln;CyRbInT9Y5kvp_rn`@Bq(bYUS_`X>a-xJ<_ z(AKVrnbxt36wU7IIl{SE_qd-hV;Sx5+e1)r*3u3_tzR%DN)L{Ht~sV{QGxkGeYbV) zSI8PCV2i0AsVlC1tp6oVS(MUmjV;i7s{3u#CG-RYro^FTYKCKr39U^aDF2Bb@kUDg ztI6e9>7c2K@a=8m?>xW#om{UPCo8X&%4c0_fQ zibfZovS}0Le}oaS<7ic+gbALZ5>z`^i2c${bz-5`HfZx_OL$8L%`O?UH(a+4ej%Dg z8#7|w0%M~i7p^c@jH&&rI)R5&Yb$2rZ?E6Z8zRkhu@v@CVwFt>d-Pd_D3yn!xl~r( z6WdP2sY6(1FFjlAJjq^yLaL;^NH;uLBwJGpijnRYywepQvP_~Xk;AdQakU6@SH4co z{_eUESYtzr=(F8U@`UIwJYvADN3~B~xen~`65-k=&4HP@a5Gz@j&wNeFMAn97KvU6 zx0*f-v&7y!#b^%nsd$AXntIeqgl3IF$Lw>(v2C#2Iu4U4AR-a?oJCD>wRIF^IeF_l zrXqw1J+0Vi4w}*D>BvuD5p?i$4E>cj%Xq}-+WM<@>F1;s>~=|B`E+$lapiRJ0BtPB z_iV}tqCn2|qt~9PX-Y=Qwxq~Qj1tTY0|k#TEkRsrahzZ6nroI(l*cFwW9$27p-LkW z<73tIO%`9laW!{BEqYB1HqDJYhP%sQ)4nRa@K`VlV=$(3*4~Q2IGf-~5w zhMMk-llk3OSiJmMGB&c$@cPc2Og1|1tT9cVZ=50TgpUBr7`2aRb%+F_3ZxPDM8xiHbuvqLCrFz)>~QnF5Ho@ zsNgm=qxb7$Z6-wHs9i(lvt}v1YA|cJA>g9^zj!}PB!v6@^j6^YRVHbE0hBQH&f7#cr) z|GD`$mOWU=K&AcA*gXr#A_{Xtcfb4O*`9WH`v9_SKNiUhBdahQNQ~UC@vg?F%`_i5 z@qWg-=v{3A`NmT;y$YyKgGWst`t}LK21Q(Tcj78ux(4L~5~oqXw(S=<|NZwL+&SyZ zeUxJR>m>>+{CQoJaC~W3+TUi+hYtpxFxTyFwDnhb0E1L>T*Y-B<=(B;dO2i$b@-;2 z#npa3g)%a7v&MUF@wIm9Do zQ7sTR!-CD&v*$07=i1=sT7PH!-52NzWyGMgX3sEj+`qP(0@){CMzr|QD(~kH$psc4 zMV|2~x{0GTA63`kf!Nc>+gN}zWcqc=K8gs;;dBR%KfHb2O& z9&u%sKQQeFV*U->pzuTEv|is)z&6jy0Oc*hPsjZ750_^t4!3o0aQ3yu4Fp(r?_LVL z=Ab`tDiItdSx*r}0v5f6C66oX4ork2*q~>3(6gQ}Kx}Sh6MFJRfg01K&IPn-Jzzn_ zT~$^|0tlzo7Mk7|;IXLg@e3d&xwmt1PTu01jHH323fx_i>M1lbi=A`BdyN>mBxoJw z;v1xzzioiZ>EZY99vC!x2CnoWt?~ov#aQ@Q27=hXp}TMf*E{wncuct~jBp^TH`}Mg zaFcNw%R%L;>9l%qvuE$i zItg1Ihi7Y+9mx3r+ItrWuY?3@Z8azUg8ZJ>cy_THp1kyD8C;+Nz0(5p!sWm<#uO~( zqO{6`aOK%DaqopM;WnQMMD+@h>k0iOH-lUj@`*wtLl2fNO`_cE{C@4H?}EeQPxYM^2Ts`YnHkz9?;6wfWk^MZxQE z%-MS8Z6A@deyNtg?`rIso6J3;Wjj}SnD>@%w)*n@LciCj>qD++;9pnm^0xG! za%muAab&G8!Gggc{wi_b-(!<*`(t##-5vJ!_CBtZ6wX=HvIDqbNZ21>Pb(JJS)%^s z?@e%9KV7;(?_bcg_iz3!R-GxX6!b3K6LHePYw45#{>cESvY2e+%WzWF``*EYPhn%; zHdwWc$MLHgd?m#qX{*LBD}&g^?8aj1ugf5@#XUEf1^DB*`3BQ4vASj5A$Gc5> zz}M5jk`a>OYo4XV1qE$34*y&>RzXZJHrPo9(|H>`8b#1e+!8RY>hQP)wTT_={AdoN z;dK(;{I9bDi^Pv!!b1taQLGt{$xjYlre3Ov0zQ!B zYqPSSVdXW}B`wK{8=PtG_5HWNlH?L6pu-vdGYy>nojA_}Nw}Rz zgrHP!6_RQG)fs6FQF?}bq{3_D_vzqztNzZUE~QU@-#dFuw#eg8BJe%MM}2E7F$)L4>eGK_AOzmqf-Z**hlD?F~Xe#7VPT0x~e!Vt{d>68%n_TH+Q1O8ZbZKHx z!HI8Yi!y#1TUz+l_^sT01s8#O6TOBp+gHu9Z?|?avEV!FK(h(6zV2H>o)s9b9>nGv z;RUYXa$~*pXV;xjWN0rG2jusWBHKt=t2cem^uH4Qn$^&uC#E}ai(}DKo{-^PhVNz^ zkHRWZRo7j|8G9ljRi@PW^VAi|;q2){Q%P(>FR)#emH9(pVvRN)B{_5=Ul2GD}pSCD!@|RGtTK~ir+mZw|W$`bkrQ6f3cFi{Xe+9TLX&3?; zxixi@1ap^1Vvy3{h z-XbTdAfKA{Fprt#8qQt$Jq^ikoIL}<+OKzibm~H44JNYSEa?(V2IAU$YuJZaQXa)a za0v$D864gKFTj9;&@IL@=Vzlmit$fIlLexRwqH{*dfPXDmdl@yx{e8!QN3(1D*7pH z38g%G@SILIfUNG(s4tvl_Q#hvU_pKGS%F|YLmf#AieV**@Xqa!bga&-Z+Myja3gxV zI(WRLW5Puv2Y|g9RB5e$55aIMbqUMsWBKTE!|ncbuGKqnHjnB)EFa<|cF?L5C9|5TK+b%alzDIFWB@l#b3iktG^d8dt`nO5rRi5n zji;$ypM5Qy6c^np=v?8Ev&VY%i~5$M0y2Q1$5Q+J^gw$=;y9fA9bxAsR;Y5!+k@~ zFDn%&&7ZHykvH?5fx+JRb;CsDAo57FQm_2u@xZY9oT0=&%eoAZam0Jw0NZ230U`OX^ee3F?RtBi==|CY{&ft z6H&!S8p9>z>%wb@RpjtI1Fbb7Z_=7wbWR%oR|}w@7?BIoS~;WAB$fOA4|*#h6IZ@T zE)`eD;Rz@Tv7TA@XhSJcI*9I^3mHOpw^=t2xg{eA!@_aVH6!rw@X+mQ?TOGCTh2!H zT?Pex5F0;%8a5SAWC~d04}?qCLEEK^^(>~VMnIISO(Tm340D;Bmt#={bOf@Bk@>04 zA7Hq)sfiw=#+A8MLhjcS7wqcSdN?;_)eEs9LS^&Rr5lAe(bGE-Lsx~AXIaHV>V?o0 zmrtP;YLR*|3aT`DM*1-paetqwO7~tOs=VZrqY*CxLNnw7YwEoo(`-<-ZzAYe8kp_6 z`|x|Xl^Wt|I8>*Dm8T9vx?PsHPLFb?X|-EJ7S|v8cv9@1}jXQ|%a}tOFg}_KyWTb#+vCrm`#dunm@iTPYev)t1 zI!v6P*?My2OuIwRt%>S<}HCiN?8i=ej)X+}11y7uZBo zAm8~{NzFt@*~EF9CCoSyDP&sMa7xFwyCQ7r0R|I>UgrmWwX}KaQz!- z&MshGGmn%Qsdn2G zd9g+k;{)jr0qGS8l5ZIu4H4e3+^dBnr&vv0m*q=pFsBW!I6dBGuYn~PMLj={b_g`ugKvduHUaPu^t9A#I)dVQfk`5=bc9m{N3S%yOMEnpkTpL$tZ zTYaqy$<3TKzgAg3t9&L6j$uLugZhiK#z~^c1e}-2i>qJaDb|H|s9bIAR_Im&ENa-j z$58*m>gIgZ=W-MQLsQ+;3RvFB3f-o2 z)CWC97dv2YJYHk+WCoAU=H9f)XL=K6Z>6qT?-v-(eQHpm-x*L>ZgSwpjEYXhOcTr! z{Zv{`w$hmCs_h~o_-E07`fcDyq(08hx>k49^Q9*IeUtZ5WWWUn@z>t1E0IUZu84li z_YAh6r?c#4plh$kB|y8q@;u70yO;02pvA~M8p7rG=OytFw#<~5$ z-OtMV47PbC8uq2vw)Vq5f~$L_^vYWPReg3wF{V#x&Aaomt`|#^@u0z{q;R^Fw3OYv zG#)Es@nI)Q5yOk>g$qH_s5@#r-y8)Ik~a3&(XPjNv6F}LoW&r=MJq**C4K*L=HtE6 zmKH}Z=|!WOfsExQk4DSQErgVg)wu=ti(S^mzS}y6)7iNu?-Stv`d8xWAm2L2n=>H3 zu%b(RKXkn7kuXOo_^xyPDII(TtH2VsgY11UXkT)(a$ICyhhCrL3_D?+yq#A+!^uSZ zFGH<&u9i6|v86+R7xAmW)-F9ow*qI~8>|caMu+8&Hwc%q-?1)`8yyhF5P`w#3hPR6 z$$jPuwmLydqxh#Iy9MsK_rYLea?My0*KhnW_tMEV^kGI&#QmCV)n=%qTOL3?AL#xc z07^l%zEi)R~AWsf{EA!x3}fy(X)hfFvUz_hMzzA$nB;Kgo?iQOy&9vr-k#;Hu- zQ9;P6AbQ*T+WPuBFTVJqP^@T~gW&e~IjeA*sJVRk3LdZcrGRKZ8x(iv&L=H3L^w8h z>v1p`mLgpE85rYuiR6jvRb^@U#&C@dW}gHV@ic{0X#j|ByKx@s8B??eN7UL zLzE1#_FdAfbX$kw? zhYb=-SP_(%W`(HrlPBz9NI0a-sBcHv$yzqZT&#@F(YJHz3nq=&)+R`Q%^rawj0gk_rpg&68?;6nNC6l z(V>bc6om@%u^-%2-^m<1nOM>KWxl&itka~LD)M+doE9QwWy%y)9zIQkxQz0$7gY2$ zw^gogD?(Mw=_-hBnf`ND$#a=D?Pk{T3B;-5nVy#X_9E*ajwxlk@k}XudQhcu6^&J~ z(B`&E<+FyTMY<~}8%+pZ0 zn*UIYFmMBwLjomhaq#WQZ&toe;=Z_2_K%+Xe;Q?XDVnsB*75w3f00k-dgrOqYY;5L zIdhh5VU0iuq94v+)WK74>>&2k!KgJJo;r+$Cpg^Q!gKUmdu;RXpBqD(bg_2m_ zbJ6)%h7j(KZCA>+<7(;(w=z$!nobm-W~Hp#1en_@*Jn71XG&Q$P(c)m65Xl@y=P$?G=QrU)etz7BKGuKMti=Pwh$6c<({Eq)Jst{`DH;c`%*}x@)`WZNreW}ccAbwb zdrRG6aap^>9jiBC(~enYS+i5Q{ad*@t8dkW;%?HP6fjLNi?CIEOrQjwBIpk+JazEa z8aJ(;>e1gvBy6R+Nif)W&!`=du{H1lUJX1zRI?znBV>cAf{+C{l~q4HZX@w-uioOy zcq3_Cll*F;`MmjWE|ev+n;A$nsamKwE9wuYh_`-qCv~w64I!;J!S$`eJ4fWHmnrWw zw==f}lCe#=t%zzOWgOc#k4kW!h8y&4w-Ug$`r+Et6^1;FK*B2PADC_p<=F7q0)PrRDvpS+JvGC zmAL4fB2%W!adFe-K*gM{;@bbT;r5)qkrPwH%EC?OGF80CD4fhQrK}>TAX?m1iJXP{ zpW*c2=DBuTCGEB%>a325|L&jsQ~ux&|1YmjOmJ3+sGIiAuy#$X z%td37m724C?eFLRKI!#wptpj|4%V!5mkrl8uJQU$zYM^=@fH5|^M89H=I`A5&)Kc? zw=T}iZ}BM9*ah5+fP=F^hP}P~HjCe1BzrN-pZ&_8DXZss?HWtk5`S*~g_81n5@jPm zhNzQ?RZ+hvWR8=HWBO^vZ~fcfl2Xe4;XnC9;n?{2O_HmJ8AI zZ0$U>C1pFFS79=Bp4@69)>{Kl4HBtYCeB~t_xHZn(H2pqm8eDMC@QOAu^!#%c;2*& z?IvlVp_q#s3GS6v*r;uMstKEJrEE8O)r*jIVgYjAI7iBJOh~4pV`TEXwy_VY57;xa zt>^6vXjhHr_)_GnfXQ0r9{=X>IDhaci@)tk+3r5z6!|%dN*3Hv%C@(;2|K0rS%4F& zSkcA)=DBuDDeK0(+73~b?QUoff5`7Df#N1U4N6%R1e6N$+U;DJXVoI~G;tP{va$rO z(@I&lRpO#}rd&Oncv{ZOsPnH~PT85r4EvkwBP(Tx#aUe^9~HKVN%BVjd8ftU9qzy{cGYY1IT<`+6?5^p?fQzn<)0neKi7^KZH9GA z@JHEmiM#caq{L1*!_~L1@^kAW=`x$K^>c&Ii3(D}i85DsARK#NF!q6j`tH^M<<>CB zE$@?FA7|yuD^!=n6l6~0#<^vd_O6q-pI~8ok$-pYJ00(z-?&01V!ue-#Lny{52qS8 zn~tdOhKv)ffARZ`#njAfMySkDkkI0`uRAd&RFH=NY8?g6KXC zv>%6F$E5q$el7bDuVDF^jfah!u(r#JgN-$U*I$LMJt(3|E76>ZDpXdoXp&#=mfqv4 z@f=ge6e%M`+(>k&02f$fskTI>=A3%=v~&51qCsxH-g@4TBy^%p-3r)VgsdIfkKd-b z%e~S~76Rv)_04d#@?48-QM3THJxtc*%b^!&M<3)5|jR~0H( z8S;EKI>TY*aA2GaN$SLybbCXH+bVHUxc!^v_WbXrO1xiO_v>z}#Ct)-{JXQKMmZ~r zr^$^{lz&{jxM)wxiW0Iiv2GJ}DhOFsM05Me?q{F4bpCl>`A=eYazA|O5-U%R?J0kI z%bpzZPR&r=I5~i=+0N%L?pS!wFH(JI-zk5d)@)yI|9mS(gBN$LBM&zkTLpX^Klio0 z<~e>{k56M(o-|(b9L2;eFdiR2*8sik;c0tK1N6tO=ho3{CY_HuVDcF2==todMKM$4 zzxp4Z$MmmJ(|3+y8nJaAwLZJHrnNqop0%)A<$=W`YHiO=8VavEjfK8iD-P=1tv$`M0uxqS8^L0m@s96!TxY%O-!!wVv)1wXdaG^2VI)P= z|2Sl&L)PEITm9cwv7jwNWDde(R)u44W51|t>K2w|QMXL#GG$^_kP<2g2^ESyRrU8m zlN=nTOeg#LjaP5*<@*h_?Ayz4^PQ#d4EV$`?mzblyOGV-bD3iz+J2euIjH`nou$^_ zPbQtc*6BWfA6qwhoiEwO%6uocNi`MY=d%R2NnsUzN9J7neLl*S%D}j0KYLC496z>x z(l_>!c8Mq4?I2WpVKRN5%*NmiIO7Y?k-aTORJf_K8Wu_KIFrHSn~7WdKRf=rcDsY5 z=~mG;iQ0w0V&5FJD(vJ`EQ;AJAjOS@Eg`F7v8TD%6x4&lpPBSbb|_`rv1e{`$9t1h zEq?qx3fK~FGK*)ari`$IPb$@{=fn%y$wU7jCOu-LC&M zp@Qg8VQ~w`ZJqb^@9#3#7%Il3+eEhtQco4pewuK5{#P-6R9HEyAY@gH3E2%5I~ix^ z-_uS7+ReRiCGILFjlcLvv9f1!kmBtja~@Gu z+yiJMHdm7xb9+5LTlx4nwjbkl?*mBndA|++bhYdJ_4-`(q5XTMuICXTbGz}c4c_RE z??&V(rb&(_06%!HU8nx!2Ka%%(ZdS_8}H+5``7ollfZ5Ms~^R90T1ZDSxjrKLCESf zKGROnHec5P&n2qd?IKw_$xREW$L2BhZ4Rpzp0TYHvCZe{bKqr`L)Kb^XN^wMwfi&O z?{)uM2V%^!*R~+p>`Co}ZF@ba{uPDW^RL^4d@sm+PZ2^Ej{Dgl zLbe&(b~tVIg=}oI{qL6EBNmO3t~Sz9d@1reQ>7`} zaiK!_;)E(z1<^68ay9I4IE@^X#jXMDAnJ19^!z&r-F@q|`OkG6*Ivh1RW5B6L`SdK zCkGo`o4qzvxuQs<=s)%+` zoJM~8)2?3yd3{zb&Q)9!$!@6d3rCAVhR{@@a+N91jzAuj&7ZFhq^yReX=u6y9?*2qjT&`*rA2=F0vdIo zYMF#$opJ~*@)7>hE13R6a+}u(Oy2BCa+VY<6z?CE=~i~c8D@Fx;sSWDg<`wcWER!W zB4paGLJ=iO2*{M_wwU|@ zF}PK`4TT0NIG32?t=gMH3RIazIVY6EqPE3ut1o0?|9bmxI_$5T->>_-Il1`gq(yNz zWGy;HkCo_LIT4@0ZzS;hf|M&oN|gh)^Y*{7GG#iU+#PkU_t*U=j@SSD!M_yxtg8O2 zg6MEtktGVZ$!irVS5MRY#!e(=*xNc8rzs*Mx(U#wYfCKOJUunJD1j_W9uJD?AZ0}ru`Z1BeF!J;Hc8N;(;0YxM>%%wI(}bS$rNq;A!~8^)g;qh8;~ zr$NoEP^uL07#>W5pjl+{I@*y{v8E>|9Aqe!EOd_!S^%%N#D1~B!Qmm5`XP1G!m`Gw zSq17A6c0_%EzG)x?g3xDOe}E$lOno*1|wVmt&Ry)J=^%h7W>-8%KCYndbv@B{?2`mq#N|B0LBvaTVwrGLnrKVK~$HN@@9$^K`=uyR+ z61vb%ORuvgt+o|`=mNORg07n?CmE<9DrFYG2Pv|4tQ}^UWt+^%N(>CL(`+YUr^cq(D-7)i?+fDh1&K$}xdQY_hR3xZTUO(wU~dVcNVH9lDX zfZWkU+^e6yx%d^{Tlwz5x>XS^XH~tV0&bJnDpam2>~K}}HBqQ2Qw1Ror%QCZonKh= z__@8IMCP2RICpLKR7m+p#VnO0>!-XH`vrqR`J>5+XpQl%s-W%0N~9S~!k%phhKF4Mch1PjOH#Qa3G1 z)e^C2j6>7FZGnLFg-QV$N}pCQ#X&Ti1lpaU%>Ks&^+AXPG!rx*rk=vm(hVX&YmknWS_;!@Py^*^4by5&K!vP_VzG)h;HO@TqJ@t9kTpO{ zV_JSDqZ)?yF4_~5gKU*r)u6by3z|jU4C3|H(f9NQF>HCL)jgP|Nu^e&RI;Ej!Qqxg zp_U^tH-YY-A(fm*ujmvjB}&PC%Km-0xc zZswew-kc_t9AhPMZ(!bBx93z<^Ry_bcvd%G$Uw!sri$ox6DsS~4=h z{+^&B>cVsE-MKxmOs619AaoP5c1qYLLm5o+6${!jXf6ubDGYP9Y>UuRwb0e9KdC1un)W0Pz<4yxc7Er?>xb51&obNb zZt1<2<@7>e(Uu^03bGrz2iX=UZHTa_9&P+l#MbsX=}D5*6CF8sRoTf6!mZkEZe?%t z_1bT?j(^HX^(0J1>%VF|$C9-~JR+uwRj~m=w9JdfMP__66w8f19@0ZSV<*xRZ0*?3 ziD6@+<9RxnV#mnvT;c_)hmEmNIXL+{)33~7(YH*KMhYi86d~q|QLdEHHI2>NTg2k= z*4w>~y$B%->WCHT7P6se%v(@nhvSsr9sw=T3}Cw+TVF zmEUfwT-{blyJ?ZH;ya~MGvuF))~95MOBtfGS6nx#8VQFxNZEdMh$v^9pO?vH+a!DY z+84_xVlP~{z=H=52F5vIJ0t^9@={7U>bA;NqJB|AR)!SbA3x9idXQ2$jIq6jnVLf{ z>@v3W1w0y53psqcj^^``-rJ+-_fbBql1#*j#iICqek{u(n>&OG)DCjs4^XchVCp6o zCIKC$0~)o%LyDyeMPG!92P|KdVzG!}RM;<@Xhwq|E!Sz-5E~jkpTChy)*HvPa_FAQ z5m5?gz7{#F>6OL;m=2m2#I)*|8dzAAs};~R44)5Q;ON5|L}CUOU}_MFLq6+6_gWMW zAsCs$7tk;*i)y_FR+v&XOCp{ipRH3bT4*m!>3{B0Zgq5S{=P^;?ba1 z)(GeZ_&j*S8o~M`=g!ShGb~oOvMgS@LegV$c#y>^L;VLY;=ddqGybOo&)=HFLhS>W zNi`LAmQRDCPF4LfvEAg!I%~YBy=1#;{Ipv{%RmLup^7}|b)K6Rx|!LGl6qmdT$r6| z*(?0`wU1gc_n-TOU_>b6f^_{Vh)O#wet(e+yJVIIA9uIsR8`7v(Ro6q{?oKGKCSvy z5Z!KDME8P;M2D07*naRCuS=*WyNkU!D3@rgrS}%=SZ5mENA$85(5ls&|zi z75<~`=TvNfkQskkRqIQ}HX%cv?(7|3yLm&Q*1y%m!wz!RX+l=E%tS0scK`UAU~^}K zL-Vk)aovQSgB_+8C-C?h*VH1%RfV1OY1@f*_qEe@^K(;C__V08zpJIF}Ekvl!Of}p| z>|#gB=PIgl6(v)fuXn%StBw8I-fUOj6;2sNtOy|sa&{In6Oal;sBkV-3FWE^<*p2R zl`C3TDLz9nI!18w3EI?oE=7Jhwl~o<8u??b#>!N& zTmlPfwK{0v@#s(~;`8~aYEY{dsnx3Z3@@dcj#VwPzk9&mW|le@xxFbY4-FF5Lz_~z z?cr&AO#{uN6OKekrN<~&Az#Q-EM*%+tYx-HTT^S0yynp&n#s{(TJty^sb|r3blpQd zkt7reV*v+cFtI2VEy80K^+FoF71r0+DVLyH)$texp*WxyF+!kuO={L*BfqVtqx-8;uLX^rSOshhvzD?Ah;#^{$KsZQ_J<$Esy(NrNiol})*Y|#x53l@l0FunI zE3nv@W|mFCMahLTx=`%4%G7B^ovQj}Vr58HH!Y%_v}hg%Ps@gYCfcow2dOnj!LYe7 zkJYj|^BeQrzH*C==~Z?kVg$o5^{XH%yWzxfe_B+ovazGWZ98MPbGfRp{a5jwRLpDf z;9xRD7Bb`Kn)f;nijBD@o}a;=u_sF{4QfW?QMQdZ#`*d4Tzs@3)8rGV@0p~Hak1b- zdd7yM$4arheYe)W9OPKI7!~L2-?*KLEBCw#f?NuIoO?lRs>Eg z=)M(rvqRClSWf5x{1m` zaUNeU>FG&$L!lNq3-;>S(?t9C%pK$!3U`C!^$`;utUV-<4)!YI1XS2byKN`xwws>{ zQbfg^e%erRtlcJ0RE!^)bC)@EeiOFaM4<}uUWLW36YW$nPTh7caC`HGioD4x=Jc~_ zy9{FPPMLCs>PA(lJg2OHyHPB5y8QGjv;Dn6Bc>TZJ$4VCLzgv3`&O%hJTn4Fv<9*<*sJX9(bsFcZN zvjnOotV#)w*GI_XA>#8g8;>v*2{IA#lL!Tg`n)6q24m3>>2!)-fKRhE{`m&5N$<iKt5lfR4O&jtF9kcrZw78wDz!kSt5pqxRyfq`tV2N=o4Oi z6G_f_U*z+<-vnUqXi;&H)%%Xb;;V?2aT8C|Lb01=&NAy-nWqi6$qT0mS$KLj1T@i9 z$*z34_l2NL|8ctiE~l6AJl|M3npjQq@#UXL6S8(l5FZ?*5F*EY5ZqL`p3huSvQa|@ zD&{rOGG*!(?dvMal)-6_2^I5NuIT(ih0OT5S#A4G88I(x6TNZ+j)Fu?{9I3@kBQh) zu0PQ<2u%fB2b?g@ci$fpl>C}{PY_ERNe*Ev1R(kfcJu`d4+IcqB zzfb1O<6|S*e`PRAneUd~;|GQJ$<-QTc_FaKHxu9F7m{D-`I)x@Z}QE=H#_?4a%q`w z72X-zhFZl!smwZ&2q7yIXNM*^8y=s)7Z%&V(v9}{w;x33)KalXBGE|abZP!lD~(gV zR>v&WJ7Q;}GkjtG^FrnJn*Z$J_LxvnzY|bFil~^=-G+*DJ?Q#jm{^%HArpI6;WkmI zf~Znqu`8<*cQOv-`no8b7?W;qzL0^6`B%j?{i(u^k=^(|;h#NhJiglyAbhU8$}g`z z8TxVc$3N|SEh|6o3{u2Gf0eEZH0x>BYk;`QRR$L>T%hJ~b|jgd0-wrUvb|KU3hb2a zuzBJ0c;abxaz*r@pK>n4#AKR4AV8s1VQo8uWm$x(Me6<_VV{?}ZjeZh5%Bx*dcF7# z_wWS5=#?UxrnSh%kY<8zK`4k-t6=Fh>RyXFRiZJ2dSsgY+&bBE!vfgStcC(s1L_B8 z9_`qo7*71HX%GpQDVMzjgBn{KyBL16L9%LXD{0!%|MWw2O-I)>EHug$jYKj;xuOw` z#t6s#Sf)WVmca5<2!tvGLm@1nRH8lTzrFl+E61hCcX87Wy;od% zYm)TVBs&wEJWMt6`kuD(+)YL7(_|4X+An0rgxf9$qDUpj$n5PpR=@1`J~uPR&_S+7*6SF3ouUgnPR(d-*JLlXL8B?0^Y+z|#@BmS0z*(sO%ExS3y5l|`uA7SX2(73W$7c_K3= z+$O|TI1;$65_H>Q_cZe+yKSeeVobU{SGk?b^{lG2?T{LqVZS?{>|cEc{_yX#y)e)J z#6$i|&I9%-a)!Yw@bHyaq;kA=!_Ln5w8&V1rE5zp-(2pf*W>ki|M%{|3l}bs&5pJ^ zI-AWB`+Nc+vuQ!(EBTJ+zqfAojJ5W~7GyormfX4{tCX$ z`+O2R$LBB15(@gzb)Buf93QT2v3FP`S1hwrG1)Da*(p|eQaHrp^fgs_4MQZvYUY~(K6e1Q2 zlN?Lp_51J!VraTSp)vuwPAKfh@C7iuLA<^IhHnhR@PihlUN7S@d>BRm!`pa7A_>Bg z0MTfgNF+`oF;03SMKU?b!onP>bc*Sj2@+#bf}s%MaDZ~POlBv~VKGlOm*er;8oRr@ z?CxebEaf>kJY-{Ii(0*g;kU4~D(5av5sHNH89}^8fEr~?-yxdELi1R7{T@OwKcSeP zSUN-^9mVw2$>$5~?(I^mn1rH1JU$ImKOj&Zqpn+2sZp($F~T1FMKCs|*tOOm(%2rc z%T|l{Z9dGd=N6D<*ESBD*nRTCTQBlB-+yPBb-Y}eGDTxAYnRwXe4$u0RuoQ@xxprH z>2L8P>qi4)WzLCc>=xqrltjyvIVLjoi^A#iJO~Th3yeJ)1K`j9?w?Eb3(>yr#F*F) zZF6b&B7tmxu}5S4=tC;NZG zgW5x>ejyqwdQ4>M-YPWa_9<(Mn02f~^LRXs6iRIvH1~OYKIzRU>12w-uHPV!*NYJd z;PLs;JqGov7&+U7%=~W`>ovUO5A&cyv3$sWVIO=DOav%;dhbk_jm{ABM>(IGZyncu zaBEHsV=y*+LoI2glRn@Oz?8-nzzmSriu=4tkIx92Jq{b!i#7q{xSgHZ=h z9X#gIzej&p3VC$v__c%8f6B^V|MrQ`{|Dmyw}e>WJ0!u8M=%`Z|2FOIkY}c*JJNcz z|Gju|k-co=95?^9dv6eAVtZkG=j6Gz%_*xwIjbVUxr}nvbLl$uyMq-Sjwn}cUQ?AL zc2tPAsXloTP4iIEedv`ER^@%vHLFUcS|y|D_~J=I zx{qKo&U`uqfFAULSHqf^YUFV>EHJ>*P4HNl9+Mh%Dz!49Sden9jHM-+zc`KMnQr7o zF*IuR8lLrC^kSLS=?TIm1Cu1rT@InIW-!mET6R5Xe$XtYXM&(v7+&L8RjX@Q8d#Qf zlsi_VZkd=Cl*?Xf^*sCe9QlI->ZZwlexI6IZ`dkZP^V#ZtP`Qm!Lco}Wi?1l%LH@^ z`2!-+9Gc|^3k;8kLAPk*@oD_N4B==5kH?@|t8=)Q0}VpK3S-s`mS&Q-@|YEa;G~bh zLqE^m|21w#{uP8zPF{1`B_159MA~mv?Hu@~nB|GXDj6r#lut`8K^ZlW+sa*0$eceJ zMV+X6N`-P(CJ*Lmt6ZHxw}q~od6Ng#eVkhseq;IX^H)oM?P&cn7$p~`6S-vF%tbuQ zEJbQ3UQcgLw*K9jXx!-6QU|W9^z9&{2vsrv%akeF*0Xq=dtp?SwjESDZ?wwov*T=5 znse%Y@_ev@w%-Z>GY;ylkC%yp<_`=NPG_RK67 z`ov}O#~V7jt&Y1<$yJy)&he=Bcwk#a`&uj-1F;lcC(u-lH&wF>fkhTLR*j3~ja8u% zRIyIfRKo`Rjohi#BSN$yNsNkOXRmYPfZyk*Txl$ld%RveUN7EIh*B;qtelmZ|LtP^ zem`U36uX5C=#Yx1***A#OuYZ1;#z)P>YS*W(?w%t^8?DnIz9iotq40!MXZW?+|Gr0 z7S+U~;%Um|dYb*$&1)*z`iDs|F$iww(iVjZMYZE&LdLN?Vlfk%X8lmDdeiEYWkEB+ za|pf?1WFJpg1-!bV&i$B2*DBrJW#H`+OwQ}KF64YZMM6+Y${^A)voP|)PBlZ5!LN5 zv7%VIw$#WeI|$dVT^p(btxasJBEh+gZLbI+3vxMERmF-zPmAXx6OHYapSH008ot%r zY>u5L7Vz<8W0R^s$nv8#@_Tz6tUt!u-GOX|z+oQ$;XZ-fHrnPY{zwEfw@dlpfMn%> z$B$Qeyt>N0M~`{9w#tKCfycQ6*7grsuLoG$FOxI<(7xDSW@p{u#YvIPDnxs-4 z1CpQ}?Y*$#V8+2pP_Ip3)_tt6uk+!DAF_P&KXLQsG7ld;WM^la-MtL8TCI_{wtkei z_9!uJodPuT&(a`eONAEH1-AUx=@_k?HsnuJ!_AbwHE>VbJD9^8H-cVMR}PrMf;Bod83Nxb~?5h zCqfR2_FoY1!^8IV<@7Syi;atjz*?|poRjtU!YJgm6S-tZA-c0xj_0+L*Kke}icM?d zshbO&&s-5IS2Ulg%=uF>uezN}RwmZ%yve;FI)2=?=x-itk@L7_b=L1hvX*8p!NNg- zWIWk7Ry3dBxtTfX`t48>+!b7}R$GLu$K$~_q6H|ZUjS{ARQF0N9i&||_vYp5WubD~ z+xb@D&7OoT$lVinizs$UGj(OvpaGk?o(0OXlFB>-!LiuG=N%5r|yS!!X zcD=b;wsj6f@}U*Y;=o+80EgCL-}h6V6e&-NSNtz?)%zT;CSD<_+pBOz`}%%_4S>f^dT(UyHT!`saLDit5vFp zhm>+z4z{;!30cuxvLHYI$0KoO60^)CX7S@^YJB=ctQ}ElcTSwhWvIgXQU-44a#dyh z>1LTKa=EI=TkLi&;!i_eNCoMs>nqwGk&g5+pqtQ0w?*#yau1>%R*#7S@%)kJZIhte4IHk10#|0VpSA0kjRR=i^dk5i_Gv-PNdMHH!Nh zhx-}_2O5O~ja*qHThZ99YJ|h$jxA23mqjtqB4mdx*U7kkvCB7??d^-Zv9q%yTv@yI zar}h@R*&mO8996}nSHl?v3~B7u*I)Oh&)Isw0q&kGuLpbl0E^rOH18sW(> zfdI_U#yB?@fq+Im?ZfMbtg%aFUAtY*LA!;FVR>WUH1_7Ca7r@EGz|k3O+YxNRFMV~6Ob#je}!9Jb7tw3paq zlMOZp#`c4Zou{b9t}2UY6&9tvpz>UQ_1j+s=xd=XW6?Z{9d0k2_)c+{zd27J8|bhd zl{ro-ETTov_1nvDbAET8N~OY||J^@#q)cd#=c4CoNqe4cw%MltbzHytC-!Fv9UO0` zOnH+OO?%tBc6;MQG1b%FxZ9$)*O-(!e=6ox6@5*`IERzR^faMj{uLP$P5a{J2DL$W z^!%gNJkpJ3UAycG)!lAiY}6a}#YSQHoGne;;mPp{_Vam4<=)nkqIQ-tQDCnq;G6D>eTU+Jp<#m>RTkkNz9r_u5$92 zP8(CLzrC6lYLM_Ggw92;^^b1*Vwo}V-%R}u=k*I6HpOMLL_iM^&;uR)T-8_;u?ZZ- zHnH2j*p7Vlcs#9*BOZ?jUDF%)^G7?XjX)6HGx+>>qh762FPEtv9#AWns2&_pE0w5M zD_He<&(De4&ckr?zhM{{9s|QL$m@AFw8nj0^Ej)p=u}~m>69I9yM1xfwp;|FZB;RL z`ay-Ar<=CrAa0v0Q@@JuBy;{`>UVNZO$6eMg_7(Z3a))98k3{+^i_V= z?D#bMfjmU$`?!8?iS7N~$4cAP&mpiO!7uW3Dnw z{z;+ZHS(wQDAV(?o7=-v1ic7)sqxUtpjChhSXH13@x%<(gZKF0{(oz z)o_siFBU!SlZ8(0Y`2B+un;XnrmlXmw)VxNpxyeoVpcG)zkyegpjw4;7SyO*Mce9x zow6Nd?VNL|c@k79`@+m7qFBJ=?M#EHv`jQjLywPP?q!a6N$u$2LDO|K!|1rV(L!Np zE;v=o4H6QLS-&IZPYWfn%I!ZuTIZi8$M(Ywci;w&UJu2*K&e%<1`P&PgNBs#c+pGK zz%an1j?WLKRVEw`AKjoeEQo2^5$i|a@2EW*7Mj&oho+%f4Z_yrFA~%OM_>s$^x#b*lbhkxggGUd)oXpWymWue1Cs!|!-=5~AO8@%xM9DF~@#WsaSUN?a5& z^=GPsZwk{}lgtLDJM4`grtEX>f!vr>@tdLoPou^8uuw7oO7+P-v4y7OUW)VD74o4R zyFvTSMY44Rob!vTw40WigD{bv5Vj*eH#5iMwmh_>)@>JCIVhkXS#Wlvn~?2>NB5A@ z8;U`IOg%&1%(G`^dw!-DRH%%)?=!nCUZK<0xEa%q_E>;>+xKiOdhOuE0zx-tqciQd zI4v~KLCTY&XcjrN4v8n@e6;QCT-nRc?cLIQq>L1CBf(N&iCcx+18w4_j45u_ZcACz z{oedProP|Uy#4>P_ijOsTxova?imbwIcfLLu0GMN;O+@$?1b+wyfehx`RV|ZJthY_ z{bD9DGq702XZY|LzV?h&qfuuzndY=S`nqg38d!}6@o<>a!r9o6#5&`z>X;7dzZD^W zfK)2YZm#qDHtf7zX4qUW<^;!~R4uU-TV%iV*b|lBwAH{~gh=)x9Jx+Cbwb?g*s5aK z@p~1`W71>lQ9)f~<<&KLk#kk9m6?lVII8q6&^p(cFh-oZo?hjC&V2!UHa6E<+&HX-wUZ_atC_@bN{)+Jp#ag^BeyQ|JP6cQO{@p1OGFV z*3gbyYB5YTdr^#1oRTVbWo1P<@2nR;$~v}QLvjf(*Cc8^jTYKuBSK)eu-#izJm2**acpWdU|)A1tA$l2nfg!sYHO8m?U>npmzbT&2I4)92}{+}xg}YVz=Cwcn z>?m?p$*%{$DPCaOxxBsT>s~B~y3EBN&;8iEZD1}A76P)DP}+7jU#GD;bHAQ z>s(i|Rh^XA$q%bKd4JLTgpG0uUveeAZk{_FZ^fz*F*@lJ`UzR*e7Qllt-A@@Zr|N)ah@D!{ke^yw|_cz&inp; z-rbMAAa5pt{yLpmr=+dUvvyE+l(NTX3dDpTij4}sfDdU|SW?ocSE*Z_@a$&2qi)J8 z3bM-i&b3#zMvs|CU#P2`jvl+)F3m5of4EP%P^41GV;JD`!A@`=7G1vrbms0RJznYN zeVugPKUG^V@)PP{66gIg7B7v0RxV=2X@!qUcRjIfV+`4KpZhT3=)=pgW%f#H=L3t0 zNdN#K07*naR9`j6hQlnU=_T3u*Qq<9cF^`-KbiUl-yo8(wC&s(Agx*SKF) zD_6uy8cEs4*?8M&=WT`b_ep+o1FrnZxRW!0C(j5`rbBe7 zPU`+DsGPhY$_l6x{9dR`rwuRadJ*z(7_wwZ9i`fYZ2m@mC?Ts;{$;Ct@6O%j&W$^y zwo|qtSM{OM@Dr2)7I&^wk5-sHm?xcyv+3KW7OYVXK2If9 z9!k`@wYA&xsgBB3)mF!6I20Zk{`kCT*6TDIjUKgZ^)x?LA?Bc;)B<pXc0X$l zQ_cc*sIS(u$Elg;ZuRa^5^&o25xWUlH#lwaeCj5TPIoEG@>oUlc_!LEF+YVOZDRJ- z@GGt)whHE}QsD8d0 zUL)hrv=!f8kT+i7*gBzF?~H%z;o*6qug+iR(cxeushPTuO2zIkjYgG7C_<%H;k032 z3y1aLr0GI(frC@^MKvmD`&5XK9}mST)`~nlc}VT7f~b}W#yXz|LQN{AIxIz8zwZ!Q zyL1RM9Yxq+h4htOssxx0QPyoM=OofEp*mQ%U3Qg;miydCKCfo0ibw2%lX`B9T1}Mz z^NJ`_#hug!ALWNUyY&%d*@&j1PXQ`E9kNS@D7`3j%2CZR*-yv<_KoU+K-7EB_2%O( zJ)*83F2tRVnsJkDWm~aiAo2oH8Err9g%VyYUOLZ$tV!ZBqa5h8oz6X-7g0J?q0=T_ z+&^8k|31m@(O%lty5z4euW`83Ti1h~O_HHaf*3Rj5}rv=s8@;2%_*nTaf@c+hDj(_ z-M+6{{v^d87*!Bi;_6kCp2*Y3|8Ugxpsf1bts04yRz?sxJ$IXFr z&)OBjSol&%neVt8;Z}$^vY!AI5Q&8G`Fu2`L`n-oq>(ablcK_o9W0R`1;S{3sYR9s z#R4@ByFw**x%M@?i@~thp7b3|-yup{Ia{UZdMKu-6DEX(-4;G8NK6E{ntF~vEXpsf zdCrW<=NEVyphI-1P5^rmPIKDop=p<|L!M7tQFxi~D)i^?zxDg=_aA+I__@?6|1wp+ z4nF$&N8I5K*AB1p@>?&n^zxFH;&&8u$Vb&a`P$vr2nB=G>h-bpoOX!lVdy?5vC`<- zDOExiI-!pppR>^`uIj{ThZy&wd>wc}3VV?vz>5VXlYmM%*kIY7kS>**%tq&_hwYrS z#hD_o$Z7nHIj(SnUZR$ayT4knNF!0fXTihL0U`*71->R25{xGJ%>w?WorBhB<)ZaH z+2m?#pU;Bj*?Imy^C1WI-bwxKJ+-iBK<9RPg2*K2I6gfhavEngy-ZEk*gx5!R2v*W z7m^Ev8X-cy&O*n|6a8>F%1yU0$6kav)SbL@BWJsDY##H8IX)ck(~jf9Nl#m>FkI1m z-ifwP%uiXYF1E?P$L8a)idHwM5VHMts&ETo+zoTVgdz~d4%0W{IdgU423rT)O66wa zvm6&Y3m7u3K_`Q~a3N&b%v>ftYd`lwoA|m_y~Rd-qnC`05g zgw@;{Nq>s(q`qUH&)K(o?A#Pt!?2cIWApU<*My9Zw`toROJtXNRr-e$TW94ev+=8# zR-HyGFMC<$Ic+@Y%#!(`Oc~-Z6Hfv#Ly{U*PGpW!UzDyV9N2wgf@u3x7~2aJabhw1 z1aJl-0EPhz$tAWb+ZZ8}SUN@`l~5wUbQEDcePvjbZ_uv_C?PE&4I-_S)Kb!&vP*+> zcjqb{(jXwQO0!FMBi)@#NQb1<(r}*t`<`>I>-hp7c42q!duDzyb5CAypb36>x|F`S znwxuK*5oRl~KDh$zmSvXLkwr(SrppbR)T0QZn{0Cl>>^aILUX21L z6}h1Clg2(VHn#+$BJ@^G8{-%YAr7j}wDWw>7PAy@rY*;GJBPQ+G2ed$;F`0?g71QK zK3hS+aR8Ej6wF=xuy{Yz(A+#QIKzimf3VSdxr>}V^n%w%}D8yEm3A zS&-OoP3}S2F{{`$zsDQkz#zS@lZ1etXGvGpNj6;6^_s9Bmy|NqRV0l@wGj;Bx`chm zJC8%?ScxGT_kbeIh#TH+2uT(T+J3K7SZJxA0!R=@l0y6z^~i`79(Us<-xBo6D3`4TV=6zBes} zYIV$el~2UZOW7*<-u@C8YwUpv4KQfD!t3z;@&zl9`0j%Anr%&SPbl`1wkAT??~IRb z{HNJU#bW^jw_*y>HO?md{MmJ;Afg!a>)9detd4?*F(@cNIlv9kWB zlezVIsRtIX9dB^oS`MB5vaTIs^Ko;A?yP3Z+-=G|SeRcq)(sj&?v#s-S;f8ozWxiC zY4Kd*X(v9Wpy1*Qsn3`lHW%L{i#8P@hO(G_qBOZp1dq9*wJp#LKYc~dPEJ8Vv5>^* zQpx#IlkoxJU5pm%YAaUhbBi#V3(2>;y6@-iHV5j@INT}10Sc{^<-Ns35v>85gvgnYi^qv3}N=MZJM=AzcGJZ`C=U*dN zp=0;lH40IA#qd*%SLt_2{Y*6|KEGvIxH-Ap;hfz#bjXg|n)BO)kX5q@K`v_)CY;eS zkqSoj#$J{rL$|hZ;z{)f=`!M~1{uZ0L7j|JzL#iu-4zVetP73Sw}WTb{-VdtB$XS5 zpU@@eL&{$faV)mK6sTY$l0p|`rK;k&v^xkDdwqqHiiw;Iz-P*DP4myL8&qIF-+2Wt zYYHh~Yr%98emV7WqS$Ufbj&2=z~`)g?|XSvbmETq!WH4IHtLX|cfQ-ISA6Kw_$qY= z<)hJXeZbUpS$+^#?{Pq7vDP4x1qVi}XZz)gXor$H2s)(fPf;|k&Wq5? z__qAQvCMH99c(4a299L@(&qvSX8Gs{8@-Ts5;Mj*$zsnCChVWziWIFdnx;qr!uvn;4`73nli^RsMvQhk20japIZ_GU`=Jjo zhT3x)DfdlfhK?p{8KvulZA^YH8`ZUcCdTk4`QGA3b%ASy)J%)b#zA1=2^%8pe(^^{ z-?hvk*`30TLm)G-BM1?L_qA5f$c(*pV6nD7{H7V&GyvAytS!KHNMks7_{)@IEq;Zm zME5P4Gk1yoh@L>J1Y7NgT0h3Yj-LRJ)!9j16@$&$32BD?3H65Xle>;T`z;pkfZ)^+ z%__qx;xlYaY<=_Ms=mVsvAM$87JhYog|qvuQ|Ds#tIO~5vA_Vj^Ezwn5F|VpYh9fV zJGk$iJQc`xxGN(# zW)&%tUdOP{vljZZm-p0VFt3J9E7#|aEq)G^RyQ~keOh>UrmKFF< zL6kS+>cS+28ck8aV}EFTs6?XcE1P1)>^&B355S4u4w5dT= zL^$K;W$WUDBg5?O?V{8;|C0FrLSAlW{@3KsSV>C?39gOyYVT^nRVZU6E&XHR&0>3} zcRYHSd0&`3sQ4T>NSTRh%_vE*-*$GqR@ML}hAOo7(Jq(EIQgIgBk4ZM_b#BjeBzHJ zck!19{zJ;N`o3K?ArJK45gQfaDKW7FBsi>%a$0Iw z(w9LOka}sV>V4}!pH3{!C^DZ;Vj5mOWP$G;XbXX&Rd;fldC1-PR9Ft^9gqJ!qJ3W( zc;-oi6u&DKr?N%3sd8d3w{3@Y?b6fwZ=lVp&0_6zg?KUKy|Jky?M1k1E$Y5-6nk7~ zzqb3L687l5)d!^OOy-n_X8N{H`fzlttlJ+AZ98prW_(SOWhus`M4V^VJ{kUdX{Gsb zLdr*O6ru%070mCdJM-}`Ie&ICJ>scn{61g5Nk{h`q;M_&)lBXD)84N$^42O~ypc(3 zQToM>V``b1o~VumDmqs0zX+yHSg9c->L*nI+r6wu@a+xD@xD@eJGjPsXZhvsj+@zy zIkQ_eURG&&0bA|BNph90xAq@f&tS32xE|`Tpd8tBVV_VTYnP$$Zk#3cpOCqu9rR`o zn^sQ<+X_RPnzR!q8RxD3J)b3|O-B8U*+$(|*QdA5F8Y&->jG#IO+WQYG|Q(6Nw_@` znULowuoBo4r#X{U%|~l~>)_y9XA;A@4vRzM{Zi=<6SoQHRo6>XZKTMpT<8($MW$d6=;Yt9AVd z#3KndD^Bj~u+PBI88R#pd07~P=TnzxM6W&SqDQNR_wJg^@E)?4QfZ-Gg5A9R9{7hc z-|VNsOEgo!kURE6F;C!aDooUV%faY=jn>Q{^?K%f}wft4(Yj7UBdR$`Bd42I!6dPESc}7?XA_3*{XTPvk3HW zT!Cg40V+dz=HGQ%s(x?W5mP|W2tw{PIv-f7f5})%MPL0RJ{zM8>6lz1Q6h(=3&)%|CD76>{lf9KB#MP%!wV{!X2L87d6E4OM+?JZRg-Xemk}n+qXpX9cC9 z(#jU*+>f%{2feB<1lAb6BFZmH_U$D9ewYhfZf(E4uqssuN1k(Rxu)wmxL*1WMJtuD zMrlowX1#z1y7^o@Y*_9$iJYSj7Y9|r4s*Q0jb1GPXa|n7PYLiP@b%GbG^g%QLQ}mb zluTf;?24^?doRI7g<*ee4~ys~Oc0d49%iz=|4Jh{%fB~|$5RtbkTBgpCP(|_R?MV3 z>=ne}9>W|Ri#*T%tvx%sOTC@2e?_bAWM@T=U`?qs!#f}nwc88|w2e30OL${$3Y(e1%s%7T`nldf1Y4Ar@!Uu1`!bR3FrZP?K| z6Z!CHkuI3nPA(N7=Pd1cvHAkjZ`r*n>frwU8*V z4eS=*PTUE08>sAh@xZ)YXb%<;8qKPpFxmisvNwm#Lo_LJr0@SQyF#*~W`wb*B5}ib zX~OJfTm5I;+PQ?ivmC$zKD>_wh#(K5tM0qxdc<)Bc$tx~{_QDZjjt`~X0#ur7`C(# zd>P)B*)5U~d-F!Sg1LtRV&(kdU6N$(Z(u@2b?<9jM920KN?v?moCGJ6PsnO8A zj5n*Ut-6N$n`(m!IR)M-Aoq$yz-t)L zoQ+SlWkys}&>IPyHgrG=n!vjdFypcXqxX<(KDOX^A8f3gtJk)BHGyr)xJby22mB{+16UmStd=rRhg#9{=$ueV8~XOp3{?!`g5? z!JHggefjhNzMi+ofaFg0c>zF|pv?_NrYH|Cm7GzWM9n_WoXta_WHY#QI^NSlsp*)S z!yq!oEv}Z6E`f#em3vh4lf00d3*MJT9LeJ+w@UlDPjmjtQHq1WW<*JiE9i2DY| z0Cex^n8e(rc>NK3l3uf`_Q3o5+?Vq6cMx{-^NM&hioPGsYzi=c1uKW5Pn-aX>nkz8vpgwX!J?YZ-9#u7CalH61USB_w z0$J?DTvIuv<%>klxX`h147Hez|AN>hNQ^TIh;C=wg)vFCZjNuv=D@_9PAtlU)d}RA zt>Yt_xcBYND_*c$lZGwmSMNsR{hR6GGl0Py>z@y7F$@TY-t59~&ks!ww=jJ2d{qpL z8^lh}^r{s{N;IrrVfNlTFnGQq<;^9_4)G^U{3X=+K#$WtrmOt|6m8zL7A=EmWr;aD z8n3NB>R<6l&voxy1DF1#dfi2eZGb+-wAVt8Xr;r3l5hdzyNnEyjLwazVemS)la8Vn zT|Yh4+#~xQIYK`{O80Bd*wr$AgWo|H`aalZ(#X*XPe{`q;n%^~)VQ!g=KFa8svvQW z-^+e`(U~Zk<2Z%9$)H%*|0qKwDra0HM6qX_GYOJzn|l1!74qU<+Nt<6!Z0HxN=0?{ zMoQLQD@RkY;vn6MFt+ZUGz$-ed;Ec8wlLz5SxAp~v6J?=NIAc zL*V(z*PGYNSXO$PS}^$wu-g2Bj!8SIp~pqEPV~>(12;zD@a@l*{E7nRD=WUn@0TLT zv!q6@jb_*uFY4)5alTsP!k^K&(jt91n=#)`Ts}n3%haJRlhp2SJ$uS{iZ6sNQw~no z-PgsK+iF)aSWm$&a>zom!DSQYj9qcB>!{6np9mi6XR6^vls1c@LxWCt04gi*P`Hq{ zx-4{SNyj-e;K!*oX%s&hyBxPchmD$xRfkOm&{v9?DtkV^D5N0mJccb;W6`r#i#iO&uM#wimoEC`8tZ| zFXmp7Ac(DSc|%nDSa4={mk|gsxn|-!LFIEQA~sr)x94W#-lZRyHb>x@(D+ zd+=9_B%{-6KkT14osC@8`=T0)>*T(R|B7r2lxc{v_0&{vWm?iIsI^R)(#yU-rNLLi z_tC7CA{G~eP(Jn|XMT{NhJ-~p0%R>A0UCL528b6Bck7`04jh?e;P#Bxl9iCN$&0cf z_AvT3V?+=NI^4nV5p&qOoPztG=REFRY1N9d#o`UE;FkL3u+p}(WzRmi5iTlFP1S%G z#uOh}uWktSY$kXKI3T#n@NPa4t9LHejY zBC7$(F|p;t_Q(90uE+=-A_`k>M8Lk+>gMMq|0u+mNy|5<_c&WYMBy9Fb$C|HJ6nMU zzmi~{0Wbv?}<3jd8MHhlpKBZkg?b`!cd1G`rDj1 zSi%R3Wv0>&CW}xy(G16(3_2Tv;HEy?hnncNjF9}ya z82_}952SfC!FQTAoU=2{Y7ud{SDwu9@&uQ-ai}fahIK^W{b;I7#mb@zfY*TVUW3uxh8T!&PgSI{?{`HH|JYtxd4hJLjq%I0;Ol@`t2iMek@c%VdbRJD^Lp25 zaYRrF+xNYSyKFEF@z;Co^VVC5d?qvXsvhNG<$GOL$ZNBhf~+^QRug|xRXN6sk{6Df z#og-MJwss$QVhizU1xuQA_3n5>sB}#yX%2P>@GP2Be8=qCJgyda#S7HGmzBia8z?< zo<05HCNJFQ(GeJ`oMO!^&N@Ci@po0EvBY!ug}=^yJR@(GfAxcI;&A+lRT?aPqr|tj z_2z2#6G&(@TTL_$IRi*hjrt17t}Aa`$^+xTkGP$(4Oz4xt8HJ`)MqV30r^=<7gk&N zz1!*@&e<&%VBNPCj98e$>*IBeQ)cz#?L7R2C2mKL>j$Z#*Cyb>b|Bfb^PSZ%_ASQX zBWT%Z)#}wqzS$iE{S@`tQvsqe!n%X_(XP`G-^d4F)J}5DwHXxzpM@Wr+$6Yb(nOz- z@bIoxYatjO#2_! zRem4gBfC$3qaReXco=QoPrYVlN>Qp1E-WEyq-*Wh_nEl+LiP?y)cDe4^eoR!HQ3kq zjIF(r%!eK94-&G#A50p1U9vFuegPW3l`MMP+RNg-=H~dq&+-3h0f^Edk1kw?C&na3 z-=Il1S%T#-jg|dJd(Hc~l|jP&-AOFBzeN z3lJghT6Ila?{L~pa1g;_6OdkzKNER`bd=>$MA%v`Ysc~BL_xvaWksKtdqT=Pg zvB_n0IC)r{GovyKdFSaZW?0ab|AQy_rUsX)TBX?SYlZ-v6(p-^p(6Lqe)k;Yg+r)y zC{fs-SrJ(}Zh}LzGqk5P1lw5OE6zHxGyWdlSndQ!QPs7AVEX<166^`&S7|Bi!`yRq zXT&C9r|O-_sLNY1;wq^t2CN87O~p~c999m=?xI`x@EFGzl2!e?R?q33r(a$Dg)%2sW{y@wOC8V*$|%S!rh;0?K%ZziHo!2x@jg+pOvYa$+}5V)jV zzQDlUAf+5-No%w0SB7iKYd7L5$A3BhVLX3&MN#DkX8?tXR)H#OwH-M$*gd~^rI24o zQIL3n4VvqImkldYTRtts;#|<{E8n{kKU_%$UfTmSTAbkPx4*d5UZ+CuSbw3gWO#kw z*dp$Jl0Zo_dqiyIuQM<;g(hot8a!x|-DvmP(=AC{ZH}yroxMuSep%8TG^qQcwm?PX z@PlW+(ZK0I+Yh*tXmvpiTz|>tzgzi9!!tf11i7X4O4z9dz+Bj1j#cWLSQbo!HV zp;+ zLya3<0Zg;Oh+TtS> z+#=8?O>Pq}eg>}c89QUzE{!SFHl{^<@GgbDyNmwYCWn_MVU8pon}vQzDT$K0fSo+7 z8}k~IT;*l13A@RT8_fAzUbBFm0QQ#i{|q7MLhkxR1&AVf4IWmc!S~K@_%uU$582CI$CUF(GS8=MYo7` zuP0adr)o8WP(7?x&J+8O;hSy!SGPbVx)9CPln~Kp82P@Q`?ST(qXd18LYfUl`ndJ1 z!{EzDG*U^N%q_eH#f6V({jl5R( z{PN{6%pzT+_(+|{fykWm7N6V)yjz9{g1)>ybeD3{B z$`p|*BRYpX9jp@PC6R5MGm|kZ&Ub;hU+`%k{Y|$nE=P_6kpXyrhTDC9xiT%!*57gd zOF4JYj6tH>G!FCh+VCb$G7_BVRHsQFI7c`qiqKQ+pZ`0>BD~Y4*GJm zi`m=RhtJdx4(w8UH+vM}a^acTDqLTs=&DME4^NX>Q(aw&TRn1r z53$_8RY@J$yS+6&xqLodef~(@x!BfU-U$8q#fDwdV^F*HBIm9!UF1YkW2dLmH{o&y zN3ssKy9=>)Y->SE@q14|JytO$%5sSA9*zUrsYiX1O+7We50C8h*qAwQ%41I#qwOZ6 zxvdvAe#A0({4l$)c=s?K`k&U|TRUhjk8I~S&wcgb%Z%4CWkmO{pOCrG%^+7X36jO+ z1O{Q4#ijaT=AVY9K~!!j>NY-tfQa5}C6e*FlT~RAtaw31Qr%AzoL4d$k~w;oi!Gaw z0}?!T+gqIR@@~FSjU%cmea}Jd1{)~b)OWDbYn6&! zvDJE~woa(;Rav4MClk!0Y+xuv8yNKqC?y~M{ze$2B>@dQU3n|RE6(b2HT}1{p^8+i zdCrnNnN&)HzAnmRn#P}cWR4@3xDL&Jpfm9mc)_aWxp>ZbsokOFkGHx0M&@^fQrlP6 zNIpC-CWI>(+z^!Q3OIOGuR(Qe{|s0u4Jltb@UaRi>b{eKhm}UWO_5~q13yeXkz@6< zL>C(Uv+27PVtbS}=4J(8z2>#wENZJuP5Cpl1})MC2#gzo2y*0D_kU7P%=@f$W7ln9 zc*$$mw~HAlAb*vICsd8Dt3SoGNrF3=&J4W3$7P1R*+Fh?jZ_U zo-A5EW`jVsclU5RoGwMTp$^p^@y?v$@F`!``Jz_tFQDbGR6bg~jQvhGnV)P3-SNUY zWKQ1W!DgR>Jel`ta5FJBVju+zA3uqaO^0^1pI7kj0XWbvxvyBZd8vDhQAeBMltN3! zg~p)-;X55(nkz2LP}^-E#8t3T8Lq*lF{S!IXHRmKjafE(8;6B1W0X@7s18`Nq|m)_ zHzoI|Tue11gA0nL)nWo?HCawpA99@~sgK51-T$~?Kw5?;Q_ER<##y*kzm8QsP8lL~rzXY3gq_ zR}%xpi-QV)>HD}3{`W$kpTF69@j}AWj#HR`{696fN$ zVSB&C4igBy;rlCN7;ds49Z43&$f*UH8Z9rD>fe6Yt0bcTuY@}BNx!GE_c+)dLIoQF z(r~YKV3kuW|NG7AcHHo-#2F1N-(Rj-{~^dO+lckps#3Cmk!WsF8BJti>>-!;#QP~4 z_Oaohs?u0r&#%`fvbGc4PxTw~qTG4-{>V@5bY_CS!q)}JBY2b4nSY{vWtqF*DE|c% za!4xxzqiNXe|`I(+VnrB{E z54NsWR<$EYILvG&@YmGb5eM=T&k;~ktR=&$@t%5f-+8pXhNk4L(D(ra+JAgNKi2}t z?8lyT{%A_*A}cl!!0V7VQI+}iNVO@mR7^y(Bp5A(a!ITm$h%TT1*hs?xf|EHbn&Y$v-Zr4hv|{`hCb#G^Vx5WaKQA*+Ah;g&LSSgAg*4I^#y~-@~kTpr{<`mHiDbTvk%dTBM z`z*BFXy<%bg9Bkj;OqUseTdW|+1C>fTY5#SfB60Xe(yYdp&hCs2$OJ-Jq)*9OB^8P zN_%#IZmb>j4Xm+;h zjc63}vR|y+9Atd?p^3!F(GM^3pIyV4C_&@wb*DZx0*dr0BdxWbs|&OcGZBl1aHrxt4UO+n3A$pxt@;Y$!T%PeHlHhr5^!-a18cuejq_gu=;c z+m@MED7*u3!gNf+( zv+1*zxsVxq_0p|FhnIwlxHH^3Rwa;HF!faM8bR$(7>~2FzcgA=-^;Q;dXx>2rbVCn z3W2I+k20*R8VmTpAZy@31&K^lW`(G6cCxBv06+Opp9raFs(58)GO>y}oCcD&VDB8r zL}783DR3U0wb1!`_`?@sDQ<83z5p;`gXiBiz@Y%a#)>-w!U-(-T38*Iu!LAqr`Deu zW`%KKg)PutmUqB)>S1Li*T^+vP-FD+i4m(6*a1vZ*R+M`tS=MOK$z|;F=EM?O%J|> zGd#Iq3q$_=dmJAgs|aBrjC}QUsM}hrk^|ABkD81MX3T9i^)!v2Z?s-c%!$3igQQh= z>dL*vY2Cw=P{LWPRl*FR=X!}|f*D?z&#LH9#ZS7wnNtk*MSG%O6t2KlpIkkORl4*7 zVKea$OxXF;9Ce>~<>B0M zn^+poAkbDgq#VkWozXhnMR*xQ>q}X5{k$9)x)1EUj5kg?h%Nj$BOIx7G)bmtpiI9o z5BqA~kQvk|8vNhz+7Ic|>S*xvQD`YLY=aN7Qc)O43%pE%H15qerqI58X}l_^DvFRC zR>fW(oZn6_t)Y_b1&ya$p8`v62cbX>hA)(HUZ{gxei5&2q^z}1)xL+m%NTj|Y09V~ zKBCVDh_cA5bBf&9M}TK6?RkdvdwpDFb!vfG%OWXNa>d@59Zp|d{1|Csf9?0$Y%k9~e1`tJYL&ZNO1hoywqw~T?0(kiGLwBruMOIQ ztZvsVH-HZg0yhqT$WI)A1LtiLVMYYYM#bj^rB&2nHi@=Pmv}~USn1M8P~Fs#-GAtF zgYv1~3nPM7qoNu$J1evuXCfTECT{rhtvIE}vf+oD_z%y6B}WRwFJVs?ze!HBp1&#v zjcb&{I}uGyiB<4TM6By9v5dXqa-r+I5$;wAUd!oz*ml50q#lX>P+}T$_~zJXyjb%P zBhQ&U4po$zVx)ya9{T=4HxpK9J6Jy0l0Df)K-o>6Uvns+9&MsV3VYwVAt-8Sv;%Yz zFz{Yh@n!na%MW-1OEUeS7w=#%KRJDugY@*JH9dR!nnAhb z-RcFgG^R=Yr-9X?(}uo4RX2blSQS2u)Z=9GXvM4qRC9ARQqpP}ELuHN6b#dUcm9KO zr|U}3k^VkYd;;q=T@$_%Vn*knc44p72R?C7bgKIxKF0Df>}D~)Ia{CyL_28AlDhU0 zyror&8~17|P61)yaj-OqkDepNp`kfu>5sF7?XS{!2h6VV^pKQ5gamtZeUNf$1E@5) zQZMSS9|_DGYT-O94m+inuFZSk!*sft=V{PVo3 z**TI7#(tYwFsNvCa1pipPch(%qYEczksWXYg6rVp0Q@4Yn#O;<+jGG?yi;?#P}3#k z=c1zQcjuhJ#%ElQf~5(yqh3olOB)rd-^_e>mI(bEKUvOWc zt)WL3t1(Mq$^S%8Nm!L_q%orL3}~^ zvO9f>E+h;o`;CP&v`t|_U0YlKu`5aJJjof7@`j{=Rf@9ghcmK}g7R~d} z1Y99ILbtl=?*Hi`q?aHTPGEt>!yT4)UujGswRc09%mUc=IL|X5u8mF%*}mUCTMl$Z zU2V?K95HxYnC5sJAY)xozzg547gb|g^0mxD!i+;QXI`^|6~N`a#(=V(teqs`bGJvk z{;lEm=55{?C9H3j9k2zRlx(_QFtl&iVEt0~Sor8oC}gs*nF}9NRu+|s96d4KzVDLp z_tkh{B&9*Y_J>-SjyW6}-Y1jKKEUtSdC1^~-%H7G_$JTx#F!I?z~R5aJv9N2j!x@1 z=+7R_GuI9m>xDodihXBC$5_|KvyX(=ipjrAZm};ehAEg+GBstwk!^sDVXA)KpgVD# zobie1*B4v;ycgqkdUY1HOKPX)&N7w`*Gvpl>n4?|47_Sp8l6O9v1dL-fK{e>(%_}BV`$UbuMju?f%KBL$2!*=@*dC}IY`>+$-y7}$+lS^ku_0|H3fRf3-RseIKb=um%lwH6bpjk)O$i%ts zcHx|Y#`(l0~ziyJa z+t@qA9`U*BQqk4LbOWwTH~ zlIE;_P}0^0P)gc4<<7i!A||H~QdRGG=e8+vrcNPf~KF-H_d++G@1Z zwHGdR`2WeTyn9cW+O3tse}cS^2<4d@gjnJJLTndeO&cf%YN1wcmSsESUc)aA&j|QC z8PnISLf3Xi5xyXuD9&g98m_#HVy4tmgR-znE~Af63TIR)qL@@P+t#9Ka%8`~edJ4Q zd&Mi}M|c)KgI~L?rFDDExNYOkRRS%%uWor2sDOZR4$4?=ew)=P#xCz&(QN#1avF{# z{q`(QW=BZ1@X)6cTE0np5qBRfkSV{xbEZ*0x#oOGk;0!en8s;3b@oR_~b2d$eBy094tm`(kjCp#>? z`Z<3VIA36Eb%5il?=w&K0fsp&C2_B#K7utUB=J{SodsJ}DX6bcM%6ZGBW!h?h)Vt| zu#ng~zs5x~V(Zj)XSx#hVb-yPb*=-4gY!MEDF0hcNN7BUFQ)F3N?QV5XM8ul$fx}= z$*mtGXEAyWAnA7>%1YT2;2<#o%r{V&!AXHSP}>r9Sre({vuN3w`|}?*XtTVDDwH3x zMOaW;5>I_NVX&$TnUmWqKapim(PAi5o}{> z&OWfqOg-Q@2-!ZIe@kj9y{bKwj`l8r->TA&BFdpp?~ZTd*PyiTwMJ*(jKj{nR=r|5>qC>a73k2jC#)i) zx48YqdySBqF21=4x;u*!Nk?y?lWB60OQ-^Ej^r((7pT=J2km-9%%?)ndFGA{nc2S= zYaJ>a-o=QB-y_7g`q;(W)UQDSu0(TVHDqiJSxJtjq@PjIx@{*N0?GZzxuZ7OgSOH? zKoR7Y*9wRf+#LkEwFNhwIav2Gt_!QxrDn>tH*@z+9^o;6ld4*G`FxCEc&wDz&u#d_ z^SXB>-DWobEHRtydx6a(Bl`QBJd>&f{P(W}lF;((#YwkGdsW+n^MI~z?#HyYge_CC zNb#}dV$I&+$Ops+ihPu%E^b~;MM)UDjXsYeS{}!|^ru=QU=r>=*{Jj&7mp{RX`r3; zL3|0ZvSD&D!6hJ?wk>@T1r1HJcr5tFU_pJ5hF_FsK>^8C(JQ@iqI(zp29f*oJV-0! zT)I*piATQ}6R1h*8;LwioJ#5x)cnsFd#88a<0&r6cXk(D4V{=WdIHvEvM|RK979OO zqpTucqXbV(F3{BEYi(3s32z?6bi0L=#s;~)5?Wm0q}D_+sJ}+Eo)?24;Zi2U1wylB zi&o;Si}*YK4>9`fefPO%;bWOh8iI}of0--_Rr-A;_KIWMLI0wPKE3T>cFArjYA4&Q zja5tW^pr=+Vbu2Xfp-2@$^S)0WHB7I$z~!M zcSgD?8V$nHMMcD7@}|i94hPW|)d!=|K_-NPSm|&?9+`S04fSy|Un+HOG)3JL^_@ z`7Uv`(uF_#n}^>DgH>n|T}*`Gch0cnx57HUWRdI`pS5fTo!OVTsHkQe+V7)dHD?KQ zhzOny73d^%iak+M%&4#@tj$uHv`;8eVbvWL8LPc;kG{htuG(gy3{NW^A0X1#uzMP~ zKFv~hKQCsTYEj$y=0$|*E31Fu=p&H8mCwARClgpHi37{qFt>jr;)Pgw1FpZzN+&UX z7-q~Y++2DcMUUzk&Vuw2}%shI-3{GxGqTeiN+5R(Ie~vi47oyX}G0 zjO#9Q;V_rEdb}Kq2(82RUldFJxBr2>?+?7T7O_}jUpacV!T9U!ZZFJ{=oBay z^~7$mhL5<~#~7O8`UY}=Hd&Tt4v<#W-v-U~iI*4}>D9O~La(lN&|nvrb3hurIG+lH z0l;v|ZPyr+mFIA;cu$?Q;Jum{I{hck#wq2R&K;iJO$TRTHKAO?OS-isNGW@XGVmjjj&AjkB9OqA{9+4j#Ms56Z2fvjv9INm*$sj6CW|B zcusE7R>Q-WROHOKflGJs=fujsRd5(c})zHp9Vz31$_DxaTL8Dw7=Hv#Qn#z@Q_EK|*%>Tt;u z{Cq<@M4pjPkx_C0(x$IaZCQEm9B$d5$S5ea?psmnCH$XFm2Rl*MH1YIzyn^_j=c#Z z^LcC;+=AQg%LGc6%YRk4SaD?FPs-jBoYTPCa@xG!-KWJRs7#e{_r}V4*pP``c{qjE zoV)=}K=rwKB;ZzE$e{Gu*i7_Tuu4kcGzT6x!uZ zUk$ffCwcbczweJ2{GF5zrb8Y7LDb>LF>lSNy-)6TdqN7}V?Ynhm6T>uW`by=IvtED zIgRrFbRj%yC2&nT65``__TtdLGWQ?k?^VBW3t}^ zNK(uuJGdnO1B5#APTekZA9bQ@8E|-mfl)71No1G!ARo2X-FEFQp61ZM#7epHs^kI6 z7}(^cSk3~H(;a3s8(r4KIb9Vle!o@vODLsd#Rk?H-4Fuqp6 zE`bN=LbEnYVVFhk(+dN=I3k-kt7$)T$FW@$;8=>-Otm49c_i}n{Bc2Y)}~5F zsv>eo>PP?zv(Eh;H^LG14y~Uab8iR^TrUac8LDO&#*G8flqG3zR6JS*1DT?evpi^Aw=eFdw#9|LuHpZp2z)8H6iN1FyTw$}Jev(_ z9-DqOXFI}$!!wr!7gn7fCRTo`bEs-L?C|+K z(9Wc_WW)0b><|RX^YDI!@l-G}o{mG9JbKacrC;3r4XQW#?sS(BU+q1#s*M%{LCnPQ zKdf}Av3a5!6$}-oyn^lY>Ea@clkzfiPNmnA(}+UWx%f(iQw#jO$@$Zu(KP-`HXfMe zIlK7^+ryLH_#bT8^Fvz0Am{B5Hz`&3(U<@;<4<#C5S^@3RQ~cF*woCl&iyd821EIK zF4d&2dL~tmB~sW@-K6v_&%+&0=lzERePB8xq5-qjQQm^8m7sJHyL|QZsa52Bpi6dO z?pYQf5%RAoM-B59_t4_WvRbrvPocT+Xa3VQ*4cXa`oq?hDt+s-P;0l5s>8E~(HUGZ z-@IAq+|FDBwCLkGV=7WOOT;HDib*%Zc&$2kB3cHhT~KwLs@dP(oR0?2q)8HxFsI=V3BxMO$D~qN{lwZ)x|`Yvyu@L9iHH#6uoWSZ4yd-VaYk!Fn+ zLbL9)cl$cJ*{gUK{^4Duh3@KEZ6}Vt{6TyVbtm`>JxCfJqS-ija)R}s{w2(Y9;2jm z#e8j0M2wK0fz(EaZ*+F^9 z6Ry}{j1zycKrj~|&;Y*)zOJ0JndkzgqXYa++MoMde}j&_X@9o*o3HTC*Dwo(f-QuD75KvdHg8I0sGybZ=3!hX6Nv$#^PD7*f^7V(Md|}}xpB{XU zC7WfVCLH5hhzBd1%Jc?7#R5@smA1o_UVj zVM#P@=Y-ljEArX?0gZ;Ojuk@SGYsbaf}O)7gkg}3$BFn2e32M4R-I60f!bM~aKHds zpis8hEZG^{%1TA8KnGQOao>9fNf8=(Y^dJf@(lY*q$gh)h?nKf+U z)(}Ku5nF)}%n*)%*(?Dy5E6gDkMN0>@)djmA5z$LYPQs<#Znnz2#Tfh|IgmL2FG<> zXQJOZ{eCyl-9R^<4FVttlBW1Dt-z!t%dr#Nv6C4lSB^6?*Un6_QueJRHB+Uze{<_r z-5;Z>TQzaro1`?JI1gtM&mCHhJ$7Wrjv|qgWyvHZJ|I#ApLhceG=P4;&i&Cijnk*k zWAE;>`*f4|svr@K)q9`E+WYLYzWuEQ0l;=@2V2`)C<_8maibvYK)@~;D+o1JEdZo4 zIV>(M!s&9t>G8l~vErj2dm3J!7giwvYsH5Gzl|KXRU>6xEUi*j z{JgY#y!%SoMzA0dIw76&Z&`lRP*Rpf&CpIlH>+Ze28)dvEXIV`x0(XaNR@0mphwE? zgACo05rEa^rFPVJZU#mwWu?%&HhdXy=c=`2Nl00139uGmC@ISVOh^G#Ns*szysb;h z{(9sKuw`v^WUQJhmX`eMR7gq5SIhs~+DIBvsRr_5_Eo>xF zD3Y>)WI$7`ELDAx5Li>5r|Rl1ix~1rNZHLjQa0r4!R^&scvR9MkdoxeEmqJm zN1p`%jEz@o4yH3{q|#N=F;mGPlSyNK#e_{=yL&ME!hKj>H-26v#mLYI9?tJ=%E_cM z*hx0V-bez<72^NZC#$Ivz)` zAO%?UPwJOulP6j!N?DMy?S`C`-3J+-J@YJHzx29c?F~eC)sGA}b?7~djvYCM_iwyU z)c-!rgBmHzV*Y2felU9TiCW)XrIeKuxN4*<3zaF2ElvM4wPZ=bLb(e7D^Gn2j;&?< zVzY?jA3uviY715f2nGY-@;NN6ts?^t?qUvQy9*o#+_-TA{(v7A-U5d|0FL8f;dxlf zMQ|KftL-ZA0Gv*sl7(QY08ST5#T1GtB3ltqDy5Mr1DxFkyS)OdwS)>M02ZODvgNsI z-Zv}uez#Qr&G8&877O|YhT!qo0G`7KAIzbGYQ8w9+YOtogbM5c4>+7|I9z}r*kQ5R z;qiK4cUJ4<@>XlLZYu|5b9tn*SyTkz{{02moIFaE3MxVc15`-Eln@XjT+}eWE?Sa$nM7bg$=#9W)bt6@(V7;6` zu~>lH5<#ywkNNkLNIKWB^3k_cNmlXyCCR@hxTBaAt`m{6l6T}){DKlb^{+2$rNrzfJW&hSCTbj z+v5o1nB@o#gsWuIH{btr!uIM@94Zl9&yGHevGD^n-@m(l7jL|;9hjq0WRa@827)mx zCL8UZIrePryaC`ZzxmAuo8R~s{{n$v5clTp;*B@Rf{K%q2QhQzF$u`>M5lw~|TRym7PTeuKdJ|7$$L?lw}>+033wa+)!S1>;6w5^fdKzm~udi2As=Hlo+`dD0Zw^izB(gP|c%^|FDXRqO^)KZMaOCo^ zpc-xgs&R_~fU?&OSS*U)>qID#vNT|!5+tqr$BNM0PxtxwVrXCx05HEuw?3y)KC+tA zMW575Uu>pIupQ8vA85y}(s{8M|7OoAX5T*+Ya+9+DJce`F{Cr;eWffRS|VljYR*bY zSr$dV_m#4(fi|7-(%m_fPdyJ|={{C_$8c~cik;*JwsJXyBVho5!)}M&=|XyE2gza? zcdlKxQLIGYcGkgERM!hz>Ga6FHJ;Qt>aJ4X%Y@v)I5_sx@W#-MX@TWw&mu?Ek#% z|6+aF6En}^XG?QfTr((zs6rV+xpGPiq-2AhT{5wWd^V5C$%7aj8G*;=MIhL?d8t`K z%k1C_EheX)g3IMWB<#cBP*r)LL`=4VXP$YsrXB=9MQ*Z${J7MJQ#Ddn?_NuZ*-%d} zzW@F2>-tkG(}+y-=|NWMkbr75doEa0oGg| zc2vVI01%&;#H~9YV(`!*JX|7M6OodS0K0j;RZ?~z=Am7wH(Ny~rHF2pl&_1WSN+~PHch>tbaIf=KuACK zcBQ?X#e!1F0>5_zp%|+F4g^s~7QEF4i`5G79CEn=9zJ@6#k)C_3pTi&z3A-?!DhEY z0KjoPvgHIyl?qDbGP1cGz;P&7%HVh&0yvb)Wmw%n&xjM5d>(#JF9Km7_(}k&QUyDf z9Tf9Gxl%ze9fNIE!0kh?VJY;kCdoR$P2hoWN0*e1U=WK~AR=X1kdJ1QH~XkUPRi1N z1<_%2-?X+z){g*yA`uJhk+FqHo=GjveXxf#HR{FRyolIJtRYouv*ax4yk>dC>)MDI z=f*K7)Gt*3o#)@;8|nHwg@cwsER+ey#I7y3piJ6vl6qx>jzKKs_1hh=4q&lFMmPnm z0c@4nr#R=|Z!amy|2Ojc+AgpNbkV%jH?yNyu8NbxVYee+DAazxH+L65dhJz|EhWGL z3`K`9zc`OWBZm-h2Z>+GlpqoTQjn^wr1<==ejeX{_4`d9M<*f>2w;449Co{1lZXYt zT-6A$2{zHZ)Ia@8pFlQO^~=G*C?XL*fJRc*2$j|3g`>3!>0WpEL^lHD$>`M9RkF zagf%Xm4Y=XyRVcr9wel6$>ql__b^J8JaWYXO63ap;e)W{QgHM|kx6cVhXBFh!p`~% zHuEK9ie>oyew4t&?yv)b0E-0!l&|a5^CrvnUBAfJgN+yA`Qy8pjX#vAVH} zNPh$tmm3aW7`%{xuuI5ha~Why0B7Z3cT{#sRsjMhz~l8|b0dL3Zval06IQzwi9`a~ ze735VtyJnrS%Cv8yQFMckdm^(?(f1b(QCoL(2#_%1#;O6DiGie@v!ketS2_Gva*W# zdnxdO3s##IPPYqoyB(!U1suo2YPEv1Sitku6v<^ls1mc~GD_tN@`VEIUJJrwZe;U$ z1U*CW_VywrBNyP8|o3G%{|LU7&A4W&P?A_~Tr+Dn97hOH*k+O2k-MNETFaB_M zQy;2}7yu{$F2M~8XVLh!Hk3%&W}rvP(kQ2lQn^Y&s6S$%;|Eqtdx}f=|8>-hYekk&aPe1nu`O00DNAbDnV-B-#!9%y#+g_e(~)tr@o$Lw*YbWHnT2P4Q{IVsCxO+e#oEc!Rf zC%Zx^tCsp$PRcT=56hrUT3b?>p|ag}hp_GNVr?UVEUW+oI71O+wzk0AtXL^jkQO*3 zOMu1UMAqs+Bocws>4eQ@hsDCfVyy`ptj(rH-i79^9K;JGrqE(oS2urDZ7Xf`(KSM73*f|;nAaq_})*xi=p8m%&+bS-FJ)PIm!;$ zELEkC-{*(dwZ!m;RI&Da;O*7G~N?fZx=z*~z?4&jg zC1sV4vz^4O(prnQ)@w60WwqJ?j5%ldbwUXh-s{cY z{H)i1A*oiFT>7(@07al6v*Sw_cEen2*tChLPbIY;HF=o&#^QR@JRs^+(_Ua6N6Q`~Tg~I1amP zEx>VH?cd<4wPwqeGAcp^;5Z0ku4SP1ImcTe2pm=x@^E+nhg-nvB2dVes(;&g1Ae$`W{?dn7>HAPZDA%W6*89nroKBI&L(%LU@hntU ztkOa1;a5IcT|oTkr$08Ny>>z*UIAtDRS#Rq>LO?(v4Q2~<=W@X1eVQK)UkT0C$%+u zOp-tvz|{+qPfi|0G+HGg^hjEuo~T`3US>*8OpPDJ;lqdVo$tNEtPi7LX6iRq>A1`u zlTQL@m9lr|=I{@1`~Z`allbt#ht+l6?#?qu!2z4CO3F6#>?9#&NmNcEDa)dkAPeQ} zkwb@3Dp$AXDb;SwX0ljbUB-jE_Yn&8np(HbEDQ~eqc^PlQeIWcMgU}(DrKdRKH~r~ zg0vNA5wcqMuN6{OK8DqZSz7W$x*gtLK<#%U+I(Em6e&ABJ&oB}{Sl@c!TZRqg_ zQ7V-%G%$pGz5ut!4Tr;lfX@$(<4_SQs8lKt1VGsRcd=MRDwTpD2)m0l4x5`BRf1Fy zV71!daysF0S6{j~jzcgQM5$PU+v5hnA(P3#;jqKya-&=>p;#zFfB=`ngt!E=@>v016!Bk})YU!k5L!l7PdvsvVFSrm&!tR>b_E|*a* zm*Mqzz*{URo%ll@vj(617Imzj9J`-+%X^1T!}z(b$rt zCl#TloUPTAweHoF&15pzSl)ow?rZ5dpA@C6mKs)sNW^Y!?Y%1{6Pw6q^KCgsHIVw6 zk!xx#LKcvcvU&XFH@`u3oHUTP*)G*=GYVM|Mk!@QNY8mInZ$Qrq1&(|C3dCX|NLiv zt&WtX0qMP#s%4!H9*3qU04Q%9Gkc?t*=m}P96N@5S$(eYd9~+yKwCX4g-Ftx0gv0G zZ=`?+_wVDuy$3Dz-6`wIW{*RQlw~n~jIOUq(|4z!8G@`GXjKiy0mL|&XK3q--lHS2a?WMcr4uHUohG03g~IMNc4zTv0t3rbNU_p+w3)?*1#U1*(KSQnrG> z{N|sw=fHNMM$8&DS4qdG&+EmHUi}f(vy6n4rJbvrA!e0o)4uV>>$NsXNLeF%eQ2m! z=icSA)Q)FgDcgwAu~8g4JZ)P4EHV-p+2(=}!uyX_iP9m)f*vd-(})GD^Vm`{4Pose z1YQ6_F>pK}#Euf3LqppNimY~^(l>;s`vZ8eoxyUp*!KR71gSENhG-zQrD?NU6j5gP z&k9ok7gjR`Y_>@3nTe-*Jy=ZTu~sN)+OfEYEXG79_?mbOYNVPPM#DZlSf~3A3FM@i zQSf*iNT>D5{7{Kadf-sdj|5@K0J&|jlu))KEZYMB(Y}77tPnJ9lGutH;C51EzT&Xk zkuU6x39HklXjjV7KesC-c5|Q7anc^6CMg?_$8rDueceX1l(TYD*6aY5*?~qDFuVUw z1F0#|zf{@1U3rS`c}pwnpbZ*uY=4jw#+ z?d@$tiCS??l900dMBzTxK(Ygk-pK6Rei?}W7TKM5i0cDc~g+q+B30)PL?w~Z!Anqiz1A_SATTAKMvQF{1kLJ+MYp6t8 z1>AOG1sJJqB;dlDOp&UFkjDZ0)|#$eU(gGI1Jda{G6ij-px5KVMw+aDmQW(cqLE%~ z@1&8*HLsMVA;(xDSV~ZlU%*~QH$9M&Z(5KOOaYgV_*nZx5iG4N>l=cc0F3oV72A{_ zXDL^N!|p)7pzj}*qJFm3+Hr-@=2{W5G00N^*qLip}IHbFBb94YPKZ0ZUC;Ln23wyobz zgWCO`+P152Kn5}TW<#0@E8(I}EzNo2D*#G+9wEh`aq zdqkK>g86(t?CdDdL*jKT<%*hia?lWE@^+;}nDjbMjF02aobr2SMW%38B9B@HO`8sf z1NnUSrI7~INw#)Ei_lBh$Vw-)g1(Rss|j^qU$FJ6{!I-7{a!4t)IWRNUK?ECk&vYv z@9TA8bwmI8^Dr33T$*g&INIaH^-W_lZ;X3v#QnDl?(pHm0*M+HAg?70?5S+^NLjP% zp0Eh??V~ecl>dC>&{5cIHe9}T#dK1F)PMJbzxz-E&AtAQ|KUI4KmFhT2|&HF6{sg% zMWTg-Oj6s?CnsD1ax%&6T2}k$K1d1K)#VlZ!$16x=zA>YUnT!lB5JpiN!>9vGB^wX zSXo=CO9!I{>9_;-#-1F@3NOMW1TV{aQY>mhwOid|1ZYT!qhTMeukV0gH7;1)?sSAx zz1}+VM-O+?cD%M@gRs4h7?;8F_BJrsn0k>^EhfdMLlxMQ_w)@lKtsxQ8?Fw28uy(& zhP6jicZzge&?usm+U%_qF_y2NM?)Sb5*js&f|Wcbiq$#wUB@WyIfB^W$w^%!A(D_H zl*rU}v>`$yWm{=O3tGo2_6-0@YY5k!BZ`D9&>Sh-ipooklx2}lRN7~!K#w4^?<}@F z7k4^Z*_7k;_!KiY=qZ&`UjdIYa!)Rc2TB%iFKA#smJM})nTltpGQ;SrSlZiB> znv?+5A{GY*2C%qDrqCxPz-UxnTK)I+^qO%~_W zO_=ah=iNJPA~wwgssE_i?JH#&pj#A4G`3HgN@SmyB!k(CYBTHpvFhIpDAj8P_EfFm z-Y||#AI8-i&8Jjsg=jS!X5T*+^O4ybqB;p;+Tx@&gje2XlQxtEX?SpAuT7;O<;gx9 zESwd07nX>3pOdB&A`P-7tsw+FZfvD9wa*e(buxL$>aY7PF3%{{C=Gv=J* z4fC?oWHz0v9@-5pP6dp7fqT+pVx<-)DBXa6jB;B%=#n! zSXm?6%riVVj7JNPP%3JZPQgGB$t|*abTs{wpj;>+7z`qrBNBbBFGbu~ z+$rE8dVkaEb03`#`TewPsHcmLI4oGp>)-1!pAGkR z$b5~|cFbpk$HHSJTf$nt41V>Ys_n@>4=%5gt?3VV?YNuLf2TPbaN;_}#zO$GJR}pJ zvVbBfYeX$s5h5wevcBg&_R$PzNC_irxpte6ciZu@hS>z22(9}fCt3Y|KdiR;+6GE0 zJGFpzZ?Fd=gTr;Ctk3Jk{CvH_N{MV;Szcz6VwV)1=)Wu#gQ|TpAO&^%)KD5u1YEd7 zST{!r<=*~=&uCO4qODXZqn4VmTk*^N)pPmDN@Jiy8pu~7bd~D)bV6D&X>eRl?n;S+ zR_-H-B8aB$6DcX8Msz44qQQ{1>kwq(l185 zA#4XHYj!mESA=V41w-qXslFpeyOgq|=`?AeM+&dUo`%y}U55-t0$5n9+A7U8BIFx7 zw7??8qDa2!&waMtA2R4|9ssK6Oh-uRZc)ecqMIyL+ z?_NvSx0Q5=q;1xdWFqxJ{*!?kDNB>KkVfTYWPPwgp@5Zyair(thH~f# z%E1vL+lk=_?mXJ7Te-3R2-e~%I19jYz=5$*+`9b$k;o*9Ha|kebp(srH3g;jaL#>H zl`IQ+9Svy@)j(?-?f2luoc4J4_d4<29S2dHEL2wecyhpkD3toz)BPU2y`oNfw5syb z>)!}GKjg#1&0O2kiAteGe02)OT~^$Ca97u^8L~HxA=&zcl=zyCcri;* z^Lxzgz`YFF+)r!!;CuRI+nUKF`=sFT;lo&4Tf^F#e(h^B!Q#Hq`o+FdRt6S|J{IKP zetk`Ip>N-7+kP@;+ zq(`K=)_Uqc5i}|%IgxZM+KaMK!i|;20OpjVfNhPGnj%OPNg}C2PGEF5I*r)iMafE+ zgNA@2g*-+6&ejG}J1el+s-$ed--C_KO%w{i@aSRm1bdoRil;Maq|)_7i4yr))=*rH zjZ|xR-g{_H>P^FXQ~@F=G=|x*QKyks=kzhxG}S_7NLj& z@4&Xr51{>IxshtJ6PW}~%>5mDdU~+AsjuiGwPR%)jYbvALbPJ5)%SetdHg6mP1K(p zXZ&US;_{ntIsridiY1`Xa{#4ab^ZLWGxut~NrKk{&zhnn{K8lO-@DhjnI!=86@6wC zbxO8MqyXn8%h1=E2*6bEftuV5DBo;gF(ErK>`H~61?gUIgLXP?FEufJ}1 z|1^XQEqOy?PfFfQPfsJ8%@Xx*M9tYJjX>-)klsU@`$R(&lH$aP6S#8aisIkoq%4d6 z9~TgjvNV&0+-~@{&MVrEM}nAJBYQXm9CmEwjSVW(5IuS@LxI#uFr)4ojmoMWq=b@c zYafp%EE_8=tMn!VPS_KByM{!inp80&5*svuYBgKAx-1m*;CiY)kgugI`&_K5K>NXx zu_}~(bPfjHb_BP{$h26%jioI@^^%IBPOi?RNk^z>tEIe>LMuHX&38KqQqp2{XaoX) zhx5h+3s|U{^hg#O^-x3GDx^0Jfj|ng6hSO)n@N#J0ve@Nv*2wO#rwauwg5p$!)^!q z`UbGNx`=WaD3^giU<3|_v*|u}QaecQv=;Q57@q(D+?l(hYC{viX8{^gLJC{#IGi?R zH7RM@#Dp!3V90|cK`q&k&yB>6{&ULbb7E(QEJ!T3brp9Y60%8)tIjqa?ZN%!>UApc zdt`Lp;y_;V`(SasMq<1kcor_-pr=F$W9a54YYy zu()h!yGnt6H6n?m-=l6DP7L|*SGUR5=|&J8&lk7w>{c~6{eOhNfTKN5Y^_)4^jN97 zS;SSQn`5&U2Y&9T-|R`6=8%+VX_v}MBxU6=d+zKM%v*->lj!N%?}tN9+)NPMKUbC5 zpUalOWs*4HvEgpI2*JI#DfmmyEEOsHM(F_7VuQGu$Pp1+q$;n&As22Y)Z;{-p9tam zcdBd4ehZJ4vN7vhkpw#t3*gF+du*0xZZk8s*YQLLOWr2o%t?yRUNUOwjlR={;njsG}tcN!nzk{A1zk&7?DJ1xHFd zb;`C_X}f_S3YHQLsq2);RJp=O4y81nEb1`=WTdR#^&?3MDhCbuCshe5rDGLg6!|B= zuQX{ENg=jrBmt5NO6Ma71S*?F=Y2D*rS)aww(m!eTuSW_< zNm)_?fre-p9UaAk2M>sBNkQ8GmGLj)ikoipOQ&MET)=_+-rSzG?2)V)-i|HaUi@mUO{5ut9lYgWzTRAIjvs=;^cLHjpEUVoIq@?VVN|r0ZXxNR?fWJ4neVk;GI|w@K@YsS#xfYY=w3 z1qDeUs4wWnYO;}(@pv3aOZ;8*A0<_5vmmJjCc-r^iKSKJQalDr3ElpWA327H3y-jo zq*KQjNdTIWwy@px&dfQ-*84PyP?Qp7PKO;i!VDQfp9e|8wCRQ3A=o$OYs#LaEviVu z(Ws}Q(IA$Wld5&Gq#z}a)W|<2Qb;ZM{hI?`0KorPq)#`_B5m3}l)<9L7z;%bscMR* zO@MtZEjjF43veXwR%^`R;;>*X z-}*CeP@+Oyu+XJsmXlu3RH1eL z{CNa}LCnp~;lhOrhO{rmxpU|6^wUq*)Jsx=NKP(Yym%4GWU?WEb?DF`95`?QKls59 zYM&XcauOlNUuI@zaQ5u40I=ZFrArNV!^1;(^k|-_&1^P3V-t=0Zp zC1pFo&%0eIYeY(6DQM?DGdESRp40Wv3I5ydXvTj}o;-=mmoKaSoyELrwxYV(jSAc! z{^1`oQ_6Zg9u)iIs`aj#B{E0}44Sl`daAT$Ktr^ctzK#sO6RI}{iUB*N@e)GKJ28F z$!YoDNZM@1)(DWat9GtRhLP?cai3jlcOrI(oXZ$vsS>9GRUO;$hn!4HU(Zq4+sN6NMmP*EaX<>x_SbLPw$ z08k`HS)qC#o&(@+soz9m1-EWpHSWN6VRoQxVsZlh9>1o|(BKdbj33Zd`DfA@?4)*J zwOEnZ(0_j$86LsIM`UW_fq?a9L0Me|cvW(1{q#jMCRHHMGW&!ADgRP=WXiL*(9)L}`KH_k> zfLJMo3~$GEn^)6T3KrxkO`As4Et94x{A>4E(~3eZH5Ls~IPS7yF1z=vP)i-yOwB9K zF#yZ`B%IfNLG?Wv?EK^##4bsLMF1rFvpa-#qAlrkd5h52h~Tq)>yH_=Or&_yR3bP2 zk?dYCK--S{#52IqAQd4>llGFdU7G%B2;59M1GmSGjDczTS)`sbV*Dt5ztx}|={SkS z;!FbFG;OLK>(Qe}>we$f-bO4&mOj^r{+qP}>hGTx*($w%7cN|=vpswEEMl=(jUb+$ zCf`tFe4x0z`=gIYB!soKdP1>PLRM=$(A*am_j+l03Hegv8Y~itU}$g%Zcla9A|+(S zd2J`PgRQNtrqk`we2+y+zwra(n7cbiWJ@ytN_~8Gb{2wNfZ!0S3l|Q6t-7(CFY(|6 z4*mV)YJb0U(m&7S{ApR+V=vQX*Kz-*OMw~*2Y4je!(M;1Fb;+nGX-`Uw& zL?RK>`X^NgYPBi9wyZbb>D^1xdrhN|B<+s{A>PSg@%&;j_pqA(S%AemA&o7mUy`=j zlu}l%^wLy+#hwDf@!GGXiXaj@Q6)s92qGmA)X0NY+GKH@0PrvvCJHK_>T}~4tH#zm zWCa%K{LF@0@SlbhV5Lej8Z3^pS)X_ueW{&zKIp))K`;LE4PzC)T6i23nXU9sGJY%@ z%MFB{9)_(JL<`$+?xtSMSsZwW_vn6)b&auBm4;f7rb3hkS6QV)>;#BGg)e{k%eZ;- zrt0o!)+rW^vZL*PAKeWz{U;ue4nFuJfD&V%0Ks+&mpmq zz}r73t0!e7B9RCJf$Hugy}7V}ery*|SPA046JH+3`=c&;_au(@}Nz|`$$Q8oU<1tSudluF7 z#q?>?v z#Df%OzZB6dl)v(ouhe$gKF)-!6o2pse}F&!<3Be0Fdhq-S<8ggi`J7GRNw^xwn_yS z03`qd&!fl@rV!D97AZ@L&;06VaQpUc+`V^K*R~yj{)vfdI%S{N*Fb1Qqfsm`FB1{8 z0e=AZ?%vZSWmyDNI^ECr2sQ^UU8)8gJE_j679lAmV3NrsUViyy;&w^y3oR+D=ReZp z4Tr;c<&{^62q8In4(weADJk2o`B!>R{_!7w2A8WkHkA~ya_`JS` zG{vouv7G`MQdn-QM#}1~sRanAcq)J$IQQ%4aN+wGfC_*Lz-2h_#nwpKcFonNPMrb( z{NfkvvdHX18)g&DX0N~72^OSmyCElKy9F%X34yAwt*xyYno^mC|334~GkD_-vbC&P zBrOZl^+|-%{c9&FYsBV{X4|B-RRZUByP4IL1@uW-T4<#V6fx$r5!E82wI#*jkP|l( z1Su9N$cvMGZd{hAT(yV{(lmz$yms78ktLBn+2_IK)y~=B-Y$Zr({W(#Cx$=lSv;IN z<$+iE<$u@I_q1yMwbK{PApBl<;ROJ|x4->u!`n79^^n~tEQyYB4~|P%67}R*7M&g!S>4l?0ER_0UkY?2cZ3IZrA!n zPOvDEqjF;Q`t|EgDc_Xtr;$q8W)!j{?c{PfT)uqSB&96y*MI%rF*Y_u^gSsd%i^8T zY@$OX&nFK~qEK#(Z-`{9-{&XZ(9%isuTf}8DQhnSE?{hQ4EGl9)v{>wc^+JWYZxDT z<+04DDcdS3Yj&2I{mpkz4ve^ea#EJn`xDFg-$+unQ_1sg0*eilX5SYx$!nVaJ0+%0 zf_di`sZRj-H+#Lno_!|LuO5{ZeGMO0X3l{@T~RhWFlkudM;6 zeYB2PERJY&xTc_xLsV3dkg}w{W;Ri#)}|QP1!oa2yWcGp=+n5#+4JaqHDG zvittKhfjRsvp9Wv20(oZT(i}(q;*$mZE2uJ%F?dsPo6xfOUTl+`PHv}6<)6w01%7C zaPQtdeEsWRSL~a``=gYUy?F5=ayhHwT5ouGs7CVZDP+6-U3X??21kz`MKBmdp-{j| zVg*2Fs$xlrUREiRNlDrGZaV*;{`9A{&jemT#Z{@LFFrDH1UIhTz|rxen4O(9J$*3= z_LZ`YFq?cc+qT>1KP@~7N?Ehll>5qWGPJXQrP$TuJkI4{snRB`<;rm!Zr;49Yio9j zXclo!TJZ7@XgVT2QJOZVr_~i{a>V0tVp~$2IB~-8Hus?nnu%7)R_XrVzkk1OP-*!H z>Aj}$U$MV%IIL+G4u^^Rr}0S^{>x&VwHq|PMtZ+n_1{)O^YCir0TK)b+eXOJ_^;j= zYo<*aUnlLq-Qy<~i{r$JXD~K4rAo*GsHM1zMu&CVB=t2KKVz||QEKztxpQ@O@1%iZ zqe0Uq=~}1RHPPwQr?IuAoO0akbylZ7Q_S{Xv!5xXenE5pXy#wi{z>Ovr8YT1sFlJ4 z08tyu%f55s#0gbGwp0C=1|)u(ojZ4M=gu8mx^xLED=T>Kz4z+=-rwJkg9i`d z%$YNon3%xvW5;WMGt++o@_Wd-&8ey5@cDWa?OZN5KK}9Ni2FAZa`mg6IFZkP7cN}D z+}xh8oIQIM=gyr|v~32VP^j*A8vh|7WNF*{lRx^TjrU)Tq*Xgs7WY~_CUGKC>wA5Dow$FR<79bGX2I-5CF!KfqD`81+xehp1seY) zeb}=iuSxr7F@Dtid}``=0~tFxNw#C1mH)DMrjZ`&ul?Gu)q=5drH%Z)&;$h4z+zEr z_J)#nk>_e4y)S0Z>8yzEb`pRrHd@lmzbsz#8rtMI2&gJ#0l*)L)YP&-)!$}kXEl$T z=KM*6{R6Q9!`lR^idYhiA0SsYDcMR1+S|8pV`XIp(db_3n*RQNeDtFq#fvY#h;!%8 z)d)Ky(JgbO*rr}-0RYHm^-IyvLT^qvfBt;!xtYu5@bb$q6Dir`#O(O^xZ-`LnJeXF ztQyqXR8sJYM5-Q0=H8cIei?~G0ydis!CpmC9HSvq=dS>lYU931+V;&3wRb6w1w(`i5w zClR0VW^cYTbMq9dn2s7~IT?%1X8WU-d)>wK^fd9JIv$S`y%>?&0o9u#O`T;#yGEQ7 z>G9LrvS^dkmZnY8>(^>-dbMMsc>y>2`X`e~CcYjHhjkZNv~99De zCQZ9W*LDDaFMQz(a5x-9H9TnMO47NS)%?!_?HoVyex|05V`}OtxZU0c+l`G)&9-bd z8y-EHW9Gjst_jJp&dkizQj`I}H@=}=kC|jX717T1L$h|LPMtzFo5k(hw~6}iRFK{m zv*&agTNckW7SDPXYid^WBCB+sGv&BW-=L+0pxie;5e#zKn|D31-so|_gOxl zC;IMAY6n17)pzmIMNM1MHUSWm5}TXa&j}jaOeTYkjSbAs&LWq~p;Rh?=Xmr4dSJ0w z(A(RK-rioEIdcZlXcV)vvrPPgg-_DhYR&&rLe}keV{mW)<#HL19@Q%zZ8jT9r7}{f zBz6BxeRWWjUD!7gq97oxNJ%%+NQ-oLmozLPUDBd-H_{CY$WqeXB`qb=-5m?x;d$qM z=bPET7~P%woO56Ci|be`-QEuky%4&c9i28yyb5c*LNBScu&{Xh3{gTt0s*19xw*!R zDZsq^M+RWTwxLtD>VYb0*7OO|x3tY8LYY`;X=ydiJu;gMFRC||mY0|3xO}dT-fnDe zwmS%TdhP@|If^C*RaEH|G7fL&M3D-(zf>r!x~P}xx?fy^ldu@Jgh#AB)w6RH$HeHW zpM!Es+t%!b22sFL1o3011!Mlso3d+LFs83|`6?X-mArEI47l=iP$?tB`<9lio+(M>vfj;B$h_CIl?Yf;(A9Kg-RM# zXg35qGORM;lPF8TP#wBT$E2o zpbCjAsn;&jldi%>SaaeUc8I-L8mb4|35n$2CZ^3iTnp9u-uYp%6^BoMtQRI2Suco(nKP%Lg1_PE+ZpAW_vPQ*v73dLn7s+>W_y2)Ek?lx)HbG6{D050 z;`xTQolQKhKXqXkCjkyRn0T)=KFOezK8yPX&XB`V{dN~5MMBS$_i6$ zH&Sx);!zOl=20V8E9 z?5=(U4J1g^Q>T|w#z@IaQ#=%_F_iemJ>+p%QSe)(0fbnAp7Fc8;q=T5c33xFZ?JpR z`aL6q**aa)o5Sz!@@uPs-FnP5X{o6lCnqp#vUH+NPX7B(=5nz?j-mKkP%<4WRpO|V znw;6gF3xwN^bm8o@jYHj46UY3*b&+I3#?;zz2o;1xSL8h;pTEOw&x>d>Bqi_PM*HL z!ZP`>8*Yt3g(flbigvyAi*_G6eaLJ@1xRU)=cMa5O@KOtY+bI{Z*B{p65~FwvEu(hc|Mva+ zW7DfwfAX!IxzwmW1{7&c<#U_TZAqv3Y5UZUK!%I({0><}Iy&-H~AE$B1A;}L%AL7J~OO23hg zf}9XZDyZXS0O|w1R-be!2f6^$d;AGtru@_dznE9MRQr+v(reS*$zTJ#G@r>lWYqh> z>6h0fi_q0Sq^VWQjXCQNYTQWs?|WT89;6{Ga{UlukLVAKEAe&nDuHZ)c4|eQnaM^{ zQu6p;JJQG7NQvBryvdF`#J}$HzQe2m=KFM)-h#<&VAKU}W*aDzK^N0pdja9p>O$6r zP7EJBI7CiFix5YRryeeTQ}o_Z)zZ`J8cyTEfW)1pNB8(@g+C`){qfYi7qi;vtdf4Q zRUyKgYnM=GiDTTix2FdIA%Hx2r*#qWqxC>-m7OT#JFlcDf+4kd=ZOOjg3T_Od~Z;% zf4t@Kx~qO;UWzB(ZhZLy!_u`n<|g%*?A1i(J?H&~{rxv^O>8>f1H<`52oRc2I$Xiw z0G<-FjV-aLtE+>!n4Pz+STJJ3gfF9{NJUhR5T${hkCuVy+EN_ ztft^NPx(E{=#xV>z4#>fdQUH}b_YFq59_t4VLQn7EwJ{S*Lb$d(8Pfzt&HA+hlgiZ z?VIu9tkJt?rBefX%En@8*0sfII8mg-?fVztLxJ-g_$_uA%=~vYidCeuGzR~R1H3+W z?##JjRe5jwxv-~lJwvsrr4nE=TxR+3H{yNcQp393VJD7>*>M7;n$JNoj2nY70;j6Ef9pd<&C;BZ9eWhSb`bUd}7577e~f0{vEmqNtA29q-TF|GA~T0iZFrmGPV21^bWcl zMP;~T)P@p6LW~?uv>c65rCPL1e)MnwM3}fYSB+uXM+`^v1wtt(>nIas*x$rizl)8= zM}p;jWwL!>3KmuQ9T~Ej;f1+$J>te`JCxz8jT}n${e613#QUm={xLt4x20wDUp z-=IA(-|_KK`ef~i20FlJL82JKl99yzoy$shX=j@zg~H#4*9ywhRniP9>T-QG5;cjW zwCO?P@}`d|OJ*c8JiHAo?*7WbnMmao6Drf^#%8g+Jzx!6u(RKPzlb)HDQr036hFGj z#>4a7-g{R!6l;l!*`I$t88kM!h%Rj;>Zp=H-^aXQijN5e+9Bg$4Obxk9WUI%#1Ox=hLl1dI z_!Cx}61nEL1vO?*C^vk;yYx0;wS<~4oXSkQi68PIqvg+Da_y`MZ2kjoqiH3L)%pF{ zU&iZ8?IA&#-eT8qPBv*3M13E5F_meX}6y~Kb!V$tyi)KHd zfGVPf8YK)REAe4q9vlvURHbwuuvXn#JgG7at)Ba`97Nc5`bGanl`;yK-1qkzwvoml zfhX18f(bIyJ{p=yF;bHcOsvAtTaPnKOzIlSaMa)iQ2Gkk8W9%FGTxA|x*6Jj^#rs>5^T=x%!o1AV@43y;6U8<~E_zyW6 zHsJCq)vU0tr57F@yP~`EX$5ja&*unFQJ)_F%l6@u1v)vAj|Kp5EinPSsedzDw#10c zR29N3v9YVS2$ycm50Y1}I{y88hv1^3@l^-z#vHs!HNA-^U6GK0|JXj3oSWpoThX_7 zb*(M$fp!~@QJW~F^99M|=aj^w?C_Yz;J|cxrP1l>OC_Yx1C%IB@`M&_WCUtbVT)23 zbj7vj@s-P;@v@bKJv}>Kk!G|V9U*rtKS4%po@x!ceTf#Ngk6%CpTeN2VaqMshq#jm z#lFvfmhd~aT<9M%0pbd`|lfUMZIQN3WLr@)!7 z%zoi1CkG8^XhBs`S*2QrZs#gDzsJ^($YksYRbTO3Qs$r5I5aHXWulCSIsUGe#Eql! zE=)4SWd?4MD}MU9evV_#^BO5bQcDANt+fdAv5m8{>gC#F_aD*^ocpf)mIqwLWedLD zBzrQpKaX6h;B`86DrDxjtnv?FJQen);(zJ<-Xw43YxS`CoCVuR{;CcZ)0gxDdCK0k z@p1UvXqm1iM0hdy_VRES2j+JT!AW%xTTQa&^}cb|{~Xn=*Kd6fgr2Eov%87}PJG*` z8Rq+n6T-vah*gp+eI7&nY;^7H(vqSn>RvNc1{*V|GH%Z5YGK_GyKY|Q0UFqtf9`z*!DQdztE~w&7z3bp+90FRS@Z9J6h2ZWLwbMiR z?WF@Ka&<6NvTmSXuGf=x`vzUZ`vKrkPf!h18WoMc!vclj(6^8-uYlBtrt@iCE@6VV z!l36~N$DtQnRyfftc0<0F9_EgGAt(P)|FGlXcgZMtvgcU?MTv1Vr3Q*+G#%XIV8XP z`@vlgn|IHDZq%Rc+_TEDXgDGLDP^SUwm}^qi{*4H(@Hp#^^;UVA1!FH)$d}5RJ-~a zCga0JbBrW}@{8)!ecsU<3&TDI z&J1(y93lVK$$nBiXvvlAixtMv4%f~z8+|B=xgi=xN1^vXtWFXrJSH3O&Y8W3T*zXV zp3t?5~>XBI`PlLarU8fL8b2cBz}oqdzITx6Iu7|_}S{y5E4 z!G{!*cuJJ8VM5OR)SBy$qZ-V%KXHb1goC;BY|Ek0tvCAt-|mLY`*#8-+WI(MDJ-R) z%(-=-6SDjRGKydB$HqvN=V0+xKtcXkDK5k7?BTJf(e~u2@h>AVac|c^y#|7E6v*mX z4gBzx?y%6bB&}##k<}|@N^`4BRSpggkOgW+bpSwkYd`G^4#4k!tvO4n^3K&^BG}$4 zGCdL7%l`BhEyx zb(KH6=24oJUKqcZFe2-Nsk2FC4-m|Ydhimb2&jU}xHz(1ir){Tu%BIFLIg~zdfb}4 ztwiY{^#@MO$>K&gEv9L$DU zh(M~)oo3&nLunyM>J}JLl$apePdl2<|Gmm$bo!aLGKp;3N;-1&=yT?7D4xo=I_7qL zjZEKo4*ml+4`J{o*^8&gj~l$!ANTEI@p-LE>&t$vZEsncxJUWK(amlJ?j^IWlht+$ z4cq)o;RE!i*4``9(9Tbn9s6kQ#txQqaU%(wP7Gl-&p2(ZZG&%?v3#W_pB5|roV#mB zWSR~I$)O;pB8?l5=n27T<}3v&!8=u|j}XX(M4=rjdMjs|fCYAG{<>-W&A`_ky_hXQcaSyay2_~x1QQ4qQ}wo^z7l-~Sgy0M7i5wLS)<|fkRfb3O! z$$_|+YyFAa1U1<(_bX89O^$I)%t+1gJ8irGi=|Q=Z@ws)+n!^Gf&O4NCR}PE!@qk` zi?VzEls_K?>uotlerI={K`945me6)4i;A;?ObSihu7kXaeaegC!d zk=sT<0Dftacfro7Q2kC!S63iH)?abezDk{SLJYg&u!=BA)#)>@D4i0y&G>+L?K0hP!8Fjqd3v9RO4%bu zh4XF#=8Ul*@VOHwESVo#dX2j( z!Yn5&4JobcKYxC?ySrO(*k_tOZjz5~m%OTW1UF;`9n752xhLXAV4nS^K9`|W;f`eBsJfR;$Toed*A%vH0z z$=^nU|B6R|Gwb^DOLjv@&)yJ<&O6F<*j62<(>kb?E6Y+KBvl-B$z^vY3H8wQcZ~$* zh30=>E<5v8HZ%<6?Yow3>$4;oOEVLURx1n>J^vXZ99Qx%H1bp$z?1J)=4WSTYkR5_ zq&}%Q@BFai9yO7mZvc}SR|=}r?o5uAIIHCSB2<6x-BF-KFo*di&ThY&e_xzJQe<|V zh59F)Yy5rRUJ^xBU=tHTiA4DGD%J2hN;(Tj~E zbC9NiNB%`4DO;&pt;lnz)N=w`gO)GaWA=dd)OKSI=Ph(?79LQw2&)O7+UcnsZ=F0C zNZ{ezWfx90oU~yy{DUaMQwSrMmY(>F)V8%%vXedA>g! zS?nwuDoG>|`9_65Vav$hPJ3eF&v+AVn*K`f5Z)$qW81ZSN;?EABBONbi|BSsEUAS6 zDUbJQO^Qn$zr3l2tl^NTu>z&0dCW$F_>LLDHj`yrjy%^-nawuQ276aN34+T!-5%r! z#ae!n7u&>L6zOTRCIL@ROyChqR~UCdgJKn^&p#g7W9;w(vxkkH{dweSjLcNs#~s2v zD-Eq{d;U+Zp|1#vOV?^0MK3_MuTlHXH13d+f|g$3o6r4!fPytDxz)T`kn4G_s{+$q z$DXqt=Ow6&djKJJog~iJ_?cHPi7x^dnU?|o%jau$n*hJRMhK)}hU<4vc~K7;X)6X9 zwutSXji>56vP97Z{qY6*wK_jOzxOh#^Z57kw(T@=Zpr;`K$$H&N>Ar^tjY#a^Z9{P zOCV?hnH4YtF2$di3D64)3queI@_asZrD|k^y88GSOlinL_FQlOU0wp?NUr-%G36t? zpl|)B!WX`aQS4_mJqbuby7O9WNY3@O$Fl&X#-{*Gs8Q?gml?WN-l>`> zFR=tbl0Py`n*XI2YfZS>>+6$Z&aXWC5&xxN_CDh5JSF8dxIX*AXPD4`M`!;LhU{cR zbhf&b@@9_FlE`EImXToq1_uq3Rm=nqKiWP}Y-ltqE9-S+Ppvjafp(~JzoP?@fRHdo ziYnN5ytsNpk7=ZJJOWYXciLzkm@ThtW8&mg^-00J+2=Rdc;hm&YLc?Dl>DaZHewapsEzy%I*}LSFl^;_s=F4%QljDT< z8duJ7y=*Pqz%@=AhOWl%Mf`i-4#`WBl-^iGMfabA9W6iaFy!Jnd2@}J*F;@NRQ?q6+l+>+_;jLhE_O0it1_I zJbK#jH<|o!v7Gx4mYnn*;9|-AL`M0DmjvfxQu{4u`K(j--p4EA#x>%!+4_)x|HU7O zgbF=aQnuqbjXpR}_;ufO2VXDkfhoKqPU#UBPWjyXK;VF2g8(ghn%lYj5=|6^AWXbC z(s?{e|uWPo$!pi`5rgKj9BQ)tJPJLt;48Eq0F>2Rcc1*(f)PEw?q** zg1Zr^x0AuMEiElX^o;6r-az|++GhTdYuHI8BHp&vx0$a$X9)~o;e0nRGYZOPfG$p# zFD@()w;V^pFe+;;0}C0+>eg@3x<1o zo_YodCa0xM)Z|u9?drbx0vNsU?%vN2?eK=tHQ_fQ7o-j2(%esXe((^hP`sHtExQ&h4Z0qdX>tYtyJR8dhO zsjM9H^V!?6UB!~l+-*nq1dB}RPY zNf&*Y%Lydjdm2=h1M?MtmoC)=?`pJKa0r$Z6+H&ogQYX)ZW&s9mD=)h1$S?gSsza{ z)A#8k^7Mkbe&?JVKl8<)aqN&Z0T?t34R@3riJ9&!DQEbF3RZf0I)b0ul6O)QYbL8- zNr?^~0iTJ`rRN|U7rrPRXGnYd;J2mC%3=Z7cFykTz>o2%DSY|BUeP`k0m5mQr&vYP zRKho7QAcjRmu`uUYOAz?lSo1ERV!82{R(WYULx@anKYT|tYxP^3t|v`k^?L(%FBL9 z^&0-=@*|_FqG#9L;&LRzMPIXJ)h1=lY*z0cTO{`@v^+zo12RZ z|8jPvgQB4D?72nE?+G%OIbD?1)zz!nQJ}gIMfB2LbJrrKM#XD%lq!y4BO`Up>_~@a^VJ zCAzObttOkU9B5r$QB))XI(RvPIKW^tGiUo*-2J?;r_oeXK~@YxmB;W}E-mSqo8u!O zh`_3r8x`n+KR+${y^k!T3mvvLL8;4t6b!l$X$;8DHlcCg&eWM11`3$wvEzVryKC z7YB>z2)}&beA;9?MSu##zP!xOH$xE7(BLK&_$^$6(kHCU#F6tlI`h5%%30n8-_+N= z-@ji9-E2{Q)JDO(NHe}uE|Y$ouyMLMsyomxgw4vIivme=oik+Ui!AzAiHoOP-jss7 zV8>&()MCq^yZ5<`?3vNV^C$H%qV|C~hK{hX|mB8Mi#`eXYmm0#3D(T2Yr2gHsxFyXXr_D zem?cp7a>j_p3cqF*E=m^g4b{#USdpWMFoeX9xY zKO-Y%Nqj{ziL&$05uc;x$yOn2!DEB~ z%gtiQEp$|hBEEq1ov90}~X0$-6k`WQl`*l96!c$j^zon(6VIlGPe`xc8iOjFr#DWF4?w&|~90k_#Gy+jtQ6))?RFtqT6M^=jh^V?EE`BB_! z$tM~lIa-ic{UkzPw0K-B83H=)PyA}+XHjF_&ytMgyO5^ui>Ik_4h+XIIxk?bcgII> z?F?EY<;gcJK1$x*f35il(5~fiGuJde=kJ0r*?HgMQpEgnG)^vJk^K>KJUkn-(pO{_ zQCsLi<~g>uaNST9P5M-#)SvdFLX!v3sr~sEc)RvBdTwq!3YkJAs*IJDmDrC|homHG zRr&E2)o#Y5wH)x@{NQsz1FbMi68iGzSAv3qV;*Chr`cs?7>@!!Z*M^~baZ7ct-dem zXz_gultf?ruk?0!EuI7q(a;Nd~_W6p_mk*DxH+&R7ecY3X)p+RtZC$87oc-Rug zVKLGrfNOj96ERe<*dVRl=;eQ>co_W5kTN#Zq@&1}E8e1F+S^5b9)#neuO<@(Gm}?2 ztrbuvYCP&eYhR1aKQkr*wXy1n78yoU(%=N0oTOVq_#*)#iDY=I^K!pe(daT`k?yo> zjxA}>Y)-@D{k)J823jVuVk4fd$~DzKa<@>Db>?tGdEqZww9Kp+Ju@>iz1cA5*SKib z*496pY<#lp`L9^CT_Of9S>`WCO9&}uu+ZpwsIW|TD`vfL_I+c9Nsj%DT@N2gvnz%;!kn)9~l0Z){74-e3yAPem@ar8A^xLytSr8WrQW`$>g;h(Y6o zKi#UWwihctIdpSFL@MwqL8$P^FDH?SalF4kw`P893_IefvAn(cq%eLl&FNV~jGnwa zMw0<+xn4aEJiOz+Uuc_7*Owj;N9v2TXg@C$YiO{G&}^-LbfUDA|Sp;`$rvnU3Y3pUU(&ln$hU{RxwV54mt6 z1pHp-W@}3e3sr8gK{d}$aZeP)Cof*Sh~AT~u?0NOzklt4V{W;Tlji%Gn;u&=+u#tY zsv@;6VO7k$x!kLAg2f~y5yBq^2H5Qu?$F9(9oIJajBVx??!v9&nIL(LkToXq>4MYR z=LqNbo&|heK!*L9H&j_=MZ)RS=jw|KNUcGmnh|qzL~1i??Yi3j#!2WwBci4j7L@$_ z=pK=KmTxph?aa)A_`5%`3%v&yevXD%_g+bBL~17D<3T)UXZz?(_YEeh28jCc@$s{N z{d$E(CR80i6*$C}-L~$SotM|eIj32B7~63fS8^kZ(m0Lf8J#ZAg^%gWI72Qf$-uw> zo~Tm|HMLN&(Sruxt=p8=i?Y96}sFOsF_-KI$cxO9xBan=HuMxn=)4fYIo z|4@b702ZI3LYTIlFWSY;S-n!fiK!D?f!6f*fycu9?9_BG^BFv$cvtO4c1)PDXc`%ojs|_{ z(B~&Un(**O|G`{?AOq{EgWDHko^Rix_nE}rn#@U*0PHu5|Hrv!B@JmMTbAnC2lD?s#gvNA%9aSJH{a`K@9x62+ z*z~TvL6q8H?banSc`KXVW&Yf=ZgB8?ufF>}1An7#LxTKC&uiJRu&f*2ZIJC z_M;NwfyBS4s3bsH#4S1;Tg2W5=})uY;>w2bTRFI~#E7fxrRa?Kz+Ltj1~$JuX1N4C-9= zo7kSDZufUraRu6!366>6jFfPkDztCkTG{uLxX#}(dY}bYZim!9w|QR^q0)c*<;mnE z^1n--+`K$Q@FJ3t|Zosra8%M`wI z)6kx^qC`S2mNhNx%$GW*=65zkHZ9P~6Xna_{*+)Q@BJYrClZaK2P+CmM3FTCuUp2` z7~z-O=nZFWKyk5FZ{qk<*(HIQ6eyGUocgSZ=moE4G~HWSlnlIKJkR!tg1yO4(5&Bv zv%5_EA8Kff7Tfw11iPxna{d%n*Vam$Z{1y={^=X&ScNj#n45{45xpTwnMbP4`5`t~ zQn7rI&iISR6@7vOi%k&s@P}&Q=_Ca!D;5Z7bWTax zR64O4h8$Mz;^LCs+$^|Jg^ES`4?wmJRw0ChgekW?RsM5s=7}9z7-MFE@mzj<`A#M# zlze=A&g;b&U7p1b=i@kD%?69y1sRiR8g*7*O((WXCqAFnS_MT$VpiAHb?&>a0+ZM) zBBG8I4hx{Qgj}VY-g0|h^h=N|wK!2*BPIBH?72`}Xy$?XV*^i|RaXbI0}QNe`hq$z zu<)m{GjM%f+`ZZCNL{l-RXI{63RRq%x=-0m?B5f{evG5CR_$|JN5|ND`Ov@&yj|K7 z97#Oe(2EI#?J5nP2DcJ&{Lph&$Ts$@4-u(S`14tz57?LSECN`gSIa4?bQfLFe;&Sg z@T#o}vlKE6_k;d}W6C&)@(n?1%b#Ggi)%2%L@M07K#IhO$F%B!ol>S~{K?N9lqdzI zAHhlKn966{uNm_Or6s53oBQxwCSN*GYym$4cez0`Q3TZJy>fwAcgv9||H(0L zG*SwEC+O2qyZeXLf;Y?))?c^cy=!;?uh+KN-1H~ln*-5T?Y4x?lU1lQ@bwoVG7Sxl zcS1sT^l6sy>Qu0=*Fj}!=~#t5N1v@<)Yo5wJ1M$4?u_Nml5sF}wUmM>EU?kg&@%Ea zn7apLpsMiWRSal(x1>HZE9+Ir_G zCqMLfVg?czlT%VY*xE9m-bnj%t4wdrf%4io$Mng?WFy7kQ*gY*4L z&vQ(~57NuVadto0%e@jGU`RGh{$OY4Q=JIiqthhS)=1VboF-uOOi4-#g28a06|6Z> zC|?9!BGJ_E=H*8JzimWQOW$mn{1?RbtXG&vL)mNT{EUer}&0d802j?VOITZVIKT_C8TJy;rEERt)#z z>aiGM75faU-`(|h{P>t9@FZ*IeBw^0;f5MVe@f=&bYxR*Zupu`WL~POxM%m<1umhZcM$4SlkAjs0O3bgL;--E z`BvMyy1DI23N$tuu;;|qWXDs*-*fden<38h6PXMR9DA;Ray;FuCBXyfBa_&^vXg+B|CS;=grB(UWJR zALnruQ1W2fkLxn90#K5J1G{Z8j_#{`sa|8(bZBvvJGqxCYn5-tZhSLMbn{3|a{&)g zoIvdkfKn0s2o2odZaA%{o}O?YZ;g=vdK>9GQr{>lCaGon#>ThWV!Ce!FJ6Nwd>qD_ zVY~2Yu7AV7Cx3tS_PWS+wP5zcU}E}qv<2q-Dqt)xPrgh9xk3jGX*Mcu=Q}E1BqHf! znG&rBdaC{X{Y29&BBl$TS1*j0TD;jZ=}q_62a_-$2@FQ>d5xx9iI}zv=x5F}^3m@B z?ksfU1r%8EREo8}Mq%L%&f7Sk6tS~4ZQ~VpV29<*ydUsKOd3QH5zenvfB2tfYRv74 zjrc0j6dW%IKs_%oF&}CFSEQue-h}4wye`aLYif&MPo3*t4w`0e^T#ygo7nT%C?1XyBM8L`J4 zbM>R^R+_-%?(jKOJ&{2w$XHJ4Y!oRMGPPrBWmUYqjDe;f=be=%`kii|Md|9Vhp8Fq zH~|WPn@bHsPvE7Qhkbp|>h#TG3Xg>UD06cTZadqtU*>>2oJG{tnQ@Pa(BzFjA35ge zQ-7VF)>y`D5+QFhgKFJu){oTIa&PnptlZPj4Uspu=i&;iN}4}_T6$bnb1tG4SP|M1 z7&VP4%)~o4(c9MN_*@JPS^~HEJ39lDlV81Uq#-@pVl8Egk}rHEEC5#(k?qTP?<6r- zV}sgsy^(g+ujmu&%nxno$&G_HNU)8#n{h}9DmAs5PM@Kmya5LTR#oTYczUwT#PFfG z^lA3%+Td|(L#_kGg zXV2V!LB;Rk#TS}Zr%UiQL`9|EatYCuEyOh|}?AQKv@6kUfu{Npe< z%9@3_w)}m0n;i+i^VUm*e}k;8)n$sLeFlXmf1EW8pN|R(hTRj&6k+k@GXjel62jKu zVO@OwQL*aPy@x4>2?bXSivT*ln<+O7=#RnY=JvMVy?p;^XDZCoBMRU&*4Btew`pU) ze}}?gXducK5cv-dhSAZ}lNZk$#pkAU`1O}JGBoxes)t&Rd45n|4X5aJFPRoKM-gY1 znT4M=VP&|4Pjg9_y{bV~4UWV3fEjNF(x_q~F>Y0~;em%1_pz1TQ7P!Re? zM#MjS5;EURib?2BJWwvaotd2c3NYT3pAHOa(>mXvj%@_5`CH#b?cIG@!^fvA%|gg1 zVZb9G%>C6B)I>`k4wU#Y>FE&(-6*DJwkyXQMAI`#FSXMpUAdzZYC?eXV{Kz2r@r_# zIyyQ40J`UHh(f{6si}Phh=8W5##yRC*I(sFu>-JL10HLldYTFHh)e#dfegcW9!5#@{cUu^0_?r}-Iar0nI`GaJh!P*+R`?FFx9@zNrb$6)zwamti(&)qv(4x zv9$#9H$WZ1T`>VIEkfZD5#5t_WyQtVr0vB`ol113*Q5Zb0jPq!>Q6pmOgutD^s=CW z$#|D~y8V&;LVpUI5)=^)zD5lJ3IT=eEHX;!Q8rNDF}@82IBwi z~0c&uVsEM=bq%#JQ=Mh3SD%Lw;L5#YIkVdyd zV=Ir>Kqru_t0U^FK#-`B_%j5<)a*(9d)-SV?d|TKRF8)?0teC%u^f~67f{!9afM>~ z!Hz+ zZ#QG|Pq0<5Cbj4D{%oF{v3Ahpp^u7olcWd=n=SEhaf!3jc-&b)Zz$(zd*@rN@}RNY zv0OycFW4!}YNAPE#IVOCT|B?nEXu7xy`xF6<5~Dpo(S{t^FKj2Y`HC8V+@HXaN(2v zSH&Li4+myQR&-2$E3E}hkj(TxzD*pVjm?V-K$^U8r zO!=auW%6ViH;MB*$8a&lS{f{2O`JHB*<^3*hm7?}0#{PeW>+{Vrh1B*eE<*X*f#o=VJ>ey1v zE`n_yG@!h^JXxpEd@K`BNotSK@XHvx3V~6ShB=CC9+ZfLgoKWjbtYmcBRM%(!j@5i zCK1UI2B!ij5$OLLOhD(>PIe^u&{|pP-@Wd>BG8(LcdeKs{3HvOgNQ{YC~ErYNsPzs zu0>e*H?BZB-92< zeND9dr_WGKFEc~`g~TV2U|Ula64DPg7FhW2*~Gtw%iH(WZbNS%sBWr;hFAy%r_c+J zZT*?5E)FwP&g=01fvt1P_IY=9b(Q`@t_!V(g_*4(ZfGrXY*~HSqe!zgy!1DlR;r~C z3i8IptaMwIN%^cT!&-$CkphL2i&2Kb2^z>ETIi-JV3T5!Z>j~pLT6o6CQk}p#ld>t z*T7YG5{jSCW@Kb+9pbsXsWlmP;OMKJf@YDM?)yyZ90{mSLuwic*igpv2`a}6@ZX{% zkbODACKY}PKGQS)A*fi`A>_a)Yy@OoXat+yc0NxST=ztj>j}lz4Ss#$`s_Kdd=^hh z%gP!VT{fwW3pK&r{Ue5)77Uemsl6C_0N4l9hLMsI21qt-*3WGLmQs4h@d2O_q`O~zV)+{z`Lao$0f}aLW|X5eZ^#(yX43gf0Y=mWi3R6i>u|@#4}avx zdt7f+jdQcOpp1LE!{v?PwB%IaQ$@{asKSF_Q0gBZ9Q1(ZJ}1&cd=#hx$Nv5$rG|XW ze#!Bn;Icd}UDJId#NXdPujgxGG>YGM#p#FZ?(VTpM%RFV==I9hCcgJ<>;dhANn{4#&Yx|i2 zmdeli3JPc@=(J~V220}b-mn{Jr`U!fGkD;Z5D6?o&Gfod! zgKrCWh-*plJuiQj&ek^|LrFAVYm>ih0|K_EsHpP&bOffoFkBAWd& z&PlpwxfmR*A41+lK+H!g9XH@v20g{Y%ANt(FbS^P;bO#lksR@eB{IoA>lj154ltW= zYKm=e?m6i#m?)IG%KDDQ3f}?sp^zs=LCzmNR-V< zOaPs%dJg4l?a)msME051cz6|sKD*8FR>fZDjO&eB_}t{JUWHgVDae}>J@-U4DP{Mg z8e-#!Bk8v<|Lc)e3rDDfkkq(6DCU*r#)P|(CB!pqz6aB3DE+vP-M>p*Y~2$tD~bRv zj>0n{ZjERXvji4Yu00{k+@P@>SZ*#7V2VP+@OBOkYULVfZ?lw3>;}%xdRLFP`2Lw@ z^dVbLW5Gh~G;Sf6^j`Y~sU7s@(*;8xG4OVmfXH88JHKLhmG~yXl(+oSEoV@EKFBEYdme4@dF0C@R zw6*O%UhPfkd0KjZvZpT&N<1QOyj?;xVGPAIJQ&{hhoYRbS`!fr1m1Loq0!!QR_zc> zQY9P`081yQb1BlYf?wY2yk&Qhugw%t_dXQ3hzhVw+~2gZv^0uc_3)M0C2X!_xIIE; zjK8m{@l}c!l_n{ES)Khm?jjO?8Xz5Dx$feb5t@q~@ zY`naEljZsshUqf=z$13HJ#p0y?s_D=Ui|Z?NOoj^h8oA=Uzt5rQh1P+K4OqaNmsw@ z*1MUrMT{>U*-8;W3i&^VY*bb|D$SV!HngcEJIJ!Ivvi*g)6A|-xT=fSS zlC{=(62*Xq>jrh``|iDr>QN`TQ= z8MuduZVN}oPl4+!#ddFJKm1ntk&*Xj(q0lt4Bvy!Q<;(9alo!m2u|&#On%zj7rFKG zqi>lCAuams4W*Z=nDSs^&Oxjc9OG#qugi{_T$)CVD6HQJJ37U4V)tApgGz(k>rM&E zWyG_qVY^q8qTH9&c}{F!$}Nb?!%{ujy0X(?y|GZdSTrS#_qt$nteB*=_c3Orem}e2i zL17^U@|vS=*2W*CE%q*NQ&idp!g1W{_2gVE{L30(=2R@`lcOKsA`h3l0IIQg@o}i_ z4S2yCUm7P$&d^PpQtbPJc|2ZT{Hdv_2+5LkyD?P=D}CB1>>=hE+^4cKm7U}i8t5*b zmp_^WK%#Xt)MT$64|g}SO`=VQP2H>mH!(FrDqFj%kRLiiLCh_0EV*G_-Hw_rBo-Wnf@-_FFKaG#iK~K%-kgl|4k~P&m=A?l#?B zMCf@ao>r^n|19Tm*2JT9;-U3wB}}@`idxsez%Dsmv=*+Jo107NsdNAcp&|NQ?SAdq zUBg6fr&IK3L%pFNwfc;ONj+Lm#Q97@E%ivX(ctnuu2d9^aR|9594e-`3z1$b8hsZN ze=t(EEsOhvQ&8oLF%7{VszhrQyY~b`re$Y+BuJH-2o09JK7IPc85fRS)Dx9X9T}UT zPAM}$(@3A1{3?Xf5(05!Hw@kj&QlZIrkr>pyIz#wK@r?rbkrm~i^~gnfQ4XEYR_WZ z!W1+6OB8jLmHh#vw83p=Uky5sl4x}v$q+niJG)vc6ORh@3xB%V@2u{&4IqEo@lT03 z{H94)v8W87$O)9xa9!kVta47SX$+D7e?)x+SkqD4H>iMuf(WR9(ltT_1WBpU-3%m@ z4Um-XFp%z$kQy+gVT3fO)CP!jgF$!q*mro|_jx}ruM6h|EdKv<&VB#tZhKp5swW)8 zOCU<%^0vDnfKQ*b?nPOh4f80MZqUrzatBvQ^sAKFl%%HLEBH;W%M0*@MWtFSuh)H& zZUsaPc(x3Uia9trbx{N!%k8es%fEcd{HbYZ1-@#&)y!t1IJ#{)Lhlb47KmbAiY0~JiOLC3rfjf{RCAj+RuW?k#ro*IfbzJcA zJ({=>d@h_BTS8NP%JVAgX_rWWR+Qj`@1Wbx(01FhF=EUG5o|9NWe+q*et?dg|IewTHPRPTt;{{om5G~Pgkuz@+_6)p%t~J+jm%vjmcj*K8g$r zqg*YkmAvwn;NIJxEI=QLEm zKAdvmoVFq^yg`~?rT|cr7XP!qI>Kg+9=AaC%Vrr*(vQ4o0TAZ$#zsdl***IW!^0}8 znpQo_cLx{Vi#NjE&4^!RFL!bX?~I?^@BVR@mds))I>W}sKB#{~Zqw?KuJ0x7O)+fg z=0+VO+e!Wr02@}jRYgVNsly`)BgKu&9`$bm;rG`lfjB^6OzgREbXC@8L_?Y0+u0W+ z?LR#Y<_wY4gqE_qpmrjtRT3-~me0x0Ct6t8fhUcv2}NZ-1RHwU+Y)JY^33P{lX?aY zJV{%CCAVp?6xv_Us&%vl0;Mo@eQe+*-}8MEo&*j+FJKu2!nm963b+T6ndU57N=8Bx zWNaF>y4hdyu4jgqzPD9BqsW$aO_7#SPonrovG4AUczr|nsEeQ8=fi)H+52M|`ni=k zlyaUQONa;;J-jF3ai%Yf+V_X63nS?QPYVLW194-4h-AZcS~BP=2br1ghLGR(H58vfX!UGbl1kpIj1?=0!q;vk2^l2A9h}gu?M#ZCV{ikZtM}Llk;83{v%Le0TC0D z09AATs{FEesN*7HxCSsFgdnd4uZ(I{*x=YJkuS+Iav&W^v1krpm{P3#`OkZ-1WoO* z+e<}lIjCY*AHoaInKh3|&8M}X8gI0F3=%Ux%WLS>7gs!K4Fcrla!ge>?a>5igBF(- z2gZMe@)(x2I4bVII?mU5(Jn4eo=L@Q z56gY9w&I=g+h2~`T*}e9PQl42(E1)e%ShJirY=6FZ)j*45WpZOCkFuGnAEM_GFN;1 zo0mZepjgq?(jtiIdJpOy5$kud+fmWctF=7!1#iJiwt{$;^Op2 zsi#Y$d@cLalhqvt(bNaxuN@qMyZ(Ix0{+v})4%WoH)MJF<3(>LN5{XDHFmvY^yDD} zgM;tDFC5AOB<)LJS|AT$J%w>m3)m+V1o8}zjv`SgV(F%zTn)t>C=kr~p)?T8^?3ry zO#sw`AQXivH!lf>2jU(#eUCQfnQn)+SU2L>2x32Fg~(bn7p>82BSp1xI-9t~+pvRo zM#n~9>CwSDSs|q%;Oko&&3}{80s(Yswf&U4^3%2WTN!(RH z@CiPSD*J?vvdU#+S64yM4YB*H_g@V^@GN@gj_Y#W(nFNPPf3l=$_op>;m+(yRJca> zSvp}r)N2@JKajn9L+6+c(pFUl54O(|3(k7+AuHi~0m}~qpJp>&KE9W)Un`%c{IdF> zwl4~n@UpnDtz79<>>O-g;P&-#DoFabyGAhoBC1=UzT4MyM)Fay@2&^Qjv*AG`8_M@ zxm*)BZJ35GcB_jE5)=kxK?{8^z(>fHC6O_Ng0U08+}j{1L+=oz9AKymI3c6(R3Xga z+l9i3Qv%X(vN!(oVzET?ON+V4>MP_Tb*C%mj-0c&jz)r@X5YiVK7r>lh44121;n_5 zKkFt%mAozOK|g&4;u)|K`aL&)agE7NuY_iJJ}-XJyiy8)pAh?`*)(YVGj}$2yEy|O zZ08a-eVFrEiES1f)_jQQ2cqxd;wUBj>fC=>czdU^$!9YR9~F$!j&|D*{6Z-k98mQ za$Cdp&Gq$zS6*A9e`uH%OnzZUwj$w(a%G^k2Yt?=<^aluYin@XSn;Fcn}4gf;Exfx zIZcG#Yu?iz?B)FB)Ji1>K$77j+1g3N(m929A9ywK5?iTVDA-DaPo^%Fs@1^&)qt`? z#>AL;;6s4goF3_!CTvSLa%hjy>r=Vv?R|JPG;)BLaeM}Fow`YwSpc2<@_~;#B0M4@ z7yRZjr8}hQhf9GMOT8aTY|f@;W}?jTr(?@2D`8;_Hum+>b;Rwf9!JLx2PI%InEt2xNZuea!wUnv+l4nev#|=*iq>kO- zLKy{NN6p1K5eznSHQIQIm1(#W0|ZIowJx=WQme&L)eMjlzX#ZaG$`-S0|NJ5gCo_G z8h~udNUEEo-}|&cWrn>I zFGwSBeVz^s0;Q_yS@G7yb>zbi&=eYZ#b<)RIFmc?R?iFzOazO|i$9*e38smkNqBv5 zi6eCsiTwhVF>38;(N%v?vs}81022FmwmvyqpHb;H;R5dD3Zd6iXhU)+AGRmrPNmiF z%0LOwBvK!KDo|fYwRN~Ua;l5MvuF5;30yVyg6q1g_gxLgC9DVCCB-FeSi?86tT&*P zpcGTG7Pk;5uCJ7>RsZCF{KHnwR#~Un)8f!9zB0;S%jBdn4i{4lv9pf$YGeW`2lp*5 z+j=xsXZYDa!v3?|F9Rz49A3M7Rkf;ddviA>wv4T!Zgb;kO!sKA2ZSW+odVCMj=?Qw zy||`=3Y<7Jzh=~xw0<@(X_NQD2{c|n38Vpr0)QQvHlS6?n3MN1*W2d$R?}WIwc@ql z3$0#=ghO~)`GcFp{1OtqFPzF&x!60~!sl?capo|GZI~ z^7;1+WCsMiWB__6lm~0vbpngAGE*ZMEUef&HwgKhnZj$bC-1bBT`9j=k?YQ_^QLgYo7O4S*_p?#>`{N z7>&qXR-%-P)6fQ&nCc6ESng7B3qClQ2pnyzSV#?eb!`p2><73PPX5rBLrKC(V(mZ> zH8NrXH32l96qpSN-HOxalrInK?CiWe_dte%C2)<}+1c^?0Q&0p(V6r5IR6Y?PndN5 z#S*ALCPXK^npzkP8I!*%@apry474WPM$^y$kXZe&P)QN)xC+!R@=H=g3PK3^Gbt<< z`)hhS62xGtPUsN_$n0jU%ynI@X`N^p;rwQdm*D&U(ialfKeqJa&fa(Rx z=Izf)e?=vou7xK&x~#hh?7O<1COBPm4)#$7W09Sj0>Y(LRaC%gu5o1s*i>^bS3_>XkZEVQ@k7*zZ^u9CKCmHd_ zUCXPh=twK#-h;t=*Dbu>+%^w5y&-(>UJCLh;o-7&CYLS)Y_#`=0E?$0FbDnoM@_jP zaX~TK?a83Eu3UJ|Sh9iDpmewS)>+{WlXD zsXRdWu#jM&pmi9%sx&SaLjDr0t?e@$zk4uPY2W`m0iwb;z|AP(cYGTp@S45QQx=<$ zN=>Emid`4+1tC3e!2A*`Z&H)K+*ayTDYzoJ*0QEp23M`?`8W-G=`&B8T&t1RrG=#q zC>9OX*eIE}K~U!g^9v7PSgO)bv}3Wcw~6#7Rv3Uuz|4#e6eX8d`aA(ae($kayYE(W zNPPSqs|;$%08o(vH84#S3m647V57lpBA?-12tWnnbWd>AAg|(uK;p~=NYq01*CCNt z>g(&(w7-JbU@jh>A>7o@3~|s&U8drgm_z{G;{7{SwxQL9t4b4KA#v=cztZ^g4XE#l ziHQLxCJOu=FTt7xfdt?d9k8)t_o=O^(Kqz$-FIPr&?zet*>o;Z0xiK@C!&t4l0Z*( zYg0O;0oW}LO={+|!hVy2LU78w3REmb#l<^+LKp=w9O(#DNy$yeui}q7UZO1pQY8yR zg(0I@>gO~?TrvY|dYM8uI!=QNOsj+eu>8t4OLshQRj3)HHYqDBKb<^+{d}N2fU?hu zw$BRB0FawUT7hZiMMB^0<-HT2b&Gq0FHw3bmrWD7UOsX}HNcs#uBu}oJiw9=n@=~q zB73pZwmDp15-SPOZK5JotX%(b58V}Wz5BVu_ep#h6=#a>y{UzB4Fll}`}~Iy#)5YY z)=~_V#s>zpF9(AR3`g-oE=riDE-)T?p_}xffn%Uj{n)ec9jJ}&Y?=#u^ND2$I^kKQ zfpy5v7W;#dH`|Mo8tTg88lDW~{mJLktxi&#GmRms+mVG2G}FU^SkzI;)K6HhcpZ{k zo&Hd1=XT8y=mKt>k>iOPJHvfXA$~g&XnCP|AkKY$Y3Uyz9+jzrZFM|+e8m3vW5JaI zJr2^2DS636N9UCimRtK8XqAAkug>p8V8}fTT?puEZI-O0*oBq3Xk27+cHhsR(a~do zctavtRNvkGHD-R-#Qr0wm<1SZ2N<67znc-Bx!D9n0jTs518&F<*b^x!r<4|>2>4i7 zR8*9ascDq+UELB_uTctMrzvekoF+n#X<_AI1&rEjpP*AhcDkxq?9EUmH%$~fLcYe1 zc;dOXIPMeLUkvTfO^ws#R!i*uuNGk3w&;#r3A$+y3c#udkYai6Pp0tZM;osEKFP)z zzlP$tE^Q6@EQ1ggO^;}waG9EitSVfe`>kTVwOBGbW7g##676pmf~^;bX4SOOB@T4V z`m6=;DU~95hbQ-|*Z+!>(Q{=qm}Ue8wMt~6fQ|=l958~IjsNj5pels>q-9#P zp^n&Do5~iuqNuwuWf+NNHl#W!QjN#jBLiDy$$X_c`VjD*A7pbxbdp(EBEqRHl1h)p z1p5U`e0D(0!0&}m=EA)MIlZ1z_>=z1`uZ@ypo}Yc*uHerTs_SuU1zhBFDs-$zp=Eu z3Mv4N!Hpv2i5RJiltRf|VbB;N;c;_YT_EP@l|5jqq?NiSUkdqK( z15zZ-M_(PwEoG}!qD&2QXA`K9$8r>LqK_b?V7Y>G{T{mwSTo4LJueA<%4)F076T44 z&Cz+hn#qKt#^^%$P^r=c{NU(Uj-0bEMYA!QbU2SUDT`RT`VgI3Wz?P$`;Z-Qdz8VN zVc+|?SX@*n3jgX3#-jz|miH=H5Qqeyl{>Kgl4N5VtXdC5FaAx=jz#{dU z+1c5;LjhNLpMU)q>-|9N9ep$xIHzNP!W9@>BevIr^h1EJPJZl)=4!JMh9-&no9-W( zn)0;z7TYCH@tw`bvo(qTUJL41)>VYA6t3h=-5`Gd(Uo!A?dMSX7E~^=R16&0L8W$1 zwzlD`PMVrAEB*jk{?e5u>`)nMj8;hpWl5P?QElK|V3`9V|Eto~>i=gmcHVqpPd5Ut z*vurFkB^Ta=-W4$53|tbA>KOJL;c;nQP}DEGV=qhVdUGeut3{F@(^rc$mXs3hY|IoJ_bZo^@a$|DA)B0q0<6 z_ak4`Ug(Z|3?sLssy+^Panu?EPMu4m@L_)5(=Uroq$Ye3e)Anw)f}(9M@b<)@9`J- zbI>ucxV%x~!F>G<8Ol~O*ZmLw-G3}ChZX9QB033|iE!@|OyZ|A7_J8kd>NMEZwhobV+P8 zXM+DP%%~Ddq99}?v0g9A!lcFwxUawgig8slP_U5wfGJYTR=3X;5YxfRW!E!zNI0RyI_UN=xL_ zKWwv$@ZKqbVr`kH3P0a)@$zWfCHGc_4dC{=2~VLJ3=q}))>NFG&-?EeSaN}c(uA=6 zEG|gn%*zAbDqtq8hNN-zG9569`-J}8k6fn`E%ZY2&M-}tb+a`T?vH($`8w-E=G2N4 z)}_ZtA6}6a9?mP4t-G=wS7!UgjvSl?HmB8ko^7w0Wdm!v$LIK#e+jmrKHTNsn;>`=+ZA0S5Z|Np3SM@U}@Qih-PN^lid&;5K+Fpe=6Az4xcaZtTt4 zC|~>?dUUp81-nY`{at)w4O!uBNO7?J zZVZV4nD=s+*H1pYH5s0ml!0K<_ZJfdGSa}FL4pxksoNGj=pNmt88zw#q72*BATW(h zQU7{6vdtSQpCDh2xtjTINCG$oIXaI2K(-yPZ3yi|-k`+oE#EHYU2{bZnm2oh{~wsG zD3y!W7uaA7&a^|k|Hfo%XXiZMO$qkef8YQU0b=3Hu{|J>{EoQCdeGcfNY_6Z@Mm9< z0u;@l-UV&(x8q|GAP43b6AK3w-1+&El%l!0`M$M<1p(02->0XyY*^HjMV}UvFr29p ziZ3}yR@c3@7=xo3Jx55l`Snlr>)Sx4xK)Lwq{Y7X5ysYJ2E;_LCSD( z@Y2k)qyIR`YBFO4)q`x# z>-hyytrsue{r&5wramM1!i4Y9BV-A$$BVJCF-tG6`+#X5;Fqh+x`dQ~(>UmO$rm)| z1R#Nf>nJ7GAyB^bzim9&Eqi-=nSfITs9C+5PVUpE)2ofWBBnfiMropatCY`x$rk6b z{43|ntr#dv@3+-`^BELlNy&@2$aHS zdzq~mx0K;~S?&NitBO)1%Q=*KE6sLYYq`8vn2_#5VLvUiK-~-$er8S7lfuQ#Eej$? z{-ormEe*~TP5GNC<5eF_AhAHk>o_i$tCbzFmy zaLFLqUK`gSO?H?^l0z|k)NnBgAoIHXW=NoAqp)i1 zybmdc$_WVx6B0O5%xIj_jckO+Up;2=ES;P&nra(gz7IBfO7f6fOM336ZkcqID>tk3 zs(~#7*ggjE1v>2|Vk!oYC;28$Odk95Yo?za)_nWJrSLLG_h<`rV$#~$4B!7K`|S@X ze%vV1z0U{+T%Meq00Q|jFD4JZ__X-?yqk)-{WJJzBF&AsL&KTHPxo5kD&{527 zc*o=xBc~0x;pyKoGv8Z4QTdk7AHg)osmQGAtf_}iRhk%btbgo%ksFm?xvHsb-ZrQhBt%sa&sFP&>uncTl$C&&gO zG@m*+IH)zwE)B=2QFUF7EGmR(#-_P_AQ zWvJ`np$AyNxqv+fy~LZw8RwrwpL%F;lEC`}kSzd@U9#p`Kt}uzsPzW2E>)X=&o^!f|24~lv-tbcwE`?EnyP zWI+MvsW$*Q_qXpmr8l9ie#L+Exh)h}d=OmImz@0mO+ELm8!!T3=OnoOc50(@uV2cE z>uXcf1DvVoi+iLiV_^pG-^C*Q1NBaMe9tR>+5x*)uLFu3IyncO)Y~6hh3zhjIzbba zM1wjFbW2tcP2#IWNPlDC+R6J6gvwDPIf$IlGAZ zH36UoZJk3Hn4c4p-%x8OFi;i-ZNLVM>J_xY6>gxgVYPZ~N3D2&5b^g91lXY;2a{2| zHm`FzgzqH0^{?>ZRJo-rXp>u2!tx0i9}5{4(vN8Y3jb zMs!Mz&m*i5#jRUlJBwMN-JN`1tn@;%y7~ds`-FU^)w_8iCCx_#^-(rqyzwjZWXNf1 z(bnA3p1dahYjrijxJrG|Z~}rTqO5Xs8Jt3N@1N<^R#ZIs=yi{f;jD+-#LzGVi0K7t zUUL+eLVA#&z`_B!f-jAi+}z#2Z5^46#_L-s=GlXsiq+NCZ475t>`~I&=Ws<)3{Xup zk9I?`;Y6Ck?10W!6E4{Q$Yqjq7;=|}=B2Z9+=_1rIzK-j1mQ-Vlz{6A&JgFhxk^hC z4o*&RxT5daYMYt;blZ;0w~};9xAhi(sf@*X6zP1JaOzSPwbUD;pL%<)N=%E(mjUG$ z5Z(NTt>5>bXt1jNqE|p`FgQi%*Iqoc5-g|`SW%|@MM>=7*!#b=*NU$ds3ELLs8{x> zM$EO*mu($js#fXNQWmnDd>Mdl#EaTT`1)y7&8_plORY*pQ5$szx2|0|-t=rGYfH0G zP15TOi_IU#9s3dL>5rr-bQV$m$3P_zRB)|8Ox?wPYA0{K6*tvdIdhG~=mw059~cHM zbVQ00ntyJ@x1^97>x_~%d5rP;S294SZc9oE0#3|LpbGVqi8d5H1n}Fg`FS>m=YHKI zW%j0qM}Z*ZXSy|z5dh2IC)G%7s&ew^BDQ@>$la$_oNtT=a6XalL++&v_o1Fyx5ouxCZtnPS$g4$uF9f_7gZaf}Y z4Ev7SW76-UT}%7Wh1!9V7d|UOO1}(5ShH31obbqwYG~yRX+i_#u{xW&m&rdMWRvW* zE`5}~&Wl%EJyeJe((rB=gO@~R-c+n43ceMV-+xC(e@a|aJOGT|1zSk$W(3JYDG@lB0CJpy82DAbtXQucf!2Kx9@vrekGk`F>67b_B0xy2RRR?GI)wfZM+!?d;4C!p}d{ zVv1TpgU~zB))ZIeqji>Av$0#-mjO;!h-ap9Dox?4M31xtT-*Y3H>t1zf|Y&*L@XD} zF&A8aKr)W-ftya_pD(4Q9l%Z-bSz)zp`FkRsaMOhBbLYxT~3f6Zr>4{mLi5*OYvw$vLAHY)OYXx?T%vw(Rg$LXH#>lwE&3?zo@v4p7e-f zK@7cC(_*@PJ-gz|6Do+^m02a2*|Izq3>#v-6Sj;kb{B!A+d_kco;|xfiGZ7?TD_S% zLP3lC1RV11^4XZ6nH2_DoYD#sDkJY!@sr0kO9eF5V1V__FjWJ5M6YjASy^XqZ{+s= zF6}s3joC6KjMQuWF%P6aq4rZ3XMJ5=_pns|AIR)`V%ydNdoI_yczr7`FQdf;B^iNK zO98-G5O`#Ajmj0}1@r_lPy@axk%|fU&S^YiZaDD4c($RXI`(g>Bc2}IVBG-I4F7Pa z`%Oi2h9krmGKskI)-Q{eCI?cJq|jVrwoIY3EJAuCw~gbSeuV(;68^Mzxob4gcA^Zo&uCtS1@Dc`XtVNx=gS zl`mZ7PuP@een+7+<+&&g4Dw3s0UM(#7;j1z?u%r4`jx&!3C5ig=h*ZF0RQi&HiXyB zHw<0GGJ0trL!rZjl`XuP@98A+kThIZ?`DoTC$CnBr_TX7!4nX*mSK14U+=&JtaK80 zg=$0UpN+3atj3nH$J?WunYV1*Wz|bAzA>H?0-*dJu61rJ1~!~ZSzMC-u$d@@vfdc@ z5-u(-Qd(E|$OY%kiG3{m$Mm!f&|$I;c;qU^D%K}9)tfbA6jlQHv+m+@>i2wJbT0+Y zgXIBy*MMhX%yCh>^tFLYl}yv;g8q;LsE@aIeQblKNB3@ZVf1ya@~+4S;T{TSc@(>Z z6;bsCMnr829Lq03a6p~U0XHm7#-Llny30pXKnXQ6qObOG9O;lL4?Z;1%HF{*AUV<# zeE<^hzT0c;oZ$eU1G@bAP4QGoXKraWWez%)?nm4y@;N)Pwk2qQ0QJ`B8X6ezj^QWM z&@3`>EG86~(M0tTeh9sQKUS~h9%+_X$8+CCIaRDq(5n}^M6DGpK-KXs`-wCf(|XhU z)#E_~Iw`}7Cy7&Qv|C?N(NtHLDrkNcgAIR?bZY|oe*HpFiQ;}78jZ2EO?Q-U7X_JQ zrKPZ1%s(wG>fyD zS_#Zz+$F!q-HbgQ%Y1h59VrcVxP1`^=SfED!9d%B)%TZaGTRG zs8vjGvt#wB0W?vTR^|C|lWk<~{7Smxy~TS-rgEmj7C1{>VpOBY#&kgZw;%fA9|52o})RBfO^ z-g?!mK<{sASRJlldqwxfeYM?K_1{>DmG46w9bw@&*WX{yc*+8U>0I3to6HQn@CMSW zKcEkh?bZ*!@ievROksR8!g#d10?x#(9-RjLTN?N63d1f-TtkNeJn4&@f^AB^sZMTv zJ?-VL+>q(mZq)G3S{)+JqHG1~(~|7)?!T`MW580Ngs2iaaH|Q1ab8s zGySpEnP%T-baZs_9G=xR-muyFyT&>m;w%IHC|XEyO`+9zqxIvmBa^NC!;Kjd5LZ$2 zLp4H`Ul^v|mh6jlw%jJx#Z!Md)c-eHYBHT?FD6?`1@_!^rmLjghg1lrdzg4MTDer3 ziJ*0^A5fQ@2VC7!4BY`J+V=NF>q+asRb#DuK+Uqtd?Kf`@F++aLOs%$p>_}Zn#xQ%M8A4uEzi9J%|k0Z zW;Z_4)JwNz+sy#5>~HY0z7Kt#yk+YWP1@v&1M|IAb8tNx)@;7GEUZS<3c8xuL=MOrLUM7@^t=sukBW+l4G6Orbsf^JDB-E{rT$8Xu(gqdd?hM2@r=0jUd~kXRg6rnI_1i; z&LlcsHvw%$egIX5nQ=Cctwkw}Y>ww>8W4v5q{0m6e3j)^z}7yHxR3MS77%~QN#}FT z1SxE)&S86_5o&wFPRCvxGIx@}BrNQrjxiz%i$w?V^ZRa2hrC$B10Npf{0TH!V`3hP z6B8Vt@Aaon{$iQ1u@ZuUyGxfMf`dI=CH&2C_e(1ijIH4%%KuENK(+mf34DG0IHj~O zluCwWC1Qy7;Naj(aWU%@y{)y zGxaMnt!@m2sfEr1c)~mUlMkK+?ma{0*>k8*S6vN1`jnLwqr~f8Y}s;dhDBzBySx0*1@eyAN@st2wt(BoenvyA3jk(QP-bj zW6T;q8kxPIj4KSLgz%UIPDL{+=IlYf-SKh3d&E~Ga~Vbe)`WZX7%GoJLpyCR+rX{a zj~}kTe7w$8W!+>Hpgore^!PuX%W7za4(z4Q=u0hGa< zWZ_D%sxL;3q2uuNayna`) zr+y+v+>=27vpK!eF`jZDv26Yk_IoaGu`OHy5@^-$W0fLDbND1mZV=gR8C?P#V zQXMtPNl6w~R%SMHjUFR_>HY(Me2d^JIMPUWHLq!-6ji`DJr1;r!PAN>>@LD1xz>HL zWra6s*jD!m=Ea#1W9qS{Zs|1Wxdd7uh#mk@2w&#{Ob+wM$w`qK9^py7%mvmY5~pXK z^iBi>uBXsATu+&3ri`uZVUto}EAO24+G8@v+4s161O!X1BK>ZBNDGBQx_t4wv@+@8 zK+sU#Uh-}spPjd_-}2Fe&TAo2f8B>$E>70~^`x08^zCcQL8*-?XWM6jr;P@|$5pm+ zWTom(cH%$fyRWqE?%r8lYrdhlQWORQOstRA^-U1S0W1|@7ApregeRQKP&ySfSZ^EP zV{|_MA#C0GVA}AKINZp4uHBLAD|8^sN+B7jQV0oJz}UR|qO<=u%iI-i#IFr0mB*g@gXGWv%qAgcrIOO znPKg?K-^I< zVlOsl`oIq+=f5zSa`ieFdB0?h{--pS_6k#~TyiNl*>ka%4X!9xHM|zNDWlqrqJkIXCS@RD9(b@}kQOASYS^q{ zP^!sSCzSNlTOKk4@rmD9%|T7Fw#J;_K{|+GJ=?*aU2KrhGw^5Q|+XL*5&N>o40?p;-37#(vdAxeP45q6Kf?+(gu&b5+V z21KamY@o&5VM83d)ync0`DwXgSD$m`T_b}4acr$)F*!lX+8e9bi|k)Qq{v5dX7vAH zQHe9-MhivsCGvxyNFnkk#=K`yVKoi?t~PIO`$~M01{?bQlD7j|JYjagTI&J{^=*ox zUZPYk2fEALci+QxvF-Q!LNje(4=uneza==I5htvbHG|4KR;{b zR6tVKC-Z?tJN!vv{u^-j^7HdkDjF=y_tPDevmRh?>IcJ{`NNcM5y-QD>q@g`C)(|9&s5$vE%S|(eYY57s41JN_HsYrexLh$r_<8!bf>`Y zp5pb~nvcmT3t^v2XX>erE{A&lc>f*+i5|hFQ`)n9rtmpX>l=k8eqf~FUpxAgTU$#U zG_3@)Sfjnn@HH$qLloUeS30%H6vD&=?6X2yD08-yJQkm5qXGR5ByNBnQ*+quzJdXH zBPC_?@?qmIx<2y7p_?pH=@Ih7u!AgSM3%!glsm$4sLVKVvY%SVW9es_$Zp?qT6{fc zuAMdWDmB{SXj5UjZf8H+;)xf5prC7=Gi$9W--MMyh2+t+qu)W2b3LKZ`GxIGDU3xf z$9Oe7J?(atPwT2LI$k|lqKbu%2LB;5OLhizx+NsES?6t#>RYo$R3$2^9Z1&kR&A)} z{bFYCC=_!XYc!^*$A0C@`TT#yAN^(^(5*Y~v4*Qw-d>_XdB>iK#Y zo>v=9J01eh9r03<6zaV$vZ2t`6j*zUjiSD@3bO0J3~o@F5=WsSaImMWmoMwDFw4O zXyFW9M@h-{$c_(uTNh8GDZh+G^N~;>r-S^gI_fE;;K?x0KlZ|)y$&3$D<6k=NE@VL3I;_{Yopl3CW*PlX7?A@*G|9Qza zi0K$q2J+^WB;oY0Pgo<=rD2Lg*XNEqZva}(nm-FuV$CUze3a^zseoJd-`q=DRVX^a zjog3ePsi?9t2m6c#g|Jr_UnIL*{ORXgi!A`k#9)d$RB}b7<3gEOV$Mjim6o7%12jj z;$ik3IdUZ13!e;cP7Oy$58aVh*h}QfN*R&xI^G_g-g+bQ>NI!R++&fILF;%J@@|^T zub}YeLO_;0gIvA!T_9@gPb_NaRKubowEw&wi*|ECp7t||Y607bMzccB5^bItsgmIN zSNx$bfy;J}`NhYxMhU1X`WNfAk#5NL{L+}?Xm59enppn+$8~GIABDTtfrpakds29D zPdshjGcFdD^++AeZ%8zw)HMPCA*wQO(1;l3w)5IezT%_SNv6AO5_{#03leGh?Pw(F z(>}NVUg+sv+yDQ4?LC!>!mTVJm!U`Kau5oL?dc2K>g==ys#1bjMo6RYk>mLeBc5MY zbGDJTvNT!^IR^)4U;6Ic(I{ppWO|kr@{@!P!hV=-qdKW$% zm*M?0`p4O&y9k&g<841-1G^_TFYg2}RpF(d-wUI;LX~c~U(H|UDNRkvg|yXijX1Oi zNi-*ABW!e<&)rDJwdJCS!cd`4ds?$1dF@D*Xjh(&#Cl_s z4DS+Lbm5P6fxE~0cvrQStNrF61$yle9!odg+Dh3KO_Y0?_UguxIX8qx2XS*zavUIN)he$< z>53dPz_!ajDYdWf4&Hf`A=z{AurXB2ow@`}I*N)Pd9S1xEZggI$-9Mf*3;ADz7)B1 zz39jH&o*{;x|>@6h-aU31zaw7*jz6WO3Z9cJ~AGnuak#io1LowH+VJK$3b z<34SMXw{LZT~^f?Ot6|UC{|<|JUlCD?w?$P-AmYUK#fZVoQoJ68*ldt_FI5UplUx= z)>ZtYAP()L1g7!Gp4Bso|@DV zn`t!kG@s=b81;|_%Wp4u$}>Q|!=Md|fa4TxyIb-D+P#(i{-3o|>G?=1pz zdqvjfL0me~f%n69(GZ!u62qSlMLm#pxXDQZMJTWLmQ>=mdl~`XzC5?T{~;kl}rIvyzxK)Cx+ zrB?5JRtZkT<;fWb{_bAhQReLb@k&r0+Zn~Dt{yVMil|p^d_^4csr81)%~g)LXITo4 z{w_?WtoeGOcTJAX@oV@_{KXu;d>?V``{4r@`MuP2{b7I8G{5;T!5B(!%t5BTood`r zjy6WnGXt4zPdF>4EEXRnyX(KAnx)7R*WQXhD^ChMy7Ok!dey&0FTNCr5G*ZYHe*<6 z0IM9~UVc{b@x2HOxn4-u7ZT&>A8VX{wr$>h>6}09^wHBZ$Uefac4*>TZ4TxN+j)hs ztHJloEI1z%Wcyi*(yh^}3ZTo+>X%}bIId0=UVlvbH`+%pE=1cFqcgQSs_l8?s>HUt zbX3_T#xI)M@%E}iyvs6=5Hus zS8Xw!GTmimB}jxJ*`ub1=Rc9F*MQRsSd0Zm$u8k!Fvgeh3IFqt2PAFDd?vdWKTGW- zaQh0FAgS|j8knG0AK2b%snnc{ba%b_a5iIx-Ht~OQWg$U`ad|@hj>|tv%ZUR7D1jj zi}{055SLh~tawIWuh7e~q|=$Yu^7SG+SS!VC#RW)TMb#wzEhx1{DKqD&$zd-(FYQb zBQ~tqE32VLFS1g&cpDgKIQ(_8Fw0z~+WfColgOw}{>0XFF>YCS8|0HGc%y0;mWQAm zBB%Sc2WMrQPM}-Ew*gYQ>;-MKM2oU`#yX>D{6N`3_H(x}T|-0tion{h&;FerOc6P_ zkL9m^ZEmL3)lKj^e)G`5;UFb5v*Sm|+I?Eu%P;j=hli%!R#o+LjK22II=h~=e66TR z89Utm)8#Vf`L)NYz|~=NbP>q1B1cEX)YR22{QYSgJ@lE<`(A;69c{&cFQP}l83R(y zDx3O26r$^#JHGDB4G%D0n&M*D`mEYopU9{g%$dErJ2_@vPE9TH_SEyX?rsM}7|MFj3$rS*2cgl|5JY_`*jWj z15^cCAb50?4lwDGM~!C%RaLa_-v|D>*w~yYuAg(7Iel`3-`Sa(^e8PA^4e9*U?#bchod~MhcY6z|a+5Qv(A-;4<5#@O$`N`>(aa5w*1+o1SxW zY(ns@;1LN$@@@bJry|*N-))N z^>9{3u4uzkVPS;^2JTv?x#(~x5wMv#gV0DY+s5+En+glu>90DO-~n zR|eYpFg@gCUJ4tUeeVIGJ~^01qz!z!APE1dkkB6x z3lBV{GC*BI@Eho5Bpv4-4eJ;B(#QuqjQ0Xr5XZQ!K*sT<7B!9|JRHG3+1LUnr2{4u{)X5P^;E5%8yU%GDXrJ zev|dcrXLKY135a8N5eo0)g-h{Z*Q6$fR zldf9XNM~dCseg3yAbcaex&}v1vV4>$ZuiB)RrA?~?%1d|Mg0*|*^X`@_3IY3IVvFL zQewLULI&e3nM2Og_Axt|2`!w_?pA{Z`xiaIucn6zU0(@!n&Aq-1TJ6GVgHdc(^l)P z7K5RsGCTUG1)Gxn{tmM{g=7Ex0!{Sw*S_NDRN^@~o-nhYU%$5bTzy-arTpz+oY3PF z%lEev0!D{-)UUtRH<=O1$lw!Y=}}Ey>3%%2waNHQbn!wmJ>$```Ix~-c{+URtJA&C z&P_nYv&2~F#@UiP8^B=6irL9iBSuRep0u#?n#~i^*?&(SJ z&YRqvxdpWIxmVB*V6B2@0t1PO0doy3LORmDQIXR+0b7R~YuJ8$oO#2(!+k^ zCJqiTLVi#D#T$nDCBGKSuA=1jy*utlTNFIXLXTg6QqiA}vj-zj$7X15A`#yr)V_`;di&!ZERe>~jF0Cw*RAra^t%fr5eerMiw!;?MPgN4oRqi4ud#J>9hL+?4@Gza5Hor>9BRf%kl8G2Ka_ zMS}_|O1->^fli=m^=aj2{)I40>u-E#U}&D(IdoXlqH`mt@Za`mWA=UV@%hm64AHOr zorRAxzmM=3I`56DuaE!9lKJ9lUf{HUHz_6mQe-|~Yc@PG5~mzxFC3A&uJ+SnIkpN2 z;Mu6+9(*L_eiu3cHmwKW5U-@MR#l?!`tCwhY4ICh=Q;rlQrXlLxx1^l;B>KIe!=dR zMgIMMk$(F+F~o%AH#0zgptl?@^N7H$duh%1_U+rW;8d*x{osn5ncE<^W`W#i*=ACR z%#0myuF!A^o@M!vVzAhE{Rv4)N(TBb6}?3lpZe(E&Wp<8_B%}NM@qz*4`SfuNF?)! zw1=Bd(;j5HiNEyRWPE>b^Qe6l%Z(~P@e2x3ZI^C8an2?TT5o@-mn7BpQy{yHgHXaq z4k0hPcyDa`w#meNuYVLMbe?+u*eOG$IAC-#2!6Y;jb90O*@>AA(lvVe5^h<#0lJ?ia{e;#uUmt!HjbynSdx4YEJ z(>d6_el76W4uV^!oI}@ti!iOI^Ja?eaFf{7M&lXDxOd}dER&@+Lc!_VH3rKaKOQfe zyOuH=gV%Bg%sEz;hCXO%?n#8C8DyQqk)t!>Mi>33>Ia`J|kMWVGqu-3ox^~odNhy~{u%gv0Qo(){Cz*a?vgE9I+Kk((nv%Vk`49dHpzjMSH~NL~H+Wjia9 z)|4z_h$xpm@BV(hFqIpnh6)L&)QbnvMYK*n7T4JAfu2QHFr^)owM^lZtirdbvB7*X zRr54yv=|d{&k$)6!Owb-jtH|CzpHSK5n3F?1fCbzlQHA!sf0ufdXRIXE@0WF8W-eM%+vy!A%QJi(-a%b+G}bAEXx zNC;Y(Hz|xLsFv4TJp@PMr_Z@+tX-^Fz~7S#P-7u<58n6-$&WuIAm9F%agq8=3|PfK z`vlUum;62CdPT}pf4v@HqN2wmSWD0Qq?ZPh-pey*Y(vNn_U0NzY`aY2M>2o z-Q$ZG>WBct>O1!PvuY$U2#WhV`|Vy~p@V?)%D+GkQSf-n0csMk`_}243R0yLG`m(R z<*)I15YeA2;z)sooRG&+MZs3V0@V)9`t!9bG6Pi9urSnN(^`Pae*dqX9q z@M`nPegZJoVPo&S0u=jK_whi6u5Ye0nj^L8Xm0OL z)^d8p)NB@?cwx*vC=m&CfS-ZO0{d53K0y4-L$tyhr&3HmuA4vxX9{=OPQ}5rK zbwq+o4zFI(V}-R6hhi}!($}&^Q{udN-~v(Lz22N|3R@GpX`76{6T5mDp+p%&Nt^*9 zY-u8|P3xCSu!ptXEpL@|U0?snxn#Bcp7!RKayw#eg;$;X;WMLjcBjgHS9;gZ#~JPZ z+%!2Pw4bcaEOgRcbu1C^K(;8uVq6GmL4Bl33&Dta#)^r5gkIw1fOuN__5!52zM){I z1a#Z01edl*Bgd}UTI-)P<}`C>m44lrbJE;!W$#PzA>dTrT{Ttk02=|I4zhx*AnqKhzmj z&Q4H348X_z*j%6Q0FY1zlQD8}-v#D0)g0g`7O!+xsAOPQPM5O6JQO<$j=~-n7g{W> zYn-j>HGJP+{KzTGJdM8!$bi}}Gy5LX8Gi#g4R{a_k39f}LZYB(>K}%tRX11P4s%%~ zM!vf(DL56yIC{Qs=4MIFecX%FvzsD) zcJ=RHhQF_DA5loep6>Wd5Y#lhbC0b;r>tJDV9K4(!Lg>RiVH~az;p36K1;5;#Z zz~E+_Wg(0W=skad?4?G?ZH!u69MHZ6mTq+()N-*|x3B&(0^Yv_hq67%`*_*Bu?H&j zP|Pn=%_x*}IO(v!_)9BT(rjbD^g*iY7F!IwsGvX!7^qyHgVP3+j1xiYC#*pt->=EePCO))$$#{Q z2$A6i4l*E%|9iFvFV0Z%7q+p8RSYMlJ!xU?HYG**h1cr_7l~Tlgvic;Ab{CR7`n|k z`YyI3_!q(8-m;)h@~R%JKG~y0z=`Uq(-5Dv0Y{J^YDiCYLi{*e{QIRBcwh?;H>Vj) zREp6G>ZwT~`oqqh<6>OX<|j9>V=^=Qez4pTP8)y(T2k=-LN{j0$2n!U!k0SSmK+=% z)swJeDnAuPcJp`>elhB4e*`VcG=8h!Pc@FNWc@IzJk@p%pc-99YJj#4)SEZ2JE7d} zeW%)Qn|WHUH~{qpyf;t=WjVPm_gbH-9Y zRvQ&Q^ABsd7u2=z~@_KHLyBl z_#Z5Qd$1*cEo(Z4E*Gg{5se$!6^Verv-r8|p1=h|j^O$a6}36$EruDZ6R4w0lx~Wa zmZMpHfV~7rzz8beu&lcvIn&bBj=|NPxH5ilyG-H*#@Vs^Kom$hb39VxY>k?l{f*BP ziF*HdtMUDsZt;Sj4##oZ?Ch)QMv%G!6FLA%&BE?r*l^SE|F{4zbH$Kg2I#>nD*90? zKWZp_EiDyXUcY~<|9!OIvk2H`J4;--{ke|UwMYc}*;Pr+QSiONf4O|FfU?!Ni&gT< z>%YwA26>}Ym2NqAt3Q4bgG%0eAu(Ra#vZ1ttK+nG%+=_z{anL`R>VytO;#igWDH$O z4E-j&5i`F(jbosRdXqs7=DjP=b|D-#Lx>5im5M<(6Y z^W6ZwIOdJdu-TPChs|!#kFbA#BG##tRG;UFjCGRK&wIN4W|qE0g|8$kboKa8qyo2O z>U*}KCQaepgfC)g{{GuxCLl^;ckNw$PD4ri$k;pov;1PE;gZ!Or8OP^Djs$SHB;1O zfR0t8a%5qQ+1{u{24*$2GC8Wi_@5#g?DRtI07citT`xe5-QC;!(=c;pe+9nA(kkrg z9kVx2uL#xS0l~ovHdejrf9~i54;3k}zCd=_cXATKnqJE1uf@q@^+ZgJ@Js3IavDRF zO}>BHF^0goT;%D~c~J)mKiQ9}BQe_AvS*;8V$s!%Z}S?K?$_KK2eD`%L|Rbp&g%+2 z--Cu37CCO$&9z(h7S}y8>?KFS*gmW;95TypCdvel{mu&x4hH^2pIt@5J;Y$EO;NiN z^E@TUww`16(}NTTeFoCJgT2nTr=1I*UL73zm#50-W)zXa++~NKd1r+DgDAhKyT(25 zF^R%yIj*!|-5E*1wSl{PH?>q{h~@4Lpm8yvo4M+AZP!sa!g=?`U*T26o&dPuL|q&nO@yUTfbg+z_))Na z?{l`GZb(r(^n04*!+BasKkpQXKYZMhQ zX?BtTiKt$XZr`YH=8vd&cM5O623T(j8+P|O8vm_SHURd=rQ3v#=;-#EUN6C;?h03F zaOZYYl#kop13BGrvudEV;L+C+QKBSZj#hA<0B8DxJO3xCQOB4+FZ^9O-F*AH^hgWO={f>$Y}y+)k8KPZakB~BJtEIm|gQ8jTA*_8=NR?*?gGB+{Bje zt-4Ex1o_Zp;)Q;8?6E`aSqt!zJh%XH5R<+h9v%j2owOd(AzV^UKz9q?ZGwfF_flpJ z%fF#qkCQO$X{zQInrcxvZf?%V>v{^y4VRfIAo-BER3a!t{OuzmA|l-W(DS^n^+7}2 zxoScTCx`P;ueUC8UET*;E!#Xz9wAiF0=`&{YztRMT-tM=dzYcSmvn0)60%p0j=T;= zZs3o&{0IOWW$q2~@MV>(Xl|aav3oajPLCXndXxc7+b-f2W9f+j6!P-r%U5+5wV&$2 z9^mBWzUSMAaDQwc8+xW%{|xQQ&YWM^nWhTwIdu90qFehjbx5(6Vc)xW;C@b2c0rMI zY{)#eI4{0$uXod*AULw^s+R2PkPV%HY1EOWbc`!?}NG#6$s z`~81D%)C0OaJrjeklEmNc9&XNaY%77w_%Ha+K`S&8buYCuHenQ z1dikQhZOgiTQ=o?0G|6&*6Xkv*y9rX`Ibu4T2M@fCon?-F*TfdCS+;yJEys8gDKUX zpj{iy;nvq79kME~Eq!-$xi5;*f@R+|$KMWkz;$$XI&I(tQsFKg36aDrd4oAtU*FRb z@8ZKFo4og;rtig;zZ7WZ78zMEQcHVVQ|PlOmZm!IGjsCjQrUfa*eTv|X-vC##ud{& z3xw|rwtOFT1+@-Jj(^I+VAi79KE4Jb*_HnU;D8$Y z?P+88>^o?hZi9~j5}XNd=)LeibA)_BFIqia$3yy)2i5I-d^r@S)C<4A{v2^CXeDYk3)0N!orikL$h_c7V&wpXzY7umWk`cw%aJ3)O zUL`X^c&O#~^MHdPG~-Lj(|l+qLA%u;u+sb=lT#m$f#EuGgPLaqe|i7vySc2Ol8N6* zk-X22WdmbnSX4#qw#vz_&;Dkv9>HOcZgW-vLyT*DT-JSx>I4_NdsETF3%mTCQf4p>P_HZVXJS@6tnaPg$H zR>^F9V-nxBG3aQ(t~?4JQcG6BXtjQOnzY^m*#OzJvDyBMQ6Um{mvyK31}_LOKg0DG3kNiy+z;t4f*hlCUj39e6i8XFDAng z$MGpz;6Vlx<|8x0imAPb#_4ejc0mBVXDY4PGsnxWc_BsW_hT}(@ zQ}uz;<09_%CT$~Jo{}=1SE|CvFfU#$L+MvdKRH>V-?AyjS&Rsw=6AVh@wm{fk2* z_j)0KLXbfNwVim0PuSNL0{V`cziC^(BtY0L`}XbI&40kCVX1k!=tN$D_5rgJ-W7Lz zrnJ>Exi7Vq{x}VR3ay1kXH{Y(kCmT3$()X9oDGfsy5H-j8bV5zaxFnwK0^WCx?L## z>+3@(Ro!J6)Pocz+WR!QYr0ix4|8~?KL?qSVP4>Tg5SqRqMWPBexprZMLV;fWeL<> zL)pd^f3)Uv*VUy7(OUF8I%FS;mWIlO8gMV_>gR!o>-M6`9W+s=7_@`Q8H6sMrqMgD zFvHFieM%+-r=7Zs!`Ys46TM?*@6*nhC_w@=;$65^QRqEVN#LRQ_wN<=O-`wC_gA`_ zq_^D!#>#GwHM>DaOH5eB9pX;CvtM7i_@p)XNsq+PT0Fb>A820|vfzMjK#Y}zs~Sy} z#21q0^LLoGZl{BmO8ev(pgYb!0iwvVVl}Hiv`z1|UwZ&6Dh38)0}n$@yz!W4l9#bZ zhrreaIn)W-rr&2;9^WGVK~yrGIrI`$ULoBKrmf^q7G3ONBE ztCb=>P5hj7`AisynddtrmW${6FHZaa;SzWAj!}apGc#`2>n|+$LV)pj*j5Y1LL8l? z)rW3R&PuwuxVQ*FL;qKz#cb9#E&hJMtziMqq9ihuRJnNHM5G-#X)B34s@EdCt9-}m zMfND-u|2EPmdhUzP3ey|8J`U`b#Usv+k^>%k5*eHTwS7;wd859DzPZima0)Hj@}BT z#a8j=34>M$V0wk4(U|Yjh-LMAm>G6MijN2eBf5A1^@fu}%3rUg&8ZswT(qQHPLAC- zu2D&MjG8n&;i1MN7_rASOlwU|O=IHye^Xxj$IKZMmt zBKMjNNlO_*%@}|Pq{-$#`S`Vi>XA?3O|W5MMhU9^Q;3Qej?(#3KOe!P#XbCg*u_>} z`f}A}0MhjG*{==}kDRBQ>+3%*5g!BA@93s=WK+&0+6`bNcu`Qn)w(Q`y}KPfaBsVa zNZ0R(?d0MnPvbiPc@Z2jR~7ezQqk~3nKe=`WoLdU#%(m(?YbURc;6%+j0VP@_yUjD zo&q`_z%1U`^NcE#zjrzo7z$#>3Z%B8ZM)8aJ-`G|fW5b6brycBo-qTwsotkH-Ui9A zG%bfR3t|DY^`)lt;Dvg&eEcWI7q-Yq$1<~riO%G)ccie4?(@L1+ry{XVUZ&(@W9Er zY8S<8{EDI>E~)Ib>r_z+de%~0oi`0}p7%X=4aT27 z@xZT4PQ@0@+OB&XitS$V-fB5$g`0$(71i6SUQ0<&Ub-FYK+gD~4 z5Ij&8N$a&|l&HIuz|{~8-@gH&4{$`f%)`Enw)F&>%rZdx0)&n~Ah5)e9=>Qe@t%Zs zK%{SLcv#>*9UU+&5EeWAE7dqJ6?yor;X(vaK?Yw767m+*tNKKK?WV2S=6KVLkl9Fy z8ude3THuvmJgEklFnJD|wISm`qw(xyy+Ws3%9_UqbugsnzeAZ_P1Zd&KAy+YR0qj7 zFtFbH1fQk^V&}T;GweMd3PJsNDgRXc^3f8*Z59h)TR|ejD&oHW(l~S-{O+T#qk>UY z!1vqPpr^T-H>I^1RUFu#M^RqC@={ZhC!ffD%x_~@*JQY_#Z@|&7QE(gt5CMckvw>7 znQn*C92cmqU!y}}-n_A~xeJ}ScQ-`3?}0Kg8KH7=ZVcJo@+8P9|SxRo|mx|qo9Npc3zM-76+&r_=t$R*8tie|JIOvYv9!W z+f+lg=iwdjlh~u0-7NO8xRcDRH@>KDD@n5IqOZTt+_^9^QCp@zU*myEllODpxH6NB z=#{m#HZWRoX%WSL#$-#+2~wSW<992g-Mo%4+GS0U+M8M!NR9w9(uAXb%#+UONv1Ti7sVCIa+m~g>_3?kp{mV=G9!0QnK>>ldg9f_ohm|D& zh6HTy{u5uHagmTnH=EAK+iS02mAz2Q%7NY^Av@xNJ%3K-IR1b#@Sfw zNbB21=G8C3aO2&U|3QNnA}!;#n>W2a6n2jhT%=DA4#v3LBM`i<=fTex ztomk79b30GP=(jH=fGniS8ns9q=;q+S7vJ3d$?|7;Iz6>ZCL~|AAqASbJb$K8u!i* z!7FUYoTw4Jo1Y@3<=1&#ZEa%NU>7{k(8-)IW%7zDHt7JZ^b=v)w%?a2?%3r}wt^R& zP`vt~t~U#yf7r=5GXFK!h}bw73tEVtQrd6KP*&SID}@L`fq+Ou-H7HmaQ3#@)lFpZ zg&Hjz3H1};1=S8F$ntI$SJK&>tRv)U{ba`r<{DZ5^VO8HUy|>cs{a>s=+%F#rJhmK zEfF?Pz*I!(^g`cX$?`&IT$BAERyF5lvnb#=fyTsl%V(yyd+V}o1D3m~q8?;#w`txY zen%+w0SxR?2NyRiz*!P!>f}ayPq$`%`V4OvTga8WX+kZq*2)00qo@cbd&CHU==Ed( z#w#1AjRTB{sUwA)>K2n$=f?2 zNS_Obv8tQD!ozDFHw_;#*qZxt1dgcPVKBH=yFbw3eS^_r3fc5G3{^#J&|$TOD@V4> zhn7b()2X~FP@A~=r7}%cKWBL*Mk;5iE6AL$`S#Im5lUb*3`}{R>b>5{h7GpAtMTEi* zwempPvv?{%kv}YAWA8e57JXa+So-W>9`-mLP)JY`+^>T|#IPiQ!BeIb^T{ zi?zaKRCKt_ic5c9%9{mYR!95=m9Psi4EzY@^B-4%LED(n$FiCtg%z;4S_C%S^9wt|0o*X=sjfq~dX~ z>aVEVoff{m0vN&2=;AaPeXQ%yPaT*1f9+IY6@knX{qyKcLMZNA6QbTcqLh#RAQ9=B|AphrSMv#-7b^SW4jF15w z=e*jZaRO#@ZJ>O*va-xX_CC~Ph_h7UXFTgoTSjiK_15opj0Zk<0{+O_7BstO(?SO5 zK$DP==%)U2FVik<4`|^D?C#_vX4t_4q?i>opW2GK(46gB0GJM#0H2eQ`1^#4e%#K} z%=z4z)9Teswt1U;{(GGZ@dg@N50wtNTvC4)`pMriwS<3e=*6tO6o-?aK$K^iVx7=~ z1Ihb(;M;U7_~5ftI%OaxbIrAh^Sf%ir(U0Ix;>)EcCSceIz@;kdu*;<;m%%d7^gntCWT{)ZetQtU8c0&(bvCNdMOU;PY%oFPtvt=80-f2 zDYBqL!Qv~cXMm-&p^>PyQBHjpPRPbx4mjW>8W~K*Grc~$ev4;w8Z&Ia@afz!UGC14 z#~YE>fxLRxK!iiAfC}`(xaO2}wkYZ7geoawR8LKf{PpYC1kdVq#Sb^wL7@x3+mN08 z-q#3bYi4E^IHZcp6piVQyrGBE{{eWSXm`|ncMlfzLULpcJx2qjeQk90If+f^dG0*H z4*rc2URlwvB=H$7it{Pf?Lzs^@?omT4Ude=6!XpqCi-vJ(AkDz)Y#O|l`1mc7dfCm z>?-r0tG=PZ09|<5@tRqGA9zA;0F*Kz0M(>}GYHE;8OYS&y@v-o(w9mI?d$V|2*a;7& zNb2WT4R$0zR8sNiYRfSf-n zH5h``l0mtQDF}b|5F7!x8iQPy^AKZtax!C8!~TFkA?HRbR?>9U-Qh#wgaQkjh)$2H zrATpQ;W)M>rrV;Js_XUd5aIHl@}oOTr85fRw%yO0092ch)DClD*4S4JwN<-*VZbFGcGinGFU1$B&)}1 zZ1%6l(r*P}4d0~CJeib;Vinwxq(1B1JA6g8AMa52F?ia5)kfXqmi-YZB0mY*d^_T% zu0D9sqF+(7Np?;4r}KA<3rzI}Cx=feI z4>4lMLI# zB;-xlPCCDe5ob}1Bl?iU}wG=@CO{69%g9sj$h0_Yo)G`I|nA?vE`RmL1BG6 zN&(7O68>dy+r&rrjD?NdyLecx)O)lSG>2l#97@BQ3(8$c}jX_zVDJn>tjXf&p1S1GjujD<(}mR6tQ3=M|D|&(e8( zgZ6A6$d9NzNeXaDyVluI^+pmdN=JyGuttkh7rNUpW&HwT8$Ec`|J8nLV^HlLU(#m> z(uFVE+M~#5Mg@|bB5s=zhSzJW`8#5x6crv@i=&ZHTH4EGk$?V^k)PO{C@X-`5FCVv}{s&5WKc9%HzdX<;fr8LKgVjmCQ+~yI`IiQRgI0fiUfvCmp=9ZcYWLJ`J1E{$Hd$lr{A1@FT5ywNUilx zw{Y#dUlFKW5>vHk57AHoW^#R4B#gM0OvXBWkL>@r00^iII-3qXv!|M2>gqG)qR4!= zM=Y)X%9r9|G9c*`f|WGYr?1w-U5}d@4md)_+ZRIutGRw5(OMnAO_y!LIH;_wtd&hb zRdV`vaH5g1F-+zsKScN>wu!(i*45B?(NWh{$K7J2M?OM=U z2tEdk6%ofMz_kQ%Vo&(_KLB<4JxRmlmD$J}F;-j;FkD5xo#7gM9O@H_n|Z)RrFoCF zu5(!u6ur@JWA}c!vCTPBWlHMnhP(L271n3OG`yWMY!DX*o(z{Wn@8e3Cld~7Nsv`- zL`A+ejOzSzSs@MyZ#L>W@;<7WtQU1KsP7zjTCK@x0kZ!mpTf zc3_(#*VA#9mB1a;_s8$f0nulocEusDWf`1jE>Xg1e9vo^G*v0w@1@GiCJvZ}fhd4( zfggBZMwLg2&uqKdkYvHkl#UzL5ZNczS?VO+&#Sy4 zaFfCyLCWX76FTM1eu+o7qP1ge;UI26>~NN7amMav*yz|RQRfi@Tfy9p_00Fdg(&jB zv~-O>)-Qd%Bbz%hIhx&_^v{<8NpWR;T^i7&flYH>f9aYX7)3gewT;AMx;|LXXu;R; z`0gUsU}0jx>F&)Lm1C`M&@xWM`_U`Gr}ZbU3;h8?lJP#il!q8ju^la2ROH?WYAxUv)A7`<*+UChJw@+tsm5IA21^U zL*M7vLnrB2;ZJRdpFx>{N-&lKYf8ua)U``P)v6BWV(kBxN53{U8XkF#o%KJD2g_Nm ztG?VpE3hW_vw3exZUmHzDIuU=$T{P>7c4fooyKnlLMy!x8DGClC-{6W9Vn0PuwrfB z1g`8mo0#(Qy9qodWW%iL!f!XJI!u=pl4HMgEmZW2-F(HglM-G2vPX6PPC1Z&BL3Ed zuFBk+X;eg^;`~QbqVL9fEjaQoV(GF(=;ZL4I8}2Z>_R}L>Msc`=SfZWsJo^k7XO(N z?pgntuQYP*`k-Kde|H_VXUk}dWvK_)L%a202qTRX&IUbtwPxe7*0EV}*xV=ixO6*f zDcWEJ%AANpXD4+H(^_`r=$p^mXwuT%dxf;A(q6b z`z+zHOcfc{1&ZkhX+mA|E?p%SQ}?;0WY}X4zJ4;(`Xrj%bYGLdV5z@B7r#^sF50c; z6K;iR<&h7?MK;EE&{cqV<595=KR8)yU2_1L1fn-GKAyz%8a%AuH}TWBT>HeIncaSf zY)klO4a8@wdR&9xYC+yozrq28Uk&EB+BzU851aaT$s*ENwc{35QE?03ci6l>4xUWt zTxx8)#6Veft9IBl`KDLpcKTnjw%R?C5imTi6W95C`I@!I*aNS8gQSXr1ymwO>h(mvc%p3xk00`hY^N=s)ABEN) z$HMdliI@*eid|)+(GP=_zYbatfw1a0UE?yqK=#>Ly$Uo88s9LKh^>S+gd|_jkSn;Q z_pP;CAW_)_ekGv4`VKtbFXPiZXR1R)~VILbrdaylS}d18CXJ?CnuQB?_^(1oQ!kK@n>9 zPJAP^0aYlpI)+wj?K@6NPtx(X+q$t}?Tqa8^#1R{5XAu96t8*4G(^ zi*;G6GI#rEOgn3)SV!S8+4ssTH{@^(+Bj7@R^dJ>?1%Kq4I`0WiPWe9jxl;Im3;w9 zEghYu;Xo8A-XmEnc3+2n+SMIvoDOaTsROv+i_3TFk#64PC zJlpBzx%B!5Fyq2jP(Wq*j{#P>2{X6KkODPp4ECC0JDbdZM0l2~bGh?M)07FBt<|U3 zs$6DDiUj_owF!sV<6YGa>%;PAYB#kpnsjhyW*)O|bUIAF7pduoa=`gPs~zxm@ip5%Fh>hTdPl4^cz zNH|tM<|E@qRJUpF^sP|7&M<}YHx2mS25{s7ydL0Yq4Hvi2yU#1U7(}!GHuHXB*lv< zu|P>X&ubp+lJJD8WV*I4`kET}W12pw9EXcSJt6Zha`x?4;#8*qT$q=a7uY`oEWk7} z49WbeMoVH-QdvoG$+;ZqKq-x!0fBp4 z2w_@MQn!)Z9p>BZn?RRPdQ|L)Wd=m63hCW;WDXn*LpHsvD)gL0gUS3qtfO}Hl&w1D zfs@dSB$wi&>>ioPadcMYqVU_XprYq}6A`NM%IO*W1K%iEx}w};d-DRNO5!+0+XR|# zt6P3DKXY8c8%EwbeGvWXYx7NpI6>~c zg>>ePIc8~P`ZP1AryMp5Yj8n)TU87+>F zV8*jJ(>U6}u;wK4Llvbm*YS(|ht1FAKt@^sg$R3WLf(bT%i8>~x-%E)MvF*5SYn~b z_2x%pN8#l;4H*R-`4wNk20;RBNQJyqRGxDhnSC!Q63ssa1KliH%e2$n>*Gvvg1F+s zpReq8tK)EGz$DY%-fo2l>rPFUyL$}&P)<%xz_u+U`)n*v!Yn@|G;J68+cqUR*;xPz zXIxd@3=wIzDNzOLPnTuYX)DN{pWD3LMog&Lr=`a_a=IMCUE*XDnIWf&BuNSr_%MMK zI-0lhAERRz`9cv4X(BADj$ZuovQ)|M<|BbpUpl#wUB~f`BbG1E23W#}0e+V6#mP+n zNoqZbljqwcHe#^N3U7!zu0O^~2lEebkF$) zrz6sUY0B+gen~zCP7p=AYacgG%A@MXq7)Rb<|z8R3TVO?gnC3(Xb|hqVgRgR*z5~; zy~r1va_q8oAT?JYa=bs)4OMw$95#Hd)8TEmweQs z)#IiMRMZPm=N!4k+Q%YI-l&2dOx<%!tv7QdHbsX+zad%UOidu zh`_N@8(z5q8Esu$vGKV*?#T8h(Y9EmSnG$Wl``|)#FUhU4vYzL?c0C6Qfmz{bq+}NTVONiQr zk9^=49=WO;It9c}d9xy|R8m}h-QBaUUJ!6UZ@@p**M{7ql$SlWlig|5a`mQMvG`@6 zrbFDaZ0cjQQmnb>73gtqA;}dheEv)S5=(Fwi%4 zW7+2^VUfh^v}!6dK3M#Hw@9#<&|xsEBAWT;BuZNFBI&Vp8ZJmGb5#t~fELDl5?UHT zVY#GAil6|XmJSw;tW-$e%me+MDYx8BJey|TIhsE2!r9{G(}3Nl3)iDFr!~QF-D{)c zOf}|mHJLFy@v2U?fx_f>&mzzpHcu-sfglFUp@W73C0??|oC5 zh!>gT*I8Zd_8yp;DvFhw@TuAq(az8uiFlfjzotb|0W1?1v^v0e3kI?QKoBcaU%KD^ zION;Q&$gGKq5S<;Io1`Fhinzx9Io4QjHsE1qCrdc_- zTGcJXi9VQRuY^YO9ng|gIY(s-`6CO{YEz$qTcPm4`XqIurVoe1mDbkEuLc8jPjf;q zLHU?pChzKud`|6f_?BOgQwF7QpapZ<)w&KLiOF(VMoWz5Bp?=^1hoCu;Xnim(nFWH zp^F?wz1kvaR_ya28m|MWcmV!VnSD*0yLN=U^KeK^DX)W&D>bdzXg9y;cqRBRg<_L18)K7PNTK9_oD z_kg}``)&mpgCxUi_^t_M?(uUl#@f6f`^JW3Q-986v^vLo+y)W}t`GpQp{JTk?~>yT zED`-~$PJ3AWY!;i(Jybk#;_4fJ?psZx_=G?UW;ObGAv3NA==2P4|aknGA1T;2BH2O zjVHU+Mbtg9?ckrMsFKK;1dk7DM~(;y+cX9f4}aMpu?~LOqSFe@z?+J#lxNx0+Rms^%*e@N> zj$37=vr~p{5)~iM)<4Wc>;_9qs$^+eAVIQ{ki+!VFA?zq8-rB&KF*Bq+^Q^)j4OH# zOrb1FR}=T~T@NF-Dqj$Hj<+?bCBzMz-5iRVR{g*!GhO?+9z#gB6IkDuof=$_pD%AI zp-7EYmC%wmv3jx|hmc5Xv*3G>SUw?PDB^ejXMg|ldH-T0hqY#cyV##{g?Pmm5g{tP zeQw{XbaC-Y+Q8jN7KGG)+)R+_kA~H$6n~rIj)-0Sv@(A^hWjgx{2fKhY=Deqq1K31 ziRHqH2iMSDQPLudrSogoZ{ZuaE|X`#~IKruN!tOqgo`Ay(Aw38uJE z)qV=^6?SFwVXkrQVh&Jecx)hEc#Wu@O@Wlj$c0d;93lL_rx{0J)5qf4t2@ah_4K%+ zyYE5Z8f-E3vF(D><#L2ZS)OC-f{4nl ziNXm(XOfmkQ^{?|ab`H7xA0Ps`C0PVxbT85uJ1l;u6I0tH`4j`rh79!tnO2Mu3vml z7#Ukyc&IJW7keFS6`N4+SJ@~gylW3^-bH$Me6j!{>Hg}~yHjX>p+e4>z?HrB`#H;O zH0ZS_iEQtxM~OarKEfhgkQo$h=w4oWytY&l!*_Pp@=-`|vo6 zhXY(TX&x!ki5aKqB5oWs&^Lru>4C+ABO(zyhPf_c&z=>ACkn8hH;3i*S(KQ73?Pi3 z8Buz!bzSS$pLD#gM^Nke!~}L`(-q_;e)YMB^)lBNPum}|)=D6>;YV9AdEDE1*J-Ca z{9DmiZb6nig_pEQP+E=GT z%3ozEq|G0+&el!$_^A!aSTq*uKt5g>!r8MgWnamxd*6`W4!y-fNk= zCmIqiEw zP-SQl`jZ|?VEY>h9l;mO6V#yBNJ_nMk55*;NXy7q(T`5|(|(5Vj!=wiJ?|tRs;;N% z=lG$WL47?vn;z7jACA-6Cx4VlbvX;qd<3Jx4}~=T9|}qRNAX<+yP_F{3Of<=$~NUC zh!g$+@jRr;((}zvY~BATNzhxty$ssrvPH2QO~4`@gu8OuIzN4ZQ!qGAW3|>?lAK%y z6Hv^I8w!OAT78;pG7*V7{aQ$8qA?O?wwEfjk${c2&7K2Gr><4k8Uequ9$u((SOil$cQK(AFedxko7J?NBpZ2u7#^zZl6 z{%1r4moz4VM455tE|G-HcgJ?ZpUJ=4VyhtvlpC;5^|~&?4$d2S5b3ZJ{k7FqM!Clz z>(dN`dl>W&-XvRQp-lSna~RZ9>r)1af`X_|dMSqy7l#pz{2e)}Y1r!UUW6odz{ADo znW6QrSypW;%&Okg;1%u~RRn~pDdu{U56k}@5a|Ae%i&~6HsKsPwafh~HZH<5Nt+j@ z*Y#SS_ic%&q-lf_V=Z-s`#wOdbC6YwE1EcexsR19@1=6$jhCytS#;{4CtbS3ze@e)^u+M1y@KbyL{=KmOsV6FOV+%xy+!Sr56F$a>(SRjY(CEJk zoEvB(C*Q)!^s%G@uefQzBOH(y25&r_7ZjsvtH=zTP^a)Ph_ULTpiq)wr@+Q;gUg@y zspfs^hu5kPUXVR+TSzi&6#fzpY{0v}6mmis+B4rDSGnXo*<4vE6>|p(xpn=nB54Ws zV-a@fzCl29B^Ap?^NxHoiV!NU?B_Vb$aV_?DBs(=e%1w58P2hSeRk3v(Qu8IL>YT8 zMc4s1cF`u=h2vXFAXRv5+m z`h1%)QXW~j5Lfe=y6owad1cnssmI93%4jm^S96y=TUzXvKK^N0c#}vdQRP#A#;7hA zi-j&K3ah1u)WW;0!%ehN<*?aL=d;On-N9TNES-POT20yFi`CxDonabS@id8*r}87_ zrHgeg!2c*!*ohF7r7K%oG-}J%?|*Yr*TwFq$GWcYTK7H}Fm31;PD`kL1+K*ZlK%@o zb0L4vzT-z&5n2aJlF2=XqEBK4sYt@#t`4yS&*{*$AqdiKL+fBQ=kc1x1ELpv<99<7 z7k^8<$EAVSoq#L63_teo-#@f_Ye$o2w`|X|jhPlYP;M`5=lN)>R~FJjwvI3L$aNPp z4Ice9NZ`sfToy3vlXYj*_~;L#xVEDOXUeZ@BT)iRcE-mpkQmNt;uxRk5tCfLA5N;J zrkaS$*wqDUeCO!5p`$=7Pw;j^n*!J?ec2E}36#K<9}TSXxGm*9uWtQRn5~Ahn$Uw3 zppQg1t!`~gw|(I;`M9p_A~{ojb1YB0aIt7 zhWj(+>Fs?T?EFW&FT5cweAdvh<`_#E-f;gDvqlxI9O2;aYk`ML-D3ZmGky+pNN@a6 zdVrQ=XYCPkVq&7b4zpZLdd@saeH6`($&`$X*}wRJ=zbbKynAt?Xx?zjO{RCHU4Kvy!b3&OtRH0{ z9_#E2Ylt<}N15nnn=1&X4AmOXH-wD{wn z33chOtVlN`j_|z(J!7l9V1Ro*Ff#IuF%UD57^3{QAYlATA1iNI}w7<0*BA&#?;qdXz}2btsjGF-eVs< zk!Lbeq4|_F9%u!vv~4)HK==LLBh^q%F3P%C{@!=~$D$7HRd&vISPXui8}|KMBKr+k zf^H7Z>tg3a#oz1W|LidPg2xOjv;?gmsR%tN7>^LQq&bM8nRm5G;gvZ1kvM|z5vVtLFmSGMyR#rz9O`to4jPB~P%q9wb3g4~|BEXqsE$q)Z1utvu)l-#Xwq2> zncL(EpRlvEmF^oZ7V{&XW2fm($er5Cg{7JGZGgheRK7yEj2sW zHostkxEw=%W^_%JYv<5rC_z<^&(`>hT~Roh?{BM%gYp?5w0`#noxa zS`YQjC~ciTZX#qF&0>3tcN>t6;~$#ql-v!+E+-jiIi%?pM&Xdd%Gbk?Nqdk;c8(OL z`t*~cFa9?lxh-6D0W_?+Pb*^&KrO3n@BG*HhViKJgR9+n6FR?ibruWL|1*CzN{&VmuB)q7?;o;&RC-|>puMth1bq0pJ#}^>7d-U z_fz*T>Tc~ST#(E$uU4+g5gK#;%>{i(jLQlY6?@QWMu3`&^bfTPZ3C<30gs;AKv>yB zh4I_O;KSitebtDxVM8T8HGRX}lBE$}3coI-v5w$@PNgBuLi+(~K?z9V0FP{Zf1qfy zrapeMKF{O~C3Ed&f@Z?!oJcyXJgVZBuEC>EWu=oq{Oz#T`*8z%IYK4(PZNsy>f%RW z5Qw6Xn|iy-;!m|iLL>rxNs{9O&nwecvz0sygunxdB~t|v2!H|VyjNSFYy|)urt5rP z0Qn$-uz;{+__XJ4>+j=}I*gz;%>C{f@NMtb&q<6xv=GtbDTA=!L-O4cqs#*xiuWwPc=B zoBjj2<2#jV8}R%6e1=U`K+#}K=dHv$#7cLO&3dh#2{5M%6=^asH7#~$Obp0^MY-N~ zvL5L2&cACi=O&!r*-(5>?v4Jf6aid!!BWduy+(k8o&FB$g{C0O{N^m6EXUGL2>J#` z`A0uiJhP;)M{rs+n$9bG*tYg}yi^8f7~qQ{aUG$t73E}CrQN@Up9>`Pqi};q1PvmC zet#*+vJ)puYz*$c90>-mRPBKEf=c%-NjJz_rQpaMoAOBC+%oQ|-@Hn`XwA$91|Q+K z*EF^5l9b0{Mtgb53*+`2GW2eD&-~qulYCDgLu`OV;Hq0!8SQTuL(vNtE&!$3x%MpW zhn%t(T`<2|PSykQLbIEznYC#vG&|ThnW2#c4_p6}<3cykgMbM<$ihB{Dkw%GbRi`^SN6ki z*k6^(aq-ikCC>#Jb=p-ya|Y^|Jc8r&f}C0+8@?LBXovUOEb$c<6YBv=R(kp9wK6tT zMhM7hRtzh;M=?-LU}89^^%(WY%)x$CJ{fy|C!@+;#8tQm4&{Nrim&6?nZlt5KIKuX zC0=2`{dyu){^bkE>Ab_KRmobtFVAc~)>~<+?&8RC@V#L{&BxE2rrJPpocPMoHu7)m zAy~4_V^CTP7fnl)hW4%-Oihg=n`gI=x%TaBBgIELHYe1)-@C2T66y#C#Hl+oq$~Nu z2Up>Qw)6dwv$sMag#jeyeGB_4nw8NYQX`<1JQpJaO~(sOiIJnw6vMW)CH1Mbu|yxe z;mU8<8iMzmv)k6xfonrez;!vO0j@Jdp%$ywZVpg+AyyjjLFB z7uC8-b4J{ZA z>!bDR!MI7Ve?pQArjfolL5IkB^`12K8tWd!H!_H&?wC%8h}6>lzO@>o@|%;F)YDO8{x6jkVRCG%gx;=$CZl~TWR)DpfEGaGLg_eAHB_nEE+AZ%EZLxTN!z78 z|C&r#5^~kna58N#MYnXVyJ%=;CMq^Iw%v1hP29oBErTEGksSblLis&~HBpcrNb(~E zh6C6k{UHMH8ZgG>nQ?%+TYyVKN3A~mkNm+^oSFBoKx!30e^h_HY+>G3 z*}S`P9GHA?Nwa_PN&GS!Df15{4K31h?1U-A`=@K7;s?LaY$mnt@g1$T9hX)Oe%Tz% zKFF0%0qqSUFETD2>rX0STcBuB|B0Yf0$M;C`AOgGDSI)5P4QYw^8U zqM#cqi_r}Gc##0egt+nM+Tu_#Uzx*azxtK=YI=)>}S&nDQU^$yL_WoW}c1ksu1B zhC$Fva8Yf!p6t7NL+hMpJ~0XC**JKxFrB+T@VXj!RzOt+lvV&%EL7Bl=d)#JXaDl$ zOZfNi-r68Eq!ZLz9xArbH~u!B(iZ5QdUv%>a|Nj z_U54cuBp4+DDXBl4q>K)i`SV8stm6+C*01y~ z(=$<&%($G#H*LlCR4Tdy5= z?qg?WINwN9_P@48ftjgAd6p z7xD>g6V6fr{X5H!SN$vthm-tW?fsIXa3>4zp33{^2<@lKM!VX^w zsTtRLwicu0<^j~fdn46LPE+-Tv1#Z?ZB)%SFz|YA_9B=eQY-S`+ZAQ1cCfwpo$RP~ zI|nhEp3xLtTgwN!ctA+H(=e##cYKbq_Z%x5D{TL({cdYD@ZEyobt;PDqvkR zezHd$9X<{G_CS<8zum)4+9(B@9%woAU&Yvo*6PC0B<52SiLm59N->g(W9hKn|8_(z z+H6?Q?L}DYs*T>^kpsr8FTlMRTnDB%W_gIOft$6Gl9IxkZ2$^vPT$nlrm*RSr<5KJ z&jen1mgxD?!CI|j8Jxk%ixYaO1ZUq(sWU`5>qB{3^6|kpw$>ovAX@nEz-3&15Jo%@ z`ujdl4_?My0`SA7*b}gd0-q(?Ov3r*plhH1e_Vf5o0^;xN@4>0x8|qYXFyT)=O6a( zNs&eRgCJ%E@7jxfFNT%T&0eIy_TgFu{R{o=zkqFjjh!8fpR*kIsdMqBYeLtrbL;N~ zi}c#=+;WK5>v;Vm9v9@yqsy}_mgS*ovEDKPN79*oI~sN$%A#aMS>{Os zmoRH;saKZo3HxC(^qMa!_ZcYpixxZ)?Uf5x4$vlKg~R}}>vILn<`-#?Awz(ayr|aa zc1<{c8OQ1lQp~b}{AQ}IRKuLbJwKifP!*piTM6FGHu?vAxZxjP-v!v1rKIP9}2c?W4=)rs1Y1D1D6pQ;|=pyWnKWJ9|)}`BYamwqQVnjsh!X` zI?+1~LXuOaiiihWbIQ#iWVvB*X0TJM41_iv2`#ZL`S*Bb^VrRFy$%di*eA?Hg1Vo) z4={h0RPCpx2e$=pBZFt>Ifd9!flLQ9lA~014ASZjGyxx+y$@;DT30cUGqqL-IN|jW5~^q{HM7sreM=!AzpUmcb-frySOtv-aCd;2 z*{36pPD`mCh`UuJ7+R96-vhrP7@e?YhVlH1g> zDS7qH?*23iZx=Qgu&v`A`dW#3F%pV{_g!RN-zC=xt9W0>FZC@Pz^=>dsPnOC<7qj8 zvr9lXeW>7WUC!I&GMJ+|GS!!VE%;SAY?!+048rFeP&!C2^yHUoWMOFRrZ$<8b;8$I zS5{u$vORMMzi+HgVQ?v#4H^B4PkBmm!3G$AvCwQ+GNLGXP&kMVV7YFUW$j^R?i-k{ z`yS_0#ZPM2e^uDhk})knG~?T&X}eLq`;fNmE(@b1Kj7qHkE0%g47i0Z+kB^|9lRTp z{pR>09G^)lddHR#nh|Zv*;deaL1ILR7b%f1&&I~O8$jAEIaxVW%a<1d7|HW56YK7V zH+z6zsV1SiH79eruDLmV7~RkyQ~$f?O_A%(TKMR>&=?dh5Du?StiPoEW1!!n`t?iX zXrPR<0!O#n>TVvo-1itHWPBbyc>SfRn4lzK@`9wfku;zF6Q)b`4&UXrxB8VI;F(>t z+kC+`#d!s<+x9;Z?Tg_|9-Uq>I`BIBc`(s!wu=iI zv*67P;s_3cTff~bYw2lF8@UdNRbM!s#o;oMi`h=YG&B?MxK_=oaPq}< z^rT55nysyYp-Jj+B7K?^ql!t_V-MaKTc`FD%N$7ymZ z22P|p$Jc4-pzUoQnAF+zKg;=76y_Kf!+GNdrr>TOuE^t$0kh0#YHw<|<_|S!X^2;= zOm|X1q4NcG;Wo?bGX94(4-!&^c!@M#vYXS8wx%(u5kcEm8NTFurbvEW5s1nNw_rEJ z2>b!@_2P3Tj*s%9uK%RT3lCm;=a{zv1SSvZ7Lb$31USFTTZ@=Lg>uG*n_5ghV<|cp z&;5H%by>bPM?|wNjKL*ekgLg8U~_i^Wac)aE=_sK-#$v0pV6;^h>I^EeV|Z>noUt& zpD8be)IuVWWmcYTN$O(!3{;#kp4whlheu~7dz89>krZ^@TQ8#d!ml6XpC(59InRlEG1KFUnYmf7P-L+$K2oez-H~SN%BM6Xy(D=BgUQjcu~(j+ ziPHi!pXN+u;Vk*HZs#H6gwF2tl7;0{9#$QP?spFV!}5r^xw+|NvVy1`a96oJ&9wTT zICa^7Lq$03rSYuN*y7$R#(Jd&F2jHQkt8mh-){f(3FiY%q9whLm+bDTCDp{rzxK~& zqt_yQP%eqo6h+E{M@L14raYS-d=0MYqcUk{2$jW&D2r~lZw5btUDtg10Ax|0+4{O& zvUJ$6oC$bw41NraGDL(LYocmcMpg@FHFeq0SCCWNsoa7DUwcgX&qHB95K8@p%Z> zdAq@F-B?fIKQ~iRJQcrI^9PG))HSp8r)0MJe2f+ooH7h)jTsiF^i1|~ zA&$p+_<$EF3ZJf~`G$~%STf%6-e&v%aX^h(%*g8~9t z9va9h%IE4mc&B)n-mdBnACGX4`Ng==b?rVfdvNL4TQ z0(Qs_POo6bz98FMf2Ml&k+f|*sl{{dTc~2#)8&(rhZg+E4%yA-ydxa2DDBt|$eJM5 zi_ufA6a#e`Y?+!h$+xZ6cWqPza}5x92C8`^s7<}(Kwa;>Y(=5~E8PaA5bFT^&!TUq z0V|UyScHeE=RVsy!q2eB#-V!Qfw=;9*s0iCt; zLyQz4EX>R5fRv&>$f)+v$EwktJBM3mstWHT? zQQ) z+eq*iRoqirTQO}(`ln1R%_K;k?h5mYPx>-sSkdMX2=Nr^T{)TuvN~ zsPER}M<%ELr_03kHLpgBK8TQcWZO@c0&2C04aFqRF6hvOe*@e~Zq~P>0n9MUSntAc z*PYOyw*wP|m7hC1JLwGgP{(6qQVFmjnE~AJdjO2y`cl_j3~j;aTr6pwSK~j+o*$nU z4*O%0H{ySJ;G|_Cv6^ezHqY_M>Uam>z=|0X1{F@4>&ne90JmNRGMm((A|#N~YrBOn ztzaFuGPXBc?r9k9=uq<8aI(4+F8wU(><}k6*1_Ljf4O1BolYUeBPspunqP``fg*n{ zK|+6zjfq|1Jg|x`>_)j9xkI2TbZY*Er^KK>r)L|zgg|3*2z&gFr{#4+YbQ`+4`j;y zPXkMUXJIAXJ8h{^au^xQI?2y&`sV;;a)on>;v28}va>We6{1)>kqWt7WEpSt7R5Aj zwM~gDc3{(p@k8f<;z(jD;y%NC1~>3A#%iL#(J=+KO7pcb&&eAK$z0=5CKNvfh8p;U ze6t_S^WCL#G!7;2guZ(n!(gqyKLJ$0%{zT}&Sxck((Q^J=y#PbzVJbCo_tGG*<@Ir z^XbwPH_A9JPlq@loeKkt_qW@BRiWk%%V~go18&5n>$^ZHJ%GKV43=#mozYr&dVl}* zgZoa5s2`vb=lNb{s5N@Y)xwmfmb(yZa<#hs$qg$OGjoW(RiUo=^srHV1;AZ8RgArt z4Xr%udT1$j6mIE?x4~DV(dh0UD^J=6D0+iM74vz~dkY6UnjivZSfn5>mA~pqXp`Q| zu2*)P1WS=yYgNtJs7t=_f#%QalXz^6FPcZ+b(YP3_plIl?y|aUm%*X`Tqv8{hLLUz zZu$G%(;_Wc$&F|?J?@D|}V$B-w8}SyFluPBBjP3UdWEp`ZSl&Ru>HOno_`^nQx;QW+5V-q0h)ra- z*^u2puMcIukG#wiGAva`4>Q7ApvFXN45)t!Xb%Sr~d5qF!3eADA}RHwWa5QY!}MCUjhu08Uh^$0K$<~BR) z^eSkYTV(N5U-LZcc0w@WH7)${uFWY9IYZxf0ZpFXOF2Fnv1mbr-1~2z{Y99(V#*bE ze;VF`RuLOpdufl&u5Sj$cn#H&OD3xy4SC1LI~dNn&tgh0b@1K_v^tuYh?EsP{ET@G z`y9$ro5emo(}IGeD+hONIbtW7oVE+z^VqI6KD%0VAEz;^$UbRey8c2|{^i}(GLeX- zYm7~m41sU1I_Xz*j2aZkf7q`s#A@utQN-Z6*FLe1?hH>lUdPrM37PK5O&zv>V@|Ad zEm62M<9A8Noca7CuFFIZMjIkldSk;gq*Dno%N!Cv)QW69s+V+c@I%=Af^1I2T&tFM z?Q5vCU0!gAO-``sb^G@iX2@rg_)YBxHPwrX`2fl?u|MCBCh=YYm)$LuuRP3rt2R!V z<7Xd#BfKgc!2U&vOlVF`GV+$AD2`L91sSrJO$W&SpJGN7nY6CGBp+ZCpW7UnMg}br ztc+QBHK+##xG!^zv3bc+`g?=S@RzmHMfF)n`*%@GW;u0Vq2y zZrb}~$y>C*^r3UX>!WPxtiiXBxV{r(+=F<%kl7yZZGL` re_S`&qqXGIP@R_m%;xBb}p4I literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/image/supported_module_avoidance.svg b/planning/behavior_path_planner/image/supported_module_avoidance.svg new file mode 100644 index 0000000000000..7d566ca3ba20a --- /dev/null +++ b/planning/behavior_path_planner/image/supported_module_avoidance.svg @@ -0,0 +1,58 @@ + + + + + + + + + + + + + + + + +
    +
    +
    + Avoidance +
    +
    +
    +
    + Avoidance +
    +
    +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/planning/behavior_path_planner/image/supported_module_avoidance_by_lane_change.svg b/planning/behavior_path_planner/image/supported_module_avoidance_by_lane_change.svg new file mode 100644 index 0000000000000..42d860d7546db --- /dev/null +++ b/planning/behavior_path_planner/image/supported_module_avoidance_by_lane_change.svg @@ -0,0 +1,58 @@ + + + + + + + + + + +
    +
    +
    + Avoidance by Lane Change +
    +
    +
    +
    + Avoidance by Lane Change +
    +
    + + + + + + +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/planning/behavior_path_planner/image/supported_module_goal_planner.svg b/planning/behavior_path_planner/image/supported_module_goal_planner.svg new file mode 100644 index 0000000000000..6b790676a0019 --- /dev/null +++ b/planning/behavior_path_planner/image/supported_module_goal_planner.svg @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + +
    +
    +
    + Goal Planner +
    +
    +
    +
    + Goal Planner +
    +
    +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/planning/behavior_path_planner/image/supported_module_lane_change.svg b/planning/behavior_path_planner/image/supported_module_lane_change.svg new file mode 100644 index 0000000000000..eb896a0f7ee98 --- /dev/null +++ b/planning/behavior_path_planner/image/supported_module_lane_change.svg @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + +
    +
    +
    + Lane Change +
    +
    +
    +
    + Lane Change +
    +
    +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/planning/behavior_path_planner/image/supported_module_lane_following.svg b/planning/behavior_path_planner/image/supported_module_lane_following.svg new file mode 100644 index 0000000000000..8b850b4595122 --- /dev/null +++ b/planning/behavior_path_planner/image/supported_module_lane_following.svg @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + +
    +
    +
    + Lane Following +
    +
    +
    +
    + Lane Following +
    +
    +
    + + + + Text is not SVG - cannot display + + +
    diff --git a/planning/behavior_path_planner/image/supported_module_start_planner.svg b/planning/behavior_path_planner/image/supported_module_start_planner.svg new file mode 100644 index 0000000000000..48d588dff4463 --- /dev/null +++ b/planning/behavior_path_planner/image/supported_module_start_planner.svg @@ -0,0 +1,48 @@ + + + + + + + + + + +
    +
    +
    + Start Planner +
    +
    +
    +
    + Start Planner +
    +
    + + + + +
    + + + + Text is not SVG - cannot display + + +
    From 1eb962ed04c385e4819efe0839907966a7c950a8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 27 Nov 2023 13:56:05 +0900 Subject: [PATCH 036/128] feat(dynamic_avoidance): accurate decision of front vehicle to avoid (#5679) * feat(dynamic_avoidance): accurate decision of front vehicle to avoid Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance.param.yaml | 3 +- .../dynamic_avoidance_module.hpp | 8 ++-- .../dynamic_avoidance_module.cpp | 48 ++++++++++++++----- .../dynamic_avoidance/manager.cpp | 7 +++ 4 files changed, 51 insertions(+), 15 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 127b70fbf7bcb..9ee86a06a4c1d 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 @@ -41,9 +41,10 @@ front_object: max_object_angle: 0.785 + min_vel: -0.5 # [m/s] The value is negative considering the noisy velocity of the stopped vehicle. + 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: "object_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 34769a98b0545..a12cc4d405d41 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 @@ -74,6 +74,8 @@ struct DynamicAvoidanceParameters double max_time_from_outside_ego_path_for_cut_out{0.0}; double min_cut_out_object_lat_vel{0.0}; double max_front_object_angle{0.0}; + double min_front_object_vel{0.0}; + double max_front_object_ego_path_lat_cover_ratio{0.0}; double min_overtaking_crossing_object_vel{0.0}; double max_overtaking_crossing_object_angle{0.0}; double min_oncoming_crossing_object_vel{0.0}; @@ -329,10 +331,10 @@ class DynamicAvoidanceModule : public SceneModuleInterface 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; - MinMaxValue calcMinMaxLateralOffsetToAvoid( + std::optional calcMinMaxLateralOffsetToAvoid( const std::vector & path_points_for_object_polygon, - const Polygon2d & obj_points, const bool is_collision_left, const double obj_normal_vel, - const std::optional & prev_object) const; + 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; 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 066684629aa45..3aa95dba6c4ad 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 @@ -591,11 +591,20 @@ void DynamicAvoidanceModule::updateTargetObjects() path_points_for_object_polygon, object.pose, obj_points, object.vel, obj_path, object.shape, time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( - path_points_for_object_polygon, obj_points, is_collision_left, object.lat_vel, prev_object); + path_points_for_object_polygon, obj_points, object.vel, is_collision_left, object.lat_vel, + prev_object); + if (!lat_offset_to_avoid) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since the object laterally covers the ego's path " + "enough", + obj_uuid.c_str()); + continue; + } 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, polygon_generation_method); } } @@ -910,10 +919,10 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( return -motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); } -MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( +std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( const std::vector & path_points_for_object_polygon, - const Polygon2d & obj_points, const bool is_collision_left, const double obj_normal_vel, - const std::optional & prev_object) const + const Polygon2d & obj_points, const double obj_vel, const bool is_collision_left, + const double obj_normal_vel, const std::optional & prev_object) const { // calculate min/max lateral offset from object to path const auto obj_lat_abs_offset = [&]() { @@ -924,28 +933,45 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( motion_utils::findNearestSegmentIndex(path_points_for_object_polygon, geom_obj_point); const double obj_point_lat_offset = motion_utils::calcLateralOffset( path_points_for_object_polygon, geom_obj_point, obj_point_seg_idx); - obj_lat_abs_offset_vec.push_back(std::abs(obj_point_lat_offset)); + obj_lat_abs_offset_vec.push_back(obj_point_lat_offset); } return getMinMaxValues(obj_lat_abs_offset_vec); }(); const double min_obj_lat_abs_offset = obj_lat_abs_offset.min_value; const double max_obj_lat_abs_offset = obj_lat_abs_offset.max_value; + if (parameters_->min_front_object_vel < obj_vel) { + const double obj_width_on_ego_path = + std::min(max_obj_lat_abs_offset, planner_data_->parameters.vehicle_width / 2.0) - + std::max(min_obj_lat_abs_offset, -planner_data_->parameters.vehicle_width / 2.0); + if ( + planner_data_->parameters.vehicle_width * + parameters_->max_front_object_ego_path_lat_cover_ratio < + obj_width_on_ego_path) { + return std::nullopt; + } + } + // calculate bound min and max lateral offset const double min_bound_lat_offset = [&]() { const double lat_abs_offset_to_shift = std::max(0.0, obj_normal_vel * (is_collision_left ? -1.0 : 1.0)) * parameters_->max_time_for_lat_shift; const double raw_min_bound_lat_offset = - min_obj_lat_abs_offset - parameters_->lat_offset_from_obstacle - lat_abs_offset_to_shift; + (is_collision_left ? min_obj_lat_abs_offset : max_obj_lat_abs_offset) - + (parameters_->lat_offset_from_obstacle + lat_abs_offset_to_shift) * + (is_collision_left ? 1.0 : -1.0); const double min_bound_lat_abs_offset_limit = planner_data_->parameters.vehicle_width / 2.0 - parameters_->max_lat_offset_to_avoid; - return std::max(raw_min_bound_lat_offset, min_bound_lat_abs_offset_limit) * - (is_collision_left ? 1.0 : -1.0); + + if (is_collision_left) { + return std::max(raw_min_bound_lat_offset, min_bound_lat_abs_offset_limit); + } + return std::min(raw_min_bound_lat_offset, -min_bound_lat_abs_offset_limit); }(); const double max_bound_lat_offset = - (max_obj_lat_abs_offset + parameters_->lat_offset_from_obstacle) * - (is_collision_left ? 1.0 : -1.0); + (is_collision_left ? max_obj_lat_abs_offset : min_obj_lat_abs_offset) + + (is_collision_left ? 1.0 : -1.0) * parameters_->lat_offset_from_obstacle; // filter min_bound_lat_offset const auto prev_min_lat_avoid_to_offset = [&]() -> std::optional { 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 6f624a9f6f017..0b2fc9e789ab3 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 @@ -71,6 +71,9 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( p.max_front_object_angle = node->declare_parameter(ns + "front_object.max_object_angle"); + p.min_front_object_vel = node->declare_parameter(ns + "front_object.min_vel"); + p.max_front_object_ego_path_lat_cover_ratio = + node->declare_parameter(ns + "front_object.max_ego_path_lat_cover_ratio"); p.min_overtaking_crossing_object_vel = node->declare_parameter(ns + "crossing_object.min_overtaking_object_vel"); @@ -166,6 +169,10 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "front_object.max_object_angle", p->max_front_object_angle); + updateParam(parameters, ns + "front_object.min_vel", p->min_front_object_vel); + updateParam( + parameters, ns + "front_object.max_ego_path_lat_cover_ratio", + p->max_front_object_ego_path_lat_cover_ratio); updateParam( parameters, ns + "crossing_object.min_overtaking_object_vel", From 9b4200676720683f86a97df83d4a08aaac2d9223 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 27 Nov 2023 17:26:09 +0900 Subject: [PATCH 037/128] feat(shape_estimation): fix truck filter max size is too small problem (#5650) fix truck size filtering Signed-off-by: yoshiri --- .../include/shape_estimation/corrector/truck_corrector.hpp | 6 +++--- perception/shape_estimation/lib/filter/truck_filter.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp index 93d9683ba2939..3b2475286fa61 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp @@ -26,11 +26,11 @@ class TruckCorrector : public VehicleCorrector { corrector_utils::CorrectionBBParameters params; params.min_width = 1.5; - params.max_width = 3.2; + params.max_width = 3.5; params.default_width = (params.min_width + params.max_width) * 0.5; params.min_length = 4.0; - params.max_length = 7.9; - params.default_length = (params.min_length + params.max_length) * 0.5; + params.max_length = 18.0; + params.default_length = 7.0; // 7m is the most common length of a truck in Japan setParams(params); } diff --git a/perception/shape_estimation/lib/filter/truck_filter.cpp b/perception/shape_estimation/lib/filter/truck_filter.cpp index 672082fe305fd..b7d75c6c8acdf 100644 --- a/perception/shape_estimation/lib/filter/truck_filter.cpp +++ b/perception/shape_estimation/lib/filter/truck_filter.cpp @@ -19,7 +19,7 @@ bool TruckFilter::filter( [[maybe_unused]] const geometry_msgs::msg::Pose & pose) { constexpr float min_width = 1.5; - constexpr float max_width = 3.2; - constexpr float max_length = 7.9; // upto 12m in japanese law + constexpr float max_width = 3.5; + constexpr float max_length = 18.0; // upto 12m in japanese law return utils::filterVehicleBoundingBox(shape, min_width, max_width, max_length); } From d99e56b3968d01233c0367a824dac154154beb9c Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 27 Nov 2023 17:45:46 +0900 Subject: [PATCH 038/128] feat(objects_of_interest_marker_interface): add name text marker (#5690) Signed-off-by: Fumiya Watanabe --- .../marker_utils.hpp | 13 ++++++++++ .../objects_of_interest_marker_interface.hpp | 10 ++++++++ .../src/marker_utils.cpp | 24 ++++++++++++++++--- .../objects_of_interest_marker_interface.cpp | 2 +- 4 files changed, 45 insertions(+), 4 deletions(-) diff --git a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp index cff45e5c1a9eb..c1fae5ecc4bec 100644 --- a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp +++ b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/marker_utils.hpp @@ -14,6 +14,7 @@ #ifndef OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_UTILS_HPP_ #define OBJECTS_OF_INTEREST_MARKER_INTERFACE__MARKER_UTILS_HPP_ +#include "objects_of_interest_marker_interface/coloring.hpp" #include "objects_of_interest_marker_interface/marker_data.hpp" #include @@ -56,6 +57,18 @@ visualization_msgs::msg::Marker createCircleMarker( const size_t id, const ObjectMarkerData & data, const std::string & name, const double radius, const double height_offset, const double line_width = 0.1); +/** + * @brief Create text marker visualizing module name + * @param id Marker id + * @param data Object marker data + * @param name Module name + * @param height_offset Height offset of target marker + * @param text_size Text size + */ +visualization_msgs::msg::Marker createNameTextMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, + const double height_offset, const double text_size = 0.5); + /** * @brief Create target marker from object marker data * @param id Marker id diff --git a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp index 79bab6d5faf69..d5a19fede4fc2 100644 --- a/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp +++ b/planning/objects_of_interest_marker_interface/include/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp @@ -78,6 +78,16 @@ class ObjectsOfInterestMarkerInterface */ static std_msgs::msg::ColorRGBA getColor(const ColorName & color_name, const float alpha = 0.99f); + /** + * @brief Get module name including this interface + */ + std::string getName() const { return name_; } + + /** + * @brief Get height offset + */ + double getHeightOffset() const { return height_offset_; } + private: rclcpp::Publisher::SharedPtr pub_marker_; diff --git a/planning/objects_of_interest_marker_interface/src/marker_utils.cpp b/planning/objects_of_interest_marker_interface/src/marker_utils.cpp index 71414eae4dbe7..23f33c0b8115a 100644 --- a/planning/objects_of_interest_marker_interface/src/marker_utils.cpp +++ b/planning/objects_of_interest_marker_interface/src/marker_utils.cpp @@ -35,7 +35,7 @@ Marker createArrowMarker( const double head_height = 0.5 * arrow_length; Marker marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name, id, Marker::ARROW, + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name + "_arrow", id, Marker::ARROW, createMarkerScale(line_width, head_width, head_height), data.color); const double height = 0.5 * data.shape.dimensions.z; @@ -77,19 +77,37 @@ Marker createCircleMarker( return marker; } +visualization_msgs::msg::Marker createNameTextMarker( + const size_t id, const ObjectMarkerData & data, const std::string & name, + const double height_offset, const double text_size) +{ + Marker marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name + "_name_text", id, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.0, 0.0, text_size), coloring::getGray(data.color.a)); + + marker.text = name; + + const double height = 0.5 * data.shape.dimensions.z; + marker.pose = data.pose; + marker.pose.position.z += height + height_offset; + + return marker; +} + MarkerArray createTargetMarker( const size_t id, const ObjectMarkerData & data, const std::string & name, const double height_offset, const double arrow_length, const double line_width) { MarkerArray marker_array; - marker_array.markers.push_back( - createArrowMarker(id, data, name + "_arrow", height_offset, arrow_length)); + marker_array.markers.push_back(createArrowMarker(id, data, name, height_offset, arrow_length)); marker_array.markers.push_back(createCircleMarker( id, data, name + "_circle1", 0.5 * arrow_length, height_offset + 0.75 * arrow_length, line_width)); marker_array.markers.push_back(createCircleMarker( id, data, name + "_circle2", 0.75 * arrow_length, height_offset + 0.75 * arrow_length, line_width)); + marker_array.markers.push_back( + createNameTextMarker(id, data, name, height_offset + 1.5 * arrow_length, 0.5 * arrow_length)); return marker_array; } diff --git a/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp b/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp index 6261b4791be48..03e71193cc5a5 100644 --- a/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp +++ b/planning/objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp @@ -57,7 +57,7 @@ void ObjectsOfInterestMarkerInterface::publishMarkerArray() for (size_t i = 0; i < obj_marker_data_array_.size(); ++i) { const auto data = obj_marker_data_array_.at(i); const MarkerArray target_marker = - marker_utils::createTargetMarker(i, data, name_, height_offset_); + marker_utils::createTargetMarker(i, data, getName(), getHeightOffset()); marker_array.markers.insert( marker_array.markers.end(), target_marker.markers.begin(), target_marker.markers.end()); } From 3dc46d022fc85e786a0db35f0be403236e483b45 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 28 Nov 2023 08:49:27 +0900 Subject: [PATCH 039/128] refactor(ar_tag_based_localizer): organized the order of the process (#5692) * Refactored ar_tag_based_localizer Signed-off-by: Shintaro Sakoda * Restored ekf input Signed-off-by: Shintaro Sakoda * Refactored convert process Signed-off-by: Shintaro Sakoda * Fixed cv_ptr Signed-off-by: Shintaro Sakoda * Restored README.md Signed-off-by: Shintaro Sakoda * Fixed as noted by linter Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda --- .../src/ar_tag_based_localizer.cpp | 351 ++++++++++-------- .../src/ar_tag_based_localizer.hpp | 19 +- 2 files changed, 211 insertions(+), 159 deletions(-) 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 a66277c699a00..3f7a2683ea906 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 @@ -44,22 +44,27 @@ #include "ar_tag_based_localizer.hpp" +#include "localization_util/pose_array_interpolator.hpp" #include "localization_util/util_func.hpp" #include #include #include +#include #include #include #include +#include #ifdef ROS_DISTRO_GALACTIC #include #else #include #endif +#include + ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options) : Node("ar_tag_based_localizer", options), cam_info_received_(false) { @@ -73,7 +78,7 @@ bool ArTagBasedLocalizer::setup() marker_size_ = static_cast(this->declare_parameter("marker_size")); target_tag_ids_ = this->declare_parameter>("target_tag_ids"); base_covariance_ = this->declare_parameter>("base_covariance"); - distance_threshold_squared_ = std::pow(this->declare_parameter("distance_threshold"), 2); + distance_threshold_ = this->declare_parameter("distance_threshold"); ekf_time_tolerance_ = this->declare_parameter("ekf_time_tolerance"); ekf_position_tolerance_ = this->declare_parameter("ekf_position_tolerance"); std::string detection_mode = this->declare_parameter("detection_mode"); @@ -103,7 +108,6 @@ bool ArTagBasedLocalizer::setup() */ tf_buffer_ = std::make_unique(this->get_clock()); tf_listener_ = std::make_unique(*tf_buffer_); - tf_broadcaster_ = std::make_unique(this); /* Initialize image transport @@ -119,6 +123,7 @@ bool ArTagBasedLocalizer::setup() 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)); @@ -160,71 +165,85 @@ void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) { + // check subscribers if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers"); return; } + // check cam_info if (!cam_info_received_) { RCLCPP_DEBUG(this->get_logger(), "No cam_info has been received."); return; } - const builtin_interfaces::msg::Time curr_stamp = msg->header.stamp; - cv_bridge::CvImagePtr cv_ptr; - try { - cv_ptr = cv_bridge::toCvCopy(*msg, sensor_msgs::image_encodings::RGB8); - } catch (cv_bridge::Exception & e) { - RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); - return; + // get self pose + const builtin_interfaces::msg::Time sensor_stamp = msg->header.stamp; + Pose self_pose; + { + // get self-position on map + std::unique_lock self_pose_array_lock(self_pose_array_mtx_); + if (self_pose_msg_ptr_array_.size() <= 1) { + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No Pose!"); + return; + } + PoseArrayInterpolator interpolator( + this, sensor_stamp, self_pose_msg_ptr_array_, ekf_time_tolerance_, ekf_position_tolerance_); + if (!interpolator.is_success()) { + return; + } + pop_old_pose(self_pose_msg_ptr_array_, sensor_stamp); + self_pose = interpolator.get_current_pose().pose.pose; } - cv::Mat in_image = cv_ptr->image; - - // detection results will go into "markers" - std::vector markers; - - // ok, let's detect - detector_.detect(in_image, markers, cam_param_, marker_size_, false); - - // for each marker, draw info and its boundaries in the image - for (const aruco::Marker & marker : markers) { - const tf2::Transform tf_cam_to_marker = aruco_marker_to_tf2(marker); + // detect + const std::vector landmarks = detect_landmarks(msg); + if (landmarks.empty()) { + return; + } - TransformStamped tf_cam_to_marker_stamped; - tf2::toMsg(tf_cam_to_marker, tf_cam_to_marker_stamped.transform); - tf_cam_to_marker_stamped.header.stamp = curr_stamp; - tf_cam_to_marker_stamped.header.frame_id = msg->header.frame_id; - tf_cam_to_marker_stamped.child_frame_id = "detected_marker_" + std::to_string(marker.id); - tf_broadcaster_->sendTransform(tf_cam_to_marker_stamped); + // for debug + if (pose_array_pub_->get_subscription_count() > 0) { + 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) { + const Pose detected_marker_on_map = + 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); + } - PoseStamped pose_cam_to_marker; - tf2::toMsg(tf_cam_to_marker, pose_cam_to_marker.pose); - pose_cam_to_marker.header.stamp = curr_stamp; - pose_cam_to_marker.header.frame_id = msg->header.frame_id; - publish_pose_as_base_link(pose_cam_to_marker, std::to_string(marker.id)); + // calc new_self_pose + const Pose new_self_pose = calculate_new_self_pose(landmarks, self_pose); + const Pose diff_pose = tier4_autoware_utils::inverseTransformPose(new_self_pose, self_pose); + const double distance = + std::hypot(diff_pose.position.x, diff_pose.position.y, diff_pose.position.z); - // drawing the detected markers - marker.draw(in_image, cv::Scalar(0, 0, 255), 2); + // check distance + if (distance > ekf_position_tolerance_) { + RCLCPP_INFO_STREAM(this->get_logger(), "distance: " << distance); + return; } - // draw a 3d cube in each marker if there is 3d info - if (cam_param_.isValid()) { - for (aruco::Marker & marker : markers) { - aruco::CvDrawingUtils::draw3dAxis(in_image, marker, cam_param_); - } - } + // publish + PoseWithCovarianceStamped pose_with_covariance_stamped; + pose_with_covariance_stamped.header.stamp = sensor_stamp; + pose_with_covariance_stamped.header.frame_id = "map"; + pose_with_covariance_stamped.pose.pose = new_self_pose; - if (image_pub_.getNumSubscribers() > 0) { - // show input with augmented information - cv_bridge::CvImage out_msg; - out_msg.header.stamp = curr_stamp; - out_msg.encoding = sensor_msgs::image_encodings::RGB8; - out_msg.image = in_image; - image_pub_.publish(out_msg.toImageMsg()); + // ~5[m]: base_covariance + // 5~[m]: scaling base_covariance by std::pow(distance / 5, 3) + const double coeff = std::max(1.0, std::pow(distance / 5, 3)); + for (int i = 0; i < 36; i++) { + pose_with_covariance_stamped.pose.covariance[i] = coeff * base_covariance_[i]; } - const int detected_tags = static_cast(markers.size()); + pose_pub_->publish(pose_with_covariance_stamped); + + // publish diagnostics + const int detected_tags = static_cast(landmarks.size()); diagnostic_msgs::msg::DiagnosticStatus diag_status; @@ -252,150 +271,178 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) } // wait for one camera info, then shut down that subscriber -void ArTagBasedLocalizer::cam_info_callback(const CameraInfo & msg) +void ArTagBasedLocalizer::cam_info_callback(const CameraInfo::ConstSharedPtr & msg) { if (cam_info_received_) { 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]; + 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; } - const cv::Size size(static_cast(msg.width), static_cast(msg.height)); + const cv::Size size(static_cast(msg->width), static_cast(msg->height)); cam_param_ = aruco::CameraParameters(camera_matrix, distortion_coeff, size); cam_info_received_ = true; } -void ArTagBasedLocalizer::ekf_pose_callback(const PoseWithCovarianceStamped & msg) +void ArTagBasedLocalizer::ekf_pose_callback(const PoseWithCovarianceStamped::ConstSharedPtr & msg) { - latest_ekf_pose_ = msg; + // lock mutex for initial pose + std::lock_guard self_pose_array_lock(self_pose_array_mtx_); + // if rosbag restart, clear buffer + if (!self_pose_msg_ptr_array_.empty()) { + const builtin_interfaces::msg::Time & t_front = self_pose_msg_ptr_array_.front()->header.stamp; + const builtin_interfaces::msg::Time & t_msg = msg->header.stamp; + if (t_front.sec > t_msg.sec || (t_front.sec == t_msg.sec && t_front.nanosec > t_msg.nanosec)) { + self_pose_msg_ptr_array_.clear(); + } + } + + if (msg->header.frame_id == "map") { + self_pose_msg_ptr_array_.push_back(msg); + } else { + TransformStamped transform_self_pose_frame_to_map; + try { + transform_self_pose_frame_to_map = tf_buffer_->lookupTransform( + "map", msg->header.frame_id, msg->header.stamp, rclcpp::Duration::from_seconds(0.1)); + + // transform self_pose_frame to map_frame + auto self_pose_on_map_ptr = std::make_shared(); + self_pose_on_map_ptr->pose.pose = + tier4_autoware_utils::transformPose(msg->pose.pose, transform_self_pose_frame_to_map); + // self_pose_on_map_ptr->pose.covariance; // TODO(YamatoAndo) + self_pose_on_map_ptr->header.stamp = msg->header.stamp; + self_pose_msg_ptr_array_.push_back(self_pose_on_map_ptr); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN( + get_logger(), "cannot get map to %s transform. %s", msg->header.frame_id.c_str(), + ex.what()); + } + } } -void ArTagBasedLocalizer::publish_pose_as_base_link( - const PoseStamped & sensor_to_tag, const std::string & tag_id) +std::vector ArTagBasedLocalizer::detect_landmarks( + const Image::ConstSharedPtr & msg) { - // Check tag_id - if (std::find(target_tag_ids_.begin(), target_tag_ids_.end(), tag_id) == target_tag_ids_.end()) { - RCLCPP_INFO_STREAM(this->get_logger(), "tag_id(" << tag_id << ") is not in target_tag_ids"); - return; - } - if (landmark_map_.count(tag_id) == 0) { - RCLCPP_INFO_STREAM(this->get_logger(), "tag_id(" << tag_id << ") is not in landmark_map_"); - return; - } + const builtin_interfaces::msg::Time sensor_stamp = msg->header.stamp; - // Range filter - const double distance_squared = sensor_to_tag.pose.position.x * sensor_to_tag.pose.position.x + - sensor_to_tag.pose.position.y * sensor_to_tag.pose.position.y + - sensor_to_tag.pose.position.z * sensor_to_tag.pose.position.z; - if (distance_threshold_squared_ < distance_squared) { - return; + // get image + cv::Mat in_image; + try { + cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(*msg, sensor_msgs::image_encodings::RGB8); + 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{}; } - // Transform to base_link - PoseStamped base_link_to_tag; + // get transform from base_link to camera + TransformStamped transform_sensor_to_base_link; try { - const TransformStamped transform = - tf_buffer_->lookupTransform("base_link", sensor_to_tag.header.frame_id, tf2::TimePointZero); - tf2::doTransform(sensor_to_tag, base_link_to_tag, transform); - base_link_to_tag.header.frame_id = "base_link"; + transform_sensor_to_base_link = + 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; + return std::vector{}; } - // (1) map_to_tag - const Pose & map_to_tag = landmark_map_.at(tag_id); - const Eigen::Affine3d map_to_tag_affine = pose_to_affine3d(map_to_tag); - - // (2) tag_to_base_link - const Eigen::Affine3d base_link_to_tag_affine = pose_to_affine3d(base_link_to_tag.pose); - const Eigen::Affine3d tag_to_base_link_affine = base_link_to_tag_affine.inverse(); - - // calculate map_to_base_link - const Eigen::Affine3d map_to_base_link_affine = map_to_tag_affine * tag_to_base_link_affine; - const Pose map_to_base_link = tf2::toMsg(map_to_base_link_affine); - - // If latest_ekf_pose_ is older than seconds compared to current frame, it - // will not be published. - const rclcpp::Duration diff_time = - rclcpp::Time(sensor_to_tag.header.stamp) - rclcpp::Time(latest_ekf_pose_.header.stamp); - if (diff_time.seconds() > ekf_time_tolerance_) { - RCLCPP_INFO( - this->get_logger(), - "latest_ekf_pose_ is older than %f seconds compared to current frame. " - "latest_ekf_pose_.header.stamp: %d.%d, sensor_to_tag.header.stamp: %d.%d", - ekf_time_tolerance_, latest_ekf_pose_.header.stamp.sec, latest_ekf_pose_.header.stamp.nanosec, - sensor_to_tag.header.stamp.sec, sensor_to_tag.header.stamp.nanosec); - return; - } + // detect + std::vector markers; + detector_.detect(in_image, markers, cam_param_, marker_size_, false); - // If curr_pose differs from latest_ekf_pose_ by more than , it will not - // be published. - const Pose curr_pose = map_to_base_link; - const Pose latest_ekf_pose = latest_ekf_pose_.pose.pose; - const double diff_position = norm(curr_pose.position, latest_ekf_pose.position); - if (diff_position > ekf_position_tolerance_) { - RCLCPP_INFO( - this->get_logger(), - "curr_pose differs from latest_ekf_pose_ by more than %f m. " - "curr_pose: (%f, %f, %f), latest_ekf_pose: (%f, %f, %f)", - ekf_position_tolerance_, curr_pose.position.x, curr_pose.position.y, curr_pose.position.z, - latest_ekf_pose.position.x, latest_ekf_pose.position.y, latest_ekf_pose.position.z); - return; - } + // parse + std::vector landmarks; + + for (aruco::Marker & marker : markers) { + // convert marker pose to tf + const cv::Quat q = cv::Quat::createFromRvec(marker.Rvec); + Pose pose; + pose.position.x = marker.Tvec.at(0, 0); + pose.position.y = marker.Tvec.at(1, 0); + pose.position.z = marker.Tvec.at(2, 0); + pose.orientation.x = q.x; + pose.orientation.y = q.y; + pose.orientation.z = q.z; + pose.orientation.w = q.w; + 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}); + } - // Construct output message - PoseWithCovarianceStamped pose_with_covariance_stamped; - pose_with_covariance_stamped.header.stamp = sensor_to_tag.header.stamp; - pose_with_covariance_stamped.header.frame_id = "map"; - pose_with_covariance_stamped.pose.pose = curr_pose; + // for debug, drawing the detected markers + marker.draw(in_image, cv::Scalar(0, 0, 255), 2); + aruco::CvDrawingUtils::draw3dAxis(in_image, marker, cam_param_); + } - // ~5[m]: base_covariance - // 5~[m]: scaling base_covariance by std::pow(distance/5, 3) - const double distance = std::sqrt(distance_squared); - const double scale = distance / 5; - const double coeff = std::max(1.0, std::pow(scale, 3)); - for (int i = 0; i < 36; i++) { - pose_with_covariance_stamped.pose.covariance[i] = coeff * base_covariance_[i]; + // for debug + if (image_pub_.getNumSubscribers() > 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()); } - pose_pub_->publish(pose_with_covariance_stamped); + return landmarks; } -tf2::Transform ArTagBasedLocalizer::aruco_marker_to_tf2(const aruco::Marker & marker) +geometry_msgs::msg::Pose ArTagBasedLocalizer::calculate_new_self_pose( + const std::vector & detected_landmarks, const Pose & self_pose) { - cv::Mat rot(3, 3, CV_64FC1); - cv::Mat r_vec64; - marker.Rvec.convertTo(r_vec64, CV_64FC1); - cv::Rodrigues(r_vec64, rot); - cv::Mat tran64; - marker.Tvec.convertTo(tran64, CV_64FC1); + Pose min_new_self_pose; + double min_distance = std::numeric_limits::max(); + + for (const landmark_manager::Landmark & landmark : detected_landmarks) { + // Firstly, landmark pose is base_link + const Pose & detected_marker_on_base_link = landmark.pose; - tf2::Matrix3x3 tf_rot( - rot.at(0, 0), rot.at(0, 1), rot.at(0, 2), rot.at(1, 0), - rot.at(1, 1), rot.at(1, 2), rot.at(2, 0), rot.at(2, 1), - rot.at(2, 2)); + // convert base_link to map + const Pose detected_marker_on_map = + tier4_autoware_utils::transformPose(detected_marker_on_base_link, self_pose); - tf2::Vector3 tf_orig(tran64.at(0, 0), tran64.at(1, 0), tran64.at(2, 0)); + // match to map + if (landmark_map_.count(landmark.id) == 0) { + continue; + } + const Pose mapped_marker_on_map = landmark_map_[landmark.id]; + + // check distance + const double curr_distance = tier4_autoware_utils::calcDistance3d( + mapped_marker_on_map.position, detected_marker_on_map.position); + if (curr_distance > min_distance) { + continue; + } + + const Eigen::Affine3d marker_pose = pose_to_affine3d(mapped_marker_on_map); + const Eigen::Affine3d marker_to_base_link = + pose_to_affine3d(detected_marker_on_base_link).inverse(); + const Eigen::Affine3d new_self_pose_eigen = marker_pose * marker_to_base_link; + + const Pose new_self_pose = matrix4f_to_pose(new_self_pose_eigen.matrix().cast()); + + // update + min_distance = curr_distance; + min_new_self_pose = new_self_pose; + } - return tf2::Transform(tf_rot, tf_orig); + return min_new_self_pose; } 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 889e76eb78ad2..2866f4a8f3ee7 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 @@ -51,6 +51,7 @@ #include #include +#include #include #include @@ -59,6 +60,7 @@ #include #include +#include #include #include #include @@ -72,6 +74,7 @@ class ArTagBasedLocalizer : public rclcpp::Node using Pose = geometry_msgs::msg::Pose; using PoseStamped = geometry_msgs::msg::PoseStamped; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; + using PoseArray = geometry_msgs::msg::PoseArray; using TransformStamped = geometry_msgs::msg::TransformStamped; using MarkerArray = visualization_msgs::msg::MarkerArray; using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; @@ -83,23 +86,23 @@ class ArTagBasedLocalizer : public rclcpp::Node private: void map_bin_callback(const HADMapBin::ConstSharedPtr & msg); void image_callback(const Image::ConstSharedPtr & msg); - void cam_info_callback(const CameraInfo & msg); - void ekf_pose_callback(const PoseWithCovarianceStamped & msg); - void publish_pose_as_base_link(const PoseStamped & sensor_to_tag, const std::string & tag_id); - static tf2::Transform aruco_marker_to_tf2(const aruco::Marker & marker); + void cam_info_callback(const CameraInfo::ConstSharedPtr & msg); + void ekf_pose_callback(const PoseWithCovarianceStamped::ConstSharedPtr & msg); + std::vector detect_landmarks(const Image::ConstSharedPtr & msg); + Pose calculate_new_self_pose( + const std::vector & detected_landmarks, const Pose & self_pose); // Parameters float marker_size_{}; std::vector target_tag_ids_; std::vector base_covariance_; - double distance_threshold_squared_{}; + double distance_threshold_{}; double ekf_time_tolerance_{}; double ekf_position_tolerance_{}; // tf std::unique_ptr tf_buffer_; std::unique_ptr tf_listener_; - std::unique_ptr tf_broadcaster_; // image transport std::unique_ptr it_; @@ -112,6 +115,7 @@ class ArTagBasedLocalizer : public rclcpp::Node // 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 diag_pub_; @@ -120,7 +124,8 @@ class ArTagBasedLocalizer : public rclcpp::Node aruco::MarkerDetector detector_; aruco::CameraParameters cam_param_; bool cam_info_received_; - PoseWithCovarianceStamped latest_ekf_pose_{}; + std::mutex self_pose_array_mtx_; + std::deque self_pose_msg_ptr_array_; std::map landmark_map_; }; From da663207abf66dc5a2cb59592afd8c56a201e3bb Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 28 Nov 2023 11:12:27 +0900 Subject: [PATCH 040/128] feat(behavior_path_planner): add objects of interest marker interface (#5695) Signed-off-by: Fumiya Watanabe --- .../behavior_path_planner/planner_manager.hpp | 3 ++ .../avoidance/avoidance_module.hpp | 4 +- .../scene_module/avoidance/manager.hpp | 4 +- .../dynamic_avoidance_module.hpp | 4 +- .../dynamic_avoidance/manager.hpp | 3 +- .../goal_planner/goal_planner_module.hpp | 4 +- .../scene_module/goal_planner/manager.hpp | 4 +- .../scene_module/lane_change/interface.hpp | 19 +++------ .../scene_module/scene_module_interface.hpp | 32 +++++++++++++- .../scene_module_manager_interface.hpp | 5 +++ .../scene_module/side_shift/manager.hpp | 4 +- .../side_shift/side_shift_module.hpp | 4 +- .../scene_module/start_planner/manager.hpp | 4 +- .../start_planner/start_planner_module.hpp | 4 +- .../avoidance/avoidance_module.cpp | 6 ++- .../dynamic_avoidance_module.cpp | 6 ++- .../goal_planner/goal_planner_module.cpp | 6 ++- .../scene_module/lane_change/interface.cpp | 42 +++++++++---------- .../src/scene_module/lane_change/manager.cpp | 5 ++- .../side_shift/side_shift_module.cpp | 7 +++- .../start_planner/start_planner_module.cpp | 6 ++- 21 files changed, 120 insertions(+), 56 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 1d1ad56342f4d..53e2427228b72 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 @@ -275,6 +275,8 @@ class PlannerManager module_ptr->publishRTCStatus(); + module_ptr->publishObjectsOfInterestMarker(); + processing_time_.at(module_ptr->name()) += stop_watch_.toc(module_ptr->name(), true); return result; @@ -298,6 +300,7 @@ class PlannerManager { module_ptr->onExit(); module_ptr->publishRTCStatus(); + module_ptr->publishObjectsOfInterestMarker(); module_ptr.reset(); } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index cbf40e59535be..76264b0532f07 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -49,7 +49,9 @@ class AvoidanceModule : public SceneModuleInterface public: AvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map> & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp index 9d89138f7cdfe..b2defad526e8f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp @@ -37,7 +37,9 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface std::unique_ptr createNewSceneModuleInstance() override { - return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; 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 a12cc4d405d41..37bd28576928c 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 @@ -268,7 +268,9 @@ class DynamicAvoidanceModule : public SceneModuleInterface DynamicAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map> & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); void updateModuleParams(const std::any & parameters) override { 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 10a0d055a5a77..1a9088f2226ff 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 @@ -37,7 +37,8 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface std::unique_ptr createNewSceneModuleInstance() override { return std::make_unique( - name_, *node_, parameters_, rtc_interface_ptr_map_); + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp index 97a5fdd966b8f..25f0a815dee8c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp @@ -261,7 +261,9 @@ class GoalPlannerModule : public SceneModuleInterface GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map> & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp index 4a7eecfc68caf..11ce4e0c3e94c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp @@ -35,7 +35,9 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface std::unique_ptr createNewSceneModuleInstance() override { - return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; 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 f2427f185fbaa..dad46494bc350 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 @@ -25,7 +25,6 @@ #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/path_shifter/path_shifter.hpp" -#include "objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp" #include @@ -49,8 +48,6 @@ namespace behavior_path_planner using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; -using objects_of_interest_marker_interface::ColorName; -using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using tier4_planning_msgs::msg::LaneChangeDebugMsg; using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; @@ -59,7 +56,9 @@ class LaneChangeInterface : public SceneModuleInterface public: LaneChangeInterface( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map > & rtc_interface_ptr_map, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map, std::unique_ptr && module_type); LaneChangeInterface(const LaneChangeInterface &) = delete; @@ -136,13 +135,6 @@ class LaneChangeInterface : public SceneModuleInterface void setObjectDebugVisualization() const; - void setObjectsOfInterestData(const bool is_approved); - - void publishObjectsOfInterestData() - { - objects_of_interest_marker_interface_.publishMarkerArray(); - } - void updateSteeringFactorPtr(const BehaviorModuleOutput & output); void updateSteeringFactorPtr( @@ -152,7 +144,6 @@ class LaneChangeInterface : public SceneModuleInterface mutable LaneChangeDebugMsgArray lane_change_debug_msg_array_; std::unique_ptr prev_approved_path_; - ObjectsOfInterestMarkerInterface objects_of_interest_marker_interface_; void clearAbortApproval() { is_abort_path_approved_ = false; } @@ -168,7 +159,9 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface 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); + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index 534594d93445c..df71f0577964a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -26,6 +26,7 @@ #include #include #include +#include #include #include #include @@ -56,6 +57,8 @@ namespace behavior_path_planner { using autoware_adapi_v1_msgs::msg::SteeringFactor; using autoware_auto_planning_msgs::msg::PathWithLaneId; +using objects_of_interest_marker_interface::ColorName; +using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using rtc_interface::RTCInterface; using steering_factor_interface::SteeringFactorInterface; using tier4_autoware_utils::calcOffsetPose; @@ -81,11 +84,15 @@ class SceneModuleInterface public: SceneModuleInterface( const std::string & name, rclcpp::Node & node, - std::unordered_map> rtc_interface_ptr_map) + std::unordered_map> rtc_interface_ptr_map, + std::unordered_map> + objects_of_interest_marker_interface_ptr_map) : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, rtc_interface_ptr_map_(std::move(rtc_interface_ptr_map)), + objects_of_interest_marker_interface_ptr_map_( + std::move(objects_of_interest_marker_interface_ptr_map)), steering_factor_interface_ptr_( std::make_unique(&node, utils::convertToSnakeCase(name))) { @@ -191,6 +198,15 @@ class SceneModuleInterface } } + void publishObjectsOfInterestMarker() + { + for (const auto & [module_name, ptr] : objects_of_interest_marker_interface_ptr_map_) { + if (ptr) { + ptr->publishMarkerArray(); + } + } + } + void publishSteeringFactor() { if (!steering_factor_interface_ptr_) { @@ -415,6 +431,17 @@ class SceneModuleInterface } } + void setObjectsOfInterestData( + const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape, const ColorName & color_name) + { + for (const auto & [module_name, ptr] : objects_of_interest_marker_interface_ptr_map_) { + if (ptr) { + ptr->insertObjectData(obj_pose, obj_shape, color_name); + } + } + } + /** * @brief Return SUCCESS if plan is not needed or plan is successfully finished, * FAILURE if plan has failed, RUNNING if plan is on going. @@ -569,6 +596,9 @@ class SceneModuleInterface std::unordered_map> rtc_interface_ptr_map_; + std::unordered_map> + objects_of_interest_marker_interface_ptr_map_; + std::unique_ptr steering_factor_interface_ptr_; mutable boost::optional stop_pose_{boost::none}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp index 38101416a80b3..849fa2666894d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_manager_interface.hpp @@ -65,6 +65,8 @@ class SceneModuleManagerInterface rtc_type == "" ? snake_case_name : snake_case_name + "_" + rtc_type; rtc_interface_ptr_map_.emplace( rtc_type, std::make_shared(node, rtc_interface_name, enable_rtc_)); + objects_of_interest_marker_interface_ptr_map_.emplace( + rtc_type, std::make_shared(node, rtc_interface_name)); } pub_info_marker_ = node->create_publisher("~/info/" + name, 20); @@ -305,6 +307,9 @@ class SceneModuleManagerInterface std::unordered_map> rtc_interface_ptr_map_; + std::unordered_map> + objects_of_interest_marker_interface_ptr_map_; + bool enable_simultaneous_execution_as_approved_module_{false}; bool enable_simultaneous_execution_as_candidate_module_{false}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp index b74be38c0faf9..0d58fc1abe240 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp @@ -36,7 +36,9 @@ class SideShiftModuleManager : public SceneModuleManagerInterface std::unique_ptr createNewSceneModuleInstance() override { - return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp index fce31b6db7369..8e2419a334352 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp @@ -43,7 +43,9 @@ class SideShiftModule : public SceneModuleInterface SideShiftModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map> & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp index 3ee376f4111f0..6cc3b6d7c1c46 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp @@ -35,7 +35,9 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface std::unique_ptr createNewSceneModuleInstance() override { - return std::make_unique(name_, *node_, parameters_, rtc_interface_ptr_map_); + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; 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 54e13de85e8da..bc5084cacbe2b 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 @@ -79,7 +79,9 @@ class StartPlannerModule : public SceneModuleInterface StartPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map> & rtc_interface_ptr_map); + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index a3cb4dd6dc8e2..ee2f1160d76c2 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -151,8 +151,10 @@ lanelet::BasicLineString3d toLineString3d(const std::vector & bound) AvoidanceModule::AvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map> & rtc_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, helper_{parameters} { 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 3aa95dba6c4ad..7bc61a4d747c7 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 @@ -248,8 +248,10 @@ double calcDistanceToSegment( DynamicAvoidanceModule::DynamicAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, - const std::unordered_map> & rtc_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{std::move(parameters)}, target_objects_manager_{TargetObjectsManager( parameters_->successive_num_to_entry_dynamic_avoidance_condition, diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index b2692200557ed..8291624f943da 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -54,8 +54,10 @@ namespace behavior_path_planner GoalPlannerModule::GoalPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map> & rtc_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_} 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 57acfa5002296..ca1b2384051f6 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 @@ -36,12 +36,13 @@ using utils::lane_change::assignToCandidate; LaneChangeInterface::LaneChangeInterface( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map, std::unique_ptr && module_type) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, - prev_approved_path_{std::make_unique()}, - objects_of_interest_marker_interface_{&node, name} + prev_approved_path_{std::make_unique()} { steering_factor_interface_ptr_ = std::make_unique(&node, name); } @@ -199,8 +200,10 @@ BehaviorModuleOutput LaneChangeInterface::plan() stop_pose_ = module_type_->getStopPose(); - setObjectsOfInterestData(true); - publishObjectsOfInterestData(); + for (const auto & [uuid, data] : module_type_->getAfterApprovalDebugData()) { + const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; + setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); + } updateSteeringFactorPtr(output); clearWaitingApproval(); @@ -224,8 +227,11 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); module_type_->updateLaneChangeStatus(); setObjectDebugVisualization(); - setObjectsOfInterestData(false); - publishObjectsOfInterestData(); + + for (const auto & [uuid, data] : module_type_->getDebugData()) { + const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; + setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); + } // 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); @@ -314,18 +320,6 @@ void LaneChangeInterface::setObjectDebugVisualization() const } } -void LaneChangeInterface::setObjectsOfInterestData(const bool is_approved) -{ - const auto debug_data = - is_approved ? module_type_->getAfterApprovalDebugData() : module_type_->getDebugData(); - for (const auto & [uuid, data] : debug_data) { - const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; - objects_of_interest_marker_interface_.insertObjectData( - data.current_obj_pose, data.obj_shape, color); - } - return; -} - std::shared_ptr LaneChangeInterface::get_debug_msg_array() const { const auto debug_data = module_type_->getDebugData(); @@ -509,9 +503,15 @@ 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) + 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, + name, + node, + parameters, + rtc_interface_ptr_map, + objects_of_interest_marker_interface_ptr_map, std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } 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 e772c21331ae8..3a0b7527e4184 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 @@ -221,10 +221,12 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod 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_)); } @@ -371,7 +373,8 @@ std::unique_ptr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_unique( - name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_); + name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); } } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 0e86508ca6afc..64ae5d3f26c2c 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -38,8 +38,11 @@ using tier4_autoware_utils::getPoint; SideShiftModule::SideShiftModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map > & rtc_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, parameters_{parameters} + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + parameters_{parameters} { } 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 06b195ea29b50..f847a8be7df2b 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 @@ -44,8 +44,10 @@ namespace behavior_path_planner StartPlannerModule::StartPlannerModule( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, - const std::unordered_map> & rtc_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map}, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()} { From ebf94dc7d53b4a91e61ff349d65e1d05319dc443 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 28 Nov 2023 12:41:47 +0900 Subject: [PATCH 041/128] refactor(behavior_path_planner): refactor object filtering functions (#5655) * refactor(behavior_path_planner): refactor object filtering functions Signed-off-by: Zulfaqar Azmi * fix build error Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../path_safety_checker/objects_filtering.hpp | 52 ++++++++ .../path_safety_checker/objects_filtering.cpp | 113 ++++++++---------- 2 files changed, 103 insertions(+), 62 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp index 67588ed0a67b6..f9ad6a7592d5d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp @@ -30,6 +30,22 @@ #include #include +namespace behavior_path_planner::utils::path_safety_checker::filter +{ + +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_planning_msgs::msg::PathPointWithLaneId; + +bool velocity_filter( + const PredictedObject & object, double velocity_threshold, double max_velocity); + +bool position_filter( + PredictedObject & object, const std::vector & path_points, + const geometry_msgs::msg::Point & current_pose, const double forward_distance, + const double backward_distance); + +} // namespace behavior_path_planner::utils::path_safety_checker::filter + namespace behavior_path_planner::utils::path_safety_checker { @@ -233,6 +249,42 @@ TargetObjectsOnLane createTargetObjectsOnLane( bool isTargetObjectType( const PredictedObject & object, const ObjectTypesToCheck & target_object_types); +/** + * @brief Filters objects in the 'selected' container based on the provided filter function. + * + * This function partitions the 'selected' container based on the 'filter' function + * and moves objects that satisfy the filter condition to the 'removed' container. + * + * @tparam Func The type of the filter function. + * @param selected [in,out] The container of objects to be filtered. + * @param removed [out] The container where objects not satisfying the filter condition are moved. + * @param filter The filter function that determines whether an object should be removed. + */ +template +void filterObjects(PredictedObjects & selected, PredictedObjects & removed, Func filter) +{ + auto partitioned = std::partition(selected.objects.begin(), selected.objects.end(), filter); + removed.objects.insert(removed.objects.end(), partitioned, selected.objects.end()); + selected.objects.erase(partitioned, selected.objects.end()); +} + +/** + * @brief Filters objects in the 'objects' container based on the provided filter function. + * + * This function is an overload that simplifies filtering when you don't need to specify a separate + * 'removed' container. It internally creates a 'removed_objects' container and calls the main + * 'filterObjects' function. + * + * @tparam Func The type of the filter function. + * @param objects [in,out] The container of objects to be filtered. + * @param filter The filter function that determines whether an object should be removed. + */ +template +void filterObjects(PredictedObjects & objects, Func filter) +{ + [[maybe_unused]] PredictedObjects removed_objects{}; + filterObjects(objects, removed_objects, filter); +} } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER__UTILS__PATH_SAFETY_CHECKER__OBJECTS_FILTERING_HPP_ diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp index f6644a4f91e8f..6c6d78966445e 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/objects_filtering.cpp @@ -22,9 +22,32 @@ #include -namespace behavior_path_planner::utils::path_safety_checker +#include + +namespace behavior_path_planner::utils::path_safety_checker::filter +{ +bool velocity_filter(const PredictedObject & object, double velocity_threshold, double max_velocity) { + const auto v_norm = std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y); + return (velocity_threshold < v_norm && v_norm < max_velocity); +} +bool position_filter( + const PredictedObject & object, const std::vector & path_points, + const geometry_msgs::msg::Point & current_pose, const double forward_distance, + const double backward_distance) +{ + const auto dist_ego_to_obj = motion_utils::calcSignedArcLength( + path_points, current_pose, object.kinematics.initial_pose_with_covariance.pose.position); + + return (backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance); +} +} // namespace behavior_path_planner::utils::path_safety_checker::filter + +namespace behavior_path_planner::utils::path_safety_checker +{ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet) { const auto & object_pos = object.kinematics.initial_pose_with_covariance.pose.position; @@ -55,9 +78,8 @@ PredictedObjects filterObjects( const double object_check_backward_distance = params->object_check_backward_distance; const ObjectTypesToCheck & target_object_types = params->object_types_to_check; - PredictedObjects filtered_objects; - - filtered_objects = filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, false); + PredictedObjects filtered_objects = + filterObjectsByVelocity(*objects, ignore_object_velocity_threshold, false); filterObjectsByClass(filtered_objects, target_object_types); @@ -77,24 +99,19 @@ PredictedObjects filterObjectsByVelocity( { if (remove_above_threshold) { return filterObjectsByVelocity(objects, -velocity_threshold, velocity_threshold); - } else { - return filterObjectsByVelocity(objects, velocity_threshold, std::numeric_limits::max()); } + return filterObjectsByVelocity(objects, velocity_threshold, std::numeric_limits::max()); } PredictedObjects filterObjectsByVelocity( const PredictedObjects & objects, double velocity_threshold, double max_velocity) { - PredictedObjects filtered; - filtered.header = objects.header; - for (const auto & obj : objects.objects) { - const auto v_norm = std::hypot( - obj.kinematics.initial_twist_with_covariance.twist.linear.x, - obj.kinematics.initial_twist_with_covariance.twist.linear.y); - if (velocity_threshold < v_norm && v_norm < max_velocity) { - filtered.objects.push_back(obj); - } - } + const auto filter = [&](const auto & object) { + return filter::velocity_filter(object, velocity_threshold, max_velocity); + }; + + auto filtered = objects; + filterObjects(filtered, filter); return filtered; } @@ -103,43 +120,22 @@ void filterObjectsByPosition( const geometry_msgs::msg::Point & current_pose, const double forward_distance, const double backward_distance) { - // Create a new container to hold the filtered objects - PredictedObjects filtered; - filtered.header = objects.header; - - // Reserve space in the vector to avoid reallocations - filtered.objects.reserve(objects.objects.size()); - - for (const auto & obj : objects.objects) { - const double dist_ego_to_obj = motion_utils::calcSignedArcLength( - path_points, current_pose, obj.kinematics.initial_pose_with_covariance.pose.position); - - if (-backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance) { - filtered.objects.push_back(obj); - } - } + const auto filter = [&](const auto & object) { + return filter::position_filter( + object, path_points, current_pose, forward_distance, -backward_distance); + }; - // Replace the original objects with the filtered list - objects.objects = std::move(filtered.objects); - return; + filterObjects(objects, filter); } void filterObjectsByClass( PredictedObjects & objects, const ObjectTypesToCheck & target_object_types) { - PredictedObjects filtered_objects; - - for (auto & object : objects.objects) { - const auto is_object_type = isTargetObjectType(object, target_object_types); - - // If the object type matches any of the target types, add it to the filtered list - if (is_object_type) { - filtered_objects.objects.push_back(object); - } - } + const auto filter = [&](const auto & object) { + return isTargetObjectType(object, target_object_types); + }; - // Replace the original objects with the filtered list - objects = std::move(filtered_objects); + filterObjects(objects, filter); } std::pair, std::vector> separateObjectIndicesByLanelets( @@ -154,16 +150,11 @@ std::pair, std::vector> separateObjectIndicesByLanel std::vector other_indices; for (size_t i = 0; i < objects.objects.size(); i++) { - bool is_filtered_object = false; - for (const auto & llt : target_lanelets) { - if (condition(objects.objects.at(i), llt)) { - target_indices.push_back(i); - is_filtered_object = true; - break; - } - } - - if (!is_filtered_object) { + const auto filter = [&](const auto & llt) { return condition(objects.objects.at(i), llt); }; + const auto found = std::find_if(target_lanelets.begin(), target_lanelets.end(), filter); + if (found != target_lanelets.end()) { + target_indices.push_back(i); + } else { other_indices.push_back(i); } } @@ -266,13 +257,11 @@ bool isCentroidWithinLanelets( const auto & object_pos = object.kinematics.initial_pose_with_covariance.pose.position; lanelet::BasicPoint2d object_centroid(object_pos.x, object_pos.y); - for (const auto & llt : target_lanelets) { - if (boost::geometry::within(object_centroid, llt.polygon2d().basicPolygon())) { - return true; - } - } + const auto is_within = [&](const auto & llt) { + return boost::geometry::within(object_centroid, llt.polygon2d().basicPolygon()); + }; - return false; + return std::any_of(target_lanelets.begin(), target_lanelets.end(), is_within); } ExtendedPredictedObject transform( From cfce96d752a6690c310a36b71532d74a12f5e312 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 28 Nov 2023 13:49:21 +0900 Subject: [PATCH 042/128] refactor(avoidance): update avoidance parameters (#5684) update avoidance parameters Signed-off-by: Kyoichi Sugahara --- .../config/avoidance/avoidance.param.yaml | 46 +++++++++---------- 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index d4394d1710e69..d3032ffdd3b99 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -11,14 +11,14 @@ enable_bound_clipping: false enable_yield_maneuver: true enable_yield_maneuver_during_shifting: false - enable_cancel_maneuver: false + enable_cancel_maneuver: true disable_path_update: false # drivable area setting use_adjacent_lane: true use_opposite_lane: true - use_intersection_areas: false - use_hatched_road_markings: false + use_intersection_areas: true + use_hatched_road_markings: true # for debug publish_debug_marker: false @@ -40,7 +40,7 @@ truck: is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 @@ -51,7 +51,7 @@ bus: is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 @@ -62,7 +62,7 @@ trailer: is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 @@ -71,9 +71,9 @@ safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true unknown: - is_target: false + is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 @@ -82,9 +82,9 @@ safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bicycle: - is_target: false + is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 @@ -93,9 +93,9 @@ safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true motorcycle: - is_target: false + is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 @@ -104,9 +104,9 @@ safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true pedestrian: - is_target: false + is_target: true execute_num: 1 - moving_speed_threshold: 1.0 + moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 @@ -130,7 +130,7 @@ # detection area generation parameters detection_area: - static: true # [-] + static: false # [-] min_forward_distance: 50.0 # [m] max_forward_distance: 150.0 # [m] backward_distance: 10.0 # [m] @@ -148,7 +148,7 @@ # params for filtering objects that are in intersection intersection: - yaw_deviation: 0.175 # [rad] (default: 10.0deg) + yaw_deviation: 0.349 # [rad] (default 20.0deg) # For safety check safety_check: @@ -162,13 +162,13 @@ # collision check parameters check_all_predicted_path: false # [-] safety_check_backward_distance: 100.0 # [m] - hysteresis_factor_expand_rate: 2.0 # [-] + hysteresis_factor_expand_rate: 1.5 # [-] hysteresis_factor_safe_count: 10 # [-] # predicted path parameters min_velocity: 1.38 # [m/s] max_velocity: 50.0 # [m/s] time_resolution: 0.5 # [s] - time_horizon_for_front_object: 10.0 # [s] + time_horizon_for_front_object: 3.0 # [s] time_horizon_for_rear_object: 10.0 # [s] delay_until_departure: 0.0 # [s] # rss parameters @@ -176,7 +176,7 @@ expected_rear_deceleration: -1.0 # [m/ss] rear_vehicle_reaction_time: 2.0 # [s] rear_vehicle_safety_time_margin: 1.0 # [s] - lateral_distance_max_threshold: 2.0 # [m] + lateral_distance_max_threshold: 0.75 # [m] longitudinal_distance_min_threshold: 3.0 # [m] longitudinal_velocity_delta_time: 0.8 # [s] @@ -184,10 +184,10 @@ avoidance: # avoidance lateral parameters lateral: - lateral_execution_threshold: 0.499 # [m] + lateral_execution_threshold: 0.09 # [m] lateral_small_shift_threshold: 0.101 # [m] lateral_avoid_check_threshold: 0.1 # [m] - soft_road_shoulder_margin: 0.8 # [m] + soft_road_shoulder_margin: 0.3 # [m] hard_road_shoulder_margin: 0.3 # [m] max_right_shift_length: 5.0 max_left_shift_length: 5.0 @@ -246,13 +246,13 @@ longitudinal: nominal_deceleration: -1.0 # [m/ss] nominal_jerk: 0.5 # [m/sss] - max_deceleration: -2.0 # [m/ss] + max_deceleration: -1.5 # [m/ss] max_jerk: 1.0 # [m/sss] max_acceleration: 1.0 # [m/ss] shift_line_pipeline: trim: - quantize_filter_threshold: 0.2 + quantize_filter_threshold: 0.1 same_grad_filter_1_threshold: 0.1 same_grad_filter_2_threshold: 0.2 same_grad_filter_3_threshold: 0.5 From b20c34f034b6ed030764d90a4a4d40744852817b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 28 Nov 2023 14:07:20 +0900 Subject: [PATCH 043/128] refactor(avoidance): separate shift line generate process (#5624) * refactor(avoidance): separate shift line generate process Signed-off-by: satoshi-ota * refactor(avoidance): move marker function to utils Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/behavior_path_planner/CMakeLists.txt | 1 + .../marker_utils/avoidance/debug.hpp | 3 + .../avoidance/avoidance_module.hpp | 192 +- .../utils/avoidance/avoidance_module_data.hpp | 7 +- .../utils/avoidance/helper.hpp | 9 + .../utils/avoidance/shift_line_generator.hpp | 251 +++ .../utils/avoidance/utils.hpp | 5 +- .../src/marker_utils/avoidance/debug.cpp | 134 +- .../avoidance/avoidance_module.cpp | 1856 ++--------------- .../utils/avoidance/shift_line_generator.cpp | 1318 ++++++++++++ .../src/utils/avoidance/utils.cpp | 24 +- 11 files changed, 1936 insertions(+), 1864 deletions(-) create mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp create mode 100644 planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 7fc35355202ff..b989779b176c5 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -34,6 +34,7 @@ ament_auto_add_library(behavior_path_planner_node SHARED src/utils/path_safety_checker/safety_check.cpp src/utils/path_safety_checker/objects_filtering.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 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp index 100e8046f8d7f..8eaed624659b9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp @@ -39,6 +39,7 @@ using behavior_path_planner::AvoidanceState; using behavior_path_planner::AvoidLineArray; using behavior_path_planner::DebugData; using behavior_path_planner::ObjectDataArray; +using behavior_path_planner::PathShifter; using behavior_path_planner::ShiftLineArray; using geometry_msgs::msg::Point; using geometry_msgs::msg::Polygon; @@ -65,6 +66,8 @@ MarkerArray createOverhangFurthestLineStringMarkerArray( const lanelet::ConstLineStrings3d & linestrings, std::string && ns, const float & r, const float & g, const float & b); +MarkerArray createDebugMarkerArray( + const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug); } // namespace marker_utils::avoidance_marker std::string toStrInfo(const behavior_path_planner::ShiftLineArray & sp_arr); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 76264b0532f07..2cce35eef7f92 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -19,6 +19,7 @@ #include "behavior_path_planner/scene_module/scene_module_visitor.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_planner/utils/path_safety_checker/safety_check.hpp" #include @@ -44,6 +45,8 @@ using motion_utils::findNearestIndex; using tier4_planning_msgs::msg::AvoidanceDebugMsg; +using helper::avoidance::AvoidanceHelper; + class AvoidanceModule : public SceneModuleInterface { public: @@ -221,6 +224,11 @@ class AvoidanceModule : public SceneModuleInterface */ void insertStopPoint(const bool use_constraints_for_decel, ShiftedPath & shifted_path) const; + /** + * @brief insert stop point in return path to original lane. + * @param flag. if it is true, the ego decelerates within accel/jerk constraints. + * @param target path. + */ void insertReturnDeadLine(const bool use_constraints_for_decel, ShiftedPath & shifted_path) const; /** @@ -288,167 +296,12 @@ class AvoidanceModule : public SceneModuleInterface */ void fillDebugData(const AvoidancePlanningData & data, DebugData & debug) const; - /** - * @brief update registered shift lines. - * @param current shift lines. - */ - void registerRawShiftLines(const AvoidLineArray & future_registered); - - /** - * @brief update path index of the registered objects. remove old objects whose end point is - * behind ego pose. - */ - void updateRegisteredRawShiftLines(); - /** * @brief check whether the ego can transit yield maneuver. * @param avoidance data. */ bool canYieldManeuver(const AvoidancePlanningData & data) const; - // shift line generation - - /** - * @brief Calculate the shift points (start/end point, shift length) from the object lateral - * and longitudinal positions in the Frenet coordinate. The jerk limit is also considered here. - * @param avoidance data. - * @param debug data. - * @return processed shift lines. - */ - AvoidOutlines generateAvoidOutline(AvoidancePlanningData & data, DebugData & debug) const; - - /* - * @brief merge avoid outlines. - * @param original shift lines. - * @param debug data. - * @return processed shift lines. - */ - AvoidOutlines applyMergeProcess(const AvoidOutlines & outlines, DebugData & debug) const; - - /* - * @brief fill gap between two shift lines. - * @param original shift lines. - * @param debug data. - * @return processed shift lines. - */ - AvoidOutlines applyFillGapProcess(const AvoidOutlines & outlines, DebugData & debug) const; - - /* - * @brief generate candidate shift lines. - * @param one-shot shift lines. - * @param debug data. - */ - AvoidLineArray generateCandidateShiftLine( - const AvoidLineArray & shift_lines, DebugData & debug) const; - - /** - * @brief clean up raw shift lines. - * @param target shift lines. - * @param debug data. - * @return processed shift lines. - * @details process flow: - * 1. combine raw shirt lines and previous registered shift lines. - * 2. add return shift line. - * 3. merge raw shirt lines. - * 4. trim unnecessary shift lines. - */ - AvoidLineArray applyPreProcess(const AvoidOutlines & outlines, DebugData & debug) const; - - /* - * @brief fill gap among shift lines. - * @param original shift lines. - * @param debug data. - * @return processed shift lines. - */ - AvoidLineArray applyFillGapProcess(const AvoidLineArray & shift_lines, DebugData & debug) const; - - /* - * @brief merge negative & positive shift lines. - * @param original shift lines. - * @param debug data. - * @return processed shift lines. - */ - AvoidLineArray applyMergeProcess(const AvoidLineArray & shift_lines, DebugData & debug) const; - - /* - * @brief add return shift line from ego position. - * @param current raw shift line. - * @param current registered shift line. - * @param debug data. - */ - AvoidLineArray applyCombineProcess( - const AvoidLineArray & shift_lines, const AvoidLineArray & registered_lines, - [[maybe_unused]] DebugData & debug) const; - - /* - * @brief add return shift line from ego position. - * @param shift lines which the return shift is added. - * Pick up the last shift point, which is the most farthest from ego, from the current candidate - * avoidance points and registered points in the shifter. If the last shift length of the point is - * non-zero, add a return-shift to center line from the point. If there is no shift point in - * candidate avoidance points nor registered points, and base_shift > 0, add a return-shift to - * center line from ego. - */ - AvoidLineArray addReturnShiftLine(const AvoidLineArray & shift_lines, DebugData & debug) const; - - /* - * @brief extract shift lines from total shift lines based on their gradient. - * @param shift length data. - * @return extracted shift lines. - */ - AvoidLineArray extractShiftLinesFromLine(ShiftLineData & shift_line_data) const; - - /* - * @brief remove unnecessary avoid points - * @param original shift lines. - * @param debug data. - * @return processed shift lines. - * @details - * - Combine avoid points that have almost same gradient - * - Quantize the shift length to reduce the shift point noise - * - Change the shift length to the previous one if the deviation is small. - * - Remove unnecessary return shift (back to the center line). - */ - AvoidLineArray applyTrimProcess(const AvoidLineArray & shift_lines, DebugData & debug) const; - - /* - * @brief extract new shift lines based on current shifted path. the module makes a RTC request - * for those new shift lines. - * @param candidate shift lines. - * @return new shift lines. - */ - AvoidLineArray findNewShiftLine(const AvoidLineArray & shift_lines, DebugData & debug) const; - - /* - * @brief generate total shift line. total shift line has shift length and gradient array. - * @param raw shift lines. - * @param total shift line. - */ - void generateTotalShiftLine( - const AvoidLineArray & avoid_points, ShiftLineData & shift_line_data) const; - - /* - * @brief quantize shift line length. - * @param target shift lines. - * @param threshold. shift length is quantized by this value. (if it is 0.3[m], the output shift - * length is 0.0, 0.3, 0.6...) - */ - void applyQuantizeProcess(AvoidLineArray & shift_lines, const double threshold) const; - - /* - * @brief trim shift line whose relative longitudinal distance is less than threshold. - * @param target shift lines. - * @param threshold. - */ - void applySmallShiftFilter(AvoidLineArray & shift_lines, const double threshold) const; - - /* - * @brief merge multiple shift lines whose relative gradient is less than threshold. - * @param target shift lines. - * @param threshold. - */ - void applySimilarGradFilter(AvoidLineArray & shift_lines, const double threshold) const; - /** * @brief add new shift line to path shifter if the RTC status is activated. * @param new shift lines. @@ -505,15 +358,6 @@ class AvoidanceModule : public SceneModuleInterface */ bool isSafePath(ShiftedPath & shifted_path, DebugData & debug) const; - bool isComfortable(const AvoidLineArray & shift_lines) const - { - return std::all_of(shift_lines.begin(), shift_lines.end(), [&](const auto & line) { - return PathShifter::calcJerkFromLatLonDistance( - line.getRelativeLength(), line.getRelativeLongitudinal(), - helper_.getAvoidanceEgoSpeed()) < helper_.getLateralMaxJerkLimit(); - }); - } - // post process /** @@ -543,8 +387,7 @@ class AvoidanceModule : public SceneModuleInterface removeRTCStatus(); } - current_raw_shift_lines_.clear(); - registered_raw_shift_lines_.clear(); + generator_.reset(); path_shifter_.setShiftLines(ShiftLineArray{}); } @@ -558,15 +401,6 @@ class AvoidanceModule : public SceneModuleInterface path_shifter_.removeBehindShiftLineAndSetBaseOffset(idx); } - // misc functions - - double getCurrentBaseShift() const { return path_shifter_.getBaseOffset(); } - - // TODO(Horibe): think later. - // for unique ID - mutable uint64_t original_unique_id = 0; // TODO(Horibe) remove mutable - uint64_t getOriginalShiftLineUniqueId() const { return original_unique_id++; } - struct RegisteredShiftLine { UUID uuid; @@ -582,9 +416,11 @@ class AvoidanceModule : public SceneModuleInterface bool safe_{true}; + std::shared_ptr helper_; + std::shared_ptr parameters_; - helper::avoidance::AvoidanceHelper helper_; + utils::avoidance::ShiftLineGenerator generator_; AvoidancePlanningData avoid_data_; @@ -594,10 +430,6 @@ class AvoidanceModule : public SceneModuleInterface RegisteredShiftLineArray right_shift_array_; - AvoidLineArray registered_raw_shift_lines_; - - AvoidLineArray current_raw_shift_lines_; - UUID candidate_uuid_; ObjectDataArray registered_objects_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index c90321ea649a6..6c223bff39ef0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -414,10 +414,10 @@ struct AvoidLine : public ShiftLine double end_longitudinal = 0.0; // for unique_id - uint64_t id = 0; + UUID id{}; // for the case the point is created by merge other points - std::vector parent_ids{}; + std::vector parent_ids{}; // corresponding object ObjectData object{}; @@ -496,9 +496,6 @@ struct AvoidancePlanningData // nearest object that should be avoid boost::optional stop_target_object{boost::none}; - // raw shift point - AvoidLineArray raw_shift_line{}; - // new shift point AvoidLineArray new_shift_line{}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp index e1d51122e5c1b..cc7d18356fbd6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp @@ -247,6 +247,15 @@ class AvoidanceHelper return std::numeric_limits::max(); } + bool isComfortable(const AvoidLineArray & shift_lines) const + { + return std::all_of(shift_lines.begin(), shift_lines.end(), [&](const auto & line) { + return PathShifter::calcJerkFromLatLonDistance( + line.getRelativeLength(), line.getRelativeLongitudinal(), getAvoidanceEgoSpeed()) < + getLateralMaxJerkLimit(); + }); + } + bool isShifted() const { return std::abs(getEgoShift()) > parameters_->lateral_avoid_check_threshold; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp new file mode 100644 index 0000000000000..6faca87db6e00 --- /dev/null +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp @@ -0,0 +1,251 @@ +// 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_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ +#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ + +#include "behavior_path_planner/data_manager.hpp" +#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_planner/utils/avoidance/helper.hpp" +#include "behavior_path_planner/utils/path_shifter/path_shifter.hpp" + +#include + +#include + +namespace behavior_path_planner::utils::avoidance +{ + +using behavior_path_planner::PathShifter; +using behavior_path_planner::helper::avoidance::AvoidanceHelper; +using motion_utils::calcSignedArcLength; +using motion_utils::findNearestIndex; + +class ShiftLineGenerator +{ +public: + explicit ShiftLineGenerator(const std::shared_ptr & parameters) + : parameters_{parameters} + { + } + + void update(AvoidancePlanningData & data, DebugData & debug); + + void setRawRegisteredShiftLine( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data); + + void setData(const std::shared_ptr & data) { data_ = data; } + + void setHelper(const std::shared_ptr & helper) { helper_ = helper; } + + void setPathShifter(const PathShifter & path_shifter) + { + base_offset_ = path_shifter.getBaseOffset(); + if (path_shifter.getShiftLines().empty()) { + last_ = std::nullopt; + } else { + last_ = path_shifter.getLastShiftLine().get(); + } + } + + void reset() + { + last_ = std::nullopt; + base_offset_ = 0.0; + raw_.clear(); + raw_registered_.clear(); + } + + AvoidLineArray generate(const AvoidancePlanningData & data, DebugData & debug) const; + + AvoidLineArray getRawRegisteredShiftLine() const { return raw_registered_; } + +private: + /** + * @brief Calculate the shift points (start/end point, shift length) from the object lateral + * and longitudinal positions in the Frenet coordinate. The jerk limit is also considered here. + * @param avoidance data. + * @param debug data. + * @return processed shift lines. + */ + AvoidOutlines generateAvoidOutline(AvoidancePlanningData & data, DebugData & debug) const; + + /* + * @brief merge avoid outlines. + * @param original shift lines. + * @param debug data. + * @return processed shift lines. + */ + AvoidOutlines applyMergeProcess( + const AvoidOutlines & outlines, const AvoidancePlanningData & data, DebugData & debug) const; + + /* + * @brief fill gap between two shift lines. + * @param original shift lines. + * @param debug data. + * @return processed shift lines. + */ + AvoidOutlines applyFillGapProcess( + const AvoidOutlines & outlines, const AvoidancePlanningData & data, DebugData & debug) const; + + /* + * @brief generate candidate shift lines. + * @param one-shot shift lines. + * @param debug data. + */ + AvoidLineArray generateCandidateShiftLine( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, + DebugData & debug) const; + + /** + * @brief clean up raw shift lines. + * @param target shift lines. + * @param debug data. + * @return processed shift lines. + * @details process flow: + * 1. combine raw shirt lines and previous registered shift lines. + * 2. add return shift line. + * 3. merge raw shirt lines. + * 4. trim unnecessary shift lines. + */ + AvoidLineArray applyPreProcess( + const AvoidOutlines & outlines, const AvoidancePlanningData & data, DebugData & debug) const; + + /* + * @brief fill gap among shift lines. + * @param original shift lines. + * @param debug data. + * @return processed shift lines. + */ + AvoidLineArray applyFillGapProcess( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, + DebugData & debug) const; + + /* + * @brief merge negative & positive shift lines. + * @param original shift lines. + * @param debug data. + * @return processed shift lines. + */ + AvoidLineArray applyMergeProcess( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, + DebugData & debug) const; + + /* + * @brief add return shift line from ego position. + * @param current raw shift line. + * @param current registered shift line. + * @param debug data. + */ + AvoidLineArray applyCombineProcess( + const AvoidLineArray & shift_lines, const AvoidLineArray & registered_lines, + [[maybe_unused]] DebugData & debug) const; + + /* + * @brief add return shift line from ego position. + * @param shift lines which the return shift is added. + * Pick up the last shift point, which is the most farthest from ego, from the current candidate + * avoidance points and registered points in the shifter. If the last shift length of the point is + * non-zero, add a return-shift to center line from the point. If there is no shift point in + * candidate avoidance points nor registered points, and base_shift > 0, add a return-shift to + * center line from ego. + */ + AvoidLineArray addReturnShiftLine( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, + DebugData & debug) const; + + /* + * @brief extract shift lines from total shift lines based on their gradient. + * @param shift length data. + * @return extracted shift lines. + */ + AvoidLineArray extractShiftLinesFromLine( + const AvoidancePlanningData & data, ShiftLineData & shift_line_data) const; + + /* + * @brief remove unnecessary avoid points + * @param original shift lines. + * @param debug data. + * @return processed shift lines. + * @details + * - Combine avoid points that have almost same gradient + * - Quantize the shift length to reduce the shift point noise + * - Change the shift length to the previous one if the deviation is small. + * - Remove unnecessary return shift (back to the center line). + */ + AvoidLineArray applyTrimProcess(const AvoidLineArray & shift_lines, DebugData & debug) const; + + /* + * @brief extract new shift lines based on current shifted path. the module makes a RTC request + * for those new shift lines. + * @param candidate shift lines. + * @return new shift lines. + */ + AvoidLineArray findNewShiftLine(const AvoidLineArray & shift_lines, DebugData & debug) const; + + /* + * @brief generate total shift line. total shift line has shift length and gradient array. + * @param raw shift lines. + * @param total shift line. + */ + void generateTotalShiftLine( + const AvoidLineArray & avoid_points, const AvoidancePlanningData & data, + ShiftLineData & shift_line_data) const; + + /* + * @brief quantize shift line length. + * @param target shift lines. + * @param threshold. shift length is quantized by this value. (if it is 0.3[m], the output shift + * length is 0.0, 0.3, 0.6...) + */ + void applyQuantizeProcess(AvoidLineArray & shift_lines, const double threshold) const; + + /* + * @brief trim shift line whose relative longitudinal distance is less than threshold. + * @param target shift lines. + * @param threshold. + */ + void applySmallShiftFilter(AvoidLineArray & shift_lines, const double threshold) const; + + /* + * @brief merge multiple shift lines whose relative gradient is less than threshold. + * @param target shift lines. + * @param threshold. + */ + void applySimilarGradFilter(AvoidLineArray & shift_lines, const double threshold) const; + + /** + * @brief update path index of the registered objects. remove old objects whose end point is + * behind ego pose. + */ + void updateRegisteredRawShiftLines(const AvoidancePlanningData & data); + + std::shared_ptr data_; + + std::shared_ptr parameters_; + + std::shared_ptr helper_; + + std::optional last_{std::nullopt}; + + AvoidLineArray raw_; + + AvoidLineArray raw_registered_; + + double base_offset_{0.0}; +}; + +} // namespace behavior_path_planner::utils::avoidance + +#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp index 7ed455ea5350e..e5da32fbc155e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp @@ -47,10 +47,9 @@ ShiftedPath toShiftedPath(const PathWithLaneId & path); ShiftLineArray toShiftLineArray(const AvoidLineArray & avoid_points); -std::vector concatParentIds( - const std::vector & ids1, const std::vector & ids2); +std::vector concatParentIds(const std::vector & ids1, const std::vector & ids2); -std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine & lines2); +std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine & lines2); double lerpShiftLengthOnArc(double arc, const AvoidLine & al); diff --git a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp b/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp index ce9cedc816a19..7c427c9821f88 100644 --- a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp +++ b/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp @@ -17,6 +17,9 @@ #include "behavior_path_planner/utils/utils.hpp" #include +#include + +#include #include #include @@ -471,6 +474,131 @@ MarkerArray createOverhangFurthestLineStringMarkerArray( return msg; } + +MarkerArray createDebugMarkerArray( + const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) +{ + using marker_utils::createLaneletsAreaMarkerArray; + using marker_utils::createObjectsMarkerArray; + using marker_utils::createPathMarkerArray; + using marker_utils::createPolygonMarkerArray; + using marker_utils::createPoseMarkerArray; + using marker_utils::createShiftGradMarkerArray; + using marker_utils::createShiftLengthMarkerArray; + using marker_utils::createShiftLineMarkerArray; + using marker_utils::showPolygon; + using marker_utils::showPredictedPath; + using marker_utils::showSafetyCheckInfo; + using tier4_planning_msgs::msg::AvoidanceDebugFactor; + + const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); + MarkerArray msg; + + const auto & path = data.reference_path; + + const auto add = [&msg](const MarkerArray & added) { appendMarkerArray(added, &msg); }; + + const auto addAvoidLine = + [&](const AvoidLineArray & al_arr, const auto & ns, auto r, auto g, auto b, double w = 0.05) { + add(createAvoidLineMarkerArray(al_arr, ns, r, g, b, w)); + }; + + const auto addShiftLine = + [&](const ShiftLineArray & sl_arr, const auto & ns, auto r, auto g, auto b, double w = 0.1) { + add(createShiftLineMarkerArray(sl_arr, shifter.getBaseOffset(), ns, r, g, b, w)); + }; + + const auto addObjects = [&](const ObjectDataArray & objects, const auto & ns) { + add(createOtherObjectsMarkerArray(objects, ns)); + }; + + const auto addShiftLength = + [&](const auto & shift_length, const auto & ns, auto r, auto g, auto b) { + add(createShiftLengthMarkerArray(shift_length, path, ns, r, g, b)); + }; + + const auto addShiftGrad = [&]( + const auto & shift_grad, const auto & shift_length, const auto & ns, + auto r, auto g, auto b) { + add(createShiftGradMarkerArray(shift_grad, shift_length, path, ns, r, g, b)); + }; + + // ignore objects + { + addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD); + addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD); + addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE); + addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL); + addObjects(data.other_objects, AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE); + addObjects(data.other_objects, AvoidanceDebugFactor::NOT_PARKING_OBJECT); + addObjects(data.other_objects, std::string("MovingObject")); + addObjects(data.other_objects, std::string("CrosswalkUser")); + addObjects(data.other_objects, std::string("OutOfTargetArea")); + addObjects(data.other_objects, std::string("NotNeedAvoidance")); + addObjects(data.other_objects, std::string("LessThanExecutionThreshold")); + addObjects(data.other_objects, std::string("TooNearToGoal")); + } + + // shift line pre-process + { + addAvoidLine(debug.step1_registered_shift_line, "step1_registered_shift_line", 0.2, 0.2, 1.0); + addAvoidLine(debug.step1_current_shift_line, "step1_current_shift_line", 0.2, 0.4, 0.8, 0.3); + addAvoidLine(debug.step1_merged_shift_line, "step1_merged_shift_line", 0.2, 0.6, 0.6, 0.3); + addAvoidLine(debug.step1_filled_shift_line, "step1_filled_shift_line", 0.2, 0.8, 0.4, 0.3); + addAvoidLine(debug.step1_return_shift_line, "step1_return_shift_line", 0.2, 1.0, 0.2, 0.3); + } + + // merge process + { + addAvoidLine(debug.step2_merged_shift_line, "step2_merged_shift_line", 0.2, 1.0, 0.0, 0.3); + } + + // trimming process + { + addAvoidLine(debug.step3_grad_filtered_1st, "step3_grad_filtered_1st", 0.2, 0.8, 0.0, 0.3); + addAvoidLine(debug.step3_grad_filtered_2nd, "step3_grad_filtered_2nd", 0.4, 0.6, 0.0, 0.3); + addAvoidLine(debug.step3_grad_filtered_3rd, "step3_grad_filtered_3rd", 0.6, 0.4, 0.0, 0.3); + } + + // registering process + { + addShiftLine(shifter.getShiftLines(), "step4_old_shift_line", 1.0, 1.0, 0.0, 0.3); + addAvoidLine(data.new_shift_line, "step4_new_shift_line", 1.0, 0.0, 0.0, 0.3); + } + + // safety check + { + add(showSafetyCheckInfo(debug.collision_check, "object_debug_info")); + add(showPredictedPath(debug.collision_check, "ego_predicted_path")); + add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation")); + } + + // shift length + { + addShiftLength(debug.pos_shift, "merged_length_pos", 0.0, 0.7, 0.5); + addShiftLength(debug.neg_shift, "merged_length_neg", 0.0, 0.5, 0.7); + addShiftLength(debug.total_shift, "merged_length_total", 0.99, 0.4, 0.2); + } + + // shift grad + { + addShiftGrad(debug.pos_shift_grad, debug.pos_shift, "merged_grad_pos", 0.0, 0.7, 0.5); + addShiftGrad(debug.neg_shift_grad, debug.neg_shift, "merged_grad_neg", 0.0, 0.5, 0.7); + addShiftGrad(debug.total_forward_grad, debug.total_shift, "grad_forward", 0.99, 0.4, 0.2); + addShiftGrad(debug.total_backward_grad, debug.total_shift, "grad_backward", 0.4, 0.2, 0.9); + } + + // misc + { + add(createPathMarkerArray(path, "centerline_resampled", 0, 0.0, 0.9, 0.5)); + add(createLaneletsAreaMarkerArray(*debug.current_lanelets, "current_lanelet", 0.0, 1.0, 0.0)); + add(createPolygonMarkerArray(debug.detection_area, "detection_area", 0L, 0.16, 1.0, 0.69, 0.1)); + add(makeOverhangToRoadShoulderMarkerArray(data.target_objects, "overhang")); + add(createOverhangFurthestLineStringMarkerArray(debug.bounds, "bounds", 1.0, 0.0, 1.0)); + } + + return msg; +} } // namespace marker_utils::avoidance_marker std::string toStrInfo(const behavior_path_planner::ShiftLineArray & sl_arr) @@ -509,14 +637,16 @@ std::string toStrInfo(const behavior_path_planner::AvoidLineArray & ap_arr) } std::string toStrInfo(const behavior_path_planner::AvoidLine & ap) { + using tier4_autoware_utils::toHexString; + std::stringstream pids; for (const auto pid : ap.parent_ids) { - pids << pid << ", "; + pids << toHexString(pid) << ", "; } const auto & ps = ap.start.position; const auto & pe = ap.end.position; std::stringstream ss; - ss << "id = " << ap.id << ", shift length: " << ap.end_shift_length + ss << "id = " << toHexString(ap.id) << ", shift length: " << ap.end_shift_length << ", start_idx: " << ap.start_idx << ", end_idx: " << ap.end_idx << ", start_dist = " << ap.start_longitudinal << ", end_dist = " << ap.end_longitudinal << ", start_shift_length: " << ap.start_shift_length << ", start: (" << ps.x << ", " << ps.y diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index ee2f1160d76c2..7c7806112fda9 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -90,56 +90,6 @@ bool isBestEffort(const std::string & policy) return policy == "best_effort"; } -AvoidLine merge(const AvoidLine & line1, const AvoidLine & line2, const uint64_t id) -{ - AvoidLine ret{}; - - ret.start_idx = line1.start_idx; - ret.start_shift_length = line1.start_shift_length; - ret.start_longitudinal = line1.start_longitudinal; - - ret.end_idx = line2.end_idx; - ret.end_shift_length = line2.end_shift_length; - ret.end_longitudinal = line2.end_longitudinal; - - ret.id = id; - ret.object = line1.object; - - return ret; -} - -AvoidLine fill(const AvoidLine & line1, const AvoidLine & line2, const uint64_t id) -{ - AvoidLine ret{}; - - ret.start_idx = line1.end_idx; - ret.start_shift_length = line1.end_shift_length; - ret.start_longitudinal = line1.end_longitudinal; - - ret.end_idx = line2.start_idx; - ret.end_shift_length = line2.start_shift_length; - ret.end_longitudinal = line2.start_longitudinal; - - ret.id = id; - ret.object = line1.object; - - return ret; -} - -AvoidLineArray toArray(const AvoidOutlines & outlines) -{ - AvoidLineArray ret{}; - for (const auto & outline : outlines) { - ret.push_back(outline.avoid_line); - ret.push_back(outline.return_line); - - std::for_each( - outline.middle_lines.begin(), outline.middle_lines.end(), - [&ret](const auto & line) { ret.push_back(line); }); - } - return ret; -} - lanelet::BasicLineString3d toLineString3d(const std::vector & bound) { lanelet::BasicLineString3d ret{}; @@ -155,8 +105,9 @@ AvoidanceModule::AvoidanceModule( std::unordered_map> & objects_of_interest_marker_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + helper_{std::make_shared(parameters)}, parameters_{parameters}, - helper_{parameters} + generator_{parameters} { } @@ -194,12 +145,12 @@ bool AvoidanceModule::canTransitSuccessState() const auto & data = avoid_data_; // Change input lane. -> EXIT. - if (!isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { + if (!isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { RCLCPP_WARN(getLogger(), "Previous module lane is updated. Exit."); return true; } - helper_.setPreviousDrivingLanes(data.current_lanelets); + helper_->setPreviousDrivingLanes(data.current_lanelets); // Reach input path end point. -> EXIT. { @@ -248,7 +199,7 @@ bool AvoidanceModule::canTransitSuccessState() // Be able to canceling avoidance path. -> EXIT. if (!has_avoidance_target) { - if (!helper_.isShifted() && parameters_->enable_cancel_maneuver) { + if (!helper_->isShifted() && parameters_->enable_cancel_maneuver) { RCLCPP_INFO(getLogger(), "No objects. Cancel avoidance path. Exit."); return true; } @@ -261,7 +212,7 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat { // reference pose data.reference_pose = - utils::getUnshiftedEgoPose(getEgoPose(), helper_.getPreviousSplineShiftPath()); + utils::getUnshiftedEgoPose(getEgoPose(), helper_->getPreviousSplineShiftPath()); // lanelet info data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( @@ -288,7 +239,7 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat parameters_->use_intersection_areas, false)); // reference path - if (isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { + if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path); } else { data.reference_path_rough = *getPreviousModuleOutput().path; @@ -343,10 +294,10 @@ void AvoidanceModule::fillAvoidanceTargetObjects( // 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); + 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(), + sparse_resample_path, planner_data_, data, parameters_, helper_->getForwardDetectionRange(), is_running, debug); for (const auto & object : object_outside_target_lane.objects) { @@ -365,7 +316,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects( filterTargetObjects(objects, data, debug, planner_data_, parameters_); // Calculate the distance needed to safely decelerate the ego vehicle to a stop line. - const auto feasible_stop_distance = helper_.getFeasibleDecelDistance(0.0, false); + const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false); std::for_each(data.target_objects.begin(), data.target_objects.end(), [&, this](auto & o) { o.to_stop_line = calcDistanceToStopLine(o); fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_); @@ -442,7 +393,7 @@ ObjectData AvoidanceModule::createObjectData( bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const { // transit yield maneuver only when the avoidance maneuver is not initiated. - if (helper_.isShifted()) { + if (helper_->isShifted()) { RCLCPP_DEBUG(getLogger(), "avoidance maneuver already initiated."); return false; } @@ -453,7 +404,7 @@ bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points); const auto to_shift_start_point = calcSignedArcLength( path_shifter_.getReferencePath().points, idx, registered_lines.front().start_idx); - if (to_shift_start_point < helper_.getMinimumPrepareDistance()) { + if (to_shift_start_point < helper_->getMinimumPrepareDistance()) { RCLCPP_DEBUG( getLogger(), "Distance to shift start point is less than minimum prepare distance. The distance is not " @@ -496,24 +447,13 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de auto path_shifter = path_shifter_; /** - * STEP1: Generate avoid outlines. - * Basically, avoid outlines are generated per target objects. - */ - const auto outlines = generateAvoidOutline(data, debug); - - /** - * STEP2: Create rough shift lines. - */ - data.raw_shift_line = applyPreProcess(outlines, debug); - - /** - * STEP3: Create candidate shift lines. + * STEP1: Create candidate shift lines. * Merge rough shift lines, and extract new shift lines. */ - const auto processed_shift_lines = generateCandidateShiftLine(data.raw_shift_line, debug); + const auto processed_shift_lines = generator_.generate(data, debug); /** - * Step4: Validate new shift lines. + * 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. */ @@ -524,7 +464,7 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de data.found_avoidance_path = found_new_sl || registered; /** - * STEP5: Set new shift lines. + * STEP3: Set new shift lines. * If there are new shift points, these shift points are registered in path_shifter in order to * generate candidate avoidance path. */ @@ -533,7 +473,7 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de } /** - * STEP6: Generate avoidance path. + * STEP4: Generate avoidance path. */ ShiftedPath spline_shift_path = utils::avoidance::toShiftedPath(data.reference_path); const auto success_spline_path_generation = @@ -543,11 +483,11 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de : utils::avoidance::toShiftedPath(data.reference_path); /** - * STEP7: Check avoidance path safety. + * STEP5: Check avoidance path safety. * For each target objects and the objects in adjacent lanes, * check that there is a certain amount of margin in the lateral and longitudinal direction. */ - data.comfortable = isComfortable(data.new_shift_line); + data.comfortable = helper_->isComfortable(data.new_shift_line); data.safe = isSafePath(data.candidate_path, debug); } @@ -583,1374 +523,177 @@ void AvoidanceModule::fillEgoStatus( } } - const auto can_yield_maneuver = canYieldManeuver(data); - - /** - * If the output path is locked by outside of this module, don't update output path. - */ - if (isOutputPathLocked()) { - data.safe_shift_line.clear(); - data.candidate_path = helper_.getPreviousSplineShiftPath(); - RCLCPP_DEBUG_THROTTLE( - getLogger(), *clock_, 500, "this module is locked now. keep current path."); - return; - } - - /** - * If the avoidance path is safe, use unapproved_new_sl for avoidance path generation. - */ - if (data.safe) { - data.yield_required = false; - data.safe_shift_line = data.new_shift_line; - return; - } - - /** - * If the yield maneuver is disabled, use unapproved_new_sl for avoidance path generation even if - * the shift line is unsafe. - */ - if (!parameters_->enable_yield_maneuver) { - data.yield_required = false; - data.safe_shift_line = data.new_shift_line; - return; - } - - /** - * TODO(Satoshi OTA) Think yield maneuver in the middle of avoidance. - * Even if it is determined that a yield is necessary, the yield maneuver is not executed - * if the avoidance has already been initiated. - */ - if (!can_yield_maneuver) { - data.safe = true; // overwrite safety judge. - data.yield_required = false; - data.safe_shift_line = data.new_shift_line; - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "unsafe. but could not transit yield status."); - return; - } - - /** - * Transit yield maneuver. Clear shift lines and output yield path. - */ - { - data.yield_required = true; - data.safe_shift_line = data.new_shift_line; - } - - /** - * Even if data.avoid_required is false, the module cancels registered shift point when the - * approved avoidance path is not safe. - */ - const auto approved_path_exist = !path_shifter_.getShiftLines().empty(); - if (approved_path_exist) { - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe. canceling approved path..."); - return; - } - - /** - * If the avoidance path is not safe in situation where the ego should avoid object, the ego - * stops in front of the front object with the necessary distance to avoid the object. - */ - { - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe. transit yield maneuver..."); - } -} - -void AvoidanceModule::fillDebugData( - const AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const -{ - if (!data.stop_target_object) { - return; - } - - if (helper_.isShifted()) { - return; - } - - if (data.new_shift_line.empty()) { - return; - } - - const auto o_front = data.stop_target_object.get(); - const auto object_type = utils::getHighestProbLabel(o_front.object.classification); - const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto & additional_buffer_longitudinal = - object_parameter.use_conservative_buffer_longitudinal - ? planner_data_->parameters.base_link2front - : 0.0; - const auto & vehicle_width = planner_data_->parameters.vehicle_width; - - const auto max_avoid_margin = object_parameter.safety_buffer_lateral * o_front.distance_factor + - object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; - - const auto variable = helper_.getSharpAvoidanceDistance( - helper_.getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin)); - const auto constant = helper_.getNominalPrepareDistance() + - object_parameter.safety_buffer_longitudinal + - additional_buffer_longitudinal; - const auto total_avoid_distance = variable + constant; - - dead_pose_ = calcLongitudinalOffsetPose( - data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance); - - if (!dead_pose_) { - dead_pose_ = getPose(data.reference_path.points.front()); - } -} - -AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & data) const -{ - if (data.yield_required) { - return AvoidanceState::YIELD; - } - - if (!data.avoid_required) { - return AvoidanceState::NOT_AVOID; - } - - if (!data.found_avoidance_path) { - return AvoidanceState::AVOID_PATH_NOT_READY; - } - - if (isWaitingApproval() && path_shifter_.getShiftLines().empty()) { - return AvoidanceState::AVOID_PATH_READY; - } - - return AvoidanceState::AVOID_EXECUTE; -} - -void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, ShiftedPath & path) -{ - if (parameters_->disable_path_update) { - return; - } - - insertPrepareVelocity(path); - - switch (data.state) { - case AvoidanceState::NOT_AVOID: { - break; - } - case AvoidanceState::YIELD: { - insertYieldVelocity(path); - insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - break; - } - case AvoidanceState::AVOID_PATH_NOT_READY: { - insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - break; - } - case AvoidanceState::AVOID_PATH_READY: { - insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - break; - } - case AvoidanceState::AVOID_EXECUTE: { - insertStopPoint(isBestEffort(parameters_->policy_deceleration), path); - break; - } - default: - throw std::domain_error("invalid behavior"); - } - - insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); - - setStopReason(StopReason::AVOIDANCE, path.path); -} - -void AvoidanceModule::updateRegisteredRawShiftLines() -{ - const auto & data = avoid_data_; - - utils::avoidance::fillAdditionalInfoFromPoint(data, registered_raw_shift_lines_); - - AvoidLineArray avoid_lines; - - const auto has_large_offset = [this](const auto & s) { - constexpr double THRESHOLD = 0.1; - const auto ego_shift_length = helper_.getEgoLinearShift(); - - const auto start_to_ego_longitudinal = -1.0 * s.start_longitudinal; - - if (start_to_ego_longitudinal < 0.0) { - return false; - } - - const auto reg_shift_length = - s.getGradient() * start_to_ego_longitudinal + s.start_shift_length; - - return std::abs(ego_shift_length - reg_shift_length) > THRESHOLD; - }; - - const auto ego_idx = data.ego_closest_path_index; - - for (const auto & s : registered_raw_shift_lines_) { - // invalid - if (s.end_idx < ego_idx) { - continue; - } - - // invalid - if (has_large_offset(s)) { - continue; - } - - // valid - avoid_lines.push_back(s); - } - - DEBUG_PRINT( - "ego_closest_path_index = %lu, registered_raw_shift_lines_ size: %lu -> %lu", - data.ego_closest_path_index, registered_raw_shift_lines_.size(), avoid_lines.size()); - - printShiftLines(registered_raw_shift_lines_, "registered_raw_shift_lines_ (before)"); - printShiftLines(avoid_lines, "registered_raw_shift_lines_ (after)"); - - registered_raw_shift_lines_ = avoid_lines; - debug_data_.step1_registered_shift_line = registered_raw_shift_lines_; -} - -AvoidLineArray AvoidanceModule::applyPreProcess( - const AvoidOutlines & outlines, DebugData & debug) const -{ - AvoidOutlines processed_outlines = outlines; - - /** - * Step1: Rough merge process. - * Merge multiple avoid outlines. If an avoid outlines' return shift line conflicts other - * outline's avoid shift line, those avoid outlines are merged. - */ - processed_outlines = applyMergeProcess(processed_outlines, debug); - - /** - * Step2: Fill gap process. - * Create and add new shift line to avoid outline in order to fill gaps between avoid shift line - * and middle shift lines, return shift line and middle shift lines. - */ - processed_outlines = applyFillGapProcess(processed_outlines, debug); - - /** - * Step3: Convert to AvoidLineArray from AvoidOutlines. - */ - AvoidLineArray processed_raw_lines = toArray(processed_outlines); - - /** - * Step4: Combine process. - * Use all registered points. For the current points, if the similar one of the current - * points are already registered, will not use it. - */ - processed_raw_lines = - applyCombineProcess(processed_raw_lines, registered_raw_shift_lines_, debug); - - /* - * Step5: Add return shift line. - * Add return-to-center shift point from the last shift point, if needed. - * If there is no shift points, set return-to center shift from ego. - */ - processed_raw_lines = addReturnShiftLine(processed_raw_lines, debug); - - /* - * Step6: Fill gap process. - * Create and add new shift line to avoid lines. - */ - return applyFillGapProcess(processed_raw_lines, debug); -} - -AvoidLineArray AvoidanceModule::generateCandidateShiftLine( - const AvoidLineArray & shift_lines, DebugData & debug) const -{ - AvoidLineArray processed_shift_lines = shift_lines; - - /** - * Step1: Merge process. - * Merge positive shift avoid lines and negative shift avoid lines. - */ - processed_shift_lines = applyMergeProcess(processed_shift_lines, debug); - - /** - * Step2: Clean up process. - * Remove noisy shift line and concat same gradient shift lines. - */ - processed_shift_lines = applyTrimProcess(processed_shift_lines, debug); - - /** - * Step3: Extract new shift lines. - * Compare processed shift lines and registered shift lines in order to find new shift lines. - */ - return findNewShiftLine(processed_shift_lines, debug); -} - -void AvoidanceModule::registerRawShiftLines(const AvoidLineArray & future) -{ - if (future.empty()) { - RCLCPP_ERROR(getLogger(), "future is empty! return."); - return; - } - - const auto old_size = registered_raw_shift_lines_.size(); - - auto future_with_info = future; - utils::avoidance::fillAdditionalInfoFromPoint(avoid_data_, future_with_info); - printShiftLines(future_with_info, "future_with_info"); - printShiftLines(registered_raw_shift_lines_, "registered_raw_shift_lines_"); - printShiftLines(current_raw_shift_lines_, "current_raw_shift_lines_"); - - // sort by longitudinal - std::sort(future_with_info.begin(), future_with_info.end(), [](auto a, auto b) { - return a.end_longitudinal < b.end_longitudinal; - }); - - // calc relative lateral length - future_with_info.front().start_shift_length = getCurrentBaseShift(); - for (size_t i = 1; i < future_with_info.size(); ++i) { - future_with_info.at(i).start_shift_length = future_with_info.at(i - 1).end_shift_length; - } - - const auto is_registered = [this](const auto id) { - const auto & r = registered_raw_shift_lines_; - return std::any_of(r.begin(), r.end(), [id](const auto & s) { return s.id == id; }); - }; - - const auto same_id_shift_line = [this](const auto id) { - const auto & r = current_raw_shift_lines_; - const auto itr = std::find_if(r.begin(), r.end(), [id](const auto & s) { return s.id == id; }); - if (itr != r.end()) { - return *itr; - } - throw std::logic_error("not found same id current raw shift line."); - }; - - for (const auto & s : future_with_info) { - if (s.parent_ids.empty()) { - RCLCPP_ERROR(getLogger(), "avoid line for path_shifter must have parent_id."); - } - - for (const auto id : s.parent_ids) { - if (is_registered(id)) { - continue; - } - - registered_raw_shift_lines_.push_back(same_id_shift_line(id)); - } - } - - DEBUG_PRINT("registered object size: %lu -> %lu", old_size, registered_raw_shift_lines_.size()); -} - -AvoidOutlines AvoidanceModule::generateAvoidOutline( - AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const -{ - // To be consistent with changes in the ego position, the current shift length is considered. - const auto current_ego_shift = helper_.getEgoShift(); - const auto & base_link2rear = planner_data_->parameters.base_link2rear; - - // Calculate feasible shift length - const auto get_shift_profile = - [&]( - auto & object, const auto & desire_shift_length) -> std::optional> { - // use each object param - const auto object_type = utils::getHighestProbLabel(object.object.classification); - const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto is_object_on_right = utils::avoidance::isOnRight(object); - - // use absolute dist for return-to-center, relative dist from current for avoiding. - const auto avoiding_shift = desire_shift_length - current_ego_shift; - const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(avoiding_shift); - - // calculate remaining distance. - const auto prepare_distance = helper_.getNominalPrepareDistance(); - const auto & additional_buffer_longitudinal = - object_parameter.use_conservative_buffer_longitudinal - ? planner_data_->parameters.base_link2front - : 0.0; - const auto constant = object_parameter.safety_buffer_longitudinal + - additional_buffer_longitudinal + prepare_distance; - const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance; - const auto remaining_distance = object.longitudinal - constant; - const auto avoidance_distance = - has_enough_distance ? nominal_avoid_distance : remaining_distance; - - // nominal case. avoidable. - if (has_enough_distance) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - if (!isBestEffort(parameters_->policy_lateral_margin)) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - // ego already has enough positive shift. - const auto has_enough_positive_shift = avoiding_shift < -1e-3 && desire_shift_length > 1e-3; - if (is_object_on_right && has_enough_positive_shift) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - // ego already has enough negative shift. - const auto has_enough_negative_shift = avoiding_shift > 1e-3 && desire_shift_length < -1e-3; - if (!is_object_on_right && has_enough_negative_shift) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - // don't relax shift length since it can stop in front of the object. - if (object.is_stoppable && !parameters_->use_shorten_margin_immediately) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - // the avoidance path is already approved - const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; - const auto is_approved = (helper_.getShift(object_pos) > 0.0 && is_object_on_right) || - (helper_.getShift(object_pos) < 0.0 && !is_object_on_right); - if (is_approved) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - // prepare distance is not enough. unavoidable. - if (remaining_distance < 1e-3) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; - return std::nullopt; - } - - // calculate lateral jerk. - const auto required_jerk = PathShifter::calcJerkFromLatLonDistance( - avoiding_shift, remaining_distance, helper_.getAvoidanceEgoSpeed()); - - // relax lateral jerk limit. avoidable. - if (required_jerk < helper_.getLateralMaxJerkLimit()) { - return std::make_pair(desire_shift_length, avoidance_distance); - } - - // avoidance distance is not enough. unavoidable. - if (!isBestEffort(parameters_->policy_deceleration)) { - object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; - return std::nullopt; - } - - // output avoidance path under lateral jerk constraints. - const auto feasible_relative_shift_length = PathShifter::calcLateralDistFromJerk( - remaining_distance, helper_.getLateralMaxJerkLimit(), helper_.getAvoidanceEgoSpeed()); - - if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) { - object.reason = "LessThanExecutionThreshold"; - return std::nullopt; - } - - const auto feasible_shift_length = - desire_shift_length > 0.0 ? feasible_relative_shift_length + current_ego_shift - : -1.0 * feasible_relative_shift_length + current_ego_shift; - - const auto infeasible = - std::abs(feasible_shift_length - object.overhang_dist) < - 0.5 * planner_data_->parameters.vehicle_width + object_parameter.safety_buffer_lateral; - if (infeasible) { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 1000, "feasible shift length is not enough to avoid. "); - object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; - return std::nullopt; - } - - { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 1000, "use feasible shift length. [original: (%.2f) actual: (%.2f)]", - std::abs(avoiding_shift), feasible_relative_shift_length); - } - - return std::make_pair(feasible_shift_length, avoidance_distance); - }; - - const auto is_forward_object = [](const auto & object) { return object.longitudinal > 0.0; }; - - const auto is_valid_shift_line = [](const auto & s) { - return s.start_longitudinal > 0.0 && s.start_longitudinal < s.end_longitudinal; - }; - - AvoidOutlines outlines; - for (auto & o : data.target_objects) { - if (!o.avoid_margin.has_value()) { - o.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; - if (o.avoid_required && is_forward_object(o)) { - break; - } else { - continue; - } - } - - const auto is_object_on_right = utils::avoidance::isOnRight(o); - const auto desire_shift_length = - helper_.getShiftLength(o, is_object_on_right, o.avoid_margin.value()); - if (utils::avoidance::isSameDirectionShift(is_object_on_right, desire_shift_length)) { - o.reason = AvoidanceDebugFactor::SAME_DIRECTION_SHIFT; - if (o.avoid_required && is_forward_object(o)) { - break; - } else { - continue; - } - } - - // use each object param - const auto object_type = utils::getHighestProbLabel(o.object.classification); - const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length); - - if (!feasible_shift_profile.has_value()) { - if (o.avoid_required && is_forward_object(o)) { - break; - } else { - continue; - } - } - - // use absolute dist for return-to-center, relative dist from current for avoiding. - const auto feasible_return_distance = - helper_.getMaxAvoidanceDistance(feasible_shift_profile.value().first); - - AvoidLine al_avoid; - { - const auto & additional_buffer_longitudinal = - object_parameter.use_conservative_buffer_longitudinal - ? planner_data_->parameters.base_link2front - : 0.0; - const auto offset = - object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal; - const auto to_shift_end = o.longitudinal - offset; - const auto path_front_to_ego = - avoid_data_.arclength_from_ego.at(avoid_data_.ego_closest_path_index); - - // start point (use previous linear shift length as start shift length.) - al_avoid.start_longitudinal = [&]() { - const auto nearest_avoid_distance = - std::max(to_shift_end - feasible_shift_profile.value().second, 1e-3); - - if (data.to_start_point > to_shift_end) { - return nearest_avoid_distance; - } - - const auto minimum_avoid_distance = - helper_.getMinAvoidanceDistance(feasible_shift_profile.value().first - current_ego_shift); - const auto furthest_avoid_distance = std::max(to_shift_end - minimum_avoid_distance, 1e-3); - - return std::clamp(data.to_start_point, nearest_avoid_distance, furthest_avoid_distance); - }(); - - al_avoid.start_idx = utils::avoidance::findPathIndexFromArclength( - avoid_data_.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego); - al_avoid.start = avoid_data_.reference_path.points.at(al_avoid.start_idx).point.pose; - al_avoid.start_shift_length = helper_.getLinearShift(al_avoid.start.position); - - // end point - al_avoid.end_shift_length = feasible_shift_profile.value().first; - al_avoid.end_longitudinal = to_shift_end; - - // misc - al_avoid.id = getOriginalShiftLineUniqueId(); - al_avoid.object = o; - al_avoid.object_on_right = utils::avoidance::isOnRight(o); - } - - AvoidLine al_return; - { - const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length; - const auto to_shift_start = o.longitudinal + offset; - - // start point - al_return.start_shift_length = feasible_shift_profile.value().first; - al_return.start_longitudinal = to_shift_start; - - // end point - al_return.end_longitudinal = [&]() { - if (data.to_return_point > to_shift_start) { - return std::clamp( - data.to_return_point, to_shift_start, feasible_return_distance + to_shift_start); - } - - return to_shift_start + feasible_return_distance; - }(); - al_return.end_shift_length = 0.0; - - // misc - al_return.id = getOriginalShiftLineUniqueId(); - al_return.object = o; - al_return.object_on_right = utils::avoidance::isOnRight(o); - } - - if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { - outlines.emplace_back(al_avoid, al_return); - } else { - o.reason = "InvalidShiftLine"; - continue; - } - - o.is_avoidable = true; - } - - // debug - { - std::vector debug_info_array; - const auto append = [&](const auto & o) { - AvoidanceDebugMsg debug_info; - debug_info.object_id = toHexString(o.object.object_id); - debug_info.longitudinal_distance = o.longitudinal; - debug_info.lateral_distance_from_centerline = o.lateral; - debug_info.allow_avoidance = o.reason == ""; - debug_info.failed_reason = o.reason; - debug_info_array.push_back(debug_info); - }; - - for (const auto & o : data.target_objects) { - append(o); - } - - debug_avoidance_initializer_for_shift_line_.clear(); - debug_avoidance_initializer_for_shift_line_ = std::move(debug_info_array); - debug_avoidance_initializer_for_shift_line_time_ = clock_->now(); - } - - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, outlines); - - debug.step1_current_shift_line = toArray(outlines); - - return outlines; -} - -void AvoidanceModule::generateTotalShiftLine( - const AvoidLineArray & avoid_lines, ShiftLineData & shift_line_data) const -{ - const auto & path = avoid_data_.reference_path; - const auto & arcs = avoid_data_.arclength_from_ego; - const auto N = path.points.size(); - - auto & sl = shift_line_data; - - sl.shift_line = std::vector(N, 0.0); - sl.shift_line_grad = std::vector(N, 0.0); - - sl.pos_shift_line = std::vector(N, 0.0); - sl.neg_shift_line = std::vector(N, 0.0); - - sl.pos_shift_line_grad = std::vector(N, 0.0); - sl.neg_shift_line_grad = std::vector(N, 0.0); - - // debug - sl.shift_line_history = std::vector>(avoid_lines.size(), sl.shift_line); - - // take minmax for same directional shift length - for (size_t j = 0; j < avoid_lines.size(); ++j) { - const auto & al = avoid_lines.at(j); - for (size_t i = 0; i < N; ++i) { - // calc current interpolated shift - const auto i_shift = utils::avoidance::lerpShiftLengthOnArc(arcs.at(i), al); - - // update maximum shift for positive direction - if (i_shift > sl.pos_shift_line.at(i)) { - sl.pos_shift_line.at(i) = i_shift; - sl.pos_shift_line_grad.at(i) = al.getGradient(); - } - - // update minumum shift for negative direction - if (i_shift < sl.neg_shift_line.at(i)) { - sl.neg_shift_line.at(i) = i_shift; - sl.neg_shift_line_grad.at(i) = al.getGradient(); - } - - // store for debug print - sl.shift_line_history.at(j).at(i) = i_shift; - } - } - - // Merge shift length of opposite directions. - for (size_t i = 0; i < N; ++i) { - sl.shift_line.at(i) = sl.pos_shift_line.at(i) + sl.neg_shift_line.at(i); - sl.shift_line_grad.at(i) = sl.pos_shift_line_grad.at(i) + sl.neg_shift_line_grad.at(i); - } - - // overwrite shift with current_ego_shift until ego pose. - const auto current_shift = helper_.getEgoLinearShift(); - for (size_t i = 0; i < sl.shift_line.size(); ++i) { - if (avoid_data_.ego_closest_path_index < i) { - break; - } - sl.shift_line.at(i) = current_shift; - sl.shift_line_grad.at(i) = 0.0; - } - - // If the shift point does not have an associated object, - // use previous value. - for (size_t i = 1; i < N; ++i) { - bool has_object = false; - for (const auto & al : avoid_lines) { - if (al.start_idx <= i && i <= al.end_idx) { - has_object = true; - break; - } - } - if (!has_object) { - sl.shift_line.at(i) = sl.shift_line.at(i - 1); - } - } - - if (avoid_lines.empty()) { - sl.shift_line_history.push_back(sl.shift_line); - return; - } - - const auto grad_first_shift_line = (avoid_lines.front().start_shift_length - current_shift) / - avoid_lines.front().start_longitudinal; - - for (size_t i = avoid_data_.ego_closest_path_index; i <= avoid_lines.front().start_idx; ++i) { - sl.shift_line.at(i) = helper_.getLinearShift(getPoint(path.points.at(i))); - sl.shift_line_grad.at(i) = grad_first_shift_line; - } - - sl.shift_line_history.push_back(sl.shift_line); -} - -AvoidLineArray AvoidanceModule::extractShiftLinesFromLine(ShiftLineData & shift_line_data) const -{ - using utils::avoidance::setEndData; - using utils::avoidance::setStartData; - - const auto & path = avoid_data_.reference_path; - const auto & arcs = avoid_data_.arclength_from_ego; - const auto N = path.points.size(); - - auto & sl = shift_line_data; - - const auto backward_grad = [&](const size_t i) { - if (i == 0) { - return sl.shift_line_grad.at(i); - } - const double ds = arcs.at(i) - arcs.at(i - 1); - if (ds < 1.0e-5) { - return sl.shift_line_grad.at(i); - } // use theoretical value when ds is too small. - return (sl.shift_line.at(i) - sl.shift_line.at(i - 1)) / ds; - }; - - const auto forward_grad = [&](const size_t i) { - if (i == arcs.size() - 1) { - return sl.shift_line_grad.at(i); - } - const double ds = arcs.at(i + 1) - arcs.at(i); - if (ds < 1.0e-5) { - return sl.shift_line_grad.at(i); - } // use theoretical value when ds is too small. - return (sl.shift_line.at(i + 1) - sl.shift_line.at(i)) / ds; - }; - - // calculate forward and backward gradient of the shift length. - // This will be used for grad-change-point check. - sl.forward_grad = std::vector(N, 0.0); - sl.backward_grad = std::vector(N, 0.0); - for (size_t i = 0; i < N - 1; ++i) { - sl.forward_grad.at(i) = forward_grad(i); - sl.backward_grad.at(i) = backward_grad(i); - } - - AvoidLineArray merged_avoid_lines; - AvoidLine al{}; - bool found_first_start = false; - constexpr auto CREATE_SHIFT_GRAD_THR = 0.001; - constexpr auto IS_ALREADY_SHIFTING_THR = 0.001; - for (size_t i = avoid_data_.ego_closest_path_index; i < N - 1; ++i) { - const auto & p = path.points.at(i).point.pose; - const auto shift = sl.shift_line.at(i); - - // If the vehicle is already on the avoidance (checked by the first point has shift), - // set a start point at the first path point. - if (!found_first_start && std::abs(shift) > IS_ALREADY_SHIFTING_THR) { - setStartData(al, 0.0, p, i, arcs.at(i)); // start length is overwritten later. - found_first_start = true; - DEBUG_PRINT("shift (= %f) is not zero at i = %lu. set start shift here.", shift, i); - } - - // find the point where the gradient of the shift is changed - const bool set_shift_line_flag = - std::abs(sl.forward_grad.at(i) - sl.backward_grad.at(i)) > CREATE_SHIFT_GRAD_THR; - - if (!set_shift_line_flag) { - continue; - } - - if (!found_first_start) { - setStartData(al, 0.0, p, i, arcs.at(i)); // start length is overwritten later. - found_first_start = true; - DEBUG_PRINT("grad change detected. start at i = %lu", i); - } else { - setEndData(al, shift, p, i, arcs.at(i)); - al.id = getOriginalShiftLineUniqueId(); - merged_avoid_lines.push_back(al); - setStartData(al, 0.0, p, i, arcs.at(i)); // start length is overwritten later. - DEBUG_PRINT("end and start point found at i = %lu", i); - } - } - - if (std::abs(backward_grad(N - 1)) > CREATE_SHIFT_GRAD_THR) { - const auto & p = path.points.at(N - 1).point.pose; - const auto shift = sl.shift_line.at(N - 1); - setEndData(al, shift, p, N - 1, arcs.at(N - 1)); - al.id = getOriginalShiftLineUniqueId(); - merged_avoid_lines.push_back(al); - } - - return merged_avoid_lines; -} - -AvoidOutlines AvoidanceModule::applyMergeProcess( - const AvoidOutlines & outlines, DebugData & debug) const -{ - AvoidOutlines ret{}; - - if (outlines.size() < 2) { - return outlines; - } - - const auto no_conflict = [](const auto & line1, const auto & line2) { - return line1.end_idx < line2.start_idx || line2.end_idx < line1.start_idx; - }; - - const auto same_side_shift = [](const auto & line1, const auto & line2) { - return line1.object_on_right == line2.object_on_right; - }; - - const auto within = [](const auto & line, const size_t idx) { - return line.start_idx < idx && idx < line.end_idx; - }; - - ret.push_back(outlines.front()); - - for (size_t i = 1; i < outlines.size(); i++) { - auto & last_outline = ret.back(); - auto & next_outline = outlines.at(i); - - const auto & return_line = last_outline.return_line; - const auto & avoid_line = next_outline.avoid_line; - - if (no_conflict(return_line, avoid_line)) { - ret.push_back(outlines.at(i)); - continue; - } - - const auto merged_shift_line = merge(return_line, avoid_line, getOriginalShiftLineUniqueId()); - - if (!isComfortable(AvoidLineArray{merged_shift_line})) { - ret.push_back(outlines.at(i)); - continue; - } - - if (same_side_shift(return_line, 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)) { - 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)) { - 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; - } - } - - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, ret); - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, debug.step1_merged_shift_line); - - return ret; -} - -AvoidOutlines AvoidanceModule::applyFillGapProcess( - const AvoidOutlines & outlines, DebugData & debug) const -{ - AvoidOutlines ret = outlines; - - for (auto & outline : ret) { - if (outline.middle_lines.empty()) { - const auto new_line = - fill(outline.avoid_line, outline.return_line, getOriginalShiftLineUniqueId()); - outline.middle_lines.push_back(new_line); - debug.step1_filled_shift_line.push_back(new_line); - } - - helper_.alignShiftLinesOrder(outline.middle_lines, false); - - if (outline.avoid_line.end_longitudinal < outline.middle_lines.front().start_longitudinal) { - const auto new_line = - fill(outline.avoid_line, outline.middle_lines.front(), getOriginalShiftLineUniqueId()); - outline.middle_lines.push_back(new_line); - debug.step1_filled_shift_line.push_back(new_line); - } - - 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, getOriginalShiftLineUniqueId()); - outline.middle_lines.push_back(new_line); - debug.step1_filled_shift_line.push_back(new_line); - } - - helper_.alignShiftLinesOrder(outline.middle_lines, false); - } - - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, ret); - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, debug.step1_filled_shift_line); - - return ret; -} - -AvoidLineArray AvoidanceModule::applyFillGapProcess( - const AvoidLineArray & shift_lines, DebugData & debug) const -{ - AvoidLineArray sorted = shift_lines; - - helper_.alignShiftLinesOrder(sorted, false); - - AvoidLineArray ret = sorted; - - if (shift_lines.empty()) { - return ret; - } - - const auto & data = avoid_data_; - - // fill gap between ego and nearest shift line. - if (sorted.front().start_longitudinal > 0.0) { - AvoidLine ego_line{}; - utils::avoidance::setEndData( - ego_line, helper_.getEgoLinearShift(), data.reference_pose, data.ego_closest_path_index, 0.0); - - const auto new_line = fill(ego_line, sorted.front(), getOriginalShiftLineUniqueId()); - ret.push_back(new_line); - debug.step1_front_shift_line.push_back(new_line); - } - - helper_.alignShiftLinesOrder(sorted, false); - - // fill gap among shift lines. - for (size_t i = 0; i < sorted.size() - 1; ++i) { - if (sorted.at(i + 1).start_longitudinal < sorted.at(i).end_longitudinal) { - continue; - } - - const auto new_line = fill(sorted.at(i), sorted.at(i + 1), getOriginalShiftLineUniqueId()); - ret.push_back(new_line); - debug.step1_front_shift_line.push_back(new_line); - } - - helper_.alignShiftLinesOrder(ret, false); - - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, ret); - utils::avoidance::fillAdditionalInfoFromLongitudinal(avoid_data_, debug.step1_front_shift_line); - - return ret; -} - -AvoidLineArray AvoidanceModule::applyCombineProcess( - const AvoidLineArray & shift_lines, const AvoidLineArray & registered_lines, - DebugData & debug) const -{ - debug.step1_registered_shift_line = registered_lines; - return utils::avoidance::combineRawShiftLinesWithUniqueCheck(registered_lines, shift_lines); -} - -AvoidLineArray AvoidanceModule::applyMergeProcess( - const AvoidLineArray & shift_lines, DebugData & debug) const -{ - // Generate shift line by merging shift_lines. - ShiftLineData shift_line_data; - generateTotalShiftLine(shift_lines, shift_line_data); - - // Re-generate shift points by detecting gradient-change point of the shift line. - auto merged_shift_lines = extractShiftLinesFromLine(shift_line_data); - - // set parent id - for (auto & al : merged_shift_lines) { - al.parent_ids = utils::avoidance::calcParentIds(shift_lines, al); - } - - // sort by distance from ego. - helper_.alignShiftLinesOrder(merged_shift_lines); - - // debug visualize - { - debug.pos_shift = shift_line_data.pos_shift_line; - debug.neg_shift = shift_line_data.neg_shift_line; - debug.total_shift = shift_line_data.shift_line; - debug.pos_shift_grad = shift_line_data.pos_shift_line_grad; - debug.neg_shift_grad = shift_line_data.neg_shift_line_grad; - debug.total_forward_grad = shift_line_data.forward_grad; - debug.total_backward_grad = shift_line_data.backward_grad; - debug.step2_merged_shift_line = merged_shift_lines; - } - - return merged_shift_lines; -} - -AvoidLineArray AvoidanceModule::applyTrimProcess( - const AvoidLineArray & shift_lines, DebugData & debug) const -{ - if (shift_lines.empty()) { - return shift_lines; - } - - AvoidLineArray sl_array_trimmed = shift_lines; - - // sort shift points from front to back. - helper_.alignShiftLinesOrder(sl_array_trimmed); - - // - Change the shift length to the previous one if the deviation is small. - { - constexpr double SHIFT_DIFF_THRES = 1.0; - applySmallShiftFilter(sl_array_trimmed, SHIFT_DIFF_THRES); - } + const auto can_yield_maneuver = canYieldManeuver(data); - // - Combine avoid points that have almost same gradient. - // this is to remove the noise. - { - const auto THRESHOLD = parameters_->same_grad_filter_1_threshold; - applySimilarGradFilter(sl_array_trimmed, THRESHOLD); - debug.step3_grad_filtered_1st = sl_array_trimmed; + /** + * If the output path is locked by outside of this module, don't update output path. + */ + if (isOutputPathLocked()) { + data.safe_shift_line.clear(); + data.candidate_path = helper_->getPreviousSplineShiftPath(); + RCLCPP_DEBUG_THROTTLE( + getLogger(), *clock_, 500, "this module is locked now. keep current path."); + return; } - // - Quantize the shift length to reduce the shift point noise - // This is to remove the noise coming from detection accuracy, interpolation, resampling, etc. - { - const auto THRESHOLD = parameters_->quantize_filter_threshold; - applyQuantizeProcess(sl_array_trimmed, THRESHOLD); - debug.step3_quantize_filtered = sl_array_trimmed; + /** + * If the avoidance path is safe, use unapproved_new_sl for avoidance path generation. + */ + if (data.safe) { + data.yield_required = false; + data.safe_shift_line = data.new_shift_line; + return; } - // - Change the shift length to the previous one if the deviation is small. - { - constexpr double SHIFT_DIFF_THRES = 1.0; - applySmallShiftFilter(sl_array_trimmed, SHIFT_DIFF_THRES); - debug.step3_noise_filtered = sl_array_trimmed; + /** + * If the yield maneuver is disabled, use unapproved_new_sl for avoidance path generation even if + * the shift line is unsafe. + */ + if (!parameters_->enable_yield_maneuver) { + data.yield_required = false; + data.safe_shift_line = data.new_shift_line; + return; } - // - Combine avoid points that have almost same gradient (again) - { - const auto THRESHOLD = parameters_->same_grad_filter_2_threshold; - applySimilarGradFilter(sl_array_trimmed, THRESHOLD); - debug.step3_grad_filtered_2nd = sl_array_trimmed; + /** + * TODO(Satoshi OTA) Think yield maneuver in the middle of avoidance. + * Even if it is determined that a yield is necessary, the yield maneuver is not executed + * if the avoidance has already been initiated. + */ + if (!can_yield_maneuver) { + data.safe = true; // overwrite safety judge. + data.yield_required = false; + data.safe_shift_line = data.new_shift_line; + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "unsafe. but could not transit yield status."); + return; } - // - Combine avoid points that have almost same gradient (again) + /** + * Transit yield maneuver. Clear shift lines and output yield path. + */ { - const auto THRESHOLD = parameters_->same_grad_filter_3_threshold; - applySimilarGradFilter(sl_array_trimmed, THRESHOLD); - debug.step3_grad_filtered_3rd = sl_array_trimmed; + data.yield_required = true; + data.safe_shift_line = data.new_shift_line; } - return sl_array_trimmed; -} - -void AvoidanceModule::applyQuantizeProcess( - AvoidLineArray & shift_lines, const double threshold) const -{ - if (threshold < 1.0e-5) { - return; // no need to process + /** + * Even if data.avoid_required is false, the module cancels registered shift point when the + * approved avoidance path is not safe. + */ + const auto approved_path_exist = !path_shifter_.getShiftLines().empty(); + if (approved_path_exist) { + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe. canceling approved path..."); + return; } - for (auto & sl : shift_lines) { - sl.end_shift_length = std::round(sl.end_shift_length / threshold) * threshold; + /** + * If the avoidance path is not safe in situation where the ego should avoid object, the ego + * stops in front of the front object with the necessary distance to avoid the object. + */ + { + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe. transit yield maneuver..."); } - - helper_.alignShiftLinesOrder(shift_lines); } -void AvoidanceModule::applySmallShiftFilter( - AvoidLineArray & shift_lines, const double threshold) const +void AvoidanceModule::fillDebugData( + const AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { - if (shift_lines.empty()) { + if (!data.stop_target_object) { return; } - AvoidLineArray input = shift_lines; - shift_lines.clear(); - - for (const auto & s : input) { - if (s.getRelativeLongitudinal() < threshold) { - continue; - } - - if (s.start_longitudinal < helper_.getMinimumPrepareDistance()) { - continue; - } - - shift_lines.push_back(s); + if (helper_->isShifted()) { + return; } -} -void AvoidanceModule::applySimilarGradFilter( - AvoidLineArray & avoid_lines, const double threshold) const -{ - if (avoid_lines.empty()) { + if (data.new_shift_line.empty()) { return; } - AvoidLineArray input = avoid_lines; - avoid_lines.clear(); - avoid_lines.push_back(input.front()); // Take the first one anyway (think later) - - AvoidLine base_line = input.front(); - - AvoidLineArray combine_buffer; - combine_buffer.push_back(input.front()); - - constexpr auto SHIFT_THR = 1e-3; - const auto is_negative_shift = [&](const auto & s) { - return s.getRelativeLength() < -1.0 * SHIFT_THR; - }; - - const auto is_positive_shift = [&](const auto & s) { return s.getRelativeLength() > SHIFT_THR; }; - - for (size_t i = 1; i < input.size(); ++i) { - AvoidLine combine{}; - - utils::avoidance::setStartData( - combine, base_line.start_shift_length, base_line.start, base_line.start_idx, - base_line.start_longitudinal); - utils::avoidance::setEndData( - combine, input.at(i).end_shift_length, input.at(i).end, input.at(i).end_idx, - input.at(i).end_longitudinal); - - combine_buffer.push_back(input.at(i)); + const auto o_front = data.stop_target_object.get(); + const auto object_type = utils::getHighestProbLabel(o_front.object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal + ? planner_data_->parameters.base_link2front + : 0.0; + const auto & vehicle_width = planner_data_->parameters.vehicle_width; - const auto violates = [&]() { - if (is_negative_shift(input.at(i)) && is_positive_shift(base_line)) { - return true; - } + const auto max_avoid_margin = object_parameter.safety_buffer_lateral * o_front.distance_factor + + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; - if (is_negative_shift(base_line) && is_positive_shift(input.at(i))) { - return true; - } + const auto variable = helper_->getSharpAvoidanceDistance( + helper_->getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin)); + const auto constant = helper_->getNominalPrepareDistance() + + object_parameter.safety_buffer_longitudinal + + additional_buffer_longitudinal; + const auto total_avoid_distance = variable + constant; - const auto lon_combine = combine.getRelativeLongitudinal(); - const auto base_length = base_line.getGradient() * lon_combine; - return std::abs(combine.getRelativeLength() - base_length) > threshold; - }(); + dead_pose_ = calcLongitudinalOffsetPose( + data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance); - if (violates) { - avoid_lines.push_back(input.at(i)); - base_line = input.at(i); - combine_buffer.clear(); - combine_buffer.push_back(input.at(i)); - } else { - avoid_lines.back() = combine; - } + if (!dead_pose_) { + dead_pose_ = getPose(data.reference_path.points.front()); } - - helper_.alignShiftLinesOrder(avoid_lines); - - DEBUG_PRINT("size %lu -> %lu", input.size(), avoid_lines.size()); } -AvoidLineArray AvoidanceModule::addReturnShiftLine( - const AvoidLineArray & shift_lines, DebugData & debug) const +AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & data) const { - AvoidLineArray ret = shift_lines; - - constexpr double ep = 1.0e-3; - const auto & data = avoid_data_; - const bool has_candidate_point = !ret.empty(); - const bool has_registered_point = !path_shifter_.getShiftLines().empty(); - - 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; }); + if (data.yield_required) { + return AvoidanceState::YIELD; + } - if (exist_unavoidable_object) { - return ret; + if (!data.avoid_required) { + return AvoidanceState::NOT_AVOID; } - // If the return-to-center shift points are already registered, do nothing. - if (!has_registered_point && std::fabs(getCurrentBaseShift()) < ep) { - DEBUG_PRINT("No shift points, not base offset. Do not have to add return-shift."); - return ret; + if (!data.found_avoidance_path) { + return AvoidanceState::AVOID_PATH_NOT_READY; } - constexpr double RETURN_SHIFT_THRESHOLD = 0.1; - DEBUG_PRINT("registered last shift = %f", path_shifter_.getLastShiftLength()); - if (std::abs(path_shifter_.getLastShiftLength()) < RETURN_SHIFT_THRESHOLD) { - DEBUG_PRINT("Return shift is already registered. do nothing."); - return ret; + if (isWaitingApproval() && path_shifter_.getShiftLines().empty()) { + return AvoidanceState::AVOID_PATH_READY; } - // From here, the return-to-center is not registered. But perhaps the candidate is - // already generated. + return AvoidanceState::AVOID_EXECUTE; +} - // If it has a shift point, add return shift from the existing last shift point. - // If not, add return shift from ego point. (prepare distance is considered for both.) - ShiftLine last_sl; // the return-shift will be generated after the last shift point. - { - // avoidance points: Yes, shift points: No -> select last avoidance point. - if (has_candidate_point && !has_registered_point) { - helper_.alignShiftLinesOrder(ret, false); - last_sl = ret.back(); - } +void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, ShiftedPath & path) +{ + if (parameters_->disable_path_update) { + return; + } - // avoidance points: No, shift points: Yes -> select last shift point. - if (!has_candidate_point && has_registered_point) { - last_sl = utils::avoidance::fillAdditionalInfo( - data, AvoidLine{path_shifter_.getLastShiftLine().get()}); - } + insertPrepareVelocity(path); - // avoidance points: Yes, shift points: Yes -> select the last one from both. - if (has_candidate_point && has_registered_point) { - helper_.alignShiftLinesOrder(ret, false); - const auto & al = ret.back(); - const auto & sl = utils::avoidance::fillAdditionalInfo( - data, AvoidLine{path_shifter_.getLastShiftLine().get()}); - last_sl = (sl.end_longitudinal > al.end_longitudinal) ? sl : al; + switch (data.state) { + case AvoidanceState::NOT_AVOID: { + break; } - - // avoidance points: No, shift points: No -> set the ego position to the last shift point - // so that the return-shift will be generated from ego position. - if (!has_candidate_point && !has_registered_point) { - last_sl.end_idx = avoid_data_.ego_closest_path_index; - last_sl.end = avoid_data_.reference_path.points.at(last_sl.end_idx).point.pose; - last_sl.end_shift_length = getCurrentBaseShift(); + case AvoidanceState::YIELD: { + insertYieldVelocity(path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); + break; } - } - - // 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. - if (std::fabs(last_sl.end_shift_length) < RETURN_SHIFT_THRESHOLD) { - const auto current_base_shift = helper_.getEgoShift(); - if (std::abs(current_base_shift) < ep) { - DEBUG_PRINT("last shift almost is zero, and current base_shift is zero. do nothing."); - return ret; + case AvoidanceState::AVOID_PATH_NOT_READY: { + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); + break; } - - // Is there a shift point in the opposite direction of the current_base_shift? - // No -> we can overwrite the return shift, because the other shift points that decrease - // the shift length are for return-shift. - // Yes -> we can NOT overwrite, because it might be not a return-shift, but a avoiding - // shift to the opposite direction which can not be overwritten by the return-shift. - for (const auto & sl : ret) { - if ( - (current_base_shift > 0.0 && sl.end_shift_length < -ep) || - (current_base_shift < 0.0 && sl.end_shift_length > ep)) { - DEBUG_PRINT( - "try to put overwrite return shift, but there is shift for opposite direction. Skip " - "adding return shift."); - return ret; - } + case AvoidanceState::AVOID_PATH_READY: { + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); + break; } - - // If return shift already exists in candidate or registered shift lines, skip adding return - // shift. - if (has_candidate_point || has_registered_point) { - return ret; + case AvoidanceState::AVOID_EXECUTE: { + insertStopPoint(isBestEffort(parameters_->policy_deceleration), path); + break; } - - // set the return-shift from ego. - DEBUG_PRINT( - "return shift already exists, but they are all candidates. Add return shift for overwrite."); - last_sl.end_idx = avoid_data_.ego_closest_path_index; - last_sl.end = avoid_data_.reference_path.points.at(last_sl.end_idx).point.pose; - last_sl.end_shift_length = current_base_shift; - } - - const auto & arclength_from_ego = avoid_data_.arclength_from_ego; - - const auto nominal_prepare_distance = helper_.getNominalPrepareDistance(); - const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(last_sl.end_shift_length); - - if (arclength_from_ego.empty()) { - return ret; - } - - const auto remaining_distance = std::min( - arclength_from_ego.back() - parameters_->dead_line_buffer_for_goal, - avoid_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 = avoid_data_.arclength_from_ego.at(last_sl.end_idx); - - // check if there is enough distance for return. - if (last_sl_distance > remaining_distance) { // tmp: add some small number (+1.0) - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 1000, "No enough distance for return."); - return ret; + default: + throw std::domain_error("invalid behavior"); } - // If the remaining distance is not enough, the return shift needs to be shrunk. - // (or another option is just to ignore the return-shift.) - // But we do not want to change the last shift point, so we will shrink the distance after - // the last shift point. - // - // The line "===" is fixed, "---" is scaled. - // - // [Before Scaling] - // ego last_sl_end prepare_end path_end avoid_end - // ==o====================o----------------------o----------------------o------------o - // | prepare_dist | avoid_dist | - // - // [After Scaling] - // ==o====================o------------------o--------------------------o - // | prepare_dist_scaled | avoid_dist_scaled | - // - 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 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; - avoid_distance_scaled *= scale; - DEBUG_PRINT( - "last_sl_distance = %f, nominal_prepare_distance = %f, nominal_avoid_distance = %f, " - "remaining_distance = %f, variable_prepare_distance = %f, scale = %f, " - "prepare_distance_scaled = %f,avoid_distance_scaled = %f", - last_sl_distance, nominal_prepare_distance, nominal_avoid_distance, remaining_distance, - variable_prepare_distance, scale, prepare_distance_scaled, avoid_distance_scaled); - } else { - DEBUG_PRINT("there is enough distance. Use nominal for prepare & avoidance."); - } - - // shift point for prepare distance: from last shift to return-start point. - if (nominal_prepare_distance > last_sl_distance) { - AvoidLine al; - al.id = getOriginalShiftLineUniqueId(); - al.start_idx = last_sl.end_idx; - al.start = last_sl.end; - al.start_longitudinal = arclength_from_ego.at(al.start_idx); - al.end_idx = - utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); - al.end = avoid_data_.reference_path.points.at(al.end_idx).point.pose; - al.end_longitudinal = arclength_from_ego.at(al.end_idx); - al.end_shift_length = last_sl.end_shift_length; - al.start_shift_length = last_sl.end_shift_length; - ret.push_back(al); - debug.step1_return_shift_line.push_back(al); - } - - // shift point for return to center line - { - AvoidLine al; - al.id = getOriginalShiftLineUniqueId(); - al.start_idx = - utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); - al.start = avoid_data_.reference_path.points.at(al.start_idx).point.pose; - al.start_longitudinal = arclength_from_ego.at(al.start_idx); - al.end_idx = utils::avoidance::findPathIndexFromArclength( - arclength_from_ego, prepare_distance_scaled + avoid_distance_scaled); - al.end = avoid_data_.reference_path.points.at(al.end_idx).point.pose; - al.end_longitudinal = arclength_from_ego.at(al.end_idx); - al.end_shift_length = 0.0; - al.start_shift_length = last_sl.end_shift_length; - ret.push_back(al); - debug.step1_return_shift_line.push_back(al); - } + insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); - return ret; + setStopReason(StopReason::AVOIDANCE, path.path); } bool AvoidanceModule::isSafePath( @@ -2048,7 +791,7 @@ bool AvoidanceModule::isSafePath( PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & original_path) const { - const auto previous_path = helper_.getPreviousReferencePath(); + const auto previous_path = helper_->getPreviousReferencePath(); const auto longest_dist_to_shift_point = [&]() { double max_dist = 0.0; @@ -2056,7 +799,7 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig max_dist = std::max( max_dist, calcSignedArcLength(previous_path.points, pnt.start.position, getEgoPosition())); } - for (const auto & sp : registered_raw_shift_lines_) { + for (const auto & sp : generator_.getRawRegisteredShiftLine()) { max_dist = std::max( max_dist, calcSignedArcLength(previous_path.points, sp.start.position, getEgoPosition())); } @@ -2128,11 +871,11 @@ BehaviorModuleOutput AvoidanceModule::plan() // set previous data 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_->setPreviousLinearShiftPath(linear_shift_path); + helper_->setPreviousSplineShiftPath(spline_shift_path); + helper_->setPreviousReferencePath(data.reference_path); } else { - spline_shift_path = helper_.getPreviousSplineShiftPath(); + spline_shift_path = helper_->getPreviousSplineShiftPath(); } // post processing @@ -2168,7 +911,7 @@ BehaviorModuleOutput AvoidanceModule::plan() updateDebugMarker(avoid_data_, path_shifter_, debug_data_); } - if (isDrivingSameLane(helper_.getPreviousDrivingLanes(), data.current_lanelets)) { + if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { output.path = std::make_shared(spline_shift_path.path); } else { output.path = getPreviousModuleOutput().path; @@ -2222,14 +965,14 @@ CandidateOutput AvoidanceModule::planCandidate() const return output; } - const auto sl = helper_.getMainShiftLine(data.safe_shift_line); + const auto sl = helper_->getMainShiftLine(data.safe_shift_line); const auto sl_front = data.safe_shift_line.front(); const auto sl_back = data.safe_shift_line.back(); utils::clipPathLength( shifted_path.path, sl_front.start_idx, std::numeric_limits::max(), 0.0); - output.lateral_shift = helper_.getRelativeShiftToPath(sl); + output.lateral_shift = helper_->getRelativeShiftToPath(sl); output.start_distance_to_path_change = sl_front.start_longitudinal; output.finish_distance_to_path_change = sl_back.end_longitudinal; @@ -2276,17 +1019,15 @@ void AvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) addNewShiftLines(path_shifter_, shift_lines); - current_raw_shift_lines_ = avoid_data_.raw_shift_line; - - registerRawShiftLines(shift_lines); + generator_.setRawRegisteredShiftLine(shift_lines, avoid_data_); - const auto sl = helper_.getMainShiftLine(shift_lines); + const auto sl = helper_->getMainShiftLine(shift_lines); const auto sl_front = shift_lines.front(); const auto sl_back = shift_lines.back(); - if (helper_.getRelativeShiftToPath(sl) > 0.0) { + if (helper_->getRelativeShiftToPath(sl) > 0.0) { left_shift_array_.push_back({uuid_map_.at("left"), sl_front.start, sl_back.end}); - } else if (helper_.getRelativeShiftToPath(sl) < 0.0) { + } else if (helper_->getRelativeShiftToPath(sl) < 0.0) { right_shift_array_.push_back({uuid_map_.at("right"), sl_front.start, sl_back.end}); } @@ -2354,101 +1095,15 @@ void AvoidanceModule::addNewShiftLines( const double road_velocity = avoid_data_.reference_path.points.at(front_new_shift_line.start_idx) .point.longitudinal_velocity_mps; const double shift_time = PathShifter::calcShiftTimeFromJerk( - front_new_shift_line.getRelativeLength(), helper_.getLateralMaxJerkLimit(), - helper_.getLateralMaxAccelLimit()); + front_new_shift_line.getRelativeLength(), helper_->getLateralMaxJerkLimit(), + helper_->getLateralMaxAccelLimit()); const double longitudinal_acc = std::clamp(road_velocity / shift_time, 0.0, parameters_->max_acceleration); path_shifter.setShiftLines(future); path_shifter.setVelocity(getEgoSpeed()); path_shifter.setLongitudinalAcceleration(longitudinal_acc); - path_shifter.setLateralAccelerationLimit(helper_.getLateralMaxAccelLimit()); -} - -AvoidLineArray AvoidanceModule::findNewShiftLine( - const AvoidLineArray & shift_lines, DebugData & debug) const -{ - if (shift_lines.empty()) { - return {}; - } - - // add small shift lines. - const auto add_straight_shift = - [&, this](auto & subsequent, bool has_large_shift, const size_t start_idx) { - for (size_t i = start_idx; i < shift_lines.size(); ++i) { - if ( - std::abs(shift_lines.at(i).getRelativeLength()) > - parameters_->lateral_small_shift_threshold) { - if (has_large_shift) { - return; - } - - has_large_shift = true; - } - - if (!isComfortable(AvoidLineArray{shift_lines.at(i)})) { - return; - } - - subsequent.push_back(shift_lines.at(i)); - } - }; - - // get subsequent shift lines. - const auto get_subsequent_shift = [&, this](size_t i) { - AvoidLineArray subsequent{shift_lines.at(i)}; - - if (!isComfortable(subsequent)) { - return subsequent; - } - - if (shift_lines.size() == i + 1) { - return subsequent; - } - - if (!isComfortable(AvoidLineArray{shift_lines.at(i + 1)})) { - return subsequent; - } - - if ( - std::abs(shift_lines.at(i).getRelativeLength()) < - parameters_->lateral_small_shift_threshold) { - const auto has_large_shift = - shift_lines.at(i + 1).getRelativeLength() > parameters_->lateral_small_shift_threshold; - - // candidate.at(i) is small length shift line. add large length shift line. - subsequent.push_back(shift_lines.at(i + 1)); - add_straight_shift(subsequent, has_large_shift, i + 2); - } else { - // candidate.at(i) is large length shift line. add small length shift lines. - add_straight_shift(subsequent, true, i + 1); - } - - return subsequent; - }; - - // check ignore or not. - const auto is_ignore_shift = [this](const auto & s) { - return std::abs(helper_.getRelativeShiftToPath(s)) < parameters_->lateral_execution_threshold; - }; - - for (size_t i = 0; i < shift_lines.size(); ++i) { - const auto & candidate = shift_lines.at(i); - - // prevent sudden steering. - if (candidate.start_longitudinal < helper_.getMinimumPrepareDistance()) { - break; - } - - if (!is_ignore_shift(candidate)) { - const auto new_shift_lines = get_subsequent_shift(i); - debug.step4_new_shift_line = new_shift_lines; - return new_shift_lines; - } - } - - DEBUG_PRINT("No new shift point exists."); - return {}; + path_shifter.setLateralAccelerationLimit(helper_->getLateralMaxAccelLimit()); } bool AvoidanceModule::isValidShiftLine( @@ -2473,7 +1128,7 @@ bool AvoidanceModule::isValidShiftLine( const auto new_shift_length = proposed_shift_path.shift_length.at(new_idx); constexpr double THRESHOLD = 0.1; - const auto offset = std::abs(new_shift_length - helper_.getEgoShift()); + const auto offset = std::abs(new_shift_length - helper_->getEgoShift()); if (offset > THRESHOLD) { RCLCPP_DEBUG_THROTTLE( getLogger(), *clock_, 1000, "new shift line is invalid. [HUGE OFFSET (%.2f)]", offset); @@ -2514,13 +1169,13 @@ void AvoidanceModule::updateData() { using utils::avoidance::toShiftedPath; - helper_.setData(planner_data_); + helper_->setData(planner_data_); - if (!helper_.isInitialized()) { - helper_.setPreviousSplineShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); - helper_.setPreviousLinearShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); - helper_.setPreviousReferencePath(*getPreviousModuleOutput().path); - helper_.setPreviousDrivingLanes(utils::avoidance::getCurrentLanesFromPath( + if (!helper_->isInitialized()) { + helper_->setPreviousSplineShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); + helper_->setPreviousLinearShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); + helper_->setPreviousReferencePath(*getPreviousModuleOutput().path); + helper_->setPreviousDrivingLanes(utils::avoidance::getCurrentLanesFromPath( *getPreviousModuleOutput().reference_path, planner_data_)); } @@ -2535,8 +1190,11 @@ void AvoidanceModule::updateData() return; } - // update registered shift point for new reference path & remove past objects - updateRegisteredRawShiftLines(); + // update shift line generator. + generator_.setData(planner_data_); + generator_.setPathShifter(path_shifter_); + generator_.setHelper(helper_); + generator_.update(avoid_data_, debug_data_); // update shift line and check path safety. fillShiftLine(avoid_data_, debug_data_); @@ -2567,16 +1225,13 @@ void AvoidanceModule::processOnExit() void AvoidanceModule::initVariables() { - helper_.reset(); + helper_->reset(); + generator_.reset(); path_shifter_ = PathShifter{}; - debug_data_ = DebugData(); debug_marker_.markers.clear(); resetPathCandidate(); resetPathReference(); - registered_raw_shift_lines_ = {}; - current_raw_shift_lines_ = {}; - original_unique_id = 0; is_avoidance_maneuver_starts = false; arrived_path_end_ = false; } @@ -2594,7 +1249,7 @@ void AvoidanceModule::updateRTCData() { const auto & data = avoid_data_; - updateRegisteredRTCStatus(helper_.getPreviousSplineShiftPath().path); + updateRegisteredRTCStatus(helper_->getPreviousSplineShiftPath().path); const auto candidates = data.safe ? data.safe_shift_line : data.new_shift_line; @@ -2603,10 +1258,10 @@ void AvoidanceModule::updateRTCData() return; } - const auto shift_line = helper_.getMainShiftLine(candidates); - if (helper_.getRelativeShiftToPath(shift_line) > 0.0) { + const auto shift_line = helper_->getMainShiftLine(candidates); + if (helper_->getRelativeShiftToPath(shift_line) > 0.0) { removePreviousRTCStatusRight(); - } else if (helper_.getRelativeShiftToPath(shift_line) < 0.0) { + } else if (helper_->getRelativeShiftToPath(shift_line) < 0.0) { removePreviousRTCStatusLeft(); } else { RCLCPP_WARN_STREAM(getLogger(), "Direction is UNKNOWN"); @@ -2618,7 +1273,7 @@ void AvoidanceModule::updateRTCData() const auto sl_back = candidates.back(); output.path_candidate = data.candidate_path.path; - output.lateral_shift = helper_.getRelativeShiftToPath(shift_line); + output.lateral_shift = helper_->getRelativeShiftToPath(shift_line); output.start_distance_to_path_change = sl_front.start_longitudinal; output.finish_distance_to_path_change = sl_back.end_longitudinal; @@ -2636,7 +1291,7 @@ TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) con 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 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; @@ -2749,138 +1404,13 @@ void AvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const void AvoidanceModule::updateDebugMarker( const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) const { - using marker_utils::createLaneletsAreaMarkerArray; - using marker_utils::createObjectsMarkerArray; - using marker_utils::createPathMarkerArray; - using marker_utils::createPolygonMarkerArray; - using marker_utils::createPoseMarkerArray; - using marker_utils::createShiftGradMarkerArray; - using marker_utils::createShiftLengthMarkerArray; - using marker_utils::createShiftLineMarkerArray; - using marker_utils::showPolygon; - using marker_utils::showPredictedPath; - using marker_utils::showSafetyCheckInfo; - using marker_utils::avoidance_marker::createAvoidLineMarkerArray; - using marker_utils::avoidance_marker::createEgoStatusMarkerArray; - using marker_utils::avoidance_marker::createOtherObjectsMarkerArray; - using marker_utils::avoidance_marker::createOverhangFurthestLineStringMarkerArray; - using marker_utils::avoidance_marker::createPredictedVehiclePositions; - using marker_utils::avoidance_marker::makeOverhangToRoadShoulderMarkerArray; - using tier4_autoware_utils::appendMarkerArray; - debug_marker_.markers.clear(); if (!parameters_->publish_debug_marker) { return; } - const auto & path = data.reference_path; - - const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); - - const auto add = [this](const MarkerArray & added) { appendMarkerArray(added, &debug_marker_); }; - - const auto addAvoidLine = - [&](const AvoidLineArray & al_arr, const auto & ns, auto r, auto g, auto b, double w = 0.05) { - add(createAvoidLineMarkerArray(al_arr, ns, r, g, b, w)); - }; - - const auto addShiftLine = - [&](const ShiftLineArray & sl_arr, const auto & ns, auto r, auto g, auto b, double w = 0.1) { - add(createShiftLineMarkerArray(sl_arr, shifter.getBaseOffset(), ns, r, g, b, w)); - }; - - const auto addObjects = [&](const ObjectDataArray & objects, const auto & ns) { - add(createOtherObjectsMarkerArray(objects, ns)); - }; - - const auto addShiftLength = - [&](const auto & shift_length, const auto & ns, auto r, auto g, auto b) { - add(createShiftLengthMarkerArray(shift_length, path, ns, r, g, b)); - }; - - const auto addShiftGrad = [&]( - const auto & shift_grad, const auto & shift_length, const auto & ns, - auto r, auto g, auto b) { - add(createShiftGradMarkerArray(shift_grad, shift_length, path, ns, r, g, b)); - }; - - // ignore objects - { - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL); - addObjects(data.other_objects, AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE); - addObjects(data.other_objects, AvoidanceDebugFactor::NOT_PARKING_OBJECT); - addObjects(data.other_objects, std::string("MovingObject")); - addObjects(data.other_objects, std::string("CrosswalkUser")); - addObjects(data.other_objects, std::string("OutOfTargetArea")); - addObjects(data.other_objects, std::string("NotNeedAvoidance")); - addObjects(data.other_objects, std::string("LessThanExecutionThreshold")); - addObjects(data.other_objects, std::string("TooNearToGoal")); - addObjects(data.other_objects, std::string("ParallelToEgoLane")); - } - - // shift line pre-process - { - addAvoidLine(debug.step1_registered_shift_line, "step1_registered_shift_line", 0.2, 0.2, 1.0); - addAvoidLine(debug.step1_current_shift_line, "step1_current_shift_line", 0.2, 0.4, 0.8, 0.3); - addAvoidLine(debug.step1_merged_shift_line, "step1_merged_shift_line", 0.2, 0.6, 0.6, 0.3); - addAvoidLine(debug.step1_filled_shift_line, "step1_filled_shift_line", 0.2, 0.8, 0.4, 0.3); - addAvoidLine(debug.step1_return_shift_line, "step1_return_shift_line", 0.2, 1.0, 0.2, 0.3); - } - - // merge process - { - addAvoidLine(debug.step2_merged_shift_line, "step2_merged_shift_line", 0.2, 1.0, 0.0, 0.3); - } - - // trimming process - { - addAvoidLine(debug.step3_grad_filtered_1st, "step3_grad_filtered_1st", 0.2, 0.8, 0.0, 0.3); - addAvoidLine(debug.step3_grad_filtered_2nd, "step3_grad_filtered_2nd", 0.4, 0.6, 0.0, 0.3); - addAvoidLine(debug.step3_grad_filtered_3rd, "step3_grad_filtered_3rd", 0.6, 0.4, 0.0, 0.3); - } - - // registering process - { - addShiftLine(shifter.getShiftLines(), "step4_old_shift_line", 1.0, 1.0, 0.0, 0.3); - addAvoidLine(data.raw_shift_line, "step4_raw_shift_line", 1.0, 0.0, 0.0, 0.3); - addAvoidLine(data.new_shift_line, "step4_new_shift_line", 1.0, 0.0, 0.0, 0.3); - } - - // safety check - { - add(showSafetyCheckInfo(debug.collision_check, "object_debug_info")); - add(showPredictedPath(debug.collision_check, "ego_predicted_path")); - add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation")); - } - - // shift length - { - addShiftLength(debug.pos_shift, "merged_length_pos", 0.0, 0.7, 0.5); - addShiftLength(debug.neg_shift, "merged_length_neg", 0.0, 0.5, 0.7); - addShiftLength(debug.total_shift, "merged_length_total", 0.99, 0.4, 0.2); - } - - // shift grad - { - addShiftGrad(debug.pos_shift_grad, debug.pos_shift, "merged_grad_pos", 0.0, 0.7, 0.5); - addShiftGrad(debug.neg_shift_grad, debug.neg_shift, "merged_grad_neg", 0.0, 0.5, 0.7); - addShiftGrad(debug.total_forward_grad, debug.total_shift, "grad_forward", 0.99, 0.4, 0.2); - addShiftGrad(debug.total_backward_grad, debug.total_shift, "grad_backward", 0.4, 0.2, 0.9); - } - - // misc - { - add(createEgoStatusMarkerArray(data, getEgoPose(), "ego_status")); - add(createPathMarkerArray(path, "centerline_resampled", 0, 0.0, 0.9, 0.5)); - add(createLaneletsAreaMarkerArray(*debug.current_lanelets, "current_lanelet", 0.0, 1.0, 0.0)); - add(createPolygonMarkerArray(debug.detection_area, "detection_area", 0L, 0.16, 1.0, 0.69, 0.1)); - add(makeOverhangToRoadShoulderMarkerArray(data.target_objects, "overhang")); - add(createOverhangFurthestLineStringMarkerArray(debug.bounds, "bounds", 1.0, 0.0, 1.0)); - } + debug_marker_ = marker_utils::avoidance_marker::createDebugMarkerArray(data, shifter, debug); } void AvoidanceModule::updateAvoidanceDebugData( @@ -2926,8 +1456,8 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; - const auto variable = helper_.getMinAvoidanceDistance( - helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); + const auto variable = helper_->getMinAvoidanceDistance( + helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); const auto & additional_buffer_longitudinal = object_parameter.use_conservative_buffer_longitudinal ? planner_data_->parameters.base_link2front @@ -2962,7 +1492,7 @@ 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); 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 @@ -2975,7 +1505,7 @@ void AvoidanceModule::insertReturnDeadLine( } // If the stop distance is not enough for comfortable stop, don't insert wait point. - const auto is_comfortable_stop = helper_.getFeasibleDecelDistance(0.0) < to_stop_line; + const auto is_comfortable_stop = helper_->getFeasibleDecelDistance(0.0) < to_stop_line; if (!is_comfortable_stop) { RCLCPP_DEBUG(getLogger(), "stop distance is not enough."); return; @@ -2986,7 +1516,7 @@ void AvoidanceModule::insertReturnDeadLine( // insert slow down speed. const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk( - shift_length, helper_.getLateralMinJerkLimit(), to_stop_line); + shift_length, helper_->getLateralMinJerkLimit(), to_stop_line); if (current_target_velocity < getEgoSpeed()) { RCLCPP_DEBUG(getLogger(), "current velocity exceeds target slow down speed."); return; @@ -3004,7 +1534,7 @@ void AvoidanceModule::insertReturnDeadLine( // target speed with nominal jerk limits. const double v_target = PathShifter::calcFeasibleVelocityFromJerk( - shift_length, helper_.getLateralMinJerkLimit(), shift_longitudinal_distance); + shift_length, helper_->getLateralMinJerkLimit(), shift_longitudinal_distance); const double v_original = shifted_path.path.points.at(i).point.longitudinal_velocity_mps; const double v_insert = std::max(v_target - parameters_->buf_slow_down_speed, parameters_->min_slow_down_speed); @@ -3022,7 +1552,7 @@ void AvoidanceModule::insertWaitPoint( return; } - if (helper_.isShifted()) { + if (helper_->isShifted()) { return; } @@ -3035,7 +1565,7 @@ void AvoidanceModule::insertWaitPoint( } // If the stop distance is not enough for comfortable stop, don't insert wait point. - const auto is_comfortable_stop = helper_.getFeasibleDecelDistance(0.0) < data.to_stop_line; + const auto is_comfortable_stop = helper_->getFeasibleDecelDistance(0.0) < data.to_stop_line; const auto is_slow_speed = getEgoSpeed() < parameters_->min_slow_down_speed; if (!is_comfortable_stop && !is_slow_speed) { RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "not execute uncomfortable deceleration."); @@ -3051,7 +1581,7 @@ void AvoidanceModule::insertWaitPoint( // If the object cannot be stopped for, calculate a "mild" deceleration distance // and insert a deceleration point at that distance - const auto stop_distance = helper_.getFeasibleDecelDistance(0.0, false); + const auto stop_distance = helper_->getFeasibleDecelDistance(0.0, false); utils::avoidance::insertDecelPoint( getEgoPosition(), stop_distance, 0.0, shifted_path.path, stop_pose_); } @@ -3094,7 +1624,7 @@ void AvoidanceModule::insertStopPoint( } // Otherwise, consider deceleration constraints before inserting deceleration point - const auto decel_distance = helper_.getFeasibleDecelDistance(0.0, false); + const auto decel_distance = helper_->getFeasibleDecelDistance(0.0, false); if (stop_distance < decel_distance) { return; } @@ -3113,11 +1643,11 @@ void AvoidanceModule::insertYieldVelocity(ShiftedPath & shifted_path) const return; } - if (helper_.isShifted()) { + if (helper_->isShifted()) { return; } - const auto decel_distance = helper_.getFeasibleDecelDistance(p->yield_velocity, false); + const auto decel_distance = helper_->getFeasibleDecelDistance(p->yield_velocity, false); utils::avoidance::insertDecelPoint( getEgoPosition(), decel_distance, p->yield_velocity, shifted_path.path, slow_pose_); } @@ -3132,7 +1662,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const } // insert slow down speed only when the avoidance maneuver is not initiated. - if (helper_.isShifted()) { + if (helper_->isShifted()) { return; } @@ -3156,13 +1686,13 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor + object_parameter.avoid_margin_lateral + 0.5 * vehicle_width; const auto shift_length = - helper_.getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin); + helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin); // check slow down feasibility - const auto min_avoid_distance = helper_.getMinAvoidanceDistance(shift_length); + const auto min_avoid_distance = helper_->getMinAvoidanceDistance(shift_length); const auto distance_to_object = object.longitudinal; const auto remaining_distance = distance_to_object - min_avoid_distance; - const auto decel_distance = helper_.getFeasibleDecelDistance(parameters_->velocity_map.front()); + const auto decel_distance = helper_->getFeasibleDecelDistance(parameters_->velocity_map.front()); if (remaining_distance < decel_distance) { return; } @@ -3172,7 +1702,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); + shift_length, helper_->getLateralMinJerkLimit(), distance_to_object); if (current_target_velocity < getEgoSpeed() && decel_distance < remaining_distance) { utils::avoidance::insertDecelPoint( getEgoPosition(), decel_distance, parameters_->velocity_map.front(), shifted_path.path, @@ -3192,7 +1722,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const // target speed with nominal jerk limits. const double v_target = PathShifter::calcFeasibleVelocityFromJerk( - shift_length, helper_.getLateralMinJerkLimit(), shift_longitudinal_distance); + shift_length, helper_->getLateralMinJerkLimit(), shift_longitudinal_distance); const double v_original = shifted_path.path.points.at(i).point.longitudinal_velocity_mps; const double v_insert = std::max(v_target - parameters_->buf_slow_down_speed, lower_speed); diff --git a/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp b/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp new file mode 100644 index 0000000000000..698bd3677096a --- /dev/null +++ b/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp @@ -0,0 +1,1318 @@ +// 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/utils/avoidance/shift_line_generator.hpp" + +#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_planner/utils/utils.hpp" + +#include + +#include + +namespace behavior_path_planner::utils::avoidance +{ + +using tier4_autoware_utils::generateUUID; +using tier4_autoware_utils::getPoint; +using tier4_planning_msgs::msg::AvoidanceDebugFactor; + +namespace +{ +bool isBestEffort(const std::string & policy) +{ + return policy == "best_effort"; +} + +AvoidLine merge(const AvoidLine & line1, const AvoidLine & line2, const UUID id) +{ + AvoidLine ret{}; + + ret.start_idx = line1.start_idx; + ret.start_shift_length = line1.start_shift_length; + ret.start_longitudinal = line1.start_longitudinal; + + ret.end_idx = line2.end_idx; + ret.end_shift_length = line2.end_shift_length; + ret.end_longitudinal = line2.end_longitudinal; + + ret.id = id; + ret.object = line1.object; + + return ret; +} + +AvoidLine fill(const AvoidLine & line1, const AvoidLine & line2, const UUID id) +{ + AvoidLine ret{}; + + ret.start_idx = line1.end_idx; + ret.start_shift_length = line1.end_shift_length; + ret.start_longitudinal = line1.end_longitudinal; + + ret.end_idx = line2.start_idx; + ret.end_shift_length = line2.start_shift_length; + ret.end_longitudinal = line2.start_longitudinal; + + ret.id = id; + ret.object = line1.object; + + return ret; +} + +AvoidLineArray toArray(const AvoidOutlines & outlines) +{ + AvoidLineArray ret{}; + for (const auto & outline : outlines) { + ret.push_back(outline.avoid_line); + ret.push_back(outline.return_line); + + std::for_each( + outline.middle_lines.begin(), outline.middle_lines.end(), + [&ret](const auto & line) { ret.push_back(line); }); + } + return ret; +} +} // namespace + +void ShiftLineGenerator::update(AvoidancePlanningData & data, DebugData & debug) +{ + /** + * STEP1: Update registered shift line. + */ + updateRegisteredRawShiftLines(data); + + /** + * STEP2: Generate avoid outlines. + * Basically, avoid outlines are generated per target objects. + */ + const auto outlines = generateAvoidOutline(data, debug); + + /** + * STEP3: Create rough shift lines. + */ + raw_ = applyPreProcess(outlines, data, debug); +} + +AvoidLineArray ShiftLineGenerator::generate( + const AvoidancePlanningData & data, DebugData & debug) const +{ + return generateCandidateShiftLine(raw_, data, debug); +} + +AvoidOutlines ShiftLineGenerator::generateAvoidOutline( + AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const +{ + // To be consistent with changes in the ego position, the current shift length is considered. + const auto current_ego_shift = helper_->getEgoShift(); + const auto & base_link2rear = data_->parameters.base_link2rear; + + // Calculate feasible shift length + const auto get_shift_profile = + [&]( + auto & object, const auto & desire_shift_length) -> std::optional> { + // use each object param + const auto object_type = utils::getHighestProbLabel(object.object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); + const auto is_object_on_right = utils::avoidance::isOnRight(object); + + // use absolute dist for return-to-center, relative dist from current for avoiding. + const auto avoiding_shift = desire_shift_length - current_ego_shift; + const auto nominal_avoid_distance = helper_->getMaxAvoidanceDistance(avoiding_shift); + + // calculate remaining distance. + const auto prepare_distance = helper_->getNominalPrepareDistance(); + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front + : 0.0; + const auto constant = object_parameter.safety_buffer_longitudinal + + additional_buffer_longitudinal + prepare_distance; + const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance; + const auto remaining_distance = object.longitudinal - constant; + const auto avoidance_distance = + has_enough_distance ? nominal_avoid_distance : remaining_distance; + + // nominal case. avoidable. + if (has_enough_distance) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + if (!isBestEffort(parameters_->policy_lateral_margin)) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + // ego already has enough positive shift. + const auto has_enough_positive_shift = avoiding_shift < -1e-3 && desire_shift_length > 1e-3; + if (is_object_on_right && has_enough_positive_shift) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + // ego already has enough negative shift. + const auto has_enough_negative_shift = avoiding_shift > 1e-3 && desire_shift_length < -1e-3; + if (!is_object_on_right && has_enough_negative_shift) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + // don't relax shift length since it can stop in front of the object. + if (object.is_stoppable && !parameters_->use_shorten_margin_immediately) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + // the avoidance path is already approved + const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; + const auto is_approved = (helper_->getShift(object_pos) > 0.0 && is_object_on_right) || + (helper_->getShift(object_pos) < 0.0 && !is_object_on_right); + if (is_approved) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + // prepare distance is not enough. unavoidable. + if (remaining_distance < 1e-3) { + object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + return std::nullopt; + } + + // calculate lateral jerk. + const auto required_jerk = PathShifter::calcJerkFromLatLonDistance( + avoiding_shift, remaining_distance, helper_->getAvoidanceEgoSpeed()); + + // relax lateral jerk limit. avoidable. + if (required_jerk < helper_->getLateralMaxJerkLimit()) { + return std::make_pair(desire_shift_length, avoidance_distance); + } + + // avoidance distance is not enough. unavoidable. + if (!isBestEffort(parameters_->policy_deceleration)) { + object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; + return std::nullopt; + } + + // output avoidance path under lateral jerk constraints. + const auto feasible_relative_shift_length = PathShifter::calcLateralDistFromJerk( + remaining_distance, helper_->getLateralMaxJerkLimit(), helper_->getAvoidanceEgoSpeed()); + + if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) { + object.reason = "LessThanExecutionThreshold"; + return std::nullopt; + } + + const auto feasible_shift_length = + desire_shift_length > 0.0 ? feasible_relative_shift_length + current_ego_shift + : -1.0 * feasible_relative_shift_length + current_ego_shift; + + const auto infeasible = + std::abs(feasible_shift_length - object.overhang_dist) < + 0.5 * data_->parameters.vehicle_width + object_parameter.safety_buffer_lateral; + if (infeasible) { + RCLCPP_DEBUG(rclcpp::get_logger(""), "feasible shift length is not enough to avoid. "); + object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; + return std::nullopt; + } + + return std::make_pair(feasible_shift_length, avoidance_distance); + }; + + const auto is_forward_object = [](const auto & object) { return object.longitudinal > 0.0; }; + + const auto is_valid_shift_line = [](const auto & s) { + return s.start_longitudinal > 0.0 && s.start_longitudinal < s.end_longitudinal; + }; + + AvoidOutlines outlines; + for (auto & o : data.target_objects) { + if (!o.avoid_margin.has_value()) { + o.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + if (o.avoid_required && is_forward_object(o)) { + break; + } else { + continue; + } + } + + const auto is_object_on_right = utils::avoidance::isOnRight(o); + const auto desire_shift_length = + helper_->getShiftLength(o, is_object_on_right, o.avoid_margin.value()); + if (utils::avoidance::isSameDirectionShift(is_object_on_right, desire_shift_length)) { + o.reason = AvoidanceDebugFactor::SAME_DIRECTION_SHIFT; + if (o.avoid_required && is_forward_object(o)) { + break; + } else { + continue; + } + } + + // use each object param + const auto object_type = utils::getHighestProbLabel(o.object.classification); + const auto object_parameter = parameters_->object_parameters.at(object_type); + const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length); + + if (!feasible_shift_profile.has_value()) { + if (o.avoid_required && is_forward_object(o)) { + break; + } else { + continue; + } + } + + // use absolute dist for return-to-center, relative dist from current for avoiding. + const auto feasible_return_distance = + helper_->getMaxAvoidanceDistance(feasible_shift_profile.value().first); + + AvoidLine al_avoid; + { + const auto & additional_buffer_longitudinal = + object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front + : 0.0; + const auto offset = + object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal; + const auto to_shift_end = o.longitudinal - offset; + const auto path_front_to_ego = data.arclength_from_ego.at(data.ego_closest_path_index); + + // start point (use previous linear shift length as start shift length.) + al_avoid.start_longitudinal = [&]() { + const auto nearest_avoid_distance = + std::max(to_shift_end - feasible_shift_profile.value().second, 1e-3); + + if (data.to_start_point > to_shift_end) { + return nearest_avoid_distance; + } + + const auto minimum_avoid_distance = helper_->getMinAvoidanceDistance( + feasible_shift_profile.value().first - current_ego_shift); + const auto furthest_avoid_distance = std::max(to_shift_end - minimum_avoid_distance, 1e-3); + + return std::clamp(data.to_start_point, nearest_avoid_distance, furthest_avoid_distance); + }(); + + al_avoid.start_idx = utils::avoidance::findPathIndexFromArclength( + data.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego); + al_avoid.start = data.reference_path.points.at(al_avoid.start_idx).point.pose; + al_avoid.start_shift_length = helper_->getLinearShift(al_avoid.start.position); + + // end point + al_avoid.end_shift_length = feasible_shift_profile.value().first; + al_avoid.end_longitudinal = to_shift_end; + + // misc + al_avoid.id = generateUUID(); + al_avoid.object = o; + al_avoid.object_on_right = utils::avoidance::isOnRight(o); + } + + AvoidLine al_return; + { + const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length; + const auto to_shift_start = o.longitudinal + offset; + + // start point + al_return.start_shift_length = feasible_shift_profile.value().first; + al_return.start_longitudinal = to_shift_start; + + // end point + al_return.end_longitudinal = [&]() { + if (data.to_return_point > to_shift_start) { + return std::clamp( + data.to_return_point, to_shift_start, feasible_return_distance + to_shift_start); + } + + return to_shift_start + feasible_return_distance; + }(); + al_return.end_shift_length = 0.0; + + // misc + al_return.id = generateUUID(); + al_return.object = o; + al_return.object_on_right = utils::avoidance::isOnRight(o); + } + + if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { + outlines.emplace_back(al_avoid, al_return); + } else { + o.reason = "InvalidShiftLine"; + continue; + } + + o.is_avoidable = true; + } + + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, outlines); + + debug.step1_current_shift_line = toArray(outlines); + + return outlines; +} + +AvoidLineArray ShiftLineGenerator::applyPreProcess( + const AvoidOutlines & outlines, const AvoidancePlanningData & data, DebugData & debug) const +{ + AvoidOutlines processed_outlines = outlines; + + /** + * Step1: Rough merge process. + * Merge multiple avoid outlines. If an avoid outlines' return shift line conflicts other + * outline's avoid shift line, those avoid outlines are merged. + */ + processed_outlines = applyMergeProcess(processed_outlines, data, debug); + + /** + * Step2: Fill gap process. + * Create and add new shift line to avoid outline in order to fill gaps between avoid shift line + * and middle shift lines, return shift line and middle shift lines. + */ + processed_outlines = applyFillGapProcess(processed_outlines, data, debug); + + /** + * Step3: Convert to AvoidLineArray from AvoidOutlines. + */ + AvoidLineArray processed_raw_lines = toArray(processed_outlines); + + /** + * Step4: Combine process. + * Use all registered points. For the current points, if the similar one of the current + * points are already registered, will not use it. + */ + processed_raw_lines = applyCombineProcess(processed_raw_lines, raw_registered_, debug); + + /* + * Step5: Add return shift line. + * Add return-to-center shift point from the last shift point, if needed. + * If there is no shift points, set return-to center shift from ego. + */ + processed_raw_lines = addReturnShiftLine(processed_raw_lines, data, debug); + + /* + * Step6: Fill gap process. + * Create and add new shift line to avoid lines. + */ + return applyFillGapProcess(processed_raw_lines, data, debug); +} + +AvoidLineArray ShiftLineGenerator::generateCandidateShiftLine( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, DebugData & debug) const +{ + AvoidLineArray processed_shift_lines = shift_lines; + + /** + * Step1: Merge process. + * Merge positive shift avoid lines and negative shift avoid lines. + */ + processed_shift_lines = applyMergeProcess(processed_shift_lines, data, debug); + + /** + * Step2: Clean up process. + * Remove noisy shift line and concat same gradient shift lines. + */ + processed_shift_lines = applyTrimProcess(processed_shift_lines, debug); + + /** + * Step3: Extract new shift lines. + * Compare processed shift lines and registered shift lines in order to find new shift lines. + */ + return findNewShiftLine(processed_shift_lines, debug); +} + +void ShiftLineGenerator::generateTotalShiftLine( + const AvoidLineArray & avoid_lines, const AvoidancePlanningData & data, + ShiftLineData & shift_line_data) const +{ + const auto & path = data.reference_path; + const auto & arcs = data.arclength_from_ego; + const auto N = path.points.size(); + + auto & sl = shift_line_data; + + sl.shift_line = std::vector(N, 0.0); + sl.shift_line_grad = std::vector(N, 0.0); + + sl.pos_shift_line = std::vector(N, 0.0); + sl.neg_shift_line = std::vector(N, 0.0); + + sl.pos_shift_line_grad = std::vector(N, 0.0); + sl.neg_shift_line_grad = std::vector(N, 0.0); + + // debug + sl.shift_line_history = std::vector>(avoid_lines.size(), sl.shift_line); + + // take minmax for same directional shift length + for (size_t j = 0; j < avoid_lines.size(); ++j) { + const auto & al = avoid_lines.at(j); + for (size_t i = 0; i < N; ++i) { + // calc current interpolated shift + const auto i_shift = utils::avoidance::lerpShiftLengthOnArc(arcs.at(i), al); + + // update maximum shift for positive direction + if (i_shift > sl.pos_shift_line.at(i)) { + sl.pos_shift_line.at(i) = i_shift; + sl.pos_shift_line_grad.at(i) = al.getGradient(); + } + + // update minumum shift for negative direction + if (i_shift < sl.neg_shift_line.at(i)) { + sl.neg_shift_line.at(i) = i_shift; + sl.neg_shift_line_grad.at(i) = al.getGradient(); + } + + // store for debug print + sl.shift_line_history.at(j).at(i) = i_shift; + } + } + + // Merge shift length of opposite directions. + for (size_t i = 0; i < N; ++i) { + sl.shift_line.at(i) = sl.pos_shift_line.at(i) + sl.neg_shift_line.at(i); + sl.shift_line_grad.at(i) = sl.pos_shift_line_grad.at(i) + sl.neg_shift_line_grad.at(i); + } + + // overwrite shift with current_ego_shift until ego pose. + const auto current_shift = helper_->getEgoLinearShift(); + for (size_t i = 0; i < sl.shift_line.size(); ++i) { + if (data.ego_closest_path_index < i) { + break; + } + sl.shift_line.at(i) = current_shift; + sl.shift_line_grad.at(i) = 0.0; + } + + // If the shift point does not have an associated object, + // use previous value. + for (size_t i = 1; i < N; ++i) { + bool has_object = false; + for (const auto & al : avoid_lines) { + if (al.start_idx <= i && i <= al.end_idx) { + has_object = true; + break; + } + } + if (!has_object) { + sl.shift_line.at(i) = sl.shift_line.at(i - 1); + } + } + + if (avoid_lines.empty()) { + sl.shift_line_history.push_back(sl.shift_line); + return; + } + + const auto grad_first_shift_line = (avoid_lines.front().start_shift_length - current_shift) / + avoid_lines.front().start_longitudinal; + + for (size_t i = data.ego_closest_path_index; i <= avoid_lines.front().start_idx; ++i) { + sl.shift_line.at(i) = helper_->getLinearShift(getPoint(path.points.at(i))); + sl.shift_line_grad.at(i) = grad_first_shift_line; + } + + sl.shift_line_history.push_back(sl.shift_line); +} + +AvoidLineArray ShiftLineGenerator::extractShiftLinesFromLine( + const AvoidancePlanningData & data, ShiftLineData & shift_line_data) const +{ + using utils::avoidance::setEndData; + using utils::avoidance::setStartData; + + const auto & path = data.reference_path; + const auto & arcs = data.arclength_from_ego; + const auto N = path.points.size(); + + auto & sl = shift_line_data; + + const auto backward_grad = [&](const size_t i) { + if (i == 0) { + return sl.shift_line_grad.at(i); + } + const double ds = arcs.at(i) - arcs.at(i - 1); + if (ds < 1.0e-5) { + return sl.shift_line_grad.at(i); + } // use theoretical value when ds is too small. + return (sl.shift_line.at(i) - sl.shift_line.at(i - 1)) / ds; + }; + + const auto forward_grad = [&](const size_t i) { + if (i == arcs.size() - 1) { + return sl.shift_line_grad.at(i); + } + const double ds = arcs.at(i + 1) - arcs.at(i); + if (ds < 1.0e-5) { + return sl.shift_line_grad.at(i); + } // use theoretical value when ds is too small. + return (sl.shift_line.at(i + 1) - sl.shift_line.at(i)) / ds; + }; + + // calculate forward and backward gradient of the shift length. + // This will be used for grad-change-point check. + sl.forward_grad = std::vector(N, 0.0); + sl.backward_grad = std::vector(N, 0.0); + for (size_t i = 0; i < N - 1; ++i) { + sl.forward_grad.at(i) = forward_grad(i); + sl.backward_grad.at(i) = backward_grad(i); + } + + AvoidLineArray merged_avoid_lines; + AvoidLine al{}; + bool found_first_start = false; + constexpr auto CREATE_SHIFT_GRAD_THR = 0.001; + constexpr auto IS_ALREADY_SHIFTING_THR = 0.001; + for (size_t i = data.ego_closest_path_index; i < N - 1; ++i) { + const auto & p = path.points.at(i).point.pose; + const auto shift = sl.shift_line.at(i); + + // If the vehicle is already on the avoidance (checked by the first point has shift), + // set a start point at the first path point. + if (!found_first_start && std::abs(shift) > IS_ALREADY_SHIFTING_THR) { + setStartData(al, 0.0, p, i, arcs.at(i)); // start length is overwritten later. + found_first_start = true; + } + + // find the point where the gradient of the shift is changed + const bool set_shift_line_flag = + std::abs(sl.forward_grad.at(i) - sl.backward_grad.at(i)) > CREATE_SHIFT_GRAD_THR; + + if (!set_shift_line_flag) { + continue; + } + + if (!found_first_start) { + setStartData(al, 0.0, p, i, arcs.at(i)); // start length is overwritten later. + found_first_start = true; + } else { + setEndData(al, shift, p, i, arcs.at(i)); + al.id = generateUUID(); + merged_avoid_lines.push_back(al); + setStartData(al, 0.0, p, i, arcs.at(i)); // start length is overwritten later. + } + } + + if (std::abs(backward_grad(N - 1)) > CREATE_SHIFT_GRAD_THR) { + const auto & p = path.points.at(N - 1).point.pose; + const auto shift = sl.shift_line.at(N - 1); + setEndData(al, shift, p, N - 1, arcs.at(N - 1)); + al.id = generateUUID(); + merged_avoid_lines.push_back(al); + } + + return merged_avoid_lines; +} + +AvoidOutlines ShiftLineGenerator::applyMergeProcess( + const AvoidOutlines & outlines, const AvoidancePlanningData & data, DebugData & debug) const +{ + AvoidOutlines ret{}; + + if (outlines.size() < 2) { + return outlines; + } + + const auto no_conflict = [](const auto & line1, const auto & line2) { + return line1.end_idx < line2.start_idx || line2.end_idx < line1.start_idx; + }; + + const auto same_side_shift = [](const auto & line1, const auto & line2) { + return line1.object_on_right == line2.object_on_right; + }; + + const auto within = [](const auto & line, const size_t idx) { + return line.start_idx < idx && idx < line.end_idx; + }; + + ret.push_back(outlines.front()); + + for (size_t i = 1; i < outlines.size(); i++) { + auto & last_outline = ret.back(); + auto & next_outline = outlines.at(i); + + const auto & return_line = last_outline.return_line; + const auto & avoid_line = next_outline.avoid_line; + + if (no_conflict(return_line, avoid_line)) { + ret.push_back(outlines.at(i)); + continue; + } + + const auto merged_shift_line = merge(return_line, 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)) { + 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)) { + 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)) { + 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; + } + } + + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, ret); + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, debug.step1_merged_shift_line); + + return ret; +} + +AvoidOutlines ShiftLineGenerator::applyFillGapProcess( + const AvoidOutlines & outlines, const AvoidancePlanningData & data, DebugData & debug) const +{ + AvoidOutlines ret = outlines; + + for (auto & outline : ret) { + if (outline.middle_lines.empty()) { + const auto new_line = fill(outline.avoid_line, outline.return_line, generateUUID()); + outline.middle_lines.push_back(new_line); + debug.step1_filled_shift_line.push_back(new_line); + } + + helper_->alignShiftLinesOrder(outline.middle_lines, false); + + if (outline.avoid_line.end_longitudinal < outline.middle_lines.front().start_longitudinal) { + const auto new_line = fill(outline.avoid_line, outline.middle_lines.front(), generateUUID()); + outline.middle_lines.push_back(new_line); + debug.step1_filled_shift_line.push_back(new_line); + } + + 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()); + outline.middle_lines.push_back(new_line); + debug.step1_filled_shift_line.push_back(new_line); + } + + helper_->alignShiftLinesOrder(outline.middle_lines, false); + } + + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, ret); + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, debug.step1_filled_shift_line); + + return ret; +} + +AvoidLineArray ShiftLineGenerator::applyFillGapProcess( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, DebugData & debug) const +{ + AvoidLineArray sorted = shift_lines; + + helper_->alignShiftLinesOrder(sorted, false); + + AvoidLineArray ret = sorted; + + if (shift_lines.empty()) { + return ret; + } + + // fill gap between ego and nearest shift line. + if (sorted.front().start_longitudinal > 0.0) { + AvoidLine ego_line{}; + utils::avoidance::setEndData( + ego_line, helper_->getEgoLinearShift(), data.reference_pose, data.ego_closest_path_index, + 0.0); + + const auto new_line = fill(ego_line, sorted.front(), generateUUID()); + ret.push_back(new_line); + debug.step1_front_shift_line.push_back(new_line); + } + + helper_->alignShiftLinesOrder(sorted, false); + + // fill gap among shift lines. + for (size_t i = 0; i < sorted.size() - 1; ++i) { + if (sorted.at(i + 1).start_longitudinal < sorted.at(i).end_longitudinal) { + continue; + } + + const auto new_line = fill(sorted.at(i), sorted.at(i + 1), generateUUID()); + ret.push_back(new_line); + debug.step1_front_shift_line.push_back(new_line); + } + + helper_->alignShiftLinesOrder(ret, false); + + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, ret); + utils::avoidance::fillAdditionalInfoFromLongitudinal(data, debug.step1_front_shift_line); + + return ret; +} + +AvoidLineArray ShiftLineGenerator::applyCombineProcess( + const AvoidLineArray & shift_lines, const AvoidLineArray & registered_lines, + DebugData & debug) const +{ + debug.step1_registered_shift_line = registered_lines; + return utils::avoidance::combineRawShiftLinesWithUniqueCheck(registered_lines, shift_lines); +} + +AvoidLineArray ShiftLineGenerator::applyMergeProcess( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, DebugData & debug) const +{ + // Generate shift line by merging shift_lines. + ShiftLineData shift_line_data; + generateTotalShiftLine(shift_lines, data, shift_line_data); + + // Re-generate shift points by detecting gradient-change point of the shift line. + auto merged_shift_lines = extractShiftLinesFromLine(data, shift_line_data); + + // set parent id + for (auto & al : merged_shift_lines) { + al.parent_ids = utils::avoidance::calcParentIds(shift_lines, al); + } + + // sort by distance from ego. + helper_->alignShiftLinesOrder(merged_shift_lines); + + // debug visualize + { + debug.pos_shift = shift_line_data.pos_shift_line; + debug.neg_shift = shift_line_data.neg_shift_line; + debug.total_shift = shift_line_data.shift_line; + debug.pos_shift_grad = shift_line_data.pos_shift_line_grad; + debug.neg_shift_grad = shift_line_data.neg_shift_line_grad; + debug.total_forward_grad = shift_line_data.forward_grad; + debug.total_backward_grad = shift_line_data.backward_grad; + debug.step2_merged_shift_line = merged_shift_lines; + } + + return merged_shift_lines; +} + +AvoidLineArray ShiftLineGenerator::applyTrimProcess( + const AvoidLineArray & shift_lines, DebugData & debug) const +{ + if (shift_lines.empty()) { + return shift_lines; + } + + AvoidLineArray sl_array_trimmed = shift_lines; + + // sort shift points from front to back. + helper_->alignShiftLinesOrder(sl_array_trimmed); + + // - Change the shift length to the previous one if the deviation is small. + { + constexpr double SHIFT_DIFF_THRES = 1.0; + applySmallShiftFilter(sl_array_trimmed, SHIFT_DIFF_THRES); + } + + // - Combine avoid points that have almost same gradient. + // this is to remove the noise. + { + const auto THRESHOLD = parameters_->same_grad_filter_1_threshold; + applySimilarGradFilter(sl_array_trimmed, THRESHOLD); + debug.step3_grad_filtered_1st = sl_array_trimmed; + } + + // - Quantize the shift length to reduce the shift point noise + // This is to remove the noise coming from detection accuracy, interpolation, resampling, etc. + { + const auto THRESHOLD = parameters_->quantize_filter_threshold; + applyQuantizeProcess(sl_array_trimmed, THRESHOLD); + debug.step3_quantize_filtered = sl_array_trimmed; + } + + // - Change the shift length to the previous one if the deviation is small. + { + constexpr double SHIFT_DIFF_THRES = 1.0; + applySmallShiftFilter(sl_array_trimmed, SHIFT_DIFF_THRES); + debug.step3_noise_filtered = sl_array_trimmed; + } + + // - Combine avoid points that have almost same gradient (again) + { + const auto THRESHOLD = parameters_->same_grad_filter_2_threshold; + applySimilarGradFilter(sl_array_trimmed, THRESHOLD); + debug.step3_grad_filtered_2nd = sl_array_trimmed; + } + + // - Combine avoid points that have almost same gradient (again) + { + const auto THRESHOLD = parameters_->same_grad_filter_3_threshold; + applySimilarGradFilter(sl_array_trimmed, THRESHOLD); + debug.step3_grad_filtered_3rd = sl_array_trimmed; + } + + return sl_array_trimmed; +} + +void ShiftLineGenerator::applyQuantizeProcess( + AvoidLineArray & shift_lines, const double threshold) const +{ + if (threshold < 1.0e-5) { + return; // no need to process + } + + for (auto & sl : shift_lines) { + sl.end_shift_length = std::round(sl.end_shift_length / threshold) * threshold; + } + + helper_->alignShiftLinesOrder(shift_lines); +} + +void ShiftLineGenerator::applySmallShiftFilter( + AvoidLineArray & shift_lines, const double threshold) const +{ + if (shift_lines.empty()) { + return; + } + + AvoidLineArray input = shift_lines; + shift_lines.clear(); + + for (const auto & s : input) { + if (s.getRelativeLongitudinal() < threshold) { + continue; + } + + if (s.start_longitudinal < helper_->getMinimumPrepareDistance()) { + continue; + } + + shift_lines.push_back(s); + } +} + +void ShiftLineGenerator::applySimilarGradFilter( + AvoidLineArray & avoid_lines, const double threshold) const +{ + if (avoid_lines.empty()) { + return; + } + + AvoidLineArray input = avoid_lines; + avoid_lines.clear(); + avoid_lines.push_back(input.front()); // Take the first one anyway (think later) + + AvoidLine base_line = input.front(); + + AvoidLineArray combine_buffer; + combine_buffer.push_back(input.front()); + + constexpr auto SHIFT_THR = 1e-3; + const auto is_negative_shift = [&](const auto & s) { + return s.getRelativeLength() < -1.0 * SHIFT_THR; + }; + + const auto is_positive_shift = [&](const auto & s) { return s.getRelativeLength() > SHIFT_THR; }; + + for (size_t i = 1; i < input.size(); ++i) { + AvoidLine combine{}; + + utils::avoidance::setStartData( + combine, base_line.start_shift_length, base_line.start, base_line.start_idx, + base_line.start_longitudinal); + utils::avoidance::setEndData( + combine, input.at(i).end_shift_length, input.at(i).end, input.at(i).end_idx, + input.at(i).end_longitudinal); + + combine_buffer.push_back(input.at(i)); + + const auto violates = [&]() { + if (is_negative_shift(input.at(i)) && is_positive_shift(base_line)) { + return true; + } + + if (is_negative_shift(base_line) && is_positive_shift(input.at(i))) { + return true; + } + + const auto lon_combine = combine.getRelativeLongitudinal(); + const auto base_length = base_line.getGradient() * lon_combine; + return std::abs(combine.getRelativeLength() - base_length) > threshold; + }(); + + if (violates) { + avoid_lines.push_back(input.at(i)); + base_line = input.at(i); + combine_buffer.clear(); + combine_buffer.push_back(input.at(i)); + } else { + avoid_lines.back() = combine; + } + } + + helper_->alignShiftLinesOrder(avoid_lines); +} + +AvoidLineArray ShiftLineGenerator::addReturnShiftLine( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data, DebugData & debug) const +{ + AvoidLineArray ret = shift_lines; + + constexpr double ep = 1.0e-3; + const bool has_candidate_point = !ret.empty(); + const bool has_registered_point = last_.has_value(); + + 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; }); + + if (exist_unavoidable_object) { + 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; + } + + // From here, the return-to-center is not registered. But perhaps the candidate is + // already generated. + + // If it has a shift point, add return shift from the existing last shift point. + // If not, add return shift from ego point. (prepare distance is considered for both.) + ShiftLine last_sl; // the return-shift will be generated after the last shift point. + { + // avoidance points: Yes, shift points: No -> select last avoidance point. + if (has_candidate_point && !has_registered_point) { + helper_->alignShiftLinesOrder(ret, false); + last_sl = ret.back(); + } + + // avoidance points: No, shift points: Yes -> select last shift point. + if (!has_candidate_point && has_registered_point) { + last_sl = utils::avoidance::fillAdditionalInfo(data, AvoidLine{last_.value()}); + } + + // avoidance points: Yes, shift points: Yes -> select the last one from both. + if (has_candidate_point && has_registered_point) { + helper_->alignShiftLinesOrder(ret, false); + const auto & al = ret.back(); + const auto & sl = utils::avoidance::fillAdditionalInfo(data, AvoidLine{last_.value()}); + last_sl = (sl.end_longitudinal > al.end_longitudinal) ? sl : al; + } + + // avoidance points: No, shift points: No -> set the ego position to the last shift point + // so that the return-shift will be generated from ego position. + if (!has_candidate_point && !has_registered_point) { + last_sl.end_idx = data.ego_closest_path_index; + last_sl.end = data.reference_path.points.at(last_sl.end_idx).point.pose; + last_sl.end_shift_length = base_offset_; + } + } + + // 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. + if (std::fabs(last_sl.end_shift_length) < RETURN_SHIFT_THRESHOLD) { + const auto current_base_shift = helper_->getEgoShift(); + if (std::abs(current_base_shift) < ep) { + return ret; + } + + // Is there a shift point in the opposite direction of the current_base_shift? + // No -> we can overwrite the return shift, because the other shift points that decrease + // the shift length are for return-shift. + // Yes -> we can NOT overwrite, because it might be not a return-shift, but a avoiding + // shift to the opposite direction which can not be overwritten by the return-shift. + for (const auto & sl : ret) { + if ( + (current_base_shift > 0.0 && sl.end_shift_length < -ep) || + (current_base_shift < 0.0 && sl.end_shift_length > ep)) { + return ret; + } + } + + // If return shift already exists in candidate or registered shift lines, skip adding return + // shift. + if (has_candidate_point || has_registered_point) { + return ret; + } + + // set the return-shift from ego. + last_sl.end_idx = data.ego_closest_path_index; + last_sl.end = data.reference_path.points.at(last_sl.end_idx).point.pose; + last_sl.end_shift_length = current_base_shift; + } + + const auto & arclength_from_ego = data.arclength_from_ego; + + const auto nominal_prepare_distance = helper_->getNominalPrepareDistance(); + const auto nominal_avoid_distance = helper_->getMaxAvoidanceDistance(last_sl.end_shift_length); + + if (arclength_from_ego.empty()) { + return ret; + } + + const auto remaining_distance = 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); + + // check if there is enough distance for return. + if (last_sl_distance > remaining_distance) { // tmp: add some small number (+1.0) + RCLCPP_DEBUG(rclcpp::get_logger(""), "No enough distance for return."); + return ret; + } + + // If the remaining distance is not enough, the return shift needs to be shrunk. + // (or another option is just to ignore the return-shift.) + // But we do not want to change the last shift point, so we will shrink the distance after + // the last shift point. + // + // The line "===" is fixed, "---" is scaled. + // + // [Before Scaling] + // ego last_sl_end prepare_end path_end avoid_end + // ==o====================o----------------------o----------------------o------------o + // | prepare_dist | avoid_dist | + // + // [After Scaling] + // ==o====================o------------------o--------------------------o + // | prepare_dist_scaled | avoid_dist_scaled | + // + 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 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; + avoid_distance_scaled *= scale; + } + + // shift point for prepare distance: from last shift to return-start point. + if (nominal_prepare_distance > last_sl_distance) { + AvoidLine al; + al.id = generateUUID(); + al.start_idx = last_sl.end_idx; + al.start = last_sl.end; + al.start_longitudinal = arclength_from_ego.at(al.start_idx); + 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_shift_length = last_sl.end_shift_length; + al.start_shift_length = last_sl.end_shift_length; + ret.push_back(al); + debug.step1_return_shift_line.push_back(al); + } + + // shift point for return to center line + { + AvoidLine al; + al.id = generateUUID(); + 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.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; + al.end_longitudinal = arclength_from_ego.at(al.end_idx); + al.end_shift_length = 0.0; + al.start_shift_length = last_sl.end_shift_length; + ret.push_back(al); + debug.step1_return_shift_line.push_back(al); + } + + return ret; +} + +AvoidLineArray ShiftLineGenerator::findNewShiftLine( + const AvoidLineArray & shift_lines, DebugData & debug) const +{ + if (shift_lines.empty()) { + return {}; + } + + // add small shift lines. + const auto add_straight_shift = + [&, this](auto & subsequent, bool has_large_shift, const size_t start_idx) { + for (size_t i = start_idx; i < shift_lines.size(); ++i) { + if ( + std::abs(shift_lines.at(i).getRelativeLength()) > + parameters_->lateral_small_shift_threshold) { + if (has_large_shift) { + return; + } + + has_large_shift = true; + } + + if (!helper_->isComfortable(AvoidLineArray{shift_lines.at(i)})) { + return; + } + + subsequent.push_back(shift_lines.at(i)); + } + }; + + // get subsequent shift lines. + const auto get_subsequent_shift = [&, this](size_t i) { + AvoidLineArray subsequent{shift_lines.at(i)}; + + if (!helper_->isComfortable(subsequent)) { + return subsequent; + } + + if (shift_lines.size() == i + 1) { + return subsequent; + } + + if (!helper_->isComfortable(AvoidLineArray{shift_lines.at(i + 1)})) { + return subsequent; + } + + if ( + std::abs(shift_lines.at(i).getRelativeLength()) < + parameters_->lateral_small_shift_threshold) { + const auto has_large_shift = + shift_lines.at(i + 1).getRelativeLength() > parameters_->lateral_small_shift_threshold; + + // candidate.at(i) is small length shift line. add large length shift line. + subsequent.push_back(shift_lines.at(i + 1)); + add_straight_shift(subsequent, has_large_shift, i + 2); + } else { + // candidate.at(i) is large length shift line. add small length shift lines. + add_straight_shift(subsequent, true, i + 1); + } + + return subsequent; + }; + + // check ignore or not. + const auto is_ignore_shift = [this](const auto & s) { + return std::abs(helper_->getRelativeShiftToPath(s)) < parameters_->lateral_execution_threshold; + }; + + for (size_t i = 0; i < shift_lines.size(); ++i) { + const auto & candidate = shift_lines.at(i); + + // prevent sudden steering. + if (candidate.start_longitudinal < helper_->getMinimumPrepareDistance()) { + break; + } + + if (!is_ignore_shift(candidate)) { + const auto new_shift_lines = get_subsequent_shift(i); + debug.step4_new_shift_line = new_shift_lines; + return new_shift_lines; + } + } + + return {}; +} + +void ShiftLineGenerator::updateRegisteredRawShiftLines(const AvoidancePlanningData & data) +{ + utils::avoidance::fillAdditionalInfoFromPoint(data, raw_registered_); + + AvoidLineArray avoid_lines; + + const auto has_large_offset = [this](const auto & s) { + constexpr double THRESHOLD = 0.1; + const auto ego_shift_length = helper_->getEgoLinearShift(); + + const auto start_to_ego_longitudinal = -1.0 * s.start_longitudinal; + + if (start_to_ego_longitudinal < 0.0) { + return false; + } + + const auto reg_shift_length = + s.getGradient() * start_to_ego_longitudinal + s.start_shift_length; + + return std::abs(ego_shift_length - reg_shift_length) > THRESHOLD; + }; + + const auto ego_idx = data.ego_closest_path_index; + + for (const auto & s : raw_registered_) { + // invalid + if (s.end_idx < ego_idx) { + continue; + } + + // invalid + if (has_large_offset(s)) { + continue; + } + + // valid + avoid_lines.push_back(s); + } + + raw_registered_ = avoid_lines; +} + +void ShiftLineGenerator::setRawRegisteredShiftLine( + const AvoidLineArray & shift_lines, const AvoidancePlanningData & data) +{ + if (shift_lines.empty()) { + RCLCPP_ERROR(rclcpp::get_logger(""), "future is empty! return."); + return; + } + + auto future_with_info = shift_lines; + utils::avoidance::fillAdditionalInfoFromPoint(data, future_with_info); + + // sort by longitudinal + std::sort(future_with_info.begin(), future_with_info.end(), [](auto a, auto b) { + return a.end_longitudinal < b.end_longitudinal; + }); + + // calc relative lateral length + future_with_info.front().start_shift_length = base_offset_; + for (size_t i = 1; i < future_with_info.size(); ++i) { + future_with_info.at(i).start_shift_length = future_with_info.at(i - 1).end_shift_length; + } + + const auto is_registered = [this](const auto id) { + const auto & r = raw_registered_; + return std::any_of(r.begin(), r.end(), [id](const auto & s) { return s.id == id; }); + }; + + const auto same_id_shift_line = [this](const auto id) { + const auto & r = raw_; + const auto itr = std::find_if(r.begin(), r.end(), [id](const auto & s) { return s.id == id; }); + if (itr != r.end()) { + return *itr; + } + throw std::logic_error("not found same id current raw shift line."); + }; + + for (const auto & s : future_with_info) { + if (s.parent_ids.empty()) { + RCLCPP_ERROR(rclcpp::get_logger(""), "avoid line for path_shifter must have parent_id."); + } + + for (const auto id : s.parent_ids) { + if (is_registered(id)) { + continue; + } + + raw_registered_.push_back(same_id_shift_line(id)); + } + } +} +} // namespace behavior_path_planner::utils::avoidance diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index d6427a1fe8c36..cee60f08ca79e 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -741,22 +741,24 @@ size_t findPathIndexFromArclength( return path_arclength_arr.size() - 1; } -std::vector concatParentIds( - const std::vector & ids1, const std::vector & ids2) +std::vector concatParentIds(const std::vector & ids1, const std::vector & ids2) { - std::set id_set{ids1.begin(), ids1.end()}; - for (const auto id : ids2) { - id_set.insert(id); + std::vector ret; + for (const auto id2 : ids2) { + if (std::any_of(ids1.begin(), ids1.end(), [&id2](const auto & id1) { return id1 == id2; })) { + continue; + } + ret.push_back(id2); } - const auto v = std::vector{id_set.begin(), id_set.end()}; - return v; + + return ret; } -std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine & lines2) +std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine & lines2) { // Get the ID of the original AP whose transition area overlaps with the given AP, // and set it to the parent id. - std::set ids; + std::vector ret; for (const auto & al : lines1) { const auto p_s = al.start_longitudinal; const auto p_e = al.end_longitudinal; @@ -766,9 +768,9 @@ std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine continue; } - ids.insert(al.id); + ret.push_back(al.id); } - return std::vector(ids.begin(), ids.end()); + return ret; } double lerpShiftLengthOnArc(double arc, const AvoidLine & ap) From bf0dbedcc166375a34424f8f73d73bdd607417f5 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 28 Nov 2023 15:17:14 +0900 Subject: [PATCH 044/128] fix(surround_obstacle_checker): prevent crash when all checks for object types to are set to false (#5671) * Fix possible call to nullptr when use_dynamic_object is false Signed-off-by: Daniel Sanchez * fixed check for pointcloud obstacles Signed-off-by: Daniel Sanchez * fixed extra enter problem Signed-off-by: Daniel Sanchez * fix(surround_obstacle_checker): fix invalid access Signed-off-by: satoshi-ota --------- Signed-off-by: Daniel Sanchez Signed-off-by: satoshi-ota Co-authored-by: satoshi-ota --- .../surround_obstacle_checker/node.hpp | 4 ++ .../surround_obstacle_checker/src/node.cpp | 67 ++++++++++--------- 2 files changed, 40 insertions(+), 31 deletions(-) diff --git a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp index c40fef5b0c43e..3962159375974 100644 --- a/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp +++ b/planning/surround_obstacle_checker/include/surround_obstacle_checker/node.hpp @@ -141,6 +141,10 @@ class SurroundObstacleCheckerNode : public rclcpp::Node std::shared_ptr last_obstacle_found_time_; std::unique_ptr logger_configure_; + + bool use_dynamic_object_; + + std::unordered_map label_map_; }; } // namespace surround_obstacle_checker diff --git a/planning/surround_obstacle_checker/src/node.cpp b/planning/surround_obstacle_checker/src/node.cpp index 1b981fcddb155..0dd021cd8ddad 100644 --- a/planning/surround_obstacle_checker/src/node.cpp +++ b/planning/surround_obstacle_checker/src/node.cpp @@ -149,19 +149,22 @@ Polygon2d createSelfPolygon( SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options) : Node("surround_obstacle_checker_node", node_options) { + label_map_ = { + {"unknown", ObjectClassification::UNKNOWN}, {"car", ObjectClassification::CAR}, + {"truck", ObjectClassification::TRUCK}, {"bus", ObjectClassification::BUS}, + {"trailer", ObjectClassification::TRAILER}, {"motorcycle", ObjectClassification::MOTORCYCLE}, + {"bicycle", ObjectClassification::BICYCLE}, {"pedestrian", ObjectClassification::PEDESTRIAN}}; // Parameters { auto & p = node_param_; // for object label - std::unordered_map label_map{ - {"unknown", ObjectClassification::UNKNOWN}, {"car", ObjectClassification::CAR}, - {"truck", ObjectClassification::TRUCK}, {"bus", ObjectClassification::BUS}, - {"trailer", ObjectClassification::TRAILER}, {"motorcycle", ObjectClassification::MOTORCYCLE}, - {"bicycle", ObjectClassification::BICYCLE}, {"pedestrian", ObjectClassification::PEDESTRIAN}}; - for (const auto & label_pair : label_map) { - p.enable_check_map.emplace( - label_pair.second, this->declare_parameter(label_pair.first + ".enable_check")); + use_dynamic_object_ = false; + for (const auto & label_pair : label_map_) { + const bool check_current_label = + this->declare_parameter(label_pair.first + ".enable_check"); + p.enable_check_map.emplace(label_pair.second, check_current_label); + use_dynamic_object_ = use_dynamic_object_ || check_current_label; p.surround_check_front_distance_map.emplace( label_pair.second, this->declare_parameter(label_pair.first + ".surround_check_front_distance")); @@ -245,13 +248,7 @@ std::array SurroundObstacleCheckerNode::getCheckDistances( node_param_.pointcloud_surround_check_back_distance}; } - std::unordered_map label_map{ - {"unknown", ObjectClassification::UNKNOWN}, {"car", ObjectClassification::CAR}, - {"truck", ObjectClassification::TRUCK}, {"bus", ObjectClassification::BUS}, - {"trailer", ObjectClassification::TRAILER}, {"motorcycle", ObjectClassification::MOTORCYCLE}, - {"bicycle", ObjectClassification::BICYCLE}, {"pedestrian", ObjectClassification::PEDESTRIAN}}; - - const int int_label = label_map.at(str_label); + const int int_label = label_map_.at(str_label); return { node_param_.surround_check_front_distance_map.at(int_label), node_param_.surround_check_side_distance_map.at(int_label), @@ -261,6 +258,14 @@ std::array SurroundObstacleCheckerNode::getCheckDistances( rcl_interfaces::msg::SetParametersResult SurroundObstacleCheckerNode::onParam( const std::vector & parameters) { + use_dynamic_object_ = false; + for (const auto & label_pair : label_map_) { + bool & check_current_label = node_param_.enable_check_map.at(label_pair.second); + tier4_autoware_utils::updateParam( + parameters, label_pair.first + ".enable_check", check_current_label); + use_dynamic_object_ = use_dynamic_object_ || check_current_label; + } + tier4_autoware_utils::updateParam( parameters, "debug_footprint_label", node_param_.debug_footprint_label); const auto check_distances = getCheckDistances(node_param_.debug_footprint_label); @@ -289,22 +294,17 @@ void SurroundObstacleCheckerNode::onTimer() if (node_param_.pointcloud_enable_check && !pointcloud_ptr_) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for pointcloud info..."); - return; } - const bool use_dynamic_object = - node_param_.enable_check_map.at(ObjectClassification::UNKNOWN) || - node_param_.enable_check_map.at(ObjectClassification::CAR) || - node_param_.enable_check_map.at(ObjectClassification::TRUCK) || - node_param_.enable_check_map.at(ObjectClassification::BUS) || - node_param_.enable_check_map.at(ObjectClassification::TRAILER) || - node_param_.enable_check_map.at(ObjectClassification::MOTORCYCLE) || - node_param_.enable_check_map.at(ObjectClassification::BICYCLE) || - node_param_.enable_check_map.at(ObjectClassification::PEDESTRIAN); - if (use_dynamic_object && !object_ptr_) { + if (use_dynamic_object_ && !object_ptr_) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for dynamic object info..."); - return; + } + + if (!node_param_.pointcloud_enable_check && !use_dynamic_object_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000 /* ms */, + "Surround obstacle check is disabled for all dynamic object types and for pointcloud check."); } const auto nearest_obstacle = getNearestObstacle(); @@ -414,7 +414,11 @@ boost::optional SurroundObstacleCheckerNode::getNearestObstacle() cons boost::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCloud() const { - if (!node_param_.pointcloud_enable_check || pointcloud_ptr_->data.empty()) { + if (!node_param_.pointcloud_enable_check || !pointcloud_ptr_) { + return boost::none; + } + + if (pointcloud_ptr_->data.empty()) { return boost::none; } @@ -422,7 +426,7 @@ boost::optional SurroundObstacleCheckerNode::getNearestObstacleByPoint getTransform("base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, 0.5); if (!transform_stamped) { - return {}; + return boost::none; } Eigen::Affine3f isometry = tf2::transformToEigen(transform_stamped.get().transform).cast(); @@ -459,11 +463,13 @@ boost::optional SurroundObstacleCheckerNode::getNearestObstacleByPoint boost::optional SurroundObstacleCheckerNode::getNearestObstacleByDynamicObject() const { + if (!object_ptr_ || !use_dynamic_object_) return boost::none; + const auto transform_stamped = getTransform(object_ptr_->header.frame_id, "base_link", object_ptr_->header.stamp, 0.5); if (!transform_stamped) { - return {}; + return boost::none; } tf2::Transform tf_src2target; @@ -480,7 +486,6 @@ boost::optional SurroundObstacleCheckerNode::getNearestObstacleByDynam if (!node_param_.enable_check_map.at(label)) { continue; } - const double front_margin = node_param_.surround_check_front_distance_map.at(label); const double side_margin = node_param_.surround_check_side_distance_map.at(label); const double back_margin = node_param_.surround_check_back_distance_map.at(label); From ea6da7984efe5ead205ab302d1dfb7ec0922b644 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 28 Nov 2023 17:03:34 +0900 Subject: [PATCH 045/128] chore(objects_of_interest_marker_interface): add maintainer (#5698) Signed-off-by: Fumiya Watanabe --- planning/objects_of_interest_marker_interface/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/objects_of_interest_marker_interface/package.xml b/planning/objects_of_interest_marker_interface/package.xml index 0aebdd3b099b1..2cdb0fe2c9a46 100644 --- a/planning/objects_of_interest_marker_interface/package.xml +++ b/planning/objects_of_interest_marker_interface/package.xml @@ -5,6 +5,8 @@ The objects_of_interest_marker_interface package Fumiya Watanabe + Kosuke Takeuchi + Zulfaqar Azmi Apache License 2.0 From e3eb2858ce55d087caec91a6fccffddc6108b63c Mon Sep 17 00:00:00 2001 From: karishma1911 <95741784+karishma1911@users.noreply.github.com> Date: Tue, 28 Nov 2023 14:16:48 +0530 Subject: [PATCH 046/128] refactor(sensing-vehicle-velocity-converter): rework parameters (#5609) * sensing-vehicle-velocity-converter-module Signed-off-by: karishma * sensing-vehicle-velocity-converter Signed-off-by: karishma --------- Signed-off-by: karishma --- .../schema/vehicle_velocity_converter.json | 44 +++++++++++++++++++ .../src/vehicle_velocity_converter.cpp | 8 ++-- 2 files changed, 48 insertions(+), 4 deletions(-) create mode 100644 sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json diff --git a/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json b/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json new file mode 100644 index 0000000000000..5d4638d090807 --- /dev/null +++ b/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json @@ -0,0 +1,44 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for vehicle_velocity_converter", + "type": "object", + "definitions": { + "vehicle_velocity_converter": { + "type": "object", + "properties": { + "stddev_vx": { + "type": "number", + "default": 0.2, + "description": "speed scale factor (ideal value is 1.0)" + }, + "frame_id": { + "type": "string", + "description": "frame id for output message." + }, + "stddev_wz": { + "type": "number", + "default": 0.1, + "description": "standard deviation for vx." + }, + "speed_scale_factor": { + "type": "number", + "default": 1.0, + "description": "standard deviation for yaw rate." + } + }, + "required": ["stddev_vx", "frame_id", "stddev_wz", "speed_scale_factor"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/vehicle_velocity_converter" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp b/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp index 997e06e8c01b0..0f4a22bbc9730 100644 --- a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp +++ b/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp @@ -17,10 +17,10 @@ VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_converter") { // set covariance value for twist with covariance msg - stddev_vx_ = declare_parameter("velocity_stddev_xx", 0.2); - stddev_wz_ = declare_parameter("angular_velocity_stddev_zz", 0.1); - frame_id_ = declare_parameter("frame_id", "base_link"); - speed_scale_factor_ = declare_parameter("speed_scale_factor", 1.0); + stddev_vx_ = declare_parameter("velocity_stddev_xx"); + stddev_wz_ = declare_parameter("angular_velocity_stddev_zz"); + frame_id_ = declare_parameter("frame_id"); + speed_scale_factor_ = declare_parameter("speed_scale_factor"); vehicle_report_sub_ = create_subscription( "velocity_status", rclcpp::QoS{100}, From 5d9f3acbb2362b10c656eba19b80287ce1b07386 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 28 Nov 2023 19:29:22 +0900 Subject: [PATCH 047/128] feat(avoidance): configurable object type for safety check (#5699) Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 28 ++++++++++----- .../avoidance_by_lc.param.yaml | 21 ++++++----- .../utils/avoidance/avoidance_module_data.hpp | 4 ++- .../src/scene_module/avoidance/manager.cpp | 36 +++++++++++++++++-- .../src/scene_module/lane_change/manager.cpp | 18 +++++++++- .../src/utils/avoidance/utils.cpp | 26 ++++++++++---- 6 files changed, 107 insertions(+), 26 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index d3032ffdd3b99..27f6a0df63cec 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -27,7 +27,6 @@ # avoidance is performed for the object type with true target_object: car: - is_target: true # [-] execute_num: 1 # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] @@ -38,7 +37,6 @@ safety_buffer_longitudinal: 0.0 # [m] use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -49,7 +47,6 @@ safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bus: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -60,7 +57,6 @@ safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true trailer: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -71,7 +67,6 @@ safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true unknown: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -82,7 +77,6 @@ safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bicycle: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -93,7 +87,6 @@ safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true motorcycle: - is_target: true execute_num: 1 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -104,7 +97,6 @@ safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true pedestrian: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -119,6 +111,16 @@ # For target object filtering target_filtering: + # avoidance target type + target_type: + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: true # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # detection range object_check_goal_distance: 20.0 # [m] # filtering parking objects @@ -152,6 +154,16 @@ # For safety check safety_check: + # safety check target type + target_type: + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: false # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # safety check configuration enable: true # [-] check_current_lane: false # [-] diff --git a/planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml b/planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml index 5ea50f90ab62c..9518185d30d63 100644 --- a/planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml +++ b/planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml @@ -7,7 +7,6 @@ # avoidance is performed for the object type with true target_object: car: - is_target: true # [-] execute_num: 2 # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] @@ -16,7 +15,6 @@ avoid_margin_lateral: 1.0 # [m] safety_buffer_lateral: 0.7 # [m] truck: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -25,7 +23,6 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 bus: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -34,7 +31,6 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 trailer: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -43,7 +39,6 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 unknown: - is_target: true execute_num: 1 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -52,7 +47,6 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.0 bicycle: - is_target: true execute_num: 2 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -61,7 +55,6 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 motorcycle: - is_target: true execute_num: 2 moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 @@ -70,7 +63,6 @@ avoid_margin_lateral: 1.0 safety_buffer_lateral: 1.0 pedestrian: - is_target: true execute_num: 2 moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 @@ -80,3 +72,16 @@ safety_buffer_lateral: 1.0 lower_distance_for_polygon_expansion: 0.0 # [m] upper_distance_for_polygon_expansion: 1.0 # [m] + + # For target object filtering + target_filtering: + # avoidance target type + target_type: + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: true # [-] + bicycle: false # [-] + motorcycle: false # [-] + pedestrian: false # [-] diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 6c223bff39ef0..191c3acf1bdf8 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -54,7 +54,9 @@ using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; struct ObjectParameter { - bool is_target{false}; + bool is_avoidance_target{false}; + + bool is_safety_check_target{false}; size_t execute_num{1}; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index f4807223503fa..d82a105930b99 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -65,7 +65,6 @@ AvoidanceModuleManager::AvoidanceModuleManager( { const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; - param.is_target = getOrDeclareParameter(*node, ns + "is_target"); param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); param.moving_speed_threshold = getOrDeclareParameter(*node, ns + "moving_speed_threshold"); @@ -105,7 +104,24 @@ AvoidanceModuleManager::AvoidanceModuleManager( // 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); + }; + 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 = @@ -147,7 +163,24 @@ AvoidanceModuleManager::AvoidanceModuleManager( // 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); + }; + 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"); @@ -346,7 +379,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorobject_parameters.at(semantic); - updateParam(parameters, ns + "is_target", config.is_target); updateParam(parameters, ns + "moving_speed_threshold", config.moving_speed_threshold); updateParam(parameters, ns + "moving_time_threshold", config.moving_time_threshold); updateParam(parameters, ns + "max_expand_ratio", config.max_expand_ratio); 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 3a0b7527e4184..56410dd8ba4ca 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 @@ -285,7 +285,6 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( { const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; - param.is_target = getOrDeclareParameter(*node, ns + "is_target"); param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); param.moving_speed_threshold = getOrDeclareParameter(*node, ns + "moving_speed_threshold"); @@ -321,7 +320,24 @@ AvoidanceByLaneChangeModuleManager::AvoidanceByLaneChangeModuleManager( // 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); + }; + 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 = diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index cee60f08ca79e..f47ee90d0ad52 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -235,7 +235,7 @@ void pushUniqueVector(T & base_vector, const T & additional_vector) namespace filtering_utils { -bool isTargetObjectType( +bool isAvoidanceTargetObjectType( const PredictedObject & object, const std::shared_ptr & parameters) { const auto object_type = utils::getHighestProbLabel(object.classification); @@ -244,7 +244,19 @@ bool isTargetObjectType( return false; } - return parameters->object_parameters.at(object_type).is_target; + return parameters->object_parameters.at(object_type).is_avoidance_target; +} + +bool isSafetyCheckTargetObjectType( + const PredictedObject & object, const std::shared_ptr & parameters) +{ + const auto object_type = utils::getHighestProbLabel(object.classification); + + if (parameters->object_parameters.count(object_type) == 0) { + return false; + } + + return parameters->object_parameters.at(object_type).is_safety_check_target; } bool isVehicleTypeObject(const ObjectData & object) @@ -500,7 +512,7 @@ bool isSatisfiedWithCommonCondition( const std::shared_ptr & parameters) { // Step1. filtered by target object type. - if (!isTargetObjectType(object.object, parameters)) { + if (!isAvoidanceTargetObjectType(object.object, parameters)) { object.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE; return false; } @@ -1705,10 +1717,12 @@ std::vector getSafetyCheckTargetObjects( }); }; - const auto to_predicted_objects = [&p](const auto & objects) { + const auto to_predicted_objects = [&p, ¶meters](const auto & objects) { PredictedObjects ret{}; - std::for_each(objects.begin(), objects.end(), [&p, &ret](const auto & object) { - ret.objects.push_back(object.object); + std::for_each(objects.begin(), objects.end(), [&p, &ret, ¶meters](const auto & object) { + if (filtering_utils::isSafetyCheckTargetObjectType(object.object, parameters)) { + ret.objects.push_back(object.object); + } }); return ret; }; From 1504234e1c12ce49000959b26276cac5fc0061f6 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 28 Nov 2023 21:57:35 +0900 Subject: [PATCH 048/128] chore(behavior_velocity_planner_common): add maintainer (#5702) Signed-off-by: Fumiya Watanabe --- planning/behavior_velocity_planner_common/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner_common/package.xml index aedbab65068fb..2112eca9fa849 100644 --- a/planning/behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner_common/package.xml @@ -8,6 +8,8 @@ Tomoya Kimura Shumpei Wakabayashi Takagi, Isamu + Fumiya Watanabe + Mamoru Sobue Apache License 2.0 From f62cc2e2b9aabcfd7949d057e2a81729e5d463b7 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 29 Nov 2023 01:18:10 +0900 Subject: [PATCH 049/128] chore(rtc_interface): add maintainer (#5700) Add Kyoichi Sugahara as a maintainer Signed-off-by: kyoichi-sugahara Co-authored-by: Tomoya Kimura --- planning/rtc_interface/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/rtc_interface/package.xml b/planning/rtc_interface/package.xml index 152ca8c572aa7..78e0f39292075 100644 --- a/planning/rtc_interface/package.xml +++ b/planning/rtc_interface/package.xml @@ -6,6 +6,7 @@ Fumiya Watanabe Taiki Tanaka + Kyoichi Sugahara Apache License 2.0 From 9f2f036d84728834b09cc83ccb47f0ba872a4f85 Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Wed, 29 Nov 2023 08:20:03 +0800 Subject: [PATCH 050/128] refactor(raw_vehicle_cmd_converter): rework parameters (#5134) * refactor(raw_vehicle_cmd_converter): rework parameters Signed-off-by: PhoebeWu21 * refactor(raw_vehicle_cmd_converter): rework parameters Signed-off-by: PhoebeWu21 * style(pre-commit): autofix * refactor(raw_vehicle_cmd_converter): rework parameters Signed-off-by: PhoebeWu21 * refactor(raw_vehicle_cmd_converter): rework parameters Signed-off-by: PhoebeWu21 * refactor(raw_vehicle_cmd_converter): rework parameters Signed-off-by: PhoebeWu21 * refactor(raw_vehicle_cmd_converter): 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> --- vehicle/raw_vehicle_cmd_converter/README.md | 8 +- .../config/converter.param.yaml | 18 -- .../raw_vehicle_cmd_converter.param.yaml | 28 +++ .../launch/raw_vehicle_converter.launch.xml | 26 +-- .../raw_vehicle_cmd_converter.schema.json | 188 ++++++++++++++++++ .../raw_vehicle_cmd_converter/src/node.cpp | 50 ++--- 6 files changed, 245 insertions(+), 73 deletions(-) delete mode 100644 vehicle/raw_vehicle_cmd_converter/config/converter.param.yaml create mode 100644 vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml create mode 100644 vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json diff --git a/vehicle/raw_vehicle_cmd_converter/README.md b/vehicle/raw_vehicle_cmd_converter/README.md index 94b0256ab5911..c033f4348b927 100644 --- a/vehicle/raw_vehicle_cmd_converter/README.md +++ b/vehicle/raw_vehicle_cmd_converter/README.md @@ -18,13 +18,7 @@ ## Parameters -| Parameter | Type | Description | -| -------------------------- | ------ | ------------------------------------------------------------------------------- | -| `update_rate` | double | timer's update rate | -| `th_max_message_delay_sec` | double | threshold time of input messages' maximum delay | -| `th_arrived_distance_m` | double | threshold distance to check if vehicle has arrived at the trajectory's endpoint | -| `th_stopped_time_sec` | double | threshold time to check if vehicle is stopped | -| `th_stopped_velocity_mps` | double | threshold velocity to check if vehicle is stopped | +{{ json_to_markdown("vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json") }} ## Limitation diff --git a/vehicle/raw_vehicle_cmd_converter/config/converter.param.yaml b/vehicle/raw_vehicle_cmd_converter/config/converter.param.yaml deleted file mode 100644 index 3e98b794d8dc4..0000000000000 --- a/vehicle/raw_vehicle_cmd_converter/config/converter.param.yaml +++ /dev/null @@ -1,18 +0,0 @@ -/**: - ros__parameters: - use_steer_ff: true - use_steer_fb: true - is_debugging: false - steer_pid: - kp: 150.0 - ki: 15.0 - kd: 0.0 - max: 8.0 - min: -8.0 - max_p: 8.0 - min_p: -8.0 - max_i: 8.0 - min_i: -8.0 - max_d: 0.0 - min_d: 0.0 - invalid_integration_decay: 0.97 diff --git a/vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml b/vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml new file mode 100644 index 0000000000000..d63a115304a87 --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml @@ -0,0 +1,28 @@ +/**: + ros__parameters: + csv_path_accel_map: "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/accel_map.csv" + csv_path_brake_map: "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/brake_map.csv" + csv_path_steer_map: "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/steer_map.csv" + convert_accel_cmd: true + convert_brake_cmd: true + convert_steer_cmd: true + use_steer_ff: true + use_steer_fb: true + is_debugging: false + max_throttle: 0.4 + max_brake: 0.8 + max_steer: 10.0 + min_steer: -10.0 + steer_pid: + kp: 150.0 + ki: 15.0 + kd: 0.0 + max: 8.0 + min: -8.0 + max_p: 8.0 + min_p: -8.0 + max_i: 8.0 + min_i: -8.0 + max_d: 0.0 + min_d: 0.0 + invalid_integration_decay: 0.97 diff --git a/vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml b/vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml index b9071fe8316cf..0a9962a7c2a30 100644 --- a/vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml +++ b/vehicle/raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml @@ -1,34 +1,14 @@ - - - - - - - - - - - - + + - - - - - - - - - - - + diff --git a/vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json b/vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json new file mode 100644 index 0000000000000..4b562f401e09b --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json @@ -0,0 +1,188 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Raw Vehicle Cmd Converter", + "type": "object", + "definitions": { + "raw_vehicle_cmd_converter": { + "type": "object", + "properties": { + "csv_path_accel_map": { + "type": "string", + "description": "path for acceleration map csv file", + "default": "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/accel_map.csv" + }, + "csv_path_brake_map": { + "type": "string", + "description": "path for brake map csv file", + "default": "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/brake_map.csv" + }, + "csv_path_steer_map": { + "type": "string", + "description": "path for steer map csv file", + "default": "$(find-pkg-share raw_vehicle_cmd_converter)/data/default/steer_map.csv" + }, + "convert_accel_cmd": { + "type": "boolean", + "description": "use accel or not", + "default": "true" + }, + "convert_brake_cmd": { + "type": "boolean", + "description": "use brake or not", + "default": "true" + }, + "convert_steer_cmd": { + "type": "boolean", + "description": "use steer or not", + "default": "true" + }, + "use_steer_ff": { + "type": "boolean", + "description": "steering steer controller using steer feed forward or not", + "default": "true" + }, + "use_steer_fb": { + "type": "boolean", + "description": "steering steer controller using steer feed back or not", + "default": "true" + }, + "is_debugging": { + "type": "boolean", + "description": "debugging mode or not", + "default": "false" + }, + "max_throttle": { + "type": "number", + "description": "maximum value of throttle", + "default": "0.4", + "minimum": 0.0 + }, + "max_brake": { + "type": "number", + "description": "maximum value of brake", + "default": "0.8", + "minimum": 0.0 + }, + "max_steer": { + "type": "number", + "description": "maximum value of steer", + "default": "10.0" + }, + "min_steer": { + "type": "number", + "description": "minimum value of steer", + "default": "-10.0" + }, + "steer_pid": { + "type": "object", + "properties": { + "kp": { + "type": "number", + "description": "proportional coefficient value in PID control", + "default": "150.0" + }, + "ki": { + "type": "number", + "description": "integral coefficient value in PID control", + "default": "15.0", + "exclusiveMinimum": 0.0 + }, + "kd": { + "type": "number", + "description": "derivative coefficient value in PID control", + "default": "0.0" + }, + "max": { + "type": "number", + "description": "maximum value of PID", + "default": "8.0" + }, + "min": { + "type": "number", + "description": "minimum value of PID", + "default": "-8.0." + }, + "max_p": { + "type": "number", + "description": "maximum value of Proportional in PID", + "default": "8.0" + }, + "min_p": { + "type": "number", + "description": "minimum value of Proportional in PID", + "default": "-8.0" + }, + "max_i": { + "type": "number", + "description": "maximum value of Integral in PID", + "default": "8.0" + }, + "min_i": { + "type": "number", + "description": "minimum value of Integral in PID", + "default": "-8.0" + }, + "max_d": { + "type": "number", + "description": "maximum value of Derivative in PID", + "default": "0.0" + }, + "min_d": { + "type": "number", + "description": "minimum value of Derivative in PID", + "default": "0.0" + }, + "invalid_integration_decay": { + "type": "number", + "description": "invalid integration decay value in PID control", + "default": "0.97", + "Maximum": 1.0, + "exclusiveMinimum": 0.0 + } + }, + "required": [ + "kp", + "ki", + "kd", + "max", + "min", + "max_p", + "min_p", + "max_i", + "min_i", + "max_d", + "min_d", + "invalid_integration_decay" + ] + } + }, + "required": [ + "csv_path_accel_map", + "csv_path_brake_map", + "csv_path_steer_map", + "convert_accel_cmd", + "convert_brake_cmd", + "convert_steer_cmd", + "use_steer_ff", + "use_steer_fb", + "is_debugging", + "max_throttle", + "max_brake", + "max_steer", + "steer_pid" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/raw_vehicle_cmd_converter" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/vehicle/raw_vehicle_cmd_converter/src/node.cpp b/vehicle/raw_vehicle_cmd_converter/src/node.cpp index 0b0e14a845200..2506fb1f70b76 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/node.cpp @@ -27,20 +27,20 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( { using std::placeholders::_1; /* parameters for accel/brake map */ - const auto csv_path_accel_map = declare_parameter("csv_path_accel_map", std::string("empty")); - const auto csv_path_brake_map = declare_parameter("csv_path_brake_map", std::string("empty")); - const auto csv_path_steer_map = declare_parameter("csv_path_steer_map", std::string("empty")); - convert_accel_cmd_ = declare_parameter("convert_accel_cmd", true); - convert_brake_cmd_ = declare_parameter("convert_brake_cmd", true); - convert_steer_cmd_ = declare_parameter("convert_steer_cmd", true); - max_accel_cmd_ = declare_parameter("max_throttle", 0.2); - max_brake_cmd_ = declare_parameter("max_brake", 0.8); - max_steer_cmd_ = declare_parameter("max_steer", 10.0); - min_steer_cmd_ = declare_parameter("min_steer", -10.0); - is_debugging_ = declare_parameter("is_debugging", false); + const auto csv_path_accel_map = declare_parameter("csv_path_accel_map"); + const auto csv_path_brake_map = declare_parameter("csv_path_brake_map"); + const auto csv_path_steer_map = declare_parameter("csv_path_steer_map"); + convert_accel_cmd_ = declare_parameter("convert_accel_cmd"); + convert_brake_cmd_ = declare_parameter("convert_brake_cmd"); + convert_steer_cmd_ = declare_parameter("convert_steer_cmd"); + max_accel_cmd_ = declare_parameter("max_throttle"); + max_brake_cmd_ = declare_parameter("max_brake"); + max_steer_cmd_ = declare_parameter("max_steer"); + min_steer_cmd_ = declare_parameter("min_steer"); + is_debugging_ = declare_parameter("is_debugging"); // for steering steer controller - use_steer_ff_ = declare_parameter("use_steer_ff", true); - use_steer_fb_ = declare_parameter("use_steer_fb", true); + use_steer_ff_ = declare_parameter("use_steer_ff"); + use_steer_fb_ = declare_parameter("use_steer_fb"); if (convert_accel_cmd_) { if (!accel_map_.readAccelMapFromCSV(csv_path_accel_map, true)) { throw std::invalid_argument("Accel map is invalid."); @@ -55,19 +55,19 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( if (!steer_map_.readSteerMapFromCSV(csv_path_steer_map, true)) { throw std::invalid_argument("Steer map is invalid."); } - const auto kp_steer{declare_parameter("steer_pid.kp", 150.0)}; - const auto ki_steer{declare_parameter("steer_pid.ki", 15.0)}; - const auto kd_steer{declare_parameter("steer_pid.kd", 0.0)}; - const auto max_ret_steer{declare_parameter("steer_pid.max", 8.0)}; - const auto min_ret_steer{declare_parameter("steer_pid.min", -8.0)}; - const auto max_ret_p_steer{declare_parameter("steer_pid.max_p", 8.0)}; - const auto min_ret_p_steer{declare_parameter("steer_pid.min_p", -8.0)}; - const auto max_ret_i_steer{declare_parameter("steer_pid.max_i", 8.0)}; - const auto min_ret_i_steer{declare_parameter("steer_pid.min_i", -8.0)}; - const auto max_ret_d_steer{declare_parameter("steer_pid.max_d", 0.0)}; - const auto min_ret_d_steer{declare_parameter("steer_pid.min_d", 0.0)}; + const auto kp_steer{declare_parameter("steer_pid.kp")}; + const auto ki_steer{declare_parameter("steer_pid.ki")}; + const auto kd_steer{declare_parameter("steer_pid.kd")}; + const auto max_ret_steer{declare_parameter("steer_pid.max")}; + const auto min_ret_steer{declare_parameter("steer_pid.min")}; + const auto max_ret_p_steer{declare_parameter("steer_pid.max_p")}; + const auto min_ret_p_steer{declare_parameter("steer_pid.min_p")}; + const auto max_ret_i_steer{declare_parameter("steer_pid.max_i")}; + const auto min_ret_i_steer{declare_parameter("steer_pid.min_i")}; + const auto max_ret_d_steer{declare_parameter("steer_pid.max_d")}; + const auto min_ret_d_steer{declare_parameter("steer_pid.min_d")}; const auto invalid_integration_decay{ - declare_parameter("steer_pid.invalid_integration_decay", 0.97)}; + declare_parameter("steer_pid.invalid_integration_decay")}; steer_pid_.setDecay(invalid_integration_decay); steer_pid_.setGains(kp_steer, ki_steer, kd_steer); steer_pid_.setLimits( From e6709ee26753bc2108a119718ea753d285308bba Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 29 Nov 2023 11:06:59 +0900 Subject: [PATCH 051/128] fix(behavior_velocity_planner_common): sync activation when safety status is set (#5697) * fix(behavior_velocity_planner_common): sync activation when safety status is set Signed-off-by: Fumiya Watanabe * Update planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp Co-authored-by: Kyoichi Sugahara * Update planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp Co-authored-by: Tomoya Kimura --------- Signed-off-by: Fumiya Watanabe Co-authored-by: Kyoichi Sugahara Co-authored-by: Tomoya Kimura --- .../scene_module_interface.hpp | 11 ++++++++++- .../src/scene_module_interface.cpp | 1 + .../include/rtc_interface/rtc_interface.hpp | 1 + planning/rtc_interface/src/rtc_interface.cpp | 16 ++++++++++++++++ 4 files changed, 28 insertions(+), 1 deletion(-) 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 90e78215cae2d..21911ab81085d 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 @@ -87,6 +87,7 @@ class SceneModuleInterface boost::optional getFirstStopPathPointIndex() { return first_stop_path_point_index_; } void setActivation(const bool activated) { activated_ = activated; } + void setRTCEnabled(const bool enable_rtc) { rtc_enabled_ = enable_rtc; } bool isActivated() const { return activated_; } bool isSafe() const { return safe_; } double getDistance() const { return distance_; } @@ -98,6 +99,7 @@ class SceneModuleInterface const int64_t module_id_; bool activated_; bool safe_; + bool rtc_enabled_; double distance_; rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; @@ -106,8 +108,15 @@ class SceneModuleInterface boost::optional first_stop_path_point_index_; VelocityFactorInterface velocity_factor_; - void setSafe(const bool safe) { safe_ = safe; } + void setSafe(const bool safe) + { + safe_ = safe; + if (!rtc_enabled_) { + syncActivation(); + } + } void setDistance(const double distance) { distance_ = distance; } + void syncActivation() { setActivation(isSafe()); } size_t findEgoSegmentIndex( const std::vector & points) const; 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 6ba982294ccfd..d6fd01fd32c59 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -218,6 +218,7 @@ void SceneModuleManagerInterfaceWithRTC::setActivation() for (const auto & scene_module : scene_modules_) { const UUID uuid = getUUID(scene_module->getModuleId()); scene_module->setActivation(rtc_interface_.isActivated(uuid)); + scene_module->setRTCEnabled(rtc_interface_.isRTCEnabled(uuid)); } } diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index d6e083421c0b7..4bf28f6c61d94 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -55,6 +55,7 @@ class RTCInterface void clearCooperateStatus(); bool isActivated(const UUID & uuid) const; bool isRegistered(const UUID & uuid) const; + bool isRTCEnabled(const UUID & uuid) const; void lockCommandUpdate(); void unlockCommandUpdate(); diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index dbc82113d403b..ae2257785f33a 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -280,6 +280,22 @@ bool RTCInterface::isRegistered(const UUID & uuid) const return itr != registered_status_.statuses.end(); } +bool RTCInterface::isRTCEnabled(const UUID & uuid) const +{ + std::lock_guard lock(mutex_); + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](auto & s) { return s.uuid == uuid; }); + + if (itr != registered_status_.statuses.end()) { + return !itr->auto_mode; + } + + RCLCPP_WARN_STREAM( + getLogger(), "[isRTCEnabled] uuid : " << to_string(uuid) << " is not found." << std::endl); + return is_auto_mode_init_; +} + void RTCInterface::lockCommandUpdate() { is_locked_ = true; From 68125d6d929c08cf4d3c34b833185d264cea4a7c Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 29 Nov 2023 13:31:33 +0900 Subject: [PATCH 052/128] refactor(image_projection_based_fusion): rename cache-related variables' name (#5709) * refactor(image_projection_based_fusion): rename sub_std_map_ to cached_msg_ Signed-off-by: kminoda * style(pre-commit): autofix * rename other cache-related variables 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> --- .../fusion_node.hpp | 7 ++- .../src/fusion_node.cpp | 62 +++++++++---------- 2 files changed, 35 insertions(+), 34 deletions(-) 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 5174aebe069a8..9572e62e0e0aa 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 @@ -118,9 +118,10 @@ class FusionNode : public rclcpp::Node // cache for fusion std::vector is_fused_; - std::pair sub_std_pair_; - std::vector> roi_stdmap_; - std::mutex mutex_; + std::pair + cached_msg_; // first element is the timestamp in nanoseconds, second element is the message + std::vector> cached_roi_msgs_; + std::mutex mutex_cached_msgs_; // output publisher typename rclcpp::Publisher::SharedPtr pub_ptr_; diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index df797369208fe..b01a910aaded1 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -96,7 +96,7 @@ FusionNode::FusionNode( // sub rois rois_subs_.resize(rois_number_); - roi_stdmap_.resize(rois_number_); + cached_roi_msgs_.resize(rois_number_); is_fused_.resize(rois_number_, false); for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { std::function roi_callback = @@ -163,12 +163,12 @@ void FusionNode::preprocess(Msg & ouput_msg __attribute__((unused))) template void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_msg) { - if (sub_std_pair_.second != nullptr) { + if (cached_msg_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); timer_->cancel(); - postprocess(*(sub_std_pair_.second)); - publish(*(sub_std_pair_.second)); - sub_std_pair_.second = nullptr; + postprocess(*(cached_msg_.second)); + publish(*(cached_msg_.second)); + cached_msg_.second = nullptr; std::fill(is_fused_.begin(), is_fused_.end(), false); // add processing time for debug @@ -183,7 +183,7 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ } } - std::lock_guard lock(mutex_); + std::lock_guard lock(mutex_cached_msgs_); auto period = std::chrono::duration_cast( std::chrono::duration(timeout_ms_)); try { @@ -211,12 +211,12 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ continue; } - if ((roi_stdmap_.at(roi_i)).size() > 0) { + if ((cached_roi_msgs_.at(roi_i)).size() > 0) { int64_t min_interval = 1e9; int64_t matched_stamp = -1; std::list outdate_stamps; - for (const auto & [k, v] : roi_stdmap_.at(roi_i)) { + for (const auto & [k, v] : cached_roi_msgs_.at(roi_i)) { int64_t new_stamp = timestamp_nsec + input_offset_ms_.at(roi_i) * (int64_t)1e6; int64_t interval = abs(int64_t(k) - new_stamp); @@ -230,7 +230,7 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ // remove outdated stamps for (auto stamp : outdate_stamps) { - (roi_stdmap_.at(roi_i)).erase(stamp); + (cached_roi_msgs_.at(roi_i)).erase(stamp); } // fuseOnSingle @@ -240,9 +240,9 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ } fuseOnSingleImage( - *input_msg, roi_i, *((roi_stdmap_.at(roi_i))[matched_stamp]), camera_info_map_.at(roi_i), - *output_msg); - (roi_stdmap_.at(roi_i)).erase(matched_stamp); + *input_msg, roi_i, *((cached_roi_msgs_.at(roi_i))[matched_stamp]), + camera_info_map_.at(roi_i), *output_msg); + (cached_roi_msgs_.at(roi_i)).erase(matched_stamp); is_fused_.at(roi_i) = true; // add timestamp interval for debug @@ -265,7 +265,7 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ postprocess(*output_msg); publish(*output_msg); std::fill(is_fused_.begin(), is_fused_.end(), false); - sub_std_pair_.second = nullptr; + cached_msg_.second = nullptr; // add processing time for debug if (debug_publisher_) { @@ -278,8 +278,8 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_ processing_time_ms = 0; } } else { - sub_std_pair_.first = int64_t(timestamp_nsec); - sub_std_pair_.second = output_msg; + cached_msg_.first = int64_t(timestamp_nsec); + cached_msg_.second = output_msg; processing_time_ms = stop_watch_ptr_->toc("processing_time", true); } } @@ -294,15 +294,15 @@ void FusionNode::roiCallback( (*input_roi_msg).header.stamp.sec * (int64_t)1e9 + (*input_roi_msg).header.stamp.nanosec; // if cached Msg exist, try to match - if (sub_std_pair_.second != nullptr) { - int64_t new_stamp = sub_std_pair_.first + input_offset_ms_.at(roi_i) * (int64_t)1e6; + if (cached_msg_.second != nullptr) { + int64_t new_stamp = cached_msg_.first + input_offset_ms_.at(roi_i) * (int64_t)1e6; int64_t interval = abs(timestamp_nsec - new_stamp); if (interval < match_threshold_ms_ * (int64_t)1e6 && is_fused_.at(roi_i) == false) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); - (roi_stdmap_.at(roi_i))[timestamp_nsec] = input_roi_msg; + (cached_roi_msgs_.at(roi_i))[timestamp_nsec] = input_roi_msg; return; } if (debugger_) { @@ -310,12 +310,12 @@ void FusionNode::roiCallback( } fuseOnSingleImage( - *(sub_std_pair_.second), roi_i, *input_roi_msg, camera_info_map_.at(roi_i), - *(sub_std_pair_.second)); + *(cached_msg_.second), roi_i, *input_roi_msg, camera_info_map_.at(roi_i), + *(cached_msg_.second)); is_fused_.at(roi_i) = true; if (debug_publisher_) { - double timestamp_interval_ms = (timestamp_nsec - sub_std_pair_.first) / 1e6; + double timestamp_interval_ms = (timestamp_nsec - cached_msg_.first) / 1e6; debug_publisher_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); debug_publisher_->publish( @@ -325,10 +325,10 @@ void FusionNode::roiCallback( if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast(rois_number_)) { timer_->cancel(); - postprocess(*(sub_std_pair_.second)); - publish(*(sub_std_pair_.second)); + postprocess(*(cached_msg_.second)); + publish(*(cached_msg_.second)); std::fill(is_fused_.begin(), is_fused_.end(), false); - sub_std_pair_.second = nullptr; + cached_msg_.second = nullptr; // add processing time for debug if (debug_publisher_) { @@ -346,7 +346,7 @@ void FusionNode::roiCallback( } } // store roi msg if not matched - (roi_stdmap_.at(roi_i))[timestamp_nsec] = input_roi_msg; + (cached_roi_msgs_.at(roi_i))[timestamp_nsec] = input_roi_msg; } template @@ -360,13 +360,13 @@ void FusionNode::timer_callback() { using std::chrono_literals::operator""ms; timer_->cancel(); - if (mutex_.try_lock()) { + if (mutex_cached_msgs_.try_lock()) { // timeout, postprocess cached msg - if (sub_std_pair_.second != nullptr) { + if (cached_msg_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); - postprocess(*(sub_std_pair_.second)); - publish(*(sub_std_pair_.second)); + postprocess(*(cached_msg_.second)); + publish(*(cached_msg_.second)); // add processing time for debug if (debug_publisher_) { @@ -380,9 +380,9 @@ void FusionNode::timer_callback() } } std::fill(is_fused_.begin(), is_fused_.end(), false); - sub_std_pair_.second = nullptr; + cached_msg_.second = nullptr; - mutex_.unlock(); + mutex_cached_msgs_.unlock(); } else { try { std::chrono::nanoseconds period = 10ms; From c4b72eb1c699c0563627dc84b9ebcd5d24a71e90 Mon Sep 17 00:00:00 2001 From: Phoebe Wu Date: Wed, 29 Nov 2023 13:02:59 +0800 Subject: [PATCH 053/128] refactor(stop_filter): rework parameters (#5696) Signed-off-by: PhoebeWu21 --- localization/stop_filter/README.md | 5 +-- .../schema/stop_filter.schema.json | 40 +++++++++++++++++++ 2 files changed, 41 insertions(+), 4 deletions(-) create mode 100644 localization/stop_filter/schema/stop_filter.schema.json diff --git a/localization/stop_filter/README.md b/localization/stop_filter/README.md index 714824b430d74..261b8c9da392c 100644 --- a/localization/stop_filter/README.md +++ b/localization/stop_filter/README.md @@ -25,7 +25,4 @@ This node aims to: ## Parameters -| Name | Type | Description | -| -------------- | ------ | --------------------------------------------------------------------------------------------- | -| `vx_threshold` | double | longitudinal velocity threshold to determine if the vehicle is stopping [m/s] (default: 0.01) | -| `wz_threshold` | double | yaw velocity threshold to determine if the vehicle is stopping [rad/s] (default: 0.01) | +{{ json_to_markdown("localization/stop_filter/schema/stop_filter.schema.json") }} diff --git a/localization/stop_filter/schema/stop_filter.schema.json b/localization/stop_filter/schema/stop_filter.schema.json new file mode 100644 index 0000000000000..ce6d4b8a2bb72 --- /dev/null +++ b/localization/stop_filter/schema/stop_filter.schema.json @@ -0,0 +1,40 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Stop Filter Node", + "type": "object", + "definitions": { + "stop_filter": { + "type": "object", + "properties": { + "vx_threshold": { + "type": "number", + "description": "Longitudinal velocity threshold to determine if the vehicle is stopping. [m/s]", + "default": "0.01", + "minimum": 0.0 + }, + "wz_threshold": { + "type": "number", + "description": "Yaw velocity threshold to determine if the vehicle is stopping. [rad/s]", + "default": "0.01", + "minimum": 0.0 + } + }, + "required": ["vx_threshold", "wz_threshold"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/stop_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From b65bfe03b241001c5476003d722b43b1c995ac4f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 29 Nov 2023 18:23:36 +0900 Subject: [PATCH 054/128] feat(tier4_autoware_utils): add yaw argument in calcOffsetPose (#5683) Signed-off-by: Takayuki Murooka --- .../geometry/geometry.hpp | 3 +- .../src/geometry/geometry.cpp | 5 +-- .../test/src/geometry/test_geometry.cpp | 35 +++++++++++++++++++ 3 files changed, 40 insertions(+), 3 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp index 6106e3a15f4c7..63cf6305e8158 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/geometry.hpp @@ -462,7 +462,8 @@ bool isDrivingForward(const Pose1 & src_pose, const Pose2 & dst_pose) * pose. */ geometry_msgs::msg::Pose calcOffsetPose( - const geometry_msgs::msg::Pose & p, const double x, const double y, const double z); + const geometry_msgs::msg::Pose & p, const double x, const double y, const double z, + const double yaw = 0.0); /** * @brief Calculate a point by linear interpolation. diff --git a/common/tier4_autoware_utils/src/geometry/geometry.cpp b/common/tier4_autoware_utils/src/geometry/geometry.cpp index 2c2de2d07a3dc..03625f19ec8ea 100644 --- a/common/tier4_autoware_utils/src/geometry/geometry.cpp +++ b/common/tier4_autoware_utils/src/geometry/geometry.cpp @@ -327,12 +327,13 @@ double calcCurvature( * pose. */ geometry_msgs::msg::Pose calcOffsetPose( - const geometry_msgs::msg::Pose & p, const double x, const double y, const double z) + const geometry_msgs::msg::Pose & p, const double x, const double y, const double z, + const double yaw) { geometry_msgs::msg::Pose pose; geometry_msgs::msg::Transform transform; transform.translation = createTranslation(x, y, z); - transform.rotation = createQuaternion(0.0, 0.0, 0.0, 1.0); + transform.rotation = createQuaternionFromYaw(yaw); tf2::Transform tf_pose; tf2::Transform tf_offset; tf2::fromMsg(transform, tf_offset); diff --git a/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp b/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp index ce91614155491..c10e04736b5bb 100644 --- a/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp +++ b/common/tier4_autoware_utils/test/src/geometry/test_geometry.cpp @@ -1138,6 +1138,7 @@ TEST(geometry, calcOffsetPose) using tier4_autoware_utils::createQuaternionFromRPY; using tier4_autoware_utils::deg2rad; + // Only translation { geometry_msgs::msg::Pose p_in; p_in.position = createPoint(1.0, 2.0, 3.0); @@ -1185,6 +1186,40 @@ TEST(geometry, calcOffsetPose) EXPECT_DOUBLE_EQ(p_out.orientation.z, 0.25881904510252068); EXPECT_DOUBLE_EQ(p_out.orientation.w, 0.96592582628906831); } + + // Only rotation + { + geometry_msgs::msg::Pose p_in; + p_in.position = createPoint(2.0, 1.0, 1.0); + p_in.orientation = createQuaternionFromRPY(deg2rad(0), deg2rad(0), deg2rad(30)); + + const auto p_out = calcOffsetPose(p_in, 0.0, 0.0, 0.0, deg2rad(20)); + + EXPECT_DOUBLE_EQ(p_out.position.x, 2.0); + EXPECT_DOUBLE_EQ(p_out.position.y, 1.0); + EXPECT_DOUBLE_EQ(p_out.position.z, 1.0); + EXPECT_DOUBLE_EQ(p_out.orientation.x, 0.0); + EXPECT_DOUBLE_EQ(p_out.orientation.y, 0.0); + EXPECT_NEAR(p_out.orientation.z, 0.42261826174069944, epsilon); + EXPECT_NEAR(p_out.orientation.w, 0.9063077870366499, epsilon); + } + + // Both translation and rotation + { + geometry_msgs::msg::Pose p_in; + p_in.position = createPoint(2.0, 1.0, 1.0); + p_in.orientation = createQuaternionFromRPY(deg2rad(0), deg2rad(0), deg2rad(30)); + + const auto p_out = calcOffsetPose(p_in, 2.0, 0.0, -1.0, deg2rad(20)); + + EXPECT_DOUBLE_EQ(p_out.position.x, 3.73205080756887729); + EXPECT_DOUBLE_EQ(p_out.position.y, 2.0); + EXPECT_DOUBLE_EQ(p_out.position.z, 0.0); + EXPECT_DOUBLE_EQ(p_out.orientation.x, 0.0); + EXPECT_DOUBLE_EQ(p_out.orientation.y, 0.0); + EXPECT_NEAR(p_out.orientation.z, 0.42261826174069944, epsilon); + EXPECT_NEAR(p_out.orientation.w, 0.9063077870366499, epsilon); + } } TEST(geometry, isDrivingForward) From 5daaf87081275251cbe0d7438d81cc30387a2217 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 29 Nov 2023 18:56:49 +0900 Subject: [PATCH 055/128] perf(image_projection_based_fusion,lidar_centerpoint): add cuda preprocess (#5681) --- .../pointpainting_trt.hpp | 3 +- .../preprocess_kernel.hpp | 12 +- .../pointpainting_fusion/voxel_generator.hpp | 4 +- .../pointpainting_trt.cpp | 45 +++++--- .../pointpainting_fusion/preprocess_kernel.cu | 103 +++++++++++++++++- .../pointpainting_fusion/voxel_generator.cpp | 80 ++------------ .../lidar_centerpoint/centerpoint_trt.hpp | 17 ++- .../network/scatter_kernel.hpp | 2 +- .../preprocess/preprocess_kernel.hpp | 12 +- .../preprocess/voxel_generator.hpp | 8 +- .../lidar_centerpoint/lib/centerpoint_trt.cpp | 67 +++++++----- .../lib/network/scatter_kernel.cu | 6 +- .../lib/preprocess/preprocess_kernel.cu | 99 ++++++++++++++++- .../lib/preprocess/voxel_generator.cpp | 76 ++----------- 14 files changed, 325 insertions(+), 209 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp index 0f5ada722c31d..d28d9eb31216d 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp @@ -23,6 +23,7 @@ namespace image_projection_based_fusion { +static constexpr size_t CAPACITY_POINT = 1000000; class PointPaintingTRT : public centerpoint::CenterPointTRT { public: @@ -33,8 +34,6 @@ class PointPaintingTRT : public centerpoint::CenterPointTRT const centerpoint::DensificationParam & densification_param, const centerpoint::CenterPointConfig & config); - ~PointPaintingTRT(); - protected: bool preprocess( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, 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 7d7f290f71a4c..c913ac33d5e84 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 @@ -20,9 +20,19 @@ namespace image_projection_based_fusion { +cudaError_t generateVoxels_random_launch( + const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, + float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, + float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels, + cudaStream_t stream); + +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); + cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, - const std::size_t num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, + const unsigned int * num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, const float voxel_size_y, const float voxel_size_z, const float range_min_x, const float range_min_y, const float range_min_z, float * features, const std::size_t encoder_in_feature_size, cudaStream_t stream); diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp index 5e7a5087efb84..d0f44b9d58706 100755 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp @@ -27,9 +27,7 @@ class VoxelGenerator : public centerpoint::VoxelGenerator public: using centerpoint::VoxelGenerator::VoxelGenerator; - std::size_t pointsToVoxels( - std::vector & voxels, std::vector & coordinates, - std::vector & num_points_per_voxel) override; + std::size_t generateSweepPoints(std::vector & points) override; }; } // namespace image_projection_based_fusion 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 f0e4de9c988e2..8911442f4c75d 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 @@ -43,26 +43,37 @@ bool PointPaintingTRT::preprocess( if (!is_success) { return false; } - num_voxels_ = vg_ptr_pp_->pointsToVoxels(voxels_, coordinates_, num_points_per_voxel_); - if (num_voxels_ == 0) { - return false; - } - const auto voxels_size = - num_voxels_ * config_.max_point_in_voxel_size_ * config_.point_feature_size_; - const auto coordinates_size = num_voxels_ * config_.point_dim_size_; - // memcpy from host to device (not copy empty voxels) - CHECK_CUDA_ERROR(cudaMemcpyAsync( - voxels_d_.get(), voxels_.data(), voxels_size * sizeof(float), cudaMemcpyHostToDevice)); + const auto count = vg_ptr_pp_->generateSweepPoints(points_); CHECK_CUDA_ERROR(cudaMemcpyAsync( - coordinates_d_.get(), coordinates_.data(), coordinates_size * sizeof(int), - cudaMemcpyHostToDevice)); - CHECK_CUDA_ERROR(cudaMemcpyAsync( - num_points_per_voxel_d_.get(), num_points_per_voxel_.data(), num_voxels_ * sizeof(float), - cudaMemcpyHostToDevice)); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + points_d_.get(), points_.data(), count * config_.point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice, stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(num_voxels_d_.get(), 0, sizeof(unsigned int), stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(voxels_buffer_d_.get(), 0, voxels_buffer_size_, stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(mask_d_.get(), 0, mask_size_, stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync( + voxels_d_.get(), 0, + config_.max_voxel_size_ * config_.max_point_in_voxel_size_ * config_.point_feature_size_ * + sizeof(float), + stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync( + coordinates_d_.get(), 0, config_.max_voxel_size_ * config_.point_dim_size_ * sizeof(int), + stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync( + num_points_per_voxel_d_.get(), 0, config_.max_voxel_size_ * sizeof(float), stream_)); + + CHECK_CUDA_ERROR(image_projection_based_fusion::generateVoxels_random_launch( + points_d_.get(), count, config_.range_min_x_, config_.range_max_x_, config_.range_min_y_, + config_.range_max_y_, config_.range_min_z_, config_.range_max_z_, config_.voxel_size_x_, + config_.voxel_size_y_, config_.voxel_size_z_, config_.grid_size_y_, config_.grid_size_x_, + mask_d_.get(), voxels_buffer_d_.get(), stream_)); + + 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_)); CHECK_CUDA_ERROR(image_projection_based_fusion::generateFeatures_launch( - voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_, + voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), config_.max_voxel_size_, config_.voxel_size_x_, config_.voxel_size_y_, config_.voxel_size_z_, config_.range_min_x_, config_.range_min_y_, config_.range_min_z_, encoder_in_features_d_.get(), config_.encoder_in_feature_size_, stream_)); 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 9789f52de5f74..d06b60633acf8 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 @@ -57,9 +57,105 @@ std::size_t divup(const std::size_t a, const std::size_t b) namespace image_projection_based_fusion { +__global__ void generateVoxels_random_kernel( + const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, + float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, + float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) return; + + float x = points[point_idx * POINT_FEATURE_SIZE]; + float y = points[point_idx * POINT_FEATURE_SIZE + 1]; + float z = points[point_idx * POINT_FEATURE_SIZE + 2]; + + if ( + x < min_x_range || x >= max_x_range || y < min_y_range || y >= max_y_range || z < min_z_range || + z >= max_z_range) + return; + + int voxel_idx = floorf((x - min_x_range) / pillar_x_size); + int voxel_idy = floorf((y - min_y_range) / pillar_y_size); + unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + + unsigned int point_id = atomicAdd(&(mask[voxel_index]), 1); + + if (point_id >= MAX_POINT_IN_VOXEL_SIZE) return; + float * address = + voxels + (voxel_index * MAX_POINT_IN_VOXEL_SIZE + point_id) * POINT_FEATURE_SIZE; + for (unsigned int i = 0; i < POINT_FEATURE_SIZE; ++i) { + atomicExch(address + i, points[point_idx * POINT_FEATURE_SIZE + i]); + } +} + +cudaError_t generateVoxels_random_launch( + const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, + float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, + float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels, + cudaStream_t stream) +{ + dim3 blocks((points_size + 256 - 1) / 256); + dim3 threads(256); + generateVoxels_random_kernel<<>>( + points, points_size, min_x_range, max_x_range, min_y_range, max_y_range, min_z_range, + max_z_range, pillar_x_size, pillar_y_size, pillar_z_size, grid_y_size, grid_x_size, mask, + voxels); + cudaError_t err = cudaGetLastError(); + return err; +} + +__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 voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; + unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; + + if (voxel_idx >= grid_x_size || voxel_idy >= grid_y_size) return; + + unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + unsigned int count = mask[voxel_index]; + if (!(count > 0)) return; + count = count < MAX_POINT_IN_VOXEL_SIZE ? count : MAX_POINT_IN_VOXEL_SIZE; + + unsigned int current_pillarId = 0; + current_pillarId = atomicAdd(pillar_num, 1); + + voxel_num[current_pillarId] = count; + + uint3 idx = {0, voxel_idy, voxel_idx}; + ((uint3 *)voxel_idxs)[current_pillarId] = idx; + + for (int i = 0; i < count; i++) { + int inIndex = voxel_index * MAX_POINT_IN_VOXEL_SIZE + i; + int outIndex = current_pillarId * MAX_POINT_IN_VOXEL_SIZE + i; + for (unsigned int j = 0; j < POINT_FEATURE_SIZE; ++j) { + voxel_features[outIndex * POINT_FEATURE_SIZE + j] = voxels[inIndex * POINT_FEATURE_SIZE + j]; + } + } + + // clear buffer for next infer + atomicExch(mask + voxel_index, 0); +} + +// 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) +{ + 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); + cudaError_t err = cudaGetLastError(); + return err; +} + __global__ void generateFeatures_kernel( const float * voxel_features, const float * voxel_num_points, const int * coords, - const std::size_t num_voxels, const float voxel_x, const float voxel_y, const float voxel_z, + const unsigned int * num_voxels, const float voxel_x, const float voxel_y, const float voxel_z, const float range_min_x, const float range_min_y, const float range_min_z, float * features, const std::size_t encoder_in_feature_size) { @@ -70,7 +166,8 @@ __global__ void generateFeatures_kernel( int point_idx = threadIdx.x % MAX_POINT_IN_VOXEL_SIZE; int pillar_idx_inBlock = threadIdx.x / MAX_POINT_IN_VOXEL_SIZE; - if (pillar_idx >= num_voxels) return; + unsigned int num_pillars = num_voxels[0]; + if (pillar_idx >= num_pillars) return; // load src __shared__ float pillarSM[WARPS_PER_BLOCK][MAX_POINT_IN_VOXEL_SIZE][POINT_FEATURE_SIZE]; @@ -155,7 +252,7 @@ __global__ void generateFeatures_kernel( cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, - const std::size_t num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, + const unsigned int * num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, const float voxel_size_y, const float voxel_size_z, const float range_min_x, const float range_min_y, const float range_min_z, float * features, const std::size_t encoder_in_feature_size, cudaStream_t stream) diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp index f1ba163ee69b9..ea10cb1237436 100755 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp @@ -18,29 +18,10 @@ namespace image_projection_based_fusion { -std::size_t VoxelGenerator::pointsToVoxels( - std::vector & voxels, std::vector & coordinates, - std::vector & num_points_per_voxel) +size_t VoxelGenerator::generateSweepPoints(std::vector & points) { - // voxels (float): (max_num_voxels * max_num_points_per_voxel * point_feature_size) - // coordinates (int): (max_num_voxels * point_dim_size) - // num_points_per_voxel (float): (max_num_voxels) - - const std::size_t grid_size = config_.grid_size_z_ * config_.grid_size_y_ * config_.grid_size_x_; - std::vector> coord_to_voxel_idx(grid_size, -1); - - std::size_t voxel_cnt = 0; // @return - // std::array point; - // std::array coord_zyx; - std::vector point; - point.resize(config_.point_feature_size_); - std::vector coord_zyx; - coord_zyx.resize(config_.point_dim_size_); - bool out_of_range; - std::size_t point_cnt; - int c, coord_idx, voxel_idx; Eigen::Vector3f point_current, point_past; - + size_t point_counter{}; for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter); pc_cache_iter++) { auto pc_msg = pc_cache_iter->pointcloud_msg; @@ -55,62 +36,25 @@ std::size_t VoxelGenerator::pointsToVoxels( point_past << *x_iter, *y_iter, *z_iter; point_current = affine_past2current * point_past; - point[0] = point_current.x(); - point[1] = point_current.y(); - point[2] = point_current.z(); - point[3] = time_lag; + points.at(point_counter * config_.point_feature_size_) = point_current.x(); + points.at(point_counter * config_.point_feature_size_ + 1) = point_current.y(); + points.at(point_counter * config_.point_feature_size_ + 2) = point_current.z(); + points.at(point_counter * config_.point_feature_size_ + 3) = time_lag; // decode the class value back to one-hot binary and assign it to point - std::fill(point.begin() + 4, point.end(), 0); + for (size_t i = 0; i < config_.class_size_; ++i) { + points.at(point_counter * config_.point_feature_size_ + 4 + i) = 0.f; + } auto class_value = static_cast(*class_iter); - auto iter = point.begin() + 4; + auto iter = points.begin() + point_counter * config_.point_feature_size_ + 4; while (class_value > 0) { *iter = class_value % 2; class_value /= 2; ++iter; } - - out_of_range = false; - for (std::size_t di = 0; di < config_.point_dim_size_; di++) { - c = static_cast((point[di] - range_[di]) * recip_voxel_size_[di]); - if (c < 0 || c >= grid_size_[di]) { - out_of_range = true; - break; - } - coord_zyx[config_.point_dim_size_ - di - 1] = c; - } - if (out_of_range) { - continue; - } - - coord_idx = coord_zyx[0] * config_.grid_size_y_ * config_.grid_size_x_ + - coord_zyx[1] * config_.grid_size_x_ + coord_zyx[2]; - voxel_idx = coord_to_voxel_idx[coord_idx].value(); - if (voxel_idx == -1) { - voxel_idx = voxel_cnt; - if (voxel_cnt >= config_.max_voxel_size_) { - continue; - } - - voxel_cnt++; - coord_to_voxel_idx[coord_idx] = voxel_idx; - for (std::size_t di = 0; di < config_.point_dim_size_; di++) { - coordinates[voxel_idx * config_.point_dim_size_ + di] = coord_zyx[di]; - } - } - - point_cnt = num_points_per_voxel[voxel_idx]; - if (point_cnt < config_.max_point_in_voxel_size_) { - for (std::size_t fi = 0; fi < config_.point_feature_size_; fi++) { - voxels - [voxel_idx * config_.max_point_in_voxel_size_ * config_.point_feature_size_ + - point_cnt * config_.point_feature_size_ + fi] = point[fi]; - } - num_points_per_voxel[voxel_idx]++; - } + ++point_counter; } } - - return voxel_cnt; + return point_counter; } } // namespace image_projection_based_fusion diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp index fee17f1c0156a..8cf250be0c049 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp @@ -32,6 +32,8 @@ namespace centerpoint { +static constexpr size_t CAPACITY_POINT = 1000000; + class NetworkParam { public: @@ -59,7 +61,7 @@ class CenterPointTRT const NetworkParam & encoder_param, const NetworkParam & head_param, const DensificationParam & densification_param, const CenterPointConfig & config); - ~CenterPointTRT(); + virtual ~CenterPointTRT(); bool detect( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, @@ -83,12 +85,13 @@ class CenterPointTRT std::size_t class_size_{0}; CenterPointConfig config_; - std::size_t num_voxels_{0}; std::size_t encoder_in_feature_size_{0}; std::size_t spatial_features_size_{0}; - std::vector voxels_; - std::vector coordinates_; - std::vector num_points_per_voxel_; + std::size_t voxels_buffer_size_{0}; + std::size_t mask_size_{0}; + std::size_t voxels_size_{0}; + std::size_t coordinates_size_{0}; + std::vector points_; cuda::unique_ptr voxels_d_{nullptr}; cuda::unique_ptr coordinates_d_{nullptr}; cuda::unique_ptr num_points_per_voxel_d_{nullptr}; @@ -101,6 +104,10 @@ class CenterPointTRT cuda::unique_ptr head_out_dim_d_{nullptr}; cuda::unique_ptr head_out_rot_d_{nullptr}; cuda::unique_ptr head_out_vel_d_{nullptr}; + cuda::unique_ptr points_d_{nullptr}; + cuda::unique_ptr voxels_buffer_d_{nullptr}; + cuda::unique_ptr mask_d_{nullptr}; + cuda::unique_ptr num_voxels_d_{nullptr}; }; } // namespace centerpoint diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp index e754d89468ba3..3dd00c25fd9e7 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp @@ -21,7 +21,7 @@ namespace centerpoint { cudaError_t scatterFeatures_launch( - const float * pillar_features, const int * coords, const std::size_t num_pillars, + const float * pillar_features, const int * coords, const unsigned int * num_pillars, const std::size_t max_voxel_size, const std::size_t encoder_out_feature_size, const std::size_t grid_size_x, const std::size_t grid_size_y, float * scattered_features, cudaStream_t stream); 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 3abc8cfeccd5b..824144fe3b22b 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp @@ -20,9 +20,19 @@ namespace centerpoint { +cudaError_t generateVoxels_random_launch( + const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, + float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, + float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels, + cudaStream_t stream); + +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); + cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, - const std::size_t num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, + const unsigned int * num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, const float voxel_size_y, const float voxel_size_z, const float range_min_x, const float range_min_y, const float range_min_z, float * features, cudaStream_t stream); diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp index 810ae3afd20d0..be15d51e91715 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp @@ -31,9 +31,7 @@ class VoxelGeneratorTemplate explicit VoxelGeneratorTemplate( const DensificationParam & param, const CenterPointConfig & config); - virtual std::size_t pointsToVoxels( - std::vector & voxels, std::vector & coordinates, - std::vector & num_points_per_voxel) = 0; + virtual std::size_t generateSweepPoints(std::vector & points) = 0; bool enqueuePointCloud( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); @@ -52,9 +50,7 @@ class VoxelGenerator : public VoxelGeneratorTemplate public: using VoxelGeneratorTemplate::VoxelGeneratorTemplate; - std::size_t pointsToVoxels( - std::vector & voxels, std::vector & coordinates, - std::vector & num_points_per_voxel) override; + std::size_t generateSweepPoints(std::vector & points) override; }; } // namespace centerpoint diff --git a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp index 53e19500ff428..67271985d3b5e 100644 --- a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp @@ -69,9 +69,9 @@ CenterPointTRT::~CenterPointTRT() void CenterPointTRT::initPtr() { - const auto voxels_size = + voxels_size_ = config_.max_voxel_size_ * config_.max_point_in_voxel_size_ * config_.point_feature_size_; - const auto coordinates_size = config_.max_voxel_size_ * config_.point_dim_size_; + coordinates_size_ = config_.max_voxel_size_ * config_.point_dim_size_; encoder_in_feature_size_ = config_.max_voxel_size_ * config_.max_point_in_voxel_size_ * config_.encoder_in_feature_size_; const auto pillar_features_size = config_.max_voxel_size_ * config_.encoder_out_feature_size_; @@ -79,14 +79,16 @@ void CenterPointTRT::initPtr() config_.grid_size_x_ * config_.grid_size_y_ * config_.encoder_out_feature_size_; const auto grid_xy_size = config_.down_grid_size_x_ * config_.down_grid_size_y_; + voxels_buffer_size_ = config_.grid_size_x_ * config_.grid_size_y_ * + config_.max_point_in_voxel_size_ * config_.point_feature_size_; + mask_size_ = config_.grid_size_x_ * config_.grid_size_y_; + // host - voxels_.resize(voxels_size); - coordinates_.resize(coordinates_size); - num_points_per_voxel_.resize(config_.max_voxel_size_); + points_.resize(CAPACITY_POINT * config_.point_feature_size_); // device - voxels_d_ = cuda::make_unique(voxels_size); - coordinates_d_ = cuda::make_unique(coordinates_size); + voxels_d_ = cuda::make_unique(voxels_size_); + coordinates_d_ = cuda::make_unique(coordinates_size_); num_points_per_voxel_d_ = cuda::make_unique(config_.max_voxel_size_); encoder_in_features_d_ = cuda::make_unique(encoder_in_feature_size_); pillar_features_d_ = cuda::make_unique(pillar_features_size); @@ -97,15 +99,16 @@ void CenterPointTRT::initPtr() head_out_dim_d_ = cuda::make_unique(grid_xy_size * config_.head_out_dim_size_); head_out_rot_d_ = cuda::make_unique(grid_xy_size * config_.head_out_rot_size_); head_out_vel_d_ = cuda::make_unique(grid_xy_size * config_.head_out_vel_size_); + points_d_ = cuda::make_unique(CAPACITY_POINT * config_.point_feature_size_); + voxels_buffer_d_ = cuda::make_unique(voxels_buffer_size_); + mask_d_ = cuda::make_unique(mask_size_); + num_voxels_d_ = cuda::make_unique(1); } bool CenterPointTRT::detect( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, std::vector & det_boxes3d) { - std::fill(voxels_.begin(), voxels_.end(), 0); - std::fill(coordinates_.begin(), coordinates_.end(), -1); - std::fill(num_points_per_voxel_.begin(), num_points_per_voxel_.end(), 0); CHECK_CUDA_ERROR(cudaMemsetAsync( encoder_in_features_d_.get(), 0, encoder_in_feature_size_ * sizeof(float), stream_)); CHECK_CUDA_ERROR( @@ -131,27 +134,33 @@ bool CenterPointTRT::preprocess( if (!is_success) { return false; } - num_voxels_ = vg_ptr_->pointsToVoxels(voxels_, coordinates_, num_points_per_voxel_); - if (num_voxels_ == 0) { - return false; - } - - const auto voxels_size = - num_voxels_ * config_.max_point_in_voxel_size_ * config_.point_feature_size_; - const auto coordinates_size = num_voxels_ * config_.point_dim_size_; - // memcpy from host to device (not copy empty voxels) - CHECK_CUDA_ERROR(cudaMemcpyAsync( - voxels_d_.get(), voxels_.data(), voxels_size * sizeof(float), cudaMemcpyHostToDevice)); - CHECK_CUDA_ERROR(cudaMemcpyAsync( - coordinates_d_.get(), coordinates_.data(), coordinates_size * sizeof(int), - cudaMemcpyHostToDevice)); + const auto count = vg_ptr_->generateSweepPoints(points_); CHECK_CUDA_ERROR(cudaMemcpyAsync( - num_points_per_voxel_d_.get(), num_points_per_voxel_.data(), num_voxels_ * sizeof(float), - cudaMemcpyHostToDevice)); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + points_d_.get(), points_.data(), count * config_.point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice, stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(num_voxels_d_.get(), 0, sizeof(unsigned int), stream_)); + CHECK_CUDA_ERROR( + cudaMemsetAsync(voxels_buffer_d_.get(), 0, voxels_buffer_size_ * sizeof(float), stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(mask_d_.get(), 0, mask_size_ * sizeof(int), stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(voxels_d_.get(), 0, voxels_size_ * sizeof(float), stream_)); + CHECK_CUDA_ERROR( + cudaMemsetAsync(coordinates_d_.get(), 0, coordinates_size_ * sizeof(int), stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync( + num_points_per_voxel_d_.get(), 0, config_.max_voxel_size_ * sizeof(float), stream_)); + + CHECK_CUDA_ERROR(generateVoxels_random_launch( + points_d_.get(), count, config_.range_min_x_, config_.range_max_x_, config_.range_min_y_, + config_.range_max_y_, config_.range_min_z_, config_.range_max_z_, config_.voxel_size_x_, + config_.voxel_size_y_, config_.voxel_size_z_, config_.grid_size_y_, config_.grid_size_x_, + mask_d_.get(), voxels_buffer_d_.get(), stream_)); + + 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_)); CHECK_CUDA_ERROR(generateFeatures_launch( - voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_, + voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), config_.max_voxel_size_, config_.voxel_size_x_, config_.voxel_size_y_, config_.voxel_size_z_, config_.range_min_x_, config_.range_min_y_, config_.range_min_z_, encoder_in_features_d_.get(), stream_)); @@ -171,7 +180,7 @@ void CenterPointTRT::inference() // scatter CHECK_CUDA_ERROR(scatterFeatures_launch( - pillar_features_d_.get(), coordinates_d_.get(), num_voxels_, config_.max_voxel_size_, + pillar_features_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), config_.max_voxel_size_, config_.encoder_out_feature_size_, config_.grid_size_x_, config_.grid_size_y_, spatial_features_d_.get(), stream_)); diff --git a/perception/lidar_centerpoint/lib/network/scatter_kernel.cu b/perception/lidar_centerpoint/lib/network/scatter_kernel.cu index da2f0e2f57c15..09cc83bf606fe 100644 --- a/perception/lidar_centerpoint/lib/network/scatter_kernel.cu +++ b/perception/lidar_centerpoint/lib/network/scatter_kernel.cu @@ -24,7 +24,7 @@ const std::size_t THREADS_PER_BLOCK = 32; namespace centerpoint { __global__ void scatterFeatures_kernel( - const float * pillar_features, const int * coords, const std::size_t num_pillars, + const float * pillar_features, const int * coords, const unsigned int * num_pillars, const std::size_t pillar_feature_size, const std::size_t grid_size_x, const std::size_t grid_size_y, float * scattered_features) { @@ -34,7 +34,7 @@ __global__ void scatterFeatures_kernel( const auto pillar_i = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x; const auto feature_i = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y; - if (pillar_i >= num_pillars || feature_i >= pillar_feature_size) { + if (pillar_i >= num_pillars[0] || feature_i >= pillar_feature_size) { return; } @@ -50,7 +50,7 @@ __global__ void scatterFeatures_kernel( // cspell: ignore divup cudaError_t scatterFeatures_launch( - const float * pillar_features, const int * coords, const std::size_t num_pillars, + const float * pillar_features, const int * coords, const unsigned int * num_pillars, const std::size_t max_voxel_size, const std::size_t encoder_out_feature_size, const std::size_t grid_size_x, const std::size_t grid_size_y, float * scattered_features, cudaStream_t stream) diff --git a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 7b59757311ff2..6f77ff84c2cea 100644 --- a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -41,9 +41,101 @@ const std::size_t ENCODER_IN_FEATURE_SIZE = 9; // the same as encoder_in_featur namespace centerpoint { +__global__ void generateVoxels_random_kernel( + const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, + float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, + float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) return; + + float4 point = ((float4 *)points)[point_idx]; + + if ( + point.x < min_x_range || point.x >= max_x_range || point.y < min_y_range || + point.y >= max_y_range || point.z < min_z_range || point.z >= max_z_range) + return; + + int voxel_idx = floorf((point.x - min_x_range) / pillar_x_size); + int voxel_idy = floorf((point.y - min_y_range) / pillar_y_size); + unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + + unsigned int point_id = atomicAdd(&(mask[voxel_index]), 1); + + if (point_id >= MAX_POINT_IN_VOXEL_SIZE) return; + float * address = voxels + (voxel_index * MAX_POINT_IN_VOXEL_SIZE + point_id) * 4; + atomicExch(address + 0, point.x); + atomicExch(address + 1, point.y); + atomicExch(address + 2, point.z); + atomicExch(address + 3, point.w); +} + +cudaError_t generateVoxels_random_launch( + const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, + float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, + float pillar_z_size, int grid_y_size, int grid_x_size, unsigned int * mask, float * voxels, + cudaStream_t stream) +{ + dim3 blocks((points_size + 256 - 1) / 256); + dim3 threads(256); + generateVoxels_random_kernel<<>>( + points, points_size, min_x_range, max_x_range, min_y_range, max_y_range, min_z_range, + max_z_range, pillar_x_size, pillar_y_size, pillar_z_size, grid_y_size, grid_x_size, mask, + voxels); + cudaError_t err = cudaGetLastError(); + return err; +} + +__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 voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; + unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; + + if (voxel_idx >= grid_x_size || voxel_idy >= grid_y_size) return; + + unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + unsigned int count = mask[voxel_index]; + if (!(count > 0)) return; + count = count < MAX_POINT_IN_VOXEL_SIZE ? count : MAX_POINT_IN_VOXEL_SIZE; + + unsigned int current_pillarId = 0; + current_pillarId = atomicAdd(pillar_num, 1); + + voxel_num[current_pillarId] = count; + + uint3 idx = {0, voxel_idy, voxel_idx}; + ((uint3 *)voxel_idxs)[current_pillarId] = idx; + + for (int i = 0; i < count; i++) { + int inIndex = voxel_index * MAX_POINT_IN_VOXEL_SIZE + i; + int outIndex = current_pillarId * MAX_POINT_IN_VOXEL_SIZE + i; + ((float4 *)voxel_features)[outIndex] = ((float4 *)voxels)[inIndex]; + } + + // clear buffer for next infer + atomicExch(mask + voxel_index, 0); +} + +// 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) +{ + 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); + cudaError_t err = cudaGetLastError(); + return err; +} + __global__ void generateFeatures_kernel( const float * voxel_features, const float * voxel_num_points, const int * coords, - const std::size_t num_voxels, const float voxel_x, const float voxel_y, const float voxel_z, + const unsigned int * num_voxels, const float voxel_x, const float voxel_y, const float voxel_z, const float range_min_x, const float range_min_y, const float range_min_z, float * features) { // voxel_features (float): (max_voxel_size, max_point_in_voxel_size, point_feature_size) @@ -53,7 +145,8 @@ __global__ void generateFeatures_kernel( int point_idx = threadIdx.x % MAX_POINT_IN_VOXEL_SIZE; int pillar_idx_inBlock = threadIdx.x / MAX_POINT_IN_VOXEL_SIZE; // max_point_in_voxel_size - if (pillar_idx >= num_voxels) return; + unsigned int num_pillars = num_voxels[0]; + if (pillar_idx >= num_pillars) return; // load src __shared__ float4 pillarSM[WARPS_PER_BLOCK][MAX_POINT_IN_VOXEL_SIZE]; @@ -144,7 +237,7 @@ __global__ void generateFeatures_kernel( // cspell: ignore divup cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, - const std::size_t num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, + const unsigned int * num_voxels, const std::size_t max_voxel_size, const float voxel_size_x, const float voxel_size_y, const float voxel_size_z, const float range_min_x, const float range_min_y, const float range_min_z, float * features, cudaStream_t stream) { diff --git a/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp b/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp index 7f4e4a849211c..07a1a2de725f5 100644 --- a/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp +++ b/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp @@ -43,34 +43,15 @@ bool VoxelGeneratorTemplate::enqueuePointCloud( return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer); } -std::size_t VoxelGenerator::pointsToVoxels( - std::vector & voxels, std::vector & coordinates, - std::vector & num_points_per_voxel) +std::size_t VoxelGenerator::generateSweepPoints(std::vector & points) { - // voxels (float): (max_voxel_size * max_point_in_voxel_size * point_feature_size) - // coordinates (int): (max_voxel_size * point_dim_size) - // num_points_per_voxel (float): (max_voxel_size) - - const std::size_t grid_size = config_.grid_size_z_ * config_.grid_size_y_ * config_.grid_size_x_; - std::vector coord_to_voxel_idx(grid_size, -1); - - std::size_t voxel_cnt = 0; // @return - std::vector point; - point.resize(config_.point_feature_size_); - std::vector coord_zyx; - coord_zyx.resize(config_.point_dim_size_); - bool out_of_range; - std::size_t point_cnt; - int c, coord_idx, voxel_idx; Eigen::Vector3f point_current, point_past; - + size_t point_counter{}; for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter); pc_cache_iter++) { auto pc_msg = pc_cache_iter->pointcloud_msg; auto affine_past2current = - pd_ptr_->pointcloud_cache_size() > 1 - ? pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world - : Eigen::Affine3f::Identity(); + pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world; float time_lag = static_cast( pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_msg.header.stamp).seconds()); @@ -80,53 +61,14 @@ std::size_t VoxelGenerator::pointsToVoxels( point_past << *x_iter, *y_iter, *z_iter; point_current = affine_past2current * point_past; - point[0] = point_current.x(); - point[1] = point_current.y(); - point[2] = point_current.z(); - point[3] = time_lag; - - out_of_range = false; - for (std::size_t di = 0; di < config_.point_dim_size_; di++) { - c = static_cast((point[di] - range_[di]) * recip_voxel_size_[di]); - if (c < 0 || c >= grid_size_[di]) { - out_of_range = true; - break; - } - coord_zyx[config_.point_dim_size_ - di - 1] = c; - } - if (out_of_range) { - continue; - } - - coord_idx = coord_zyx[0] * config_.grid_size_y_ * config_.grid_size_x_ + - coord_zyx[1] * config_.grid_size_x_ + coord_zyx[2]; - voxel_idx = coord_to_voxel_idx[coord_idx]; - if (voxel_idx == -1) { - voxel_idx = voxel_cnt; - if (voxel_cnt >= config_.max_voxel_size_) { - continue; - } - - voxel_cnt++; - coord_to_voxel_idx[coord_idx] = voxel_idx; - for (std::size_t di = 0; di < config_.point_dim_size_; di++) { - coordinates[voxel_idx * config_.point_dim_size_ + di] = coord_zyx[di]; - } - } - - point_cnt = num_points_per_voxel[voxel_idx]; - if (point_cnt < config_.max_point_in_voxel_size_) { - for (std::size_t fi = 0; fi < config_.point_feature_size_; fi++) { - voxels - [voxel_idx * config_.max_point_in_voxel_size_ * config_.point_feature_size_ + - point_cnt * config_.point_feature_size_ + fi] = point[fi]; - } - num_points_per_voxel[voxel_idx]++; - } + points.at(point_counter * config_.point_feature_size_) = point_current.x(); + points.at(point_counter * config_.point_feature_size_ + 1) = point_current.y(); + points.at(point_counter * config_.point_feature_size_ + 2) = point_current.z(); + points.at(point_counter * config_.point_feature_size_ + 3) = time_lag; + ++point_counter; } } - - return voxel_cnt; + return point_counter; } } // namespace centerpoint From 703d91f79e718793e36ef1c1c4e15e6eb200683a Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 29 Nov 2023 11:19:00 +0100 Subject: [PATCH 056/128] fix: include mussp library into the packages to avoid duplicates (#5706) Signed-off-by: Esteve Fernandez --- perception/multi_object_tracker/CMakeLists.txt | 4 ---- perception/object_merger/CMakeLists.txt | 6 +----- perception/radar_object_tracker/CMakeLists.txt | 7 +------ perception/tracking_object_merger/CMakeLists.txt | 6 +----- 4 files changed, 3 insertions(+), 20 deletions(-) diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 7dc7ee9d75cf3..3e379bcfd1cf1 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -31,9 +31,6 @@ set(MULTI_OBJECT_TRACKER_SRC src/tracker/model/unknown_tracker.cpp src/tracker/model/pass_through_tracker.cpp src/data_association/data_association.cpp -) - -ament_auto_add_library(mu_successive_shortest_path SHARED src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp ) @@ -42,7 +39,6 @@ ament_auto_add_library(multi_object_tracker_node SHARED ) target_link_libraries(multi_object_tracker_node - mu_successive_shortest_path Eigen3::Eigen ) diff --git a/perception/object_merger/CMakeLists.txt b/perception/object_merger/CMakeLists.txt index 0d5ca532bdd9d..b02983db11af3 100644 --- a/perception/object_merger/CMakeLists.txt +++ b/perception/object_merger/CMakeLists.txt @@ -18,17 +18,13 @@ include_directories( ${EIGEN3_INCLUDE_DIR} ) -ament_auto_add_library(mu_successive_shortest_path SHARED - src/object_association_merger/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp -) - ament_auto_add_library(object_association_merger SHARED src/object_association_merger/data_association/data_association.cpp + src/object_association_merger/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp src/object_association_merger/node.cpp ) target_link_libraries(object_association_merger - mu_successive_shortest_path Eigen3::Eigen ) diff --git a/perception/radar_object_tracker/CMakeLists.txt b/perception/radar_object_tracker/CMakeLists.txt index 3e3afacadd00f..54ef7b047bf17 100644 --- a/perception/radar_object_tracker/CMakeLists.txt +++ b/perception/radar_object_tracker/CMakeLists.txt @@ -18,11 +18,6 @@ include_directories( ${EIGEN3_INCLUDE_DIR} ) -# Targets -ament_auto_add_library(mu_successive_shortest_path SHARED - src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp -) - ament_auto_add_library(radar_object_tracker_node SHARED src/radar_object_tracker_node/radar_object_tracker_node.cpp src/tracker/model/tracker_base.cpp @@ -30,10 +25,10 @@ ament_auto_add_library(radar_object_tracker_node SHARED src/tracker/model/constant_turn_rate_motion_tracker.cpp src/utils/utils.cpp src/data_association/data_association.cpp + src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp ) target_link_libraries(radar_object_tracker_node - mu_successive_shortest_path Eigen3::Eigen yaml-cpp nlohmann_json::nlohmann_json # for debug diff --git a/perception/tracking_object_merger/CMakeLists.txt b/perception/tracking_object_merger/CMakeLists.txt index ed5aa76afbfd9..5e46b9403462d 100644 --- a/perception/tracking_object_merger/CMakeLists.txt +++ b/perception/tracking_object_merger/CMakeLists.txt @@ -21,19 +21,15 @@ include_directories( ${EIGEN3_INCLUDE_DIR} ) -ament_auto_add_library(mu_successive_shortest_path SHARED - src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp -) - ament_auto_add_library(decorative_tracker_merger_node SHARED src/data_association/data_association.cpp + src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp src/decorative_tracker_merger.cpp src/utils/utils.cpp src/utils/tracker_state.cpp ) target_link_libraries(decorative_tracker_merger_node - mu_successive_shortest_path Eigen3::Eigen ) From e68ddf24b0b1ee36c199d32962b72e34a89f4129 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 29 Nov 2023 21:12:10 +0900 Subject: [PATCH 057/128] feat(simple_plannign_simulator): add map acc model (#5688) * (simple_planning_simulator):add delay converter model Signed-off-by: Takumi Ito * refactoring rename and format read acc map path from config Signed-off-by: kosuke55 * update docs Signed-off-by: kosuke55 * remove noisy print Signed-off-by: kosuke55 * update map Signed-off-by: kosuke55 * fix pre-commit Signed-off-by: kosuke55 * update acc map Signed-off-by: kosuke55 * fix pre-commit and typo Signed-off-by: kosuke55 typo typo * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe * Update simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp Co-authored-by: Takamasa Horibe * update error message Signed-off-by: kosuke55 * simplify map exmaple Signed-off-by: kosuke55 * use double Signed-off-by: kosuke55 * style(pre-commit): autofix * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe * add csv loader im sim pacakges Signed-off-by: kosuke55 * revert raw vehicle cmd converter Signed-off-by: kosuke55 * Update simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp Co-authored-by: Takamasa Horibe * Update simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp Co-authored-by: Takamasa Horibe * Update simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp Co-authored-by: Takamasa Horibe --------- Signed-off-by: Takumi Ito Signed-off-by: kosuke55 Co-authored-by: Takumi Ito Co-authored-by: Takamasa Horibe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../simple_planning_simulator/CMakeLists.txt | 2 + simulator/simple_planning_simulator/README.md | 61 +- .../simple_planning_simulator_core.hpp | 3 +- .../utils/csv_loader.hpp | 44 + .../vehicle_model/sim_model.hpp | 1 + .../sim_model_delay_steer_map_acc_geared.hpp | 211 ++ .../simple_planning_simulator.launch.py | 14 +- .../media/acceleration_map.svg | 2448 +++++++++++++++++ .../simple_planning_simulator/package.xml | 2 + .../param/acceleration_map.csv | 4 + ...mple_planning_simulator_default.param.yaml | 1 + .../simple_planning_simulator_core.cpp | 23 +- .../utils/csv_loader.cpp | 150 + .../sim_model_delay_steer_map_acc_geared.cpp | 174 ++ 14 files changed, 3118 insertions(+), 20 deletions(-) create mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp create mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp create mode 100644 simulator/simple_planning_simulator/media/acceleration_map.svg create mode 100644 simulator/simple_planning_simulator/param/acceleration_map.csv create mode 100644 simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp create mode 100644 simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 6034697304059..87d0f7e5fef0b 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -16,6 +16,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp + src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp + src/simple_planning_simulator/utils/csv_loader.cpp ) target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${tf2_INCLUDE_DIRS}) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 1491f8ffea36e..b441f9f903d0d 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -62,26 +62,57 @@ The purpose of this simulator is for the integration test of planning and contro - `DELAY_STEER_VEL` - `DELAY_STEER_ACC` - `DELAY_STEER_ACC_GEARED` +- `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves based on a 1st-order with time delay model. The `STEER` means the model receives the steer command. The `VEL` means the model receives the target velocity command, while the `ACC` model receives the target acceleration command. The `GEARED` suffix means that the motion will consider the gear command: the vehicle moves only one direction following the gear. The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | Default value | unit | -| :------------------------- | :----- | :--------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | 5.0 | [rad/s] | -| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | 1.0 | [-] | -| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | 1.0 | [-] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_M_ACC_G | Default value | unit | +| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :----------- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | x | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | 5.0 | [rad/s] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | x | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | x | 1.0 | [-] | +| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | o | - | [-] | + +The `acceleration_map` is used only for `DELAY_STEER_MAP_ACC_GEARED` and it shows the acceleration command on the vertical axis and the current velocity on the horizontal axis, with each cell representing the converted acceleration command that is actually used in the simulator's motion calculation. Values in between are linearly interpolated. + +Example of `acceleration_map.csv` + +```csv +default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 13.89, 15.28, 16.67 +-4.0, -4.40, -4.36, -4.38, -4.12, -4.20, -3.94, -3.98, -3.80, -3.77, -3.76, -3.59, -3.50, -3.40 +-3.5, -4.00, -3.91, -3.85, -3.64, -3.68, -3.55, -3.42, -3.24, -3.25, -3.00, -3.04, -2.93, -2.80 +-3.0, -3.40, -3.37, -3.33, -3.00, -3.00, -2.90, -2.88, -2.65, -2.43, -2.44, -2.43, -2.39, -2.30 +-2.5, -2.80, -2.72, -2.72, -2.62, -2.41, -2.43, -2.26, -2.18, -2.11, -2.03, -1.96, -1.91, -1.85 +-2.0, -2.30, -2.24, -2.12, -2.02, -1.92, -1.81, -1.67, -1.58, -1.51, -1.49, -1.40, -1.35, -1.30 +-1.5, -1.70, -1.61, -1.47, -1.46, -1.40, -1.37, -1.29, -1.24, -1.10, -0.99, -0.83, -0.80, -0.78 +-1.0, -1.30, -1.28, -1.10, -1.09, -1.04, -1.02, -0.98, -0.89, -0.82, -0.61, -0.52, -0.54, -0.56 +-0.8, -0.96, -0.90, -0.82, -0.74, -0.70, -0.65, -0.63, -0.59, -0.55, -0.44, -0.39, -0.39, -0.35 +-0.6, -0.77, -0.71, -0.67, -0.65, -0.58, -0.52, -0.51, -0.50, -0.40, -0.33, -0.30, -0.31, -0.30 +-0.4, -0.45, -0.40, -0.45, -0.44, -0.38, -0.35, -0.31, -0.30, -0.26, -0.30, -0.29, -0.31, -0.25 +-0.2, -0.24, -0.24, -0.25, -0.22, -0.23, -0.25, -0.27, -0.29, -0.24, -0.22, -0.17, -0.18, -0.12 + 0.0, 0.00, 0.00, -0.05, -0.05, -0.05, -0.05, -0.08, -0.08, -0.08, -0.08, -0.10, -0.10, -0.10 + 0.2, 0.16, 0.12, 0.02, 0.02, 0.00, 0.00, -0.05, -0.05, -0.05, -0.05, -0.08, -0.08, -0.08 + 0.4, 0.38, 0.30, 0.22, 0.25, 0.24, 0.23, 0.20, 0.16, 0.16, 0.14, 0.10, 0.05, 0.05 + 0.6, 0.52, 0.52, 0.51, 0.49, 0.43, 0.40, 0.35, 0.33, 0.33, 0.33, 0.32, 0.34, 0.34 + 0.8, 0.82, 0.81, 0.78, 0.68, 0.63, 0.56, 0.53, 0.48, 0.43, 0.41, 0.37, 0.38, 0.40 + 1.0, 1.00, 1.08, 1.01, 0.88, 0.76, 0.69, 0.66, 0.58, 0.54, 0.49, 0.45, 0.40, 0.40 + 1.5, 1.52, 1.50, 1.38, 1.26, 1.14, 1.03, 0.91, 0.82, 0.67, 0.61, 0.51, 0.41, 0.41 + 2.0, 1.80, 1.80, 1.64, 1.43, 1.25, 1.11, 0.96, 0.81, 0.70, 0.59, 0.51, 0.42, 0.42 +``` + +![acceleration_map](./media/acceleration_map.svg) 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 b0df04285ac9f..38f689c124439 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 @@ -209,7 +209,8 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node DELAY_STEER_ACC = 2, DELAY_STEER_ACC_GEARED = 3, IDEAL_STEER_VEL = 4, - DELAY_STEER_VEL = 5 + DELAY_STEER_VEL = 5, + DELAY_STEER_MAP_ACC_GEARED = 6 } vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics std::shared_ptr vehicle_model_ptr_; //!< @brief vehicle model pointer diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp new file mode 100644 index 0000000000000..fc71837541b83 --- /dev/null +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp @@ -0,0 +1,44 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ +#define SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ + +#include +#include +#include +#include +#include + +using Table = std::vector>; +using Map = std::vector>; +class CSVLoader +{ +public: + explicit CSVLoader(const std::string & csv_path); + + bool readCSV(Table & result, const char delim = ','); + static bool validateData(const Table & table, const std::string & csv_path); + static bool validateMap(const Map & map, const bool is_col_decent); + static Map getMap(const Table & table); + static std::vector getRowIndex(const Table & table); + static std::vector getColumnIndex(const Table & table); + static double clampValue( + const double val, const std::vector & ranges, const std::string & name); + +private: + std::string csv_path_; +}; + +#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp index aef83f10ac417..9fa4516c1a522 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp @@ -17,6 +17,7 @@ #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp" 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 new file mode 100644 index 0000000000000..2cc33f9b5f82b --- /dev/null +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp @@ -0,0 +1,211 @@ +// 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 SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ +#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ + +#include "eigen3/Eigen/Core" +#include "eigen3/Eigen/LU" +#include "interpolation/linear_interpolation.hpp" +#include "simple_planning_simulator/utils/csv_loader.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" + +#include + +#include +#include +#include +#include +#include + +class AccelerationMap +{ +public: + bool readAccelerationMapFromCSV(const std::string & csv_path) + { + CSVLoader csv(csv_path); + std::vector> table; + if (!csv.readCSV(table)) { + std::cerr << "[SimModelDelaySteerMapAccGeared]: failed to read acceleration map from " + << csv_path << std::endl; + return false; + } + + vehicle_name_ = table[0][0]; + vel_index_ = CSVLoader::getRowIndex(table); + acc_index_ = CSVLoader::getColumnIndex(table); + acceleration_map_ = CSVLoader::getMap(table); + + std::cout << "[SimModelDelaySteerMapAccGeared]: success to read acceleration map from " + << csv_path << std::endl; + return true; + } + + double getAcceleration(const double acc_des, const double vel) const + { + std::vector interpolated_acc_vec; + const double clamped_vel = CSVLoader::clampValue(vel, vel_index_, "acc: vel"); + + // (throttle, vel, acc) map => (throttle, acc) map by fixing vel + for (const auto & acc_vec : acceleration_map_) { + interpolated_acc_vec.push_back(interpolation::lerp(vel_index_, acc_vec, clamped_vel)); + } + // calculate throttle + // When the desired acceleration is smaller than the throttle area, return min acc + // When the desired acceleration is greater than the throttle area, return max acc + const double clamped_acc = CSVLoader::clampValue(acc_des, acc_index_, "acceleration: acc"); + const double acc = interpolation::lerp(acc_index_, interpolated_acc_vec, clamped_acc); + + return acc; + } + std::vector> acceleration_map_; + +private: + std::string vehicle_name_; + std::vector vel_index_; + std::vector acc_index_; +}; + +class SimModelDelaySteerMapAccGeared : public SimModelInterface +{ +public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] acc_delay time delay for accel command [s] + * @param [in] acc_time_constant time constant for 1D model of accel dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] path path to csv file for acceleration conversion map + */ + SimModelDelaySteerMapAccGeared( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double acc_delay, double acc_time_constant, double steer_delay, + double steer_time_constant, std::string path); + + /** + * @brief default destructor + */ + ~SimModelDelaySteerMapAccGeared() = default; + + AccelerationMap acc_map_; + +private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum IDX { + X = 0, + Y, + YAW, + VX, + STEER, + ACCX, + }; + enum IDX_U { + ACCX_DES = 0, + STEER_DES, + DRIVE_SHIFT, + }; + + const double vx_lim_; //!< @brief velocity limit [m/s] + const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] + const double steer_lim_; //!< @brief steering limit [rad] + const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_; //!< @brief vehicle wheelbase length [m] + + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for steering dynamics + const std::string path_; //!< @brief conversion map path + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double & dt); + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle lateral velocity + */ + double getVy() override; + + /** + * @brief get vehicle longitudinal acceleration + */ + double getAx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double & dt) override; + + /** + * @brief calculate derivative of states with time delay steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; + + /** + * @brief update state considering current gear + * @param [in] state current state + * @param [in] prev_state previous state + * @param [in] gear current gear (defined in autoware_auto_msgs/GearCommand) + * @param [in] dt delta time to update state + */ + void updateStateWithGear( + Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, + const double dt); +}; + +#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index 2f9c2cfe333f4..0070646a20d49 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -18,6 +18,7 @@ from launch.actions import OpaqueFunction from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node +import launch_ros.parameter_descriptions from launch_ros.substitutions import FindPackageShare import yaml @@ -35,8 +36,9 @@ def launch_setup(context, *args, **kwargs): vehicle_characteristics_param = yaml.safe_load(f)["/**"]["ros__parameters"] simulator_model_param_path = LaunchConfiguration("simulator_model_param_file").perform(context) - with open(simulator_model_param_path, "r") as f: - simulator_model_param = yaml.safe_load(f)["/**"]["ros__parameters"] + simulator_model_param = launch_ros.parameter_descriptions.ParameterFile( + param_file=simulator_model_param_path, allow_substs=True + ) simple_planning_simulator_node = Node( package="simple_planning_simulator", @@ -129,4 +131,12 @@ def add_launch_arg(name: str, default_value=None, description=None): "path to config file for simulator_model", ) + add_launch_arg( + "acceleration_param_file", + [ + FindPackageShare("simple_planning_simulator"), + "/param/acceleration_map.csv", + ], + ) + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/simulator/simple_planning_simulator/media/acceleration_map.svg b/simulator/simple_planning_simulator/media/acceleration_map.svg new file mode 100644 index 0000000000000..55b0c685726a4 --- /dev/null +++ b/simulator/simple_planning_simulator/media/acceleration_map.svg @@ -0,0 +1,2448 @@ + + + + + + + + 2023-11-28T14:30:04.088460 + image/svg+xml + + + Matplotlib v3.5.1, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 5652be138b18f..a2038486029dc 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -11,6 +11,8 @@ ament_cmake_auto autoware_cmake + autoware_cmake + autoware_auto_control_msgs autoware_auto_mapping_msgs autoware_auto_planning_msgs diff --git a/simulator/simple_planning_simulator/param/acceleration_map.csv b/simulator/simple_planning_simulator/param/acceleration_map.csv new file mode 100644 index 0000000000000..e365ead979912 --- /dev/null +++ b/simulator/simple_planning_simulator/param/acceleration_map.csv @@ -0,0 +1,4 @@ +default,0.00,20.0 +-4,-4,-4 +0,0,0 +4,4,4 diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml b/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml index dbd56bf9e9bff..bbc92a4ffeff8 100644 --- a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml +++ b/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml @@ -17,5 +17,6 @@ steer_dead_band: 0.0 x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate + # acceleration_map_path: $(var vehicle_model_pkg)/config/acceleration_map.csv # only `DELAY_STEER_MAP_ACC_GEARED` needs this parameter # Note: vehicle characteristics parameters (e.g. wheelbase) are defined in a separate file. 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 f0b126cbc61be..9a0ea6a6c3659 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 @@ -33,6 +33,7 @@ #include #include +#include #include #include #include @@ -261,6 +262,22 @@ void SimplePlanningSimulator::initialize_vehicle_model() vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, debug_acc_scaling_factor, debug_steer_scaling_factor); + } else if (vehicle_model_type_str == "DELAY_STEER_MAP_ACC_GEARED") { + vehicle_model_type_ = VehicleModelType::DELAY_STEER_MAP_ACC_GEARED; + const std::string acceleration_map_path = + declare_parameter("acceleration_map_path"); + if (!std::filesystem::exists(acceleration_map_path)) { + throw std::runtime_error( + "`acceleration_map_path` parameter is necessary for `DELAY_STEER_MAP_ACC_GEARED` simulator " + "model, but " + + acceleration_map_path + + " does not exist. Please confirm that the parameter is set correctly in " + "{simulator_model.param.yaml}."); + } + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, + acceleration_map_path); } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); } @@ -464,7 +481,8 @@ void SimplePlanningSimulator::set_input( input << acc, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC_GEARED || - vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED) { + vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || + vehicle_model_type_ == VehicleModelType::DELAY_STEER_MAP_ACC_GEARED) { input << acc, steer; } vehicle_model_ptr_->setInput(input); @@ -560,7 +578,8 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist & state << x, y, yaw, vx, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC || - vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED) { + vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || + vehicle_model_type_ == VehicleModelType::DELAY_STEER_MAP_ACC_GEARED) { state << x, y, yaw, vx, steer, accx; } vehicle_model_ptr_->setState(state); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp new file mode 100644 index 0000000000000..c9eb7a5a237fb --- /dev/null +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp @@ -0,0 +1,150 @@ +// 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 "simple_planning_simulator/utils/csv_loader.hpp" + +#include +#include +#include +#include + +CSVLoader::CSVLoader(const std::string & csv_path) +{ + csv_path_ = csv_path; +} + +bool CSVLoader::readCSV(Table & result, const char delim) +{ + std::ifstream ifs(csv_path_); + if (!ifs.is_open()) { + std::cerr << "Cannot open " << csv_path_.c_str() << std::endl; + return false; + } + + std::string buf; + while (std::getline(ifs, buf)) { + std::vector tokens; + + std::istringstream iss(buf); + std::string token; + while (std::getline(iss, token, delim)) { + tokens.push_back(token); + } + + if (tokens.size() != 0) { + result.push_back(tokens); + } + } + if (!validateData(result, csv_path_)) { + return false; + } + return true; +} + +bool CSVLoader::validateMap(const Map & map, const bool is_col_decent) +{ + std::pair invalid_index_pair; + bool is_invalid = false; + // validate interpolation + for (size_t i = 1; i < map.size(); i++) { + const auto & vec = map.at(i); + const auto & prev_vec = map.at(i - 1); + // validate row data + for (size_t j = 0; j < vec.size(); j++) { + // validate col + if (vec.at(j) <= prev_vec.at(j) && is_col_decent) { + invalid_index_pair = std::make_pair(i, j); + is_invalid = true; + } + if (vec.at(j) >= prev_vec.at(j) && !is_col_decent) { + invalid_index_pair = std::make_pair(i, j); + is_invalid = true; + } + } + } + if (is_invalid) { + std::cerr << "index around (i,j) is invalid ( " << invalid_index_pair.first << ", " + << invalid_index_pair.second << " )" << std::endl; + return false; + } + return true; +} + +bool CSVLoader::validateData(const Table & table, const std::string & csv_path) +{ + if (table.empty()) { + std::cerr << "The table is empty." << std::endl; + return false; + } + if (table[0].size() < 2) { + std::cerr << "Cannot read " << csv_path.c_str() << " CSV file should have at least 2 column" + << std::endl; + return false; + } + // validate map size + for (size_t i = 1; i < table.size(); i++) { + // validate row size + if (table[0].size() != table[i].size()) { + std::cerr << "Cannot read " << csv_path.c_str() + << ". Each row should have a same number of columns" << std::endl; + return false; + } + } + return true; +} + +Map CSVLoader::getMap(const Table & table) +{ + Map map = {}; + for (size_t i = 1; i < table.size(); i++) { + std::vector accelerations; + for (size_t j = 1; j < table[i].size(); j++) { + accelerations.push_back(std::stod(table[i][j])); + } + map.push_back(accelerations); + } + return map; +} + +std::vector CSVLoader::getRowIndex(const Table & table) +{ + std::vector index = {}; + for (size_t i = 1; i < table[0].size(); i++) { + index.push_back(std::stod(table[0][i])); + } + return index; +} + +std::vector CSVLoader::getColumnIndex(const Table & table) +{ + std::vector index = {}; + for (size_t i = 1; i < table.size(); i++) { + index.push_back(std::stod(table[i][0])); + } + return index; +} + +double CSVLoader::clampValue( + const double val, const std::vector & ranges, const std::string & name) +{ + const double max_value = *std::max_element(ranges.begin(), ranges.end()); + const double min_value = *std::min_element(ranges.begin(), ranges.end()); + if (val < min_value || max_value < val) { + std::cerr << "Input " << name << ": " << val + << " is out of range. use closest value. Please update the conversion map" + << std::endl; + return std::min(std::max(val, min_value), max_value); + } + return val; +} diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp new file mode 100644 index 0000000000000..b04a10667adcf --- /dev/null +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp @@ -0,0 +1,174 @@ +// 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 "simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" + +#include "autoware_auto_vehicle_msgs/msg/gear_command.hpp" + +#include + +SimModelDelaySteerMapAccGeared::SimModelDelaySteerMapAccGeared( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double acc_delay, double acc_time_constant, double steer_delay, + double steer_time_constant, std::string path) +: SimModelInterface(6 /* dim x */, 2 /* dim u */), + MIN_TIME_CONSTANT(0.03), + vx_lim_(vx_lim), + vx_rate_lim_(vx_rate_lim), + steer_lim_(steer_lim), + steer_rate_lim_(steer_rate_lim), + wheelbase_(wheelbase), + acc_delay_(acc_delay), + acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), + steer_delay_(steer_delay), + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + path_(path) +{ + initializeInputQueue(dt); + acc_map_.readAccelerationMapFromCSV(path_); +} + +double SimModelDelaySteerMapAccGeared::getX() +{ + return state_(IDX::X); +} +double SimModelDelaySteerMapAccGeared::getY() +{ + return state_(IDX::Y); +} +double SimModelDelaySteerMapAccGeared::getYaw() +{ + return state_(IDX::YAW); +} +double SimModelDelaySteerMapAccGeared::getVx() +{ + return state_(IDX::VX); +} +double SimModelDelaySteerMapAccGeared::getVy() +{ + return 0.0; +} +double SimModelDelaySteerMapAccGeared::getAx() +{ + return state_(IDX::ACCX); +} +double SimModelDelaySteerMapAccGeared::getWz() +{ + return state_(IDX::VX) * std::tan(state_(IDX::STEER)) / wheelbase_; +} +double SimModelDelaySteerMapAccGeared::getSteer() +{ + return state_(IDX::STEER); +} +void SimModelDelaySteerMapAccGeared::update(const double & dt) +{ + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + acc_input_queue_.push_back(input_(IDX_U::ACCX_DES)); + delayed_input(IDX_U::ACCX_DES) = acc_input_queue_.front(); + acc_input_queue_.pop_front(); + steer_input_queue_.push_back(input_(IDX_U::STEER_DES)); + delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front(); + steer_input_queue_.pop_front(); + + const auto prev_state = state_; + updateRungeKutta(dt, delayed_input); + + // take velocity limit explicitly + state_(IDX::VX) = std::max(-vx_lim_, std::min(state_(IDX::VX), vx_lim_)); + + // consider gear + // update position and velocity first, and then acceleration is calculated naturally + updateStateWithGear(state_, prev_state, gear_, dt); +} + +void SimModelDelaySteerMapAccGeared::initializeInputQueue(const double & dt) +{ + size_t acc_input_queue_size = static_cast(round(acc_delay_ / dt)); + acc_input_queue_.resize(acc_input_queue_size); + std::fill(acc_input_queue_.begin(), acc_input_queue_.end(), 0.0); + + size_t steer_input_queue_size = static_cast(round(steer_delay_ / dt)); + steer_input_queue_.resize(steer_input_queue_size); + std::fill(steer_input_queue_.begin(), steer_input_queue_.end(), 0.0); +} + +Eigen::VectorXd SimModelDelaySteerMapAccGeared::calcModel( + const Eigen::VectorXd & state, const Eigen::VectorXd & input) +{ + const double vel = std::clamp(state(IDX::VX), -vx_lim_, vx_lim_); + const double acc = std::clamp(state(IDX::ACCX), -vx_rate_lim_, vx_rate_lim_); + const double yaw = state(IDX::YAW); + const double steer = state(IDX::STEER); + const double acc_des = std::clamp(input(IDX_U::ACCX_DES), -vx_rate_lim_, vx_rate_lim_); + const double steer_des = std::clamp(input(IDX_U::STEER_DES), -steer_lim_, steer_lim_); + double steer_rate = -(steer - steer_des) / steer_time_constant_; + steer_rate = std::clamp(steer_rate, -steer_rate_lim_, steer_rate_lim_); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vel * cos(yaw); + d_state(IDX::Y) = vel * sin(yaw); + d_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; + d_state(IDX::VX) = acc; + d_state(IDX::STEER) = steer_rate; + const double converted_acc = + acc_map_.acceleration_map_.empty() ? acc_des : acc_map_.getAcceleration(acc_des, vel); + + d_state(IDX::ACCX) = -(acc - converted_acc) / acc_time_constant_; + + return d_state; +} + +void SimModelDelaySteerMapAccGeared::updateStateWithGear( + Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt) +{ + using autoware_auto_vehicle_msgs::msg::GearCommand; + if ( + gear == GearCommand::DRIVE || gear == GearCommand::DRIVE_2 || gear == GearCommand::DRIVE_3 || + gear == GearCommand::DRIVE_4 || gear == GearCommand::DRIVE_5 || gear == GearCommand::DRIVE_6 || + gear == GearCommand::DRIVE_7 || gear == GearCommand::DRIVE_8 || gear == GearCommand::DRIVE_9 || + gear == GearCommand::DRIVE_10 || gear == GearCommand::DRIVE_11 || + gear == GearCommand::DRIVE_12 || gear == GearCommand::DRIVE_13 || + gear == GearCommand::DRIVE_14 || gear == GearCommand::DRIVE_15 || + gear == GearCommand::DRIVE_16 || gear == GearCommand::DRIVE_17 || + gear == GearCommand::DRIVE_18 || gear == GearCommand::LOW || gear == GearCommand::LOW_2) { + if (state(IDX::VX) < 0.0) { + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); + state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); + } + } else if (gear == GearCommand::REVERSE || gear == GearCommand::REVERSE_2) { + if (state(IDX::VX) > 0.0) { + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); + state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); + } + } else if (gear == GearCommand::PARK) { + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); + state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); + } else { + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); + state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); + } +} From 9444f0c5441123035d080a78b4df0f5e509dd149 Mon Sep 17 00:00:00 2001 From: Yuntianyi Chen Date: Wed, 29 Nov 2023 15:49:23 -0800 Subject: [PATCH 058/128] refactor(detection_by_tracker): rework parameters (#4989) * refactor the configuration files of the node detection_by_tracker_node according to the new ROS node config guideline. update the parameter information in the README.md Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * revert copyright info Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * update config file Signed-off-by: yuntianyi-chen --------- Signed-off-by: yuntianyi-chen 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> --- .../detection_by_tracker/CMakeLists.txt | 3 +- perception/detection_by_tracker/README.md | 11 +++ .../config/detection_by_tracker.param.yaml | 17 ++--- .../schema/detection_by_tracker.schema.json | 74 +++++++++++++++++++ 4 files changed, 95 insertions(+), 10 deletions(-) create mode 100644 perception/detection_by_tracker/schema/detection_by_tracker.schema.json diff --git a/perception/detection_by_tracker/CMakeLists.txt b/perception/detection_by_tracker/CMakeLists.txt index 51839027e0e41..3813f1ba4707f 100644 --- a/perception/detection_by_tracker/CMakeLists.txt +++ b/perception/detection_by_tracker/CMakeLists.txt @@ -44,7 +44,8 @@ rclcpp_components_register_node(detection_by_tracker_node EXECUTABLE detection_by_tracker ) -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE launch config ) diff --git a/perception/detection_by_tracker/README.md b/perception/detection_by_tracker/README.md index aece084cd319e..0cff97c4d3ab4 100644 --- a/perception/detection_by_tracker/README.md +++ b/perception/detection_by_tracker/README.md @@ -46,6 +46,17 @@ Simply looking at the overlap between the unknown object and the tracker does no ## Parameters +| Name | Type | Description | Default value | +| --------------------------------- | ------ | --------------------------------------------------------------------- | ------------- | +| `tracker_ignore_label.UNKNOWN` | `bool` | If true, the node will ignore the tracker if its label is unknown. | `true` | +| `tracker_ignore_label.CAR` | `bool` | If true, the node will ignore the tracker if its label is CAR. | `false` | +| `tracker_ignore_label.PEDESTRIAN` | `bool` | If true, the node will ignore the tracker if its label is pedestrian. | `false` | +| `tracker_ignore_label.BICYCLE` | `bool` | If true, the node will ignore the tracker if its label is bicycle. | `false` | +| `tracker_ignore_label.MOTORCYCLE` | `bool` | If true, the node will ignore the tracker if its label is MOTORCYCLE. | `false` | +| `tracker_ignore_label.BUS` | `bool` | If true, the node will ignore the tracker if its label is bus. | `false` | +| `tracker_ignore_label.TRUCK` | `bool` | If true, the node will ignore the tracker if its label is truck. | `false` | +| `tracker_ignore_label.TRAILER` | `bool` | If true, the node will ignore the tracker if its label is TRAILER. | `false` | + ## Assumptions / Known limits ## (Optional) Error detection and handling diff --git a/perception/detection_by_tracker/config/detection_by_tracker.param.yaml b/perception/detection_by_tracker/config/detection_by_tracker.param.yaml index 695704050697d..fac8687c5eeb3 100644 --- a/perception/detection_by_tracker/config/detection_by_tracker.param.yaml +++ b/perception/detection_by_tracker/config/detection_by_tracker.param.yaml @@ -1,11 +1,10 @@ /**: ros__parameters: - tracker_ignore_label: - UNKNOWN : true - CAR : false - TRUCK : false - BUS : false - TRAILER : false - MOTORCYCLE : false - BICYCLE : false - PEDESTRIAN : false + tracker_ignore_label.UNKNOWN : true + tracker_ignore_label.CAR : false + tracker_ignore_label.TRUCK : false + tracker_ignore_label.BUS : false + tracker_ignore_label.TRAILER : false + tracker_ignore_label.MOTORCYCLE : false + tracker_ignore_label.BICYCLE : false + tracker_ignore_label.PEDESTRIAN : false diff --git a/perception/detection_by_tracker/schema/detection_by_tracker.schema.json b/perception/detection_by_tracker/schema/detection_by_tracker.schema.json new file mode 100644 index 0000000000000..22c2b4fa15437 --- /dev/null +++ b/perception/detection_by_tracker/schema/detection_by_tracker.schema.json @@ -0,0 +1,74 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Detection By Tracker Node", + "type": "object", + "definitions": { + "detection_by_tracker": { + "type": "object", + "properties": { + "tracker_ignore_label.UNKNOWN": { + "type": "boolean", + "default": true, + "description": "If true, the node will ignore the tracker if its label is unknown." + }, + "tracker_ignore_label.CAR": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is CAR." + }, + "tracker_ignore_label.PEDESTRIAN": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is pedestrian." + }, + "tracker_ignore_label.BICYCLE": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is bicycle." + }, + "tracker_ignore_label.MOTORCYCLE": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is motorcycle." + }, + "tracker_ignore_label.BUS": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is bus." + }, + "tracker_ignore_label.TRUCK": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is truck." + }, + "tracker_ignore_label.TRAILER": { + "type": "boolean", + "default": false, + "description": "If true, the node will ignore the tracker if its label is TRAILER." + } + }, + "required": [ + "tracker_ignore_label.UNKNOWN", + "tracker_ignore_label.CAR", + "tracker_ignore_label.PEDESTRIAN", + "tracker_ignore_label.BICYCLE", + "tracker_ignore_label.MOTORCYCLE", + "tracker_ignore_label.BUS", + "tracker_ignore_label.TRUCK", + "tracker_ignore_label.TRAILER" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/detection_by_tracker" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 2bd9d55bb9e4d0c4d80cb178b85d9a2899551f1c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 30 Nov 2023 10:28:56 +0900 Subject: [PATCH 059/128] fix(path_smoother): faster elastic band by sparse matrix (#5718) * fix(path_smoother): faster elastic band by sparse matrix Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- planning/path_smoother/src/elastic_band.cpp | 54 ++++++++++++--------- 1 file changed, 31 insertions(+), 23 deletions(-) diff --git a/planning/path_smoother/src/elastic_band.cpp b/planning/path_smoother/src/elastic_band.cpp index fb3aff7b18419..ecf847d496f34 100644 --- a/planning/path_smoother/src/elastic_band.cpp +++ b/planning/path_smoother/src/elastic_band.cpp @@ -20,48 +20,53 @@ #include "path_smoother/utils/trajectory_utils.hpp" #include "tf2/utils.h" +#include +#include + #include #include #include namespace { -Eigen::MatrixXd makePMatrix(const int num_points) +Eigen::SparseMatrix makePMatrix(const int num_points) { - // create P block matrix - Eigen::MatrixXd P_quarter = Eigen::MatrixXd::Zero(num_points, num_points); + std::vector> triplet_vec; + const auto assign_value_to_triplet_vec = + [&](const double row, const double colum, const double value) { + triplet_vec.push_back(Eigen::Triplet(row, colum, value)); + triplet_vec.push_back(Eigen::Triplet(row + num_points, colum + num_points, value)); + }; + for (int r = 0; r < num_points; ++r) { for (int c = 0; c < num_points; ++c) { if (r == c) { if (r == 0 || r == num_points - 1) { - P_quarter(r, c) = 1.0; + assign_value_to_triplet_vec(r, c, 1.0); } else if (r == 1 || r == num_points - 2) { - P_quarter(r, c) = 5.0; + assign_value_to_triplet_vec(r, c, 5.0); } else { - P_quarter(r, c) = 6.0; + assign_value_to_triplet_vec(r, c, 6.0); } } else if (std::abs(c - r) == 1) { if (r == 0 || r == num_points - 1) { - P_quarter(r, c) = -2.0; + assign_value_to_triplet_vec(r, c, -2.0); } else if (c == 0 || c == num_points - 1) { - P_quarter(r, c) = -2.0; + assign_value_to_triplet_vec(r, c, -2.0); } else { - P_quarter(r, c) = -4.0; + assign_value_to_triplet_vec(r, c, -4.0); } } else if (std::abs(c - r) == 2) { - P_quarter(r, c) = 1.0; + assign_value_to_triplet_vec(r, c, 1.0); } else { - P_quarter(r, c) = 0.0; + assign_value_to_triplet_vec(r, c, 0.0); } } } - // create P matrix - Eigen::MatrixXd P = Eigen::MatrixXd::Zero(num_points * 2, num_points * 2); - P.block(0, 0, num_points, num_points) = P_quarter; - P.block(num_points, num_points, num_points, num_points) = P_quarter; - - return P; + Eigen::SparseMatrix sparse_mat(num_points * 2, num_points * 2); + sparse_mat.setFromTriplets(triplet_vec.begin(), triplet_vec.end()); + return sparse_mat; } std::vector toStdVector(const Eigen::VectorXd & eigen_vec) @@ -344,25 +349,28 @@ void EBPathSmoother::updateConstraint( } Eigen::VectorXd x_mat(2 * p.num_points); - Eigen::MatrixXd theta_mat = Eigen::MatrixXd::Zero(p.num_points, 2 * p.num_points); + std::vector> theta_triplet_vec; for (size_t i = 0; i < static_cast(p.num_points); ++i) { x_mat(i) = traj_points.at(i).pose.position.x; x_mat(i + p.num_points) = traj_points.at(i).pose.position.y; const double yaw = tf2::getYaw(traj_points.at(i).pose.orientation); - theta_mat(i, i) = -std::sin(yaw); - theta_mat(i, i + p.num_points) = std::cos(yaw); + theta_triplet_vec.push_back(Eigen::Triplet(i, i, -std::sin(yaw))); + theta_triplet_vec.push_back(Eigen::Triplet(i, i + p.num_points, std::cos(yaw))); } + Eigen::SparseMatrix sparse_theta_mat(p.num_points, 2 * p.num_points); + sparse_theta_mat.setFromTriplets(theta_triplet_vec.begin(), theta_triplet_vec.end()); // calculate P - const Eigen::MatrixXd raw_P_for_smooth = p.smooth_weight * makePMatrix(p.num_points); - const Eigen::MatrixXd P_for_smooth = theta_mat * raw_P_for_smooth * theta_mat.transpose(); + const Eigen::SparseMatrix raw_P_for_smooth = p.smooth_weight * makePMatrix(p.num_points); + const Eigen::MatrixXd theta_P_mat = sparse_theta_mat * raw_P_for_smooth; + const Eigen::MatrixXd P_for_smooth = theta_P_mat * sparse_theta_mat.transpose(); const Eigen::MatrixXd P_for_lat_error = p.lat_error_weight * Eigen::MatrixXd::Identity(p.num_points, p.num_points); const Eigen::MatrixXd P = P_for_smooth + P_for_lat_error; // calculate q - const Eigen::VectorXd raw_q_for_smooth = theta_mat * raw_P_for_smooth * x_mat; + const Eigen::VectorXd raw_q_for_smooth = theta_P_mat * x_mat; const auto q = toStdVector(raw_q_for_smooth); if (p.enable_warm_start && osqp_solver_ptr_) { From 3ac90b08c7a57dca222b5c65734b3ffddbad4d60 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 30 Nov 2023 10:46:05 +0900 Subject: [PATCH 060/128] feat(tier4_autoware_utils): intersection result with z (#5714) Signed-off-by: Takayuki Murooka --- common/tier4_autoware_utils/src/geometry/geometry.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/common/tier4_autoware_utils/src/geometry/geometry.cpp b/common/tier4_autoware_utils/src/geometry/geometry.cpp index 03625f19ec8ea..b88646b73dd7c 100644 --- a/common/tier4_autoware_utils/src/geometry/geometry.cpp +++ b/common/tier4_autoware_utils/src/geometry/geometry.cpp @@ -379,6 +379,7 @@ std::optional intersect( geometry_msgs::msg::Point intersect_point; intersect_point.x = t * p1.x + (1.0 - t) * p2.x; intersect_point.y = t * p1.y + (1.0 - t) * p2.y; + intersect_point.z = t * p1.z + (1.0 - t) * p2.z; return intersect_point; } From 05e9c89e1a6b9f5096d56680f1d7eb1e68482aa1 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 30 Nov 2023 10:54:46 +0900 Subject: [PATCH 061/128] feat(map_based_prediction): use glog (#5721) Signed-off-by: kyoichi-sugahara --- perception/map_based_prediction/CMakeLists.txt | 4 ++++ perception/map_based_prediction/package.xml | 1 + .../map_based_prediction/src/map_based_prediction_node.cpp | 4 ++++ 3 files changed, 9 insertions(+) diff --git a/perception/map_based_prediction/CMakeLists.txt b/perception/map_based_prediction/CMakeLists.txt index 53c78b54bc2ab..9378e09f099cc 100644 --- a/perception/map_based_prediction/CMakeLists.txt +++ b/perception/map_based_prediction/CMakeLists.txt @@ -6,6 +6,8 @@ autoware_package() find_package(Eigen3 REQUIRED) +find_package(glog REQUIRED) + include_directories( SYSTEM ${EIGEN3_INCLUDE_DIR} @@ -17,6 +19,8 @@ ament_auto_add_library(map_based_prediction_node SHARED src/debug.cpp ) +target_link_libraries(map_based_prediction_node glog::glog) + rclcpp_components_register_node(map_based_prediction_node PLUGIN "map_based_prediction::MapBasedPredictionNode" EXECUTABLE map_based_prediction diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index 6a1354b37928f..b07d9855f9821 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/map_based_prediction/package.xml @@ -18,6 +18,7 @@ autoware_auto_perception_msgs interpolation lanelet2_extension + libgoogle-glog-dev motion_utils rclcpp rclcpp_components 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 b2f1296cc85b9..263794e7e3bc5 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -43,6 +43,8 @@ #include #endif +#include + #include #include #include @@ -718,6 +720,8 @@ void replaceObjectYawWithLaneletsYaw( MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) : Node("map_based_prediction", node_options), debug_accumulated_time_(0.0) { + google::InitGoogleLogging("map_based_prediction_node"); + google::InstallFailureSignalHandler(); enable_delay_compensation_ = declare_parameter("enable_delay_compensation"); prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); lateral_control_time_horizon_ = From 4887bdcc83249be721d6545e98fa2e85101d745f Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 30 Nov 2023 10:55:07 +0900 Subject: [PATCH 062/128] fix(external_cmd_converter): define timer_rate parameter (#5719) The commit introduces a missing launch argument "timer_rate" to the external_cmd_converter. This parameter is used to set the update rate of the timer. The default value for this parameter is 10.0. The changes have been reflected in both .py and .xml launch files. Signed-off-by: kyoichi-sugahara --- .../launch/external_cmd_converter.launch.py | 6 ++++++ .../launch/external_cmd_converter.launch.xml | 2 ++ 2 files changed, 8 insertions(+) diff --git a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py index 01029004e6e47..77dbb99d9b477 100644 --- a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py +++ b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.py @@ -52,6 +52,11 @@ def generate_launch_description(): default_value="3.0", description="gain for external command accel", ), + DeclareLaunchArgument( + "timer_rate", + default_value="10.0", + description="timer's update rate", + ), DeclareLaunchArgument( "wait_for_first_topic", default_value="true", @@ -118,6 +123,7 @@ def generate_launch_description(): _create_mapping_tuple("csv_path_accel_map"), _create_mapping_tuple("csv_path_brake_map"), _create_mapping_tuple("ref_vel_gain"), + _create_mapping_tuple("timer_rate"), _create_mapping_tuple("wait_for_first_topic"), _create_mapping_tuple("control_command_timeout"), _create_mapping_tuple("emergency_stop_timeout"), diff --git a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml index 05310fe0f6e07..c4de561103de6 100644 --- a/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml +++ b/vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml @@ -6,6 +6,7 @@ + @@ -26,6 +27,7 @@ + From a736e8cecf700507d108194b88feba3f220b9973 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 30 Nov 2023 11:39:00 +0900 Subject: [PATCH 063/128] chore: remove unnecessary dynamic_avoidance config (#5680) Signed-off-by: Takayuki Murooka --- .../config/dynamic_avoidance.param.yaml | 58 ------------------- 1 file changed, 58 deletions(-) delete mode 100644 planning/behavior_path_planner/config/dynamic_avoidance.param.yaml diff --git a/planning/behavior_path_planner/config/dynamic_avoidance.param.yaml b/planning/behavior_path_planner/config/dynamic_avoidance.param.yaml deleted file mode 100644 index 896c44c9cec9a..0000000000000 --- a/planning/behavior_path_planner/config/dynamic_avoidance.param.yaml +++ /dev/null @@ -1,58 +0,0 @@ -/**: - ros__parameters: - dynamic_avoidance: - common: - enable_debug_info: true - - # avoidance is performed for the object type with true - target_object: - car: true - truck: true - bus: true - trailer: true - unknown: false - bicycle: false - motorcycle: true - pedestrian: false - - min_obstacle_vel: 0.0 # [m/s] - - successive_num_to_entry_dynamic_avoidance_condition: 5 - successive_num_to_exit_dynamic_avoidance_condition: 1 - - min_obj_lat_offset_to_ego_path: 0.0 # [m] - max_obj_lat_offset_to_ego_path: 1.0 # [m] - - cut_in_object: - min_time_to_start_cut_in: 1.0 # [s] - min_lon_offset_ego_to_object: 0.0 # [m] - - cut_out_object: - max_time_from_outside_ego_path: 2.0 # [s] - min_object_lat_vel: 0.3 # [m/s] - - crossing_object: - min_overtaking_object_vel: 1.0 - max_overtaking_object_angle: 1.05 - min_oncoming_object_vel: 0.0 - max_oncoming_object_angle: 0.523 - - front_object: - max_object_angle: 0.785 - - drivable_area_generation: - lat_offset_from_obstacle: 0.8 # [m] - max_lat_offset_to_avoid: 0.5 # [m] - - # for same directional object - overtaking_object: - max_time_to_collision: 40.0 # [s] - start_duration_to_avoid: 2.0 # [s] - end_duration_to_avoid: 4.0 # [s] - duration_to_hold_avoidance: 3.0 # [s] - - # for opposite directional object - oncoming_object: - max_time_to_collision: 15.0 # [s] - start_duration_to_avoid: 12.0 # [s] - end_duration_to_avoid: 0.0 # [s] From a710ed0ba53f104ec2d5903bc2fa78c11ddc85cd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 30 Nov 2023 11:39:56 +0900 Subject: [PATCH 064/128] feat(dynamic_avoidance): added several min_object_vel parameters (#5685) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance/dynamic_avoidance.param.yaml | 4 +++- .../dynamic_avoidance/dynamic_avoidance_module.hpp | 2 ++ .../dynamic_avoidance/dynamic_avoidance_module.cpp | 11 +++++++++-- .../src/scene_module/dynamic_avoidance/manager.cpp | 10 ++++++++-- 4 files changed, 22 insertions(+), 5 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 9ee86a06a4c1d..24bc144c40afd 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 @@ -28,10 +28,12 @@ cut_in_object: min_time_to_start_cut_in: 1.0 # [s] min_lon_offset_ego_to_object: 0.0 # [m] + min_object_vel: 0.5 # [m/s] cut_out_object: max_time_from_outside_ego_path: 2.0 # [s] min_object_lat_vel: 0.3 # [m/s] + min_object_vel: 0.5 # [m/s] crossing_object: min_overtaking_object_vel: 1.0 @@ -41,7 +43,7 @@ front_object: max_object_angle: 0.785 - min_vel: -0.5 # [m/s] The value is negative considering the noisy velocity of the stopped vehicle. + min_object_vel: -0.5 # [m/s] The value is negative considering the noisy velocity of the stopped vehicle. 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: 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 37bd28576928c..da80541223ab2 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 @@ -71,8 +71,10 @@ struct DynamicAvoidanceParameters double min_time_to_start_cut_in{0.0}; double min_lon_offset_ego_to_cut_in_object{0.0}; + double min_cut_in_object_vel{0.0}; double max_time_from_outside_ego_path_for_cut_out{0.0}; double min_cut_out_object_lat_vel{0.0}; + double min_cut_out_object_vel{0.0}; double max_front_object_angle{0.0}; double min_front_object_vel{0.0}; double max_front_object_ego_path_lat_cover_ratio{0.0}; 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 7bc61a4d747c7..900c0e178352e 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 @@ -504,7 +504,9 @@ void DynamicAvoidanceModule::updateTargetObjects() 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); - if (object.is_object_on_ego_path && is_object_aligned_to_path) { + if ( + object.is_object_on_ego_path && is_object_aligned_to_path && + parameters_->min_front_object_vel < object.vel) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, "[DynamicAvoidance] Ignore obstacle (%s) since it is to be followed.", obj_uuid.c_str()); @@ -686,6 +688,11 @@ bool DynamicAvoidanceModule::willObjectCutIn( const double obj_tangent_vel, const LatLonOffset & lat_lon_offset, PolygonGenerationMethod & polygon_generation_method) const { + // Ignore oncoming object + if (obj_tangent_vel < parameters_->min_cut_in_object_vel) { + return false; + } + // Check if ego's path and object's path are close. const bool will_object_cut_in = [&]() { for (const auto & predicted_path_point : predicted_path.path) { @@ -725,7 +732,7 @@ DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCut const std::optional & prev_object) const { // Ignore oncoming object - if (obj_tangent_vel < 0) { + if (obj_tangent_vel < parameters_->min_cut_out_object_vel) { return DecisionWithReason{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 0b2fc9e789ab3..b321331bc5b72 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 @@ -63,17 +63,20 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( node->declare_parameter(ns + "cut_in_object.min_time_to_start_cut_in"); p.min_lon_offset_ego_to_cut_in_object = node->declare_parameter(ns + "cut_in_object.min_lon_offset_ego_to_object"); + p.min_cut_in_object_vel = node->declare_parameter(ns + "cut_in_object.min_object_vel"); p.max_time_from_outside_ego_path_for_cut_out = node->declare_parameter(ns + "cut_out_object.max_time_from_outside_ego_path"); p.min_cut_out_object_lat_vel = node->declare_parameter(ns + "cut_out_object.min_object_lat_vel"); + p.min_cut_out_object_vel = + node->declare_parameter(ns + "cut_out_object.min_object_vel"); p.max_front_object_angle = node->declare_parameter(ns + "front_object.max_object_angle"); - p.min_front_object_vel = node->declare_parameter(ns + "front_object.min_vel"); p.max_front_object_ego_path_lat_cover_ratio = node->declare_parameter(ns + "front_object.max_ego_path_lat_cover_ratio"); + p.min_front_object_vel = node->declare_parameter(ns + "front_object.min_object_vel"); p.min_overtaking_crossing_object_vel = node->declare_parameter(ns + "crossing_object.min_overtaking_object_vel"); @@ -160,19 +163,22 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "cut_in_object.min_lon_offset_ego_to_object", p->min_lon_offset_ego_to_cut_in_object); + updateParam(parameters, ns + "cut_in_object.min_object_vel", p->min_cut_in_object_vel); updateParam( parameters, ns + "cut_out_object.max_time_from_outside_ego_path", p->max_time_from_outside_ego_path_for_cut_out); updateParam( parameters, ns + "cut_out_object.min_object_lat_vel", p->min_cut_out_object_lat_vel); + updateParam( + parameters, ns + "cut_out_object.min_object_vel", p->min_cut_out_object_vel); updateParam( parameters, ns + "front_object.max_object_angle", p->max_front_object_angle); - updateParam(parameters, ns + "front_object.min_vel", p->min_front_object_vel); updateParam( parameters, ns + "front_object.max_ego_path_lat_cover_ratio", p->max_front_object_ego_path_lat_cover_ratio); + updateParam(parameters, ns + "front_object.min_object_vel", p->min_front_object_vel); updateParam( parameters, ns + "crossing_object.min_overtaking_object_vel", From 061609a915876dbd603af1dbc1377e6ed0d1baa8 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 30 Nov 2023 12:24:32 +0900 Subject: [PATCH 065/128] fix(obstacle_cruise): proper handle with backward paths in the polygon expansion (#5703) * proper handle with backward paths in the polygon expansion Signed-off-by: Yuki Takagi --- planning/obstacle_cruise_planner/src/node.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index c9fe9f2210423..fb263c3a90786 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -557,13 +557,16 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( const double step_length = p.decimate_trajectory_step_length; const double time_to_convergence = p.time_to_convergence; - std::vector polygons; - const double current_ego_lat_error = - motion_utils::calcLateralOffset(traj_points, current_ego_pose.position); - const double current_ego_yaw_error = - motion_utils::calcYawDeviation(traj_points, current_ego_pose); + const size_t nearest_idx = + motion_utils::findNearestSegmentIndex(traj_points, current_ego_pose.position); + const auto nearest_pose = traj_points.at(nearest_idx).pose; + const auto current_ego_pose_error = + tier4_autoware_utils::inverseTransformPose(current_ego_pose, nearest_pose); + const double current_ego_lat_error = current_ego_pose_error.position.y; + const double current_ego_yaw_error = tf2::getYaw(current_ego_pose_error.orientation); double time_elapsed = 0.0; + std::vector polygons; std::vector last_poses = {traj_points.at(0).pose}; if (is_enable_current_pose_consideration) { last_poses.push_back(current_ego_pose); @@ -586,7 +589,7 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( tier4_autoware_utils::transformPose(indexed_pose_err, traj_points.at(i).pose)); if (traj_points.at(i).longitudinal_velocity_mps != 0.0) { - time_elapsed += step_length / traj_points.at(i).longitudinal_velocity_mps; + time_elapsed += step_length / std::abs(traj_points.at(i).longitudinal_velocity_mps); } else { time_elapsed = std::numeric_limits::max(); } From 0fe3cb0c8245669b03ceb4f4fab211f50b596e03 Mon Sep 17 00:00:00 2001 From: shulanbushangshu <102840938+shulanbushangshu@users.noreply.github.com> Date: Thu, 30 Nov 2023 12:57:42 +0800 Subject: [PATCH 066/128] feat: add SplineInterpolation test (#4617) * add SplineInterpolation test Signed-off-by: jack.song * add SplineInterpolation test Signed-off-by: jack.song * add SplineInterpolation test Signed-off-by: jack.song * style(pre-commit): autofix --------- Signed-off-by: jack.song Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takayuki Murooka --- .../test/src/test_spline_interpolation.cpp | 50 +++++++++++++++---- 1 file changed, 41 insertions(+), 9 deletions(-) diff --git a/common/interpolation/test/src/test_spline_interpolation.cpp b/common/interpolation/test/src/test_spline_interpolation.cpp index c95fc902ade44..94baf50992cf5 100644 --- a/common/interpolation/test/src/test_spline_interpolation.cpp +++ b/common/interpolation/test/src/test_spline_interpolation.cpp @@ -222,16 +222,48 @@ TEST(spline_interpolation, splineByAkima) TEST(spline_interpolation, SplineInterpolation) { - // curve: query_keys is random - const std::vector base_keys{-1.5, 1.0, 5.0, 10.0, 15.0, 20.0}; - const std::vector base_values{-1.2, 0.5, 1.0, 1.2, 2.0, 1.0}; - const std::vector query_keys{0.0, 8.0, 18.0}; - const std::vector ans{-0.075611, 0.997242, 1.573258}; + { + // curve: query_keys is random + const std::vector base_keys{-1.5, 1.0, 5.0, 10.0, 15.0, 20.0}; + const std::vector base_values{-1.2, 0.5, 1.0, 1.2, 2.0, 1.0}; + const std::vector query_keys{0.0, 8.0, 18.0}; + const std::vector ans{-0.075611, 0.997242, 1.573258}; + + SplineInterpolation s(base_keys, base_values); + const std::vector query_values = s.getSplineInterpolatedValues(query_keys); + + for (size_t i = 0; i < query_values.size(); ++i) { + EXPECT_NEAR(query_values.at(i), ans.at(i), epsilon); + } + } + + { + // getSplineInterpolatedDiffValues + const std::vector base_keys{-1.5, 1.0, 5.0, 10.0, 15.0, 20.0}; + const std::vector base_values{-1.2, 0.5, 1.0, 1.2, 2.0, 1.0}; + const std::vector query_keys{0.0, 8.0, 12.0, 18.0}; + const std::vector ans{0.671301, 0.0509853, 0.209426, -0.253628}; - SplineInterpolation s(base_keys, base_values); - const std::vector query_values = s.getSplineInterpolatedValues(query_keys); + SplineInterpolation s(base_keys, base_values); + const std::vector query_values = s.getSplineInterpolatedDiffValues(query_keys); - for (size_t i = 0; i < query_values.size(); ++i) { - EXPECT_NEAR(query_values.at(i), ans.at(i), epsilon); + for (size_t i = 0; i < query_values.size(); ++i) { + EXPECT_NEAR(query_values.at(i), ans.at(i), epsilon); + } + } + + { + // getSplineInterpolatedQuadDiffValues + const std::vector base_keys{-1.5, 1.0, 5.0, 10.0, 15.0, 20.0}; + const std::vector base_values{-1.2, 0.5, 1.0, 1.2, 2.0, 1.0}; + const std::vector query_keys{0.0, 8.0, 12.0, 18.0}; + const std::vector ans{-0.156582, 0.0440771, -0.0116873, -0.0495025}; + + SplineInterpolation s(base_keys, base_values); + const std::vector query_values = s.getSplineInterpolatedQuadDiffValues(query_keys); + + for (size_t i = 0; i < query_values.size(); ++i) { + EXPECT_NEAR(query_values.at(i), ans.at(i), epsilon); + } } } From 118e9b671159b41402453af2274f6dc6a733611f Mon Sep 17 00:00:00 2001 From: Makoto Kurihara Date: Thu, 30 Nov 2023 14:01:13 +0900 Subject: [PATCH 067/128] =?UTF-8?q?chore(mrm=5Femergency=5Fstop=5Foperator?= =?UTF-8?q?):=20add=20a=20maintainer=20for=20mrm=20operator=E2=80=A6=20(#3?= =?UTF-8?q?489)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit chore(mrm_emergency_stop_operator): add a maintainer for mrm operator packages Signed-off-by: Makoto Kurihara --- system/mrm_comfortable_stop_operator/package.xml | 1 + system/mrm_emergency_stop_operator/package.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/system/mrm_comfortable_stop_operator/package.xml b/system/mrm_comfortable_stop_operator/package.xml index 881d1f0e81bd7..ca65de87d762a 100644 --- a/system/mrm_comfortable_stop_operator/package.xml +++ b/system/mrm_comfortable_stop_operator/package.xml @@ -5,6 +5,7 @@ 0.1.0 The MRM comfortable stop operator package Makoto Kurihara + Tomohito Ando Apache License 2.0 ament_cmake_auto diff --git a/system/mrm_emergency_stop_operator/package.xml b/system/mrm_emergency_stop_operator/package.xml index 54ad68f00537a..251e79a07a73d 100644 --- a/system/mrm_emergency_stop_operator/package.xml +++ b/system/mrm_emergency_stop_operator/package.xml @@ -5,6 +5,7 @@ 0.1.0 The MRM emergency stop operator package Makoto Kurihara + Tomohito Ando Apache License 2.0 ament_cmake_auto From b5417a9dc0def367c6aa804594703d337f21d78a Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 30 Nov 2023 16:07:00 +0900 Subject: [PATCH 068/128] feat: change planning factor behavior constants (#5590) * replace module type Signed-off-by: Takagi, Isamu * support compatibility Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu Co-authored-by: Hiroki OTA --- .../src/velocity_steering_factors_panel.cpp | 90 +------------------ .../src/velocity_steering_factors_panel.hpp | 2 + .../avoidance/avoidance_module.hpp | 5 +- .../scene_module/scene_module_interface.hpp | 2 + .../steering_factor_interface.hpp | 5 +- .../src/behavior_path_planner_node.cpp | 2 +- .../avoidance/avoidance_module.cpp | 3 +- .../goal_planner/goal_planner_module.cpp | 2 +- .../scene_module/lane_change/interface.cpp | 4 +- .../start_planner/start_planner_module.cpp | 8 +- .../src/steering_factor_interface.cpp | 7 +- .../src/scene.cpp | 2 +- .../src/scene_crosswalk.cpp | 2 +- .../src/scene.cpp | 2 +- .../src/scene_intersection.cpp | 36 ++++---- .../src/scene_merge_from_private_road.cpp | 2 +- .../src/scene.cpp | 5 +- .../src/scene_no_stopping_area.cpp | 2 +- .../src/scene_occlusion_spot.cpp | 2 +- .../src/scene_out_of_lane.cpp | 2 +- .../velocity_factor_interface.hpp | 12 +-- .../src/scene_module_interface.cpp | 2 +- .../src/velocity_factor_interface.cpp | 3 +- .../src/scene.cpp | 2 +- .../src/scene.cpp | 2 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 2 +- .../src/scene.cpp | 2 +- .../src/scene_walkway.cpp | 2 +- .../obstacle_cruise_planner/type_alias.hpp | 2 + .../src/planner_interface.cpp | 2 +- .../obstacle_stop_planner/debug_marker.hpp | 2 + .../src/debug_marker.cpp | 2 +- .../debug_marker.hpp | 2 + .../src/debug_marker.cpp | 2 +- system/default_ad_api/src/planning.cpp | 88 ++++++++++++++++++ 36 files changed, 166 insertions(+), 148 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 3e95afe247c86..e27fc9b6cfa81 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 @@ -107,62 +107,9 @@ void VelocitySteeringFactorsPanel::onVelocityFactors(const VelocityFactorArray:: for (std::size_t i = 0; i < msg->factors.size(); i++) { const auto & e = msg->factors.at(i); - // type + // behavior { - auto label = new QLabel(); - switch (e.type) { - case VelocityFactor::SURROUNDING_OBSTACLE: - label->setText("SURROUNDING_OBSTACLE"); - break; - case VelocityFactor::ROUTE_OBSTACLE: - label->setText("ROUTE_OBSTACLE"); - break; - case VelocityFactor::INTERSECTION: - label->setText("INTERSECTION"); - break; - case VelocityFactor::CROSSWALK: - label->setText("CROSSWALK"); - break; - case VelocityFactor::REAR_CHECK: - label->setText("REAR_CHECK"); - break; - case VelocityFactor::USER_DEFINED_DETECTION_AREA: - label->setText("USER_DEFINED_DETECTION_AREA"); - break; - case VelocityFactor::NO_STOPPING_AREA: - label->setText("NO_STOPPING_AREA"); - break; - case VelocityFactor::STOP_SIGN: - label->setText("STOP_SIGN"); - break; - case VelocityFactor::TRAFFIC_SIGNAL: - label->setText("TRAFFIC_SIGNAL"); - break; - case VelocityFactor::V2I_GATE_CONTROL_ENTER: - label->setText("V2I_GATE_CONTROL_ENTER"); - break; - case VelocityFactor::V2I_GATE_CONTROL_LEAVE: - label->setText("V2I_GATE_CONTROL_LEAVE"); - break; - case VelocityFactor::MERGE: - label->setText("MERGE"); - break; - case VelocityFactor::SIDEWALK: - label->setText("SIDEWALK"); - break; - case VelocityFactor::LANE_CHANGE: - label->setText("LANE_CHANGE"); - break; - case VelocityFactor::AVOIDANCE: - label->setText("AVOIDANCE"); - break; - case VelocityFactor::EMERGENCY_STOP_OPERATION: - label->setText("EMERGENCY_STOP_OPERATION"); - break; - default: - label->setText("UNKNOWN"); - break; - } + auto label = new QLabel(e.behavior.empty() ? "UNKNOWN" : e.behavior.c_str()); label->setAlignment(Qt::AlignCenter); velocity_factors_table_->setCellWidget(i, 0, label); } @@ -213,38 +160,9 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray:: for (std::size_t i = 0; i < msg->factors.size(); i++) { const auto & e = msg->factors.at(i); - // type + // behavior { - auto label = new QLabel(); - switch (e.type) { - case SteeringFactor::INTERSECTION: - label->setText("INTERSECTION"); - break; - case SteeringFactor::LANE_CHANGE: - label->setText("LANE_CHANGE"); - break; - case SteeringFactor::AVOIDANCE_PATH_CHANGE: - label->setText("AVOIDANCE_PATH_CHANGE"); - break; - case SteeringFactor::AVOIDANCE_PATH_RETURN: - label->setText("AVOIDANCE_PATH_RETURN"); - break; - case SteeringFactor::STATION: - label->setText("STATION"); - break; - case SteeringFactor::START_PLANNER: - label->setText("START_PLANNER"); - break; - case SteeringFactor::GOAL_PLANNER: - label->setText("GOAL_PLANNER"); - break; - case SteeringFactor::EMERGENCY_OPERATION: - label->setText("EMERGENCY_OPERATION"); - break; - default: - label->setText("UNKNOWN"); - break; - } + auto label = new QLabel(e.behavior.empty() ? "UNKNOWN" : e.behavior.c_str()); label->setAlignment(Qt::AlignCenter); steering_factors_table_->setCellWidget(i, 0, label); } diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.hpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.hpp index fe867964239af..70f35ed3793ab 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.hpp @@ -26,6 +26,7 @@ #include #include +#include #include #include @@ -35,6 +36,7 @@ namespace rviz_plugins { class VelocitySteeringFactorsPanel : public rviz_common::Panel { + using PlanningBehavior = autoware_adapi_v1_msgs::msg::PlanningBehavior; using VelocityFactorArray = autoware_adapi_v1_msgs::msg::VelocityFactorArray; using VelocityFactor = autoware_adapi_v1_msgs::msg::VelocityFactor; using SteeringFactorArray = autoware_adapi_v1_msgs::msg::SteeringFactorArray; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 2cce35eef7f92..e67d85e5c17c2 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -123,7 +123,7 @@ class AvoidanceModule : public SceneModuleInterface if (finish_distance > -1.0e-03) { steering_factor_interface_ptr_->updateSteeringFactor( {left_shift.start_pose, left_shift.finish_pose}, {start_distance, finish_distance}, - SteeringFactor::AVOIDANCE_PATH_CHANGE, SteeringFactor::LEFT, SteeringFactor::TURNING, ""); + PlanningBehavior::AVOIDANCE, SteeringFactor::LEFT, SteeringFactor::TURNING, ""); } } @@ -137,8 +137,7 @@ class AvoidanceModule : public SceneModuleInterface if (finish_distance > -1.0e-03) { steering_factor_interface_ptr_->updateSteeringFactor( {right_shift.start_pose, right_shift.finish_pose}, {start_distance, finish_distance}, - SteeringFactor::AVOIDANCE_PATH_CHANGE, SteeringFactor::RIGHT, SteeringFactor::TURNING, - ""); + PlanningBehavior::AVOIDANCE, SteeringFactor::RIGHT, SteeringFactor::TURNING, ""); } } } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp index df71f0577964a..940674fbc0fab 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_interface.hpp @@ -34,6 +34,7 @@ #include #include +#include #include #include #include @@ -55,6 +56,7 @@ namespace behavior_path_planner { +using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::SteeringFactor; using autoware_auto_planning_msgs::msg::PathWithLaneId; using objects_of_interest_marker_interface::ColorName; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp index 3a334cf67edbf..cc9e7c727bc6a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/steering_factor_interface.hpp @@ -35,8 +35,9 @@ class SteeringFactorInterface SteeringFactorInterface(rclcpp::Node * node, const std::string & name); void publishSteeringFactor(const rclcpp::Time & stamp); void updateSteeringFactor( - const std::array & pose, const std::array distance, const uint16_t type, - const uint16_t direction, const uint16_t status, const std::string detail); + const std::array & poses, const std::array distances, + const std::string & behavior, const uint16_t direction, const uint16_t status, + const std::string detail); void clearSteeringFactors(); private: 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 689444a3bf995..aa3dcb37eb76f 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -647,7 +647,7 @@ void BehaviorPathPlannerNode::publish_steering_factor( steering_factor_interface_ptr_->updateSteeringFactor( {intersection_pose, intersection_pose}, {intersection_distance, intersection_distance}, - SteeringFactor::INTERSECTION, steering_factor_direction, steering_factor_state, ""); + PlanningBehavior::INTERSECTION, steering_factor_direction, steering_factor_state, ""); } else { steering_factor_interface_ptr_->clearSteeringFactors(); } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 7c7806112fda9..6e4bb0e68cae8 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -982,8 +982,7 @@ CandidateOutput AvoidanceModule::planCandidate() const steering_factor_interface_ptr_->updateSteeringFactor( {sl_front.start, sl_back.end}, {output.start_distance_to_path_change, output.finish_distance_to_path_change}, - SteeringFactor::AVOIDANCE_PATH_CHANGE, steering_factor_direction, SteeringFactor::APPROACHING, - ""); + PlanningBehavior::AVOIDANCE, steering_factor_direction, SteeringFactor::APPROACHING, ""); output.path_candidate = shifted_path.path; return output; diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp index 8291624f943da..647487d8c799b 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp @@ -853,7 +853,7 @@ void GoalPlannerModule::updateSteeringFactor( // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( - pose, distance, SteeringFactor::GOAL_PLANNER, steering_factor_direction, type, ""); + pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); } bool GoalPlannerModule::hasDecidedPath() const 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 ca1b2384051f6..97e8a865e6741 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 @@ -388,7 +388,7 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o // 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}, SteeringFactor::LANE_CHANGE, steering_factor_direction, + {start_distance, finish_distance}, PlanningBehavior::LANE_CHANGE, steering_factor_direction, SteeringFactor::TURNING, ""); } @@ -405,7 +405,7 @@ void LaneChangeInterface::updateSteeringFactorPtr( steering_factor_interface_ptr_->updateSteeringFactor( {selected_path.info.shift_line.start, selected_path.info.shift_line.end}, {output.start_distance_to_path_change, output.finish_distance_to_path_change}, - SteeringFactor::LANE_CHANGE, steering_factor_direction, SteeringFactor::APPROACHING, ""); + PlanningBehavior::LANE_CHANGE, steering_factor_direction, SteeringFactor::APPROACHING, ""); } void LaneChangeInterface::acceptVisitor(const std::shared_ptr & visitor) const { 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 f847a8be7df2b..fb63a3c2cf47f 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 @@ -329,7 +329,7 @@ BehaviorModuleOutput StartPlannerModule::plan() // 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}, SteeringFactor::START_PLANNER, steering_factor_direction, + {start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); } else { const double distance = motion_utils::calcSignedArcLength( @@ -339,7 +339,7 @@ BehaviorModuleOutput StartPlannerModule::plan() // 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}, - SteeringFactor::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); + PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); } setDebugData(); @@ -442,7 +442,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() updateRTCStatus(start_distance, finish_distance); steering_factor_interface_ptr_->updateSteeringFactor( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, - {start_distance, finish_distance}, SteeringFactor::START_PLANNER, steering_factor_direction, + {start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, ""); } else { const double distance = motion_utils::calcSignedArcLength( @@ -451,7 +451,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() updateRTCStatus(0.0, distance); steering_factor_interface_ptr_->updateSteeringFactor( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, - SteeringFactor::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, ""); + PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, ""); } setDebugData(); diff --git a/planning/behavior_path_planner/src/steering_factor_interface.cpp b/planning/behavior_path_planner/src/steering_factor_interface.cpp index 9ba79f1266fdc..76e0932c0f5ed 100644 --- a/planning/behavior_path_planner/src/steering_factor_interface.cpp +++ b/planning/behavior_path_planner/src/steering_factor_interface.cpp @@ -32,8 +32,9 @@ void SteeringFactorInterface::publishSteeringFactor(const rclcpp::Time & stamp) } void SteeringFactorInterface::updateSteeringFactor( - const std::array & pose, const std::array distance, const uint16_t type, - const uint16_t direction, const uint16_t status, const std::string detail) + const std::array & pose, const std::array distance, + const std::string & behavior, const uint16_t direction, const uint16_t status, + const std::string detail) { std::lock_guard lock(mutex_); SteeringFactor factor; @@ -41,7 +42,7 @@ void SteeringFactorInterface::updateSteeringFactor( std::array converted_distance; for (int i = 0; i < 2; ++i) converted_distance[i] = static_cast(distance[i]); factor.distance = converted_distance; - factor.type = type; + factor.behavior = behavior; factor.direction = direction; factor.status = status; factor.detail = detail; diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_blind_spot_module/src/scene.cpp index 775f3b1c65973..ee19278d5654b 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.cpp @@ -69,7 +69,7 @@ BlindSpotModule::BlindSpotModule( turn_direction_(TurnDirection::INVALID), is_over_pass_judge_line_(false) { - velocity_factor_.init(VelocityFactor::REAR_CHECK); + velocity_factor_.init(PlanningBehavior::REAR_CHECK); planner_param_ = planner_param; const auto & assigned_lanelet = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 56f5072a2ade9..2194144d04df7 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -184,7 +184,7 @@ CrosswalkModule::CrosswalkModule( planner_param_(planner_param), use_regulatory_element_(reg_elem_id) { - velocity_factor_.init(VelocityFactor::CROSSWALK); + velocity_factor_.init(PlanningBehavior::CROSSWALK); passed_safety_slow_point_ = false; if (use_regulatory_element_) { diff --git a/planning/behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_detection_area_module/src/scene.cpp index 4d635d3d6d641..7b003209581cd 100644 --- a/planning/behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_detection_area_module/src/scene.cpp @@ -47,7 +47,7 @@ DetectionAreaModule::DetectionAreaModule( state_(State::GO), planner_param_(planner_param) { - velocity_factor_.init(VelocityFactor::USER_DEFINED_DETECTION_AREA); + velocity_factor_.init(PlanningBehavior::USER_DEFINED_DETECTION_AREA); } LineString2d DetectionAreaModule::getStopLineGeometry2d() const diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 476238f6b1e9e..71883973d9f35 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -110,7 +110,7 @@ IntersectionModule::IntersectionModule( is_private_area_(is_private_area), occlusion_uuid_(tier4_autoware_utils::generateUUID()) { - velocity_factor_.init(VelocityFactor::INTERSECTION); + velocity_factor_.init(PlanningBehavior::INTERSECTION); planner_param_ = planner_param; { @@ -422,7 +422,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if ( @@ -438,7 +438,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, - path->points.at(occlusion_stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(occlusion_stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -470,7 +470,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -499,7 +499,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { @@ -513,7 +513,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -542,7 +542,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { @@ -564,7 +564,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -607,7 +607,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(occlusion_peeking_stop_line).point.pose, VelocityFactor::INTERSECTION); + path->points.at(occlusion_peeking_stop_line).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_default_approved) { @@ -621,7 +621,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -650,7 +650,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { @@ -668,7 +668,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -697,7 +697,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && decision_result.temporal_stop_before_attention_required) { @@ -711,7 +711,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && !decision_result.temporal_stop_before_attention_required) { @@ -749,7 +749,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { @@ -763,7 +763,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -792,7 +792,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { @@ -806,7 +806,7 @@ void reactRTCApprovalByDecisionResult( planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); } } return; 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 f1b516d72726f..a43223ecac102 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 @@ -45,7 +45,7 @@ MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( lane_id_(lane_id), associative_ids_(associative_ids) { - velocity_factor_.init(VelocityFactor::MERGE); + velocity_factor_.init(PlanningBehavior::MERGE); planner_param_ = planner_param; state_machine_.setState(StateMachine::State::STOP); } diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_no_drivable_lane_module/src/scene.cpp index 0d0e7cc6cadba..06b594a932ded 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/scene.cpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/scene.cpp @@ -33,7 +33,7 @@ NoDrivableLaneModule::NoDrivableLaneModule( planner_param_(planner_param), state_(State::INIT) { - velocity_factor_.init(VelocityFactor::NO_DRIVABLE_LANE); + velocity_factor_.init(PlanningBehavior::NO_DRIVABLE_LANE); } bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) @@ -220,8 +220,7 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state( stop_factor.stop_factor_points.push_back(current_point); planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, - VelocityFactor::NO_DRIVABLE_LANE); + path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); const auto & virtual_wall_pose = motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); 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 ceef50094e374..7429159c2ee48 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 @@ -50,7 +50,7 @@ NoStoppingAreaModule::NoStoppingAreaModule( no_stopping_area_reg_elem_(no_stopping_area_reg_elem), planner_param_(planner_param) { - velocity_factor_.init(VelocityFactor::NO_STOPPING_AREA); + velocity_factor_.init(PlanningBehavior::NO_STOPPING_AREA); state_machine_.setState(StateMachine::State::GO); state_machine_.setMarginTime(planner_param_.state_clear_time); } diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index b7278aff29902..32ee5496d8dab 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -66,7 +66,7 @@ OcclusionSpotModule::OcclusionSpotModule( const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), param_(planner_param) { - velocity_factor_.init(VelocityFactor::UNKNOWN); + velocity_factor_.init(PlanningBehavior::UNKNOWN); if (param_.detection_method == utils::DETECTION_METHOD::OCCUPANCY_GRID) { debug_data_.detection_type = "occupancy"; diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp index d739c6440ae75..1f6a332e27e8d 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp @@ -52,7 +52,7 @@ OutOfLaneModule::OutOfLaneModule( const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param)) { - velocity_factor_.init(VelocityFactor::UNKNOWN); + velocity_factor_.init(PlanningBehavior::UNKNOWN); } bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp index 5804c0cdafcf4..eea45ec03807d 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp @@ -16,6 +16,7 @@ #ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ #define BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ +#include #include #include #include @@ -27,20 +28,21 @@ namespace behavior_velocity_planner { +using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using geometry_msgs::msg::Pose; -using VelocityFactorType = VelocityFactor::_type_type; +using VelocityFactorBehavior = VelocityFactor::_behavior_type; using VelocityFactorStatus = VelocityFactor::_status_type; class VelocityFactorInterface { public: - VelocityFactorInterface() { type_ = VelocityFactor::UNKNOWN; } + VelocityFactorInterface() { behavior_ = VelocityFactor::UNKNOWN; } VelocityFactor get() const { return velocity_factor_; } - void init(const VelocityFactorType type) { type_ = type; } - void reset() { velocity_factor_.type = VelocityFactor::UNKNOWN; } + void init(const VelocityFactorBehavior behavior) { behavior_ = behavior; } + void reset() { velocity_factor_.behavior = PlanningBehavior::UNKNOWN; } void set( const std::vector & points, @@ -48,7 +50,7 @@ class VelocityFactorInterface const std::string detail = ""); private: - VelocityFactorType type_; + VelocityFactorBehavior behavior_; VelocityFactor velocity_factor_; }; 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 d6fd01fd32c59..49a52fcd60df2 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -116,7 +116,7 @@ void SceneModuleManagerInterface::modifyPathVelocity( // The velocity factor must be called after modifyPathVelocity. const auto velocity_factor = scene_module->getVelocityFactor(); - if (velocity_factor.type != VelocityFactor::UNKNOWN) { + if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { velocity_factor_array.factors.emplace_back(velocity_factor); } if (stop_reason.reason != "") { diff --git a/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp b/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp index 35c4bc00d8096..7bc46846afb83 100644 --- a/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp @@ -14,6 +14,7 @@ #include #include + namespace behavior_velocity_planner { void VelocityFactorInterface::set( @@ -23,7 +24,7 @@ void VelocityFactorInterface::set( { const auto & curr_point = curr_pose.position; const auto & stop_point = stop_pose.position; - velocity_factor_.type = type_; + velocity_factor_.behavior = behavior_; velocity_factor_.pose = stop_pose; velocity_factor_.distance = motion_utils::calcSignedArcLength(points, curr_point, stop_point); velocity_factor_.status = status; diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 54902f52c47da..8b5363ae866a3 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -43,7 +43,7 @@ RunOutModule::RunOutModule( debug_ptr_(debug_ptr), state_machine_(std::make_unique(planner_param.state_param)) { - velocity_factor_.init(VelocityFactor::UNKNOWN); + velocity_factor_.init(PlanningBehavior::UNKNOWN); if (planner_param.run_out.use_partition_lanelet) { const lanelet::LaneletMapConstPtr & ll = planner_data->route_handler_->getLaneletMapPtr(); diff --git a/planning/behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_stop_line_module/src/scene.cpp index a703f8b5566ad..bf41949a1aa54 100644 --- a/planning/behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_stop_line_module/src/scene.cpp @@ -34,7 +34,7 @@ StopLineModule::StopLineModule( stop_line_(stop_line), state_(State::APPROACH) { - velocity_factor_.init(VelocityFactor::STOP_SIGN); + velocity_factor_.init(PlanningBehavior::STOP_SIGN); planner_param_ = planner_param; } diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index b943feddc103e..a23edefff52ab 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -73,7 +73,7 @@ void TrafficLightModuleManager::modifyPathVelocity( // The velocity factor must be called after modifyPathVelocity. const auto velocity_factor = traffic_light_scene_module->getVelocityFactor(); - if (velocity_factor.type != VelocityFactor::UNKNOWN) { + if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { velocity_factor_array.factors.emplace_back(velocity_factor); } if (stop_reason.reason != "") { diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index 7c4e947a42e7b..90a547adeb930 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -175,7 +175,7 @@ TrafficLightModule::TrafficLightModule( state_(State::APPROACH), is_prev_state_stop_(false) { - velocity_factor_.init(VelocityFactor::TRAFFIC_SIGNAL); + velocity_factor_.init(PlanningBehavior::TRAFFIC_SIGNAL); planner_param_ = planner_param; } diff --git a/planning/behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_virtual_traffic_light_module/src/scene.cpp index fd71635873e7f..f3da0f7f00286 100644 --- a/planning/behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -195,7 +195,7 @@ VirtualTrafficLightModule::VirtualTrafficLightModule( lane_(lane), planner_param_(planner_param) { - velocity_factor_.init(VelocityFactor::V2I_GATE_CONTROL_ENTER); + velocity_factor_.init(PlanningBehavior::VIRTUAL_TRAFFIC_LIGHT); // Get map data const auto instrument = reg_elem_.getVirtualTrafficLight(); diff --git a/planning/behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/behavior_velocity_walkway_module/src/scene_walkway.cpp index af153b56b915e..3d59665b83e83 100644 --- a/planning/behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -38,7 +38,7 @@ WalkwayModule::WalkwayModule( planner_param_(planner_param), use_regulatory_element_(use_regulatory_element) { - velocity_factor_.init(VelocityFactor::SIDEWALK); + velocity_factor_.init(PlanningBehavior::SIDEWALK); if (use_regulatory_element_) { const auto reg_elem_ptr = std::dynamic_pointer_cast( diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp index 0d0a2890f4fa8..d46062dd8f85c 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp @@ -17,6 +17,7 @@ #include "vehicle_info_util/vehicle_info_util.hpp" +#include "autoware_adapi_v1_msgs/msg/planning_behavior.hpp" #include "autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp" #include "autoware_auto_perception_msgs/msg/predicted_object.hpp" #include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" @@ -34,6 +35,7 @@ #include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp" #include "visualization_msgs/msg/marker_array.hpp" +using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using autoware_auto_perception_msgs::msg::ObjectClassification; diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 47f62016df53b..e1daa41226ef1 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -91,7 +91,7 @@ VelocityFactorArray makeVelocityFactorArray( if (pose) { using distance_type = VelocityFactor::_distance_type; VelocityFactor velocity_factor; - velocity_factor.type = VelocityFactor::ROUTE_OBSTACLE; + velocity_factor.behavior = PlanningBehavior::ROUTE_OBSTACLE; velocity_factor.pose = pose.value(); velocity_factor.distance = std::numeric_limits::quiet_NaN(); velocity_factor.status = VelocityFactor::UNKNOWN; diff --git a/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp b/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp index 23000d97ec782..ef035b94054aa 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp @@ -16,6 +16,7 @@ #include +#include #include #include #include @@ -42,6 +43,7 @@ using std_msgs::msg::Header; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; +using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using tier4_debug_msgs::msg::Float32MultiArrayStamped; diff --git a/planning/obstacle_stop_planner/src/debug_marker.cpp b/planning/obstacle_stop_planner/src/debug_marker.cpp index 9277d373d498d..031c7d79bf4c5 100644 --- a/planning/obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/obstacle_stop_planner/src/debug_marker.cpp @@ -532,7 +532,7 @@ VelocityFactorArray ObstacleStopPlannerDebugNode::makeVelocityFactorArray() if (stop_pose_ptr_) { using distance_type = VelocityFactor::_distance_type; VelocityFactor velocity_factor; - velocity_factor.type = VelocityFactor::ROUTE_OBSTACLE; + velocity_factor.behavior = PlanningBehavior::ROUTE_OBSTACLE; velocity_factor.pose = *stop_pose_ptr_; velocity_factor.distance = std::numeric_limits::quiet_NaN(); velocity_factor.status = VelocityFactor::UNKNOWN; 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 590f026942801..e71ff302e1b60 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 @@ -18,6 +18,7 @@ #include #include +#include #include #include #include @@ -33,6 +34,7 @@ namespace surround_obstacle_checker { +using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using geometry_msgs::msg::PolygonStamped; diff --git a/planning/surround_obstacle_checker/src/debug_marker.cpp b/planning/surround_obstacle_checker/src/debug_marker.cpp index ebe5552c44c92..6c005aea5d21c 100644 --- a/planning/surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/surround_obstacle_checker/src/debug_marker.cpp @@ -230,7 +230,7 @@ VelocityFactorArray SurroundObstacleCheckerDebugNode::makeVelocityFactorArray() if (stop_pose_ptr_) { using distance_type = VelocityFactor::_distance_type; VelocityFactor velocity_factor; - velocity_factor.type = VelocityFactor::SURROUNDING_OBSTACLE; + velocity_factor.behavior = PlanningBehavior::SURROUNDING_OBSTACLE; velocity_factor.pose = *stop_pose_ptr_; velocity_factor.distance = std::numeric_limits::quiet_NaN(); velocity_factor.status = VelocityFactor::UNKNOWN; diff --git a/system/default_ad_api/src/planning.cpp b/system/default_ad_api/src/planning.cpp index 5df76e9b5f3cc..17491482a18fe 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/default_ad_api/src/planning.cpp @@ -16,6 +16,8 @@ #include +#include + #include #include #include @@ -61,6 +63,82 @@ 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 f89751bbed1e4d3649811aa5532dc8f7710a8aac Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 30 Nov 2023 16:14:51 +0900 Subject: [PATCH 069/128] fix(localization): add SmartPoseBuffer to handle ekf pose (#5713) * Added smart_pose_buffer Signed-off-by: Shintaro Sakoda * Added rpy_*_to_quaternion Signed-off-by: Shintaro SAKODA * Fixed arg name Signed-off-by: Shintaro SAKODA * Added test_smart_pose_buffer Signed-off-by: Shintaro SAKODA * Fixed time jump issue in SmartPoseBuffer Signed-off-by: Shintaro SAKODA * Removed pose_array_interpolator Signed-off-by: Shintaro SAKODA * Removed unused functions Signed-off-by: Shintaro SAKODA * Added a test about detect_time_jump_to_past Signed-off-by: Shintaro Sakoda * Fixed process of frame_id mismatch in pose callback Signed-off-by: Shintaro Sakoda * Fixed as pointed out by linter Signed-off-by: Shintaro Sakoda * Fixed mutex comment in smart_pose_buffer.hpp Signed-off-by: Shintaro SAKODA * Added comment about covariance interpolation in SmartPoseBuffer Signed-off-by: Shintaro SAKODA * Added const to some variables Signed-off-by: Shintaro SAKODA * Fixed lock range Signed-off-by: Shintaro SAKODA * Added const to some variables Signed-off-by: Shintaro SAKODA * Removed a waste cast Signed-off-by: Shintaro SAKODA * Fixed the code about get self pose Signed-off-by: Shintaro SAKODA * Removed detect_time_jump_to_past Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro Sakoda Signed-off-by: Shintaro SAKODA --- .../src/ar_tag_based_localizer.cpp | 62 ++------ .../src/ar_tag_based_localizer.hpp | 4 +- localization/localization_util/CMakeLists.txt | 10 +- ...interpolator.hpp => smart_pose_buffer.hpp} | 46 +++--- .../include/localization_util/util_func.hpp | 22 +-- .../src/pose_array_interpolator.cpp | 109 ------------- .../src/smart_pose_buffer.cpp | 148 ++++++++++++++++++ .../localization_util/src/util_func.cpp | 105 +++---------- .../test/test_smart_pose_buffer.cpp | 114 ++++++++++++++ .../ndt_scan_matcher_core.hpp | 11 +- .../src/ndt_scan_matcher_core.cpp | 111 +++++-------- 11 files changed, 382 insertions(+), 360 deletions(-) rename localization/localization_util/include/localization_util/{pose_array_interpolator.hpp => smart_pose_buffer.hpp} (55%) delete mode 100644 localization/localization_util/src/pose_array_interpolator.cpp create mode 100644 localization/localization_util/src/smart_pose_buffer.cpp create mode 100644 localization/localization_util/test/test_smart_pose_buffer.cpp 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 3f7a2683ea906..766b139ac8894 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 @@ -44,7 +44,6 @@ #include "ar_tag_based_localizer.hpp" -#include "localization_util/pose_array_interpolator.hpp" #include "localization_util/util_func.hpp" #include @@ -94,6 +93,8 @@ bool ArTagBasedLocalizer::setup() RCLCPP_ERROR_STREAM(this->get_logger(), "Invalid detection_mode: " << detection_mode); return false; } + ekf_pose_buffer_ = std::make_unique( + this->get_logger(), ekf_time_tolerance_, ekf_position_tolerance_); /* Log parameter info @@ -177,24 +178,16 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) return; } - // get self pose const builtin_interfaces::msg::Time sensor_stamp = msg->header.stamp; - Pose self_pose; - { - // get self-position on map - std::unique_lock self_pose_array_lock(self_pose_array_mtx_); - if (self_pose_msg_ptr_array_.size() <= 1) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No Pose!"); - return; - } - PoseArrayInterpolator interpolator( - this, sensor_stamp, self_pose_msg_ptr_array_, ekf_time_tolerance_, ekf_position_tolerance_); - if (!interpolator.is_success()) { - return; - } - pop_old_pose(self_pose_msg_ptr_array_, sensor_stamp); - self_pose = interpolator.get_current_pose().pose.pose; + + // get self pose + const std::optional interpolate_result = + ekf_pose_buffer_->interpolate(sensor_stamp); + if (!interpolate_result) { + return; } + ekf_pose_buffer_->pop_old(sensor_stamp); + const Pose self_pose = interpolate_result.value().interpolated_pose.pose.pose; // detect const std::vector landmarks = detect_landmarks(msg); @@ -305,37 +298,14 @@ void ArTagBasedLocalizer::cam_info_callback(const CameraInfo::ConstSharedPtr & m void ArTagBasedLocalizer::ekf_pose_callback(const PoseWithCovarianceStamped::ConstSharedPtr & msg) { - // lock mutex for initial pose - std::lock_guard self_pose_array_lock(self_pose_array_mtx_); - // if rosbag restart, clear buffer - if (!self_pose_msg_ptr_array_.empty()) { - const builtin_interfaces::msg::Time & t_front = self_pose_msg_ptr_array_.front()->header.stamp; - const builtin_interfaces::msg::Time & t_msg = msg->header.stamp; - if (t_front.sec > t_msg.sec || (t_front.sec == t_msg.sec && t_front.nanosec > t_msg.nanosec)) { - self_pose_msg_ptr_array_.clear(); - } - } - if (msg->header.frame_id == "map") { - self_pose_msg_ptr_array_.push_back(msg); + ekf_pose_buffer_->push_back(msg); } else { - TransformStamped transform_self_pose_frame_to_map; - try { - transform_self_pose_frame_to_map = tf_buffer_->lookupTransform( - "map", msg->header.frame_id, msg->header.stamp, rclcpp::Duration::from_seconds(0.1)); - - // transform self_pose_frame to map_frame - auto self_pose_on_map_ptr = std::make_shared(); - self_pose_on_map_ptr->pose.pose = - tier4_autoware_utils::transformPose(msg->pose.pose, transform_self_pose_frame_to_map); - // self_pose_on_map_ptr->pose.covariance; // TODO(YamatoAndo) - self_pose_on_map_ptr->header.stamp = msg->header.stamp; - self_pose_msg_ptr_array_.push_back(self_pose_on_map_ptr); - } catch (tf2::TransformException & ex) { - RCLCPP_WARN( - get_logger(), "cannot get map to %s transform. %s", msg->header.frame_id.c_str(), - ex.what()); - } + RCLCPP_ERROR_STREAM_THROTTLE( + get_logger(), *this->get_clock(), 1000, + "Received initial pose message with frame_id " + << msg->header.frame_id << ", but expected map. " + << "Please check the frame_id in the input topic and ensure it is correct."); } } 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 2866f4a8f3ee7..78b5086854610 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 @@ -46,6 +46,7 @@ #define AR_TAG_BASED_LOCALIZER_HPP_ #include "landmark_manager/landmark_manager.hpp" +#include "localization_util/smart_pose_buffer.hpp" #include #include @@ -124,8 +125,7 @@ class ArTagBasedLocalizer : public rclcpp::Node aruco::MarkerDetector detector_; aruco::CameraParameters cam_param_; bool cam_info_received_; - std::mutex self_pose_array_mtx_; - std::deque self_pose_msg_ptr_array_; + std::unique_ptr ekf_pose_buffer_; std::map landmark_map_; }; diff --git a/localization/localization_util/CMakeLists.txt b/localization/localization_util/CMakeLists.txt index 9490ffb67723b..ade446020d101 100644 --- a/localization/localization_util/CMakeLists.txt +++ b/localization/localization_util/CMakeLists.txt @@ -6,10 +6,18 @@ autoware_package() ament_auto_add_library(localization_util SHARED src/util_func.cpp - src/pose_array_interpolator.cpp src/tf2_listener_module.cpp + src/smart_pose_buffer.cpp ) +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_smart_pose_buffer + test/test_smart_pose_buffer.cpp + src/smart_pose_buffer.cpp + ) +endif() + ament_auto_package( INSTALL_TO_SHARE ) diff --git a/localization/localization_util/include/localization_util/pose_array_interpolator.hpp b/localization/localization_util/include/localization_util/smart_pose_buffer.hpp similarity index 55% rename from localization/localization_util/include/localization_util/pose_array_interpolator.hpp rename to localization/localization_util/include/localization_util/smart_pose_buffer.hpp index 998d8465733f5..2a2a775a9280c 100644 --- a/localization/localization_util/include/localization_util/pose_array_interpolator.hpp +++ b/localization/localization_util/include/localization_util/smart_pose_buffer.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_UTIL__POSE_ARRAY_INTERPOLATOR_HPP_ -#define LOCALIZATION_UTIL__POSE_ARRAY_INTERPOLATOR_HPP_ +#ifndef LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ +#define LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ #include "localization_util/util_func.hpp" @@ -23,33 +23,39 @@ #include -class PoseArrayInterpolator +class SmartPoseBuffer { private: using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; public: - PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time & target_ros_time, - const std::deque & pose_msg_ptr_array, - const double & pose_timeout_sec, const double & pose_distance_tolerance_meters); + struct InterpolateResult + { + PoseWithCovarianceStamped old_pose; + PoseWithCovarianceStamped new_pose; + PoseWithCovarianceStamped interpolated_pose; + }; - PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time & target_ros_time, - const std::deque & pose_msg_ptr_array); + SmartPoseBuffer() = delete; + SmartPoseBuffer( + const rclcpp::Logger & logger, const double & pose_timeout_sec, + const double & pose_distance_tolerance_meters); - PoseWithCovarianceStamped get_current_pose(); - PoseWithCovarianceStamped get_old_pose(); - PoseWithCovarianceStamped get_new_pose(); - [[nodiscard]] bool is_success() const; + std::optional interpolate(const rclcpp::Time & target_ros_time); + + void push_back(const PoseWithCovarianceStamped::ConstSharedPtr & pose_msg_ptr); + + void pop_old(const rclcpp::Time & target_ros_time); + + void clear(); private: rclcpp::Logger logger_; - rclcpp::Clock clock_; - const PoseWithCovarianceStamped::SharedPtr current_pose_ptr_; - PoseWithCovarianceStamped::SharedPtr old_pose_ptr_; - PoseWithCovarianceStamped::SharedPtr new_pose_ptr_; - bool success_; + std::deque pose_buffer_; + std::mutex mutex_; // This mutex is for pose_buffer_ + + const double pose_timeout_sec_; + const double pose_distance_tolerance_meters_; [[nodiscard]] bool validate_time_stamp_difference( const rclcpp::Time & target_time, const rclcpp::Time & reference_time, @@ -59,4 +65,4 @@ class PoseArrayInterpolator const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_) const; }; -#endif // LOCALIZATION_UTIL__POSE_ARRAY_INTERPOLATOR_HPP_ +#endif // LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ diff --git a/localization/localization_util/include/localization_util/util_func.hpp b/localization/localization_util/include/localization_util/util_func.hpp index bd9a2b9305e25..0b31333da44d3 100644 --- a/localization/localization_util/include/localization_util/util_func.hpp +++ b/localization/localization_util/include/localization_util/util_func.hpp @@ -46,16 +46,14 @@ geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose); geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose); geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); +geometry_msgs::msg::Quaternion rpy_rad_to_quaternion( + const double r_rad, const double p_rad, const double y_rad); +geometry_msgs::msg::Quaternion rpy_deg_to_quaternion( + const double r_deg, const double p_deg, const double y_deg); + geometry_msgs::msg::Twist calc_twist( const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b); -void get_nearest_timestamp_pose( - const std::deque & - pose_cov_msg_ptr_array, - const rclcpp::Time & time_stamp, - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & output_old_pose_cov_msg_ptr, - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & output_new_pose_cov_msg_ptr); - geometry_msgs::msg::PoseStamped interpolate_pose( const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b, const rclcpp::Time & time_stamp); @@ -64,19 +62,11 @@ geometry_msgs::msg::PoseStamped interpolate_pose( const geometry_msgs::msg::PoseWithCovarianceStamped & pose_a, const geometry_msgs::msg::PoseWithCovarianceStamped & pose_b, const rclcpp::Time & time_stamp); -void pop_old_pose( - std::deque & - pose_cov_msg_ptr_array, - const rclcpp::Time & time_stamp); - Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose); Eigen::Matrix4f pose_to_matrix4f(const geometry_msgs::msg::Pose & ros_pose); geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_matrix); Eigen::Vector3d point_to_vector3d(const geometry_msgs::msg::Point & ros_pos); -std::vector create_random_pose_array( - const geometry_msgs::msg::PoseWithCovarianceStamped & base_pose_with_cov, const int particle_num); - template T transform(const T & input, const geometry_msgs::msg::TransformStamped & transform) { @@ -88,7 +78,7 @@ T transform(const T & input, const geometry_msgs::msg::TransformStamped & transf double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2); void output_pose_with_cov_to_log( - const rclcpp::Logger logger, const std::string & prefix, + const rclcpp::Logger & logger, const std::string & prefix, const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov); #endif // LOCALIZATION_UTIL__UTIL_FUNC_HPP_ diff --git a/localization/localization_util/src/pose_array_interpolator.cpp b/localization/localization_util/src/pose_array_interpolator.cpp deleted file mode 100644 index ebc904fcf8d38..0000000000000 --- a/localization/localization_util/src/pose_array_interpolator.cpp +++ /dev/null @@ -1,109 +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/pose_array_interpolator.hpp" - -PoseArrayInterpolator::PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time & target_ros_time, - const std::deque & pose_msg_ptr_array) -: logger_(node->get_logger()), - clock_(*node->get_clock()), - current_pose_ptr_(new PoseWithCovarianceStamped), - old_pose_ptr_(new PoseWithCovarianceStamped), - new_pose_ptr_(new PoseWithCovarianceStamped), - success_(true) -{ - get_nearest_timestamp_pose(pose_msg_ptr_array, target_ros_time, old_pose_ptr_, new_pose_ptr_); - const geometry_msgs::msg::PoseStamped interpolated_pose_msg = - interpolate_pose(*old_pose_ptr_, *new_pose_ptr_, target_ros_time); - current_pose_ptr_->header = interpolated_pose_msg.header; - current_pose_ptr_->pose.pose = interpolated_pose_msg.pose; - current_pose_ptr_->pose.covariance = old_pose_ptr_->pose.covariance; -} - -PoseArrayInterpolator::PoseArrayInterpolator( - rclcpp::Node * node, const rclcpp::Time & target_ros_time, - const std::deque & pose_msg_ptr_array, - const double & pose_timeout_sec, const double & pose_distance_tolerance_meters) -: PoseArrayInterpolator(node, target_ros_time, pose_msg_ptr_array) -{ - // check the time stamp - bool is_old_pose_valid = - validate_time_stamp_difference(old_pose_ptr_->header.stamp, target_ros_time, pose_timeout_sec); - bool is_new_pose_valid = - validate_time_stamp_difference(new_pose_ptr_->header.stamp, target_ros_time, pose_timeout_sec); - - // check the position jumping (ex. immediately after the initial pose estimation) - bool is_pose_diff_valid = validate_position_difference( - old_pose_ptr_->pose.pose.position, new_pose_ptr_->pose.pose.position, - pose_distance_tolerance_meters); - - // all validations must be true - if (!(is_old_pose_valid && is_new_pose_valid && is_pose_diff_valid)) { - success_ = false; - RCLCPP_WARN(logger_, "Validation error."); - } -} - -geometry_msgs::msg::PoseWithCovarianceStamped PoseArrayInterpolator::get_current_pose() -{ - return *current_pose_ptr_; -} - -geometry_msgs::msg::PoseWithCovarianceStamped PoseArrayInterpolator::get_old_pose() -{ - return *old_pose_ptr_; -} - -geometry_msgs::msg::PoseWithCovarianceStamped PoseArrayInterpolator::get_new_pose() -{ - return *new_pose_ptr_; -} - -bool PoseArrayInterpolator::is_success() const -{ - return success_; -} - -bool PoseArrayInterpolator::validate_time_stamp_difference( - const rclcpp::Time & target_time, const rclcpp::Time & reference_time, - const double time_tolerance_sec) const -{ - const double dt = std::abs((target_time - reference_time).seconds()); - bool success = dt < time_tolerance_sec; - if (!success) { - RCLCPP_WARN( - logger_, - "Validation error. The reference time is %lf[sec], but the target time is %lf[sec]. The " - "difference is %lf[sec] (the tolerance is %lf[sec]).", - reference_time.seconds(), target_time.seconds(), dt, time_tolerance_sec); - } - return success; -} - -bool PoseArrayInterpolator::validate_position_difference( - const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Point & reference_point, - const double distance_tolerance_m_) const -{ - double distance = norm(target_point, reference_point); - bool success = distance < distance_tolerance_m_; - if (!success) { - RCLCPP_WARN( - logger_, - "Validation error. The distance from reference position to target position is %lf[m] (the " - "tolerance is %lf[m]).", - distance, distance_tolerance_m_); - } - return success; -} diff --git a/localization/localization_util/src/smart_pose_buffer.cpp b/localization/localization_util/src/smart_pose_buffer.cpp new file mode 100644 index 0000000000000..ba293109dcc4d --- /dev/null +++ b/localization/localization_util/src/smart_pose_buffer.cpp @@ -0,0 +1,148 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "localization_util/smart_pose_buffer.hpp" + +SmartPoseBuffer::SmartPoseBuffer( + const rclcpp::Logger & logger, const double & pose_timeout_sec, + const double & pose_distance_tolerance_meters) +: logger_(logger), + pose_timeout_sec_(pose_timeout_sec), + pose_distance_tolerance_meters_(pose_distance_tolerance_meters) +{ +} + +std::optional SmartPoseBuffer::interpolate( + const rclcpp::Time & target_ros_time) +{ + InterpolateResult result; + + { + std::lock_guard lock(mutex_); + + if (pose_buffer_.size() < 2) { + RCLCPP_INFO(logger_, "pose_buffer_.size() < 2"); + return std::nullopt; + } + + const rclcpp::Time time_first = pose_buffer_.front()->header.stamp; + const rclcpp::Time time_last = pose_buffer_.back()->header.stamp; + + if (target_ros_time < time_first || time_last < target_ros_time) { + return std::nullopt; + } + + // get the nearest poses + result.old_pose = *pose_buffer_.front(); + for (const PoseWithCovarianceStamped::ConstSharedPtr & pose_cov_msg_ptr : pose_buffer_) { + result.new_pose = *pose_cov_msg_ptr; + const rclcpp::Time pose_time_stamp = result.new_pose.header.stamp; + if (pose_time_stamp > target_ros_time) { + break; + } + result.old_pose = *pose_cov_msg_ptr; + } + } + + // check the time stamp + const bool is_old_pose_valid = validate_time_stamp_difference( + result.old_pose.header.stamp, target_ros_time, pose_timeout_sec_); + const bool is_new_pose_valid = validate_time_stamp_difference( + result.new_pose.header.stamp, target_ros_time, pose_timeout_sec_); + + // check the position jumping (ex. immediately after the initial pose estimation) + const bool is_pose_diff_valid = validate_position_difference( + result.old_pose.pose.pose.position, result.new_pose.pose.pose.position, + pose_distance_tolerance_meters_); + + // all validations must be true + if (!(is_old_pose_valid && is_new_pose_valid && is_pose_diff_valid)) { + return std::nullopt; + } + + // interpolate the pose + const geometry_msgs::msg::PoseStamped interpolated_pose_msg = + interpolate_pose(result.old_pose, result.new_pose, target_ros_time); + result.interpolated_pose.header = interpolated_pose_msg.header; + result.interpolated_pose.pose.pose = interpolated_pose_msg.pose; + // This does not interpolate the covariance. + // interpolated_pose.pose.covariance is always set to old_pose.covariance + result.interpolated_pose.pose.covariance = result.old_pose.pose.covariance; + return result; +} + +void SmartPoseBuffer::push_back(const PoseWithCovarianceStamped::ConstSharedPtr & pose_msg_ptr) +{ + std::lock_guard lock(mutex_); + if (!pose_buffer_.empty()) { + // Check for non-chronological timestamp order + // This situation can arise when replaying a rosbag multiple times + const rclcpp::Time end_time = pose_buffer_.back()->header.stamp; + const rclcpp::Time msg_time = pose_msg_ptr->header.stamp; + if (msg_time < end_time) { + // Clear the buffer if timestamps are reversed to maintain chronological order + pose_buffer_.clear(); + } + } + pose_buffer_.push_back(pose_msg_ptr); +} + +void SmartPoseBuffer::pop_old(const rclcpp::Time & target_ros_time) +{ + std::lock_guard lock(mutex_); + while (!pose_buffer_.empty()) { + if (rclcpp::Time(pose_buffer_.front()->header.stamp) >= target_ros_time) { + break; + } + pose_buffer_.pop_front(); + } +} + +void SmartPoseBuffer::clear() +{ + std::lock_guard lock(mutex_); + pose_buffer_.clear(); +} + +bool SmartPoseBuffer::validate_time_stamp_difference( + const rclcpp::Time & target_time, const rclcpp::Time & reference_time, + const double time_tolerance_sec) const +{ + const double dt = std::abs((target_time - reference_time).seconds()); + const bool success = dt < time_tolerance_sec; + if (!success) { + RCLCPP_WARN( + logger_, + "Validation error. The reference time is %lf[sec], but the target time is %lf[sec]. The " + "difference is %lf[sec] (the tolerance is %lf[sec]).", + reference_time.seconds(), target_time.seconds(), dt, time_tolerance_sec); + } + return success; +} + +bool SmartPoseBuffer::validate_position_difference( + const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Point & reference_point, + const double distance_tolerance_m_) const +{ + const double distance = norm(target_point, reference_point); + const bool success = distance < distance_tolerance_m_; + if (!success) { + RCLCPP_WARN( + logger_, + "Validation error. The distance from reference position to target position is %lf[m] (the " + "tolerance is %lf[m]).", + distance, distance_tolerance_m_); + } + return success; +} diff --git a/localization/localization_util/src/util_func.cpp b/localization/localization_util/src/util_func.cpp index 865cc02cff293..bb32741067e65 100644 --- a/localization/localization_util/src/util_func.cpp +++ b/localization/localization_util/src/util_func.cpp @@ -16,8 +16,6 @@ #include "localization_util/matrix_type.hpp" -static std::random_device seed_gen; - // ref by http://takacity.blog.fc2.com/blog-entry-69.html std_msgs::msg::ColorRGBA exchange_color_crc(double x) { @@ -82,6 +80,28 @@ geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovariance return get_rpy(pose.pose.pose); } +geometry_msgs::msg::Quaternion rpy_rad_to_quaternion( + const double r_rad, const double p_rad, const double y_rad) +{ + tf2::Quaternion q; + q.setRPY(r_rad, p_rad, y_rad); + geometry_msgs::msg::Quaternion quaternion_msg; + quaternion_msg.x = q.x(); + quaternion_msg.y = q.y(); + quaternion_msg.z = q.z(); + quaternion_msg.w = q.w(); + return quaternion_msg; +} + +geometry_msgs::msg::Quaternion rpy_deg_to_quaternion( + const double r_deg, const double p_deg, const double y_deg) +{ + const double r_rad = r_deg * M_PI / 180.0; + const double p_rad = p_deg * M_PI / 180.0; + const double y_rad = y_deg * M_PI / 180.0; + return rpy_rad_to_quaternion(r_rad, p_rad, y_rad); +} + geometry_msgs::msg::Twist calc_twist( const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b) { @@ -116,29 +136,6 @@ geometry_msgs::msg::Twist calc_twist( return twist; } -void get_nearest_timestamp_pose( - const std::deque & - pose_cov_msg_ptr_array, - const rclcpp::Time & time_stamp, - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & output_old_pose_cov_msg_ptr, - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & output_new_pose_cov_msg_ptr) -{ - for (const auto & pose_cov_msg_ptr : pose_cov_msg_ptr_array) { - output_new_pose_cov_msg_ptr = - std::const_pointer_cast(pose_cov_msg_ptr); - const rclcpp::Time pose_time_stamp = output_new_pose_cov_msg_ptr->header.stamp; - if (pose_time_stamp > time_stamp) { - // TODO(Tier IV): refactor - const rclcpp::Time old_pose_time_stamp = output_old_pose_cov_msg_ptr->header.stamp; - if (old_pose_time_stamp.seconds() == 0.0) { - output_old_pose_cov_msg_ptr = output_new_pose_cov_msg_ptr; - } - break; - } - output_old_pose_cov_msg_ptr = output_new_pose_cov_msg_ptr; - } -} - geometry_msgs::msg::PoseStamped interpolate_pose( const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b, const rclcpp::Time & time_stamp) @@ -193,19 +190,6 @@ geometry_msgs::msg::PoseStamped interpolate_pose( return interpolate_pose(tmp_pose_a, tmp_pose_b, time_stamp); } -void pop_old_pose( - std::deque & - pose_cov_msg_ptr_array, - const rclcpp::Time & time_stamp) -{ - while (!pose_cov_msg_ptr_array.empty()) { - if (rclcpp::Time(pose_cov_msg_ptr_array.front()->header.stamp) >= time_stamp) { - break; - } - pose_cov_msg_ptr_array.pop_front(); - } -} - Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose) { Eigen::Affine3d eigen_pose; @@ -237,49 +221,6 @@ geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_mat return ros_pose; } -std::vector create_random_pose_array( - const geometry_msgs::msg::PoseWithCovarianceStamped & base_pose_with_cov, const int particle_num) -{ - std::default_random_engine engine(seed_gen()); - const Eigen::Map covariance = - make_eigen_covariance(base_pose_with_cov.pose.covariance); - - std::normal_distribution<> x_distribution(0.0, std::sqrt(covariance(0, 0))); - std::normal_distribution<> y_distribution(0.0, std::sqrt(covariance(1, 1))); - std::normal_distribution<> z_distribution(0.0, std::sqrt(covariance(2, 2))); - std::normal_distribution<> roll_distribution(0.0, std::sqrt(covariance(3, 3))); - std::normal_distribution<> pitch_distribution(0.0, std::sqrt(covariance(4, 4))); - std::normal_distribution<> yaw_distribution(0.0, std::sqrt(covariance(5, 5))); - - const auto base_rpy = get_rpy(base_pose_with_cov); - - std::vector poses; - for (int i = 0; i < particle_num; ++i) { - geometry_msgs::msg::Vector3 xyz; - geometry_msgs::msg::Vector3 rpy; - - xyz.x = base_pose_with_cov.pose.pose.position.x + x_distribution(engine); - xyz.y = base_pose_with_cov.pose.pose.position.y + y_distribution(engine); - xyz.z = base_pose_with_cov.pose.pose.position.z + z_distribution(engine); - rpy.x = base_rpy.x + roll_distribution(engine); - rpy.y = base_rpy.y + pitch_distribution(engine); - rpy.z = base_rpy.z + yaw_distribution(engine); - - tf2::Quaternion tf_quaternion; - tf_quaternion.setRPY(rpy.x, rpy.y, rpy.z); - - geometry_msgs::msg::Pose pose; - pose.position.x = xyz.x; - pose.position.y = xyz.y; - pose.position.z = xyz.z; - pose.orientation = tf2::toMsg(tf_quaternion); - - poses.push_back(pose); - } - - return poses; -} - double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) { const double dx = p1.x - p2.x; @@ -289,7 +230,7 @@ double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Poin } void output_pose_with_cov_to_log( - const rclcpp::Logger logger, const std::string & prefix, + const rclcpp::Logger & logger, const std::string & prefix, const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov) { const Eigen::Map covariance = diff --git a/localization/localization_util/test/test_smart_pose_buffer.cpp b/localization/localization_util/test/test_smart_pose_buffer.cpp new file mode 100644 index 0000000000000..2520e458f2d33 --- /dev/null +++ b/localization/localization_util/test/test_smart_pose_buffer.cpp @@ -0,0 +1,114 @@ +// Copyright 2023- Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "localization_util/smart_pose_buffer.hpp" +#include "localization_util/util_func.hpp" + +#include +#include + +#include +#include + +#include +#include +#include + +using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; + +bool compare_pose( + const PoseWithCovarianceStamped & pose_a, const PoseWithCovarianceStamped & pose_b) +{ + return pose_a.header.stamp == pose_b.header.stamp && + pose_a.header.frame_id == pose_b.header.frame_id && + pose_a.pose.covariance == pose_b.pose.covariance && + pose_a.pose.pose.position.x == pose_b.pose.pose.position.x && + pose_a.pose.pose.position.y == pose_b.pose.pose.position.y && + pose_a.pose.pose.position.z == pose_b.pose.pose.position.z && + pose_a.pose.pose.orientation.x == pose_b.pose.pose.orientation.x && + pose_a.pose.pose.orientation.y == pose_b.pose.pose.orientation.y && + pose_a.pose.pose.orientation.z == pose_b.pose.pose.orientation.z && + pose_a.pose.pose.orientation.w == pose_b.pose.pose.orientation.w; +} + +class TestSmartPoseBuffer : public ::testing::Test +{ +protected: + void SetUp() override {} + + void TearDown() override {} +}; + +TEST_F(TestSmartPoseBuffer, interpolate_pose) // NOLINT +{ + rclcpp::Logger logger = rclcpp::get_logger("test_logger"); + const double pose_timeout_sec = 10.0; + const double pose_distance_tolerance_meters = 100.0; + SmartPoseBuffer smart_pose_buffer(logger, pose_timeout_sec, pose_distance_tolerance_meters); + + // first data + PoseWithCovarianceStamped::SharedPtr old_pose_ptr = std::make_shared(); + old_pose_ptr->header.stamp.sec = 10; + old_pose_ptr->header.stamp.nanosec = 0; + old_pose_ptr->pose.pose.position.x = 10.0; + old_pose_ptr->pose.pose.position.y = 20.0; + old_pose_ptr->pose.pose.position.z = 0.0; + old_pose_ptr->pose.pose.orientation = rpy_deg_to_quaternion(0.0, 0.0, 0.0); + smart_pose_buffer.push_back(old_pose_ptr); + + // second data + PoseWithCovarianceStamped::SharedPtr new_pose_ptr = std::make_shared(); + new_pose_ptr->header.stamp.sec = 20; + new_pose_ptr->header.stamp.nanosec = 0; + new_pose_ptr->pose.pose.position.x = 20.0; + new_pose_ptr->pose.pose.position.y = 40.0; + new_pose_ptr->pose.pose.position.z = 0.0; + new_pose_ptr->pose.pose.orientation = rpy_deg_to_quaternion(0.0, 0.0, 90.0); + smart_pose_buffer.push_back(new_pose_ptr); + + // interpolate + builtin_interfaces::msg::Time target_ros_time_msg; + target_ros_time_msg.sec = 15; + target_ros_time_msg.nanosec = 0; + const std::optional & interpolate_result = + smart_pose_buffer.interpolate(target_ros_time_msg); + ASSERT_TRUE(interpolate_result.has_value()); + const SmartPoseBuffer::InterpolateResult result = interpolate_result.value(); + + // check old + EXPECT_TRUE(compare_pose(result.old_pose, *old_pose_ptr)); + + // check new + EXPECT_TRUE(compare_pose(result.new_pose, *new_pose_ptr)); + + // check interpolated + EXPECT_EQ(result.interpolated_pose.header.stamp.sec, 15); + EXPECT_EQ(result.interpolated_pose.header.stamp.nanosec, static_cast(0)); + EXPECT_EQ(result.interpolated_pose.pose.pose.position.x, 15.0); + EXPECT_EQ(result.interpolated_pose.pose.pose.position.y, 30.0); + EXPECT_EQ(result.interpolated_pose.pose.pose.position.z, 0.0); + const auto rpy = get_rpy(result.interpolated_pose.pose.pose); + EXPECT_NEAR(rpy.x * 180 / M_PI, 0.0, 1e-6); + EXPECT_NEAR(rpy.y * 180 / M_PI, 0.0, 1e-6); + EXPECT_NEAR(rpy.z * 180 / M_PI, 45.0, 1e-6); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + ::testing::InitGoogleTest(&argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} diff --git a/localization/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 6f9420f5bc71a..1212fd28dd09b 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 @@ -17,6 +17,7 @@ #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" @@ -128,8 +129,6 @@ class NDTScanMatcher : public rclcpp::Node const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time); - std::optional interpolate_regularization_pose( - const rclcpp::Time & sensor_ros_time); void add_regularization_pose(const rclcpp::Time & sensor_ros_time); void publish_diagnostic(); @@ -198,16 +197,12 @@ class NDTScanMatcher : public rclcpp::Node std::vector initial_pose_offset_model_; std::array output_pose_covariance_; - std::deque - initial_pose_msg_ptr_array_; std::mutex ndt_ptr_mtx_; - std::mutex initial_pose_array_mtx_; + std::unique_ptr initial_pose_buffer_; // variables for regularization const bool regularization_enabled_; // whether to use longitudinal regularization - std::deque - regularization_pose_msg_ptr_array_; // queue for storing regularization base poses - std::mutex regularization_mutex_; // mutex for regularization_pose_msg_ptr_array_ + std::unique_ptr regularization_pose_buffer_; bool is_activated_; std::shared_ptr tf2_listener_module_; 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 1317b8bacf47f..51623182c6da5 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -15,7 +15,6 @@ #include "ndt_scan_matcher/ndt_scan_matcher_core.hpp" #include "localization_util/matrix_type.hpp" -#include "localization_util/pose_array_interpolator.hpp" #include "localization_util/util_func.hpp" #include "ndt_scan_matcher/particle.hpp" #include "tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp" @@ -167,6 +166,9 @@ NDTScanMatcher::NDTScanMatcher() initial_pose_distance_tolerance_m_ = this->declare_parameter("initial_pose_distance_tolerance_m"); + initial_pose_buffer_ = std::make_unique( + this->get_logger(), initial_pose_timeout_sec_, initial_pose_distance_tolerance_m_); + use_cov_estimation_ = this->declare_parameter("use_covariance_estimation"); if (use_cov_estimation_) { std::vector initial_pose_offset_model_x = @@ -232,6 +234,9 @@ NDTScanMatcher::NDTScanMatcher() "regularization_pose_with_covariance", 10, std::bind(&NDTScanMatcher::callback_regularization_pose, this, std::placeholders::_1), initial_pose_sub_opt); + const double value_as_unlimited = 1000.0; + regularization_pose_buffer_ = + std::make_unique(this->get_logger(), value_as_unlimited, value_as_unlimited); } sensor_aligned_pose_pub_ = @@ -375,42 +380,21 @@ void NDTScanMatcher::callback_initial_pose( { if (!is_activated_) return; - // lock mutex for initial pose - std::lock_guard initial_pose_array_lock(initial_pose_array_mtx_); - // if rosbag restart, clear buffer - if (!initial_pose_msg_ptr_array_.empty()) { - const builtin_interfaces::msg::Time & t_front = - initial_pose_msg_ptr_array_.front()->header.stamp; - const builtin_interfaces::msg::Time & t_msg = initial_pose_msg_ptr->header.stamp; - if (t_front.sec > t_msg.sec || (t_front.sec == t_msg.sec && t_front.nanosec > t_msg.nanosec)) { - initial_pose_msg_ptr_array_.clear(); - } - } - if (initial_pose_msg_ptr->header.frame_id == map_frame_) { - initial_pose_msg_ptr_array_.push_back(initial_pose_msg_ptr); + initial_pose_buffer_->push_back(initial_pose_msg_ptr); } else { - // get TF from pose_frame to map_frame - auto tf_pose_to_map_ptr = std::make_shared(); - tf2_listener_module_->get_transform( - this->now(), map_frame_, initial_pose_msg_ptr->header.frame_id, tf_pose_to_map_ptr); - - // transform pose_frame to map_frame - auto initial_pose_msg_in_map_ptr = - std::make_shared(); - *initial_pose_msg_in_map_ptr = transform(*initial_pose_msg_ptr, *tf_pose_to_map_ptr); - initial_pose_msg_in_map_ptr->header.stamp = initial_pose_msg_ptr->header.stamp; - initial_pose_msg_ptr_array_.push_back(initial_pose_msg_in_map_ptr); + RCLCPP_ERROR_STREAM_THROTTLE( + get_logger(), *this->get_clock(), 1000, + "Received initial pose message with frame_id " + << initial_pose_msg_ptr->header.frame_id << ", but expected " << map_frame_ + << ". Please check the frame_id in the input topic and ensure it is correct."); } } void NDTScanMatcher::callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr) { - // Get lock for regularization_pose_msg_ptr_array_ - std::lock_guard lock(regularization_mutex_); - regularization_pose_msg_ptr_array_.push_back(pose_conv_msg_ptr); - // Release lock for regularization_pose_msg_ptr_array_ + regularization_pose_buffer_->push_back(pose_conv_msg_ptr); } void NDTScanMatcher::callback_sensor_points( @@ -459,17 +443,15 @@ void NDTScanMatcher::callback_sensor_points( if (!is_activated_) return; // calculate initial pose - std::unique_lock initial_pose_array_lock(initial_pose_array_mtx_); - if (initial_pose_msg_ptr_array_.size() <= 1) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No Pose!"); + std::optional interpolation_result_opt = + initial_pose_buffer_->interpolate(sensor_ros_time); + if (!interpolation_result_opt) { + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No interpolated pose!"); return; } - PoseArrayInterpolator interpolator( - this, sensor_ros_time, initial_pose_msg_ptr_array_, initial_pose_timeout_sec_, - initial_pose_distance_tolerance_m_); - if (!interpolator.is_success()) return; - pop_old_pose(initial_pose_msg_ptr_array_, sensor_ros_time); - initial_pose_array_lock.unlock(); + initial_pose_buffer_->pop_old(sensor_ros_time); + const SmartPoseBuffer::InterpolateResult & interpolation_result = + interpolation_result_opt.value(); // if regularization is enabled and available, set pose to NDT for regularization if (regularization_enabled_) { @@ -483,7 +465,7 @@ void NDTScanMatcher::callback_sensor_points( // perform ndt scan matching const Eigen::Matrix4f initial_pose_matrix = - pose_to_matrix4f(interpolator.get_current_pose().pose.pose); + pose_to_matrix4f(interpolation_result.interpolated_pose.pose.pose); auto output_cloud = std::make_shared>(); ndt_ptr_->align(*output_cloud, initial_pose_matrix); const pclomp::NdtResult ndt_result = ndt_ptr_->getResult(); @@ -528,7 +510,7 @@ void NDTScanMatcher::callback_sensor_points( const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; // publish - initial_pose_with_covariance_pub_->publish(interpolator.get_current_pose()); + initial_pose_with_covariance_pub_->publish(interpolation_result.interpolated_pose); exe_time_pub_->publish(make_float32_stamped(sensor_ros_time, exe_time)); transform_probability_pub_->publish( make_float32_stamped(sensor_ros_time, ndt_result.transform_probability)); @@ -539,8 +521,8 @@ void NDTScanMatcher::callback_sensor_points( publish_pose(sensor_ros_time, result_pose_msg, ndt_covariance, is_converged); publish_marker(sensor_ros_time, transformation_msg_array); publish_initial_to_result( - sensor_ros_time, result_pose_msg, interpolator.get_current_pose(), interpolator.get_old_pose(), - interpolator.get_new_pose()); + sensor_ros_time, result_pose_msg, interpolation_result.interpolated_pose, + interpolation_result.old_pose, interpolation_result.new_pose); pcl::shared_ptr> sensor_points_in_map_ptr( new pcl::PointCloud); @@ -828,42 +810,20 @@ std::array NDTScanMatcher::estimate_covariance( return ndt_covariance; } -std::optional NDTScanMatcher::interpolate_regularization_pose( - const rclcpp::Time & sensor_ros_time) -{ - std::shared_ptr interpolator = nullptr; - { - // Get lock for regularization_pose_msg_ptr_array_ - std::lock_guard lock(regularization_mutex_); - - if (regularization_pose_msg_ptr_array_.empty()) { - return std::nullopt; - } - - interpolator = std::make_shared( - this, sensor_ros_time, regularization_pose_msg_ptr_array_); - - // Remove old poses to make next interpolation more efficient - pop_old_pose(regularization_pose_msg_ptr_array_, sensor_ros_time); - - // Release lock for regularization_pose_msg_ptr_array_ - } - - if (!interpolator || !interpolator->is_success()) { - return std::nullopt; - } - - return pose_to_matrix4f(interpolator->get_current_pose().pose.pose); -} - void NDTScanMatcher::add_regularization_pose(const rclcpp::Time & sensor_ros_time) { ndt_ptr_->unsetRegularizationPose(); - std::optional pose_opt = interpolate_regularization_pose(sensor_ros_time); - if (pose_opt.has_value()) { - ndt_ptr_->setRegularizationPose(pose_opt.value()); - RCLCPP_DEBUG_STREAM(get_logger(), "Regularization pose is set to NDT"); + std::optional interpolation_result_opt = + regularization_pose_buffer_->interpolate(sensor_ros_time); + if (!interpolation_result_opt) { + return; } + regularization_pose_buffer_->pop_old(sensor_ros_time); + const SmartPoseBuffer::InterpolateResult & interpolation_result = + interpolation_result_opt.value(); + const Eigen::Matrix4f pose = pose_to_matrix4f(interpolation_result.interpolated_pose.pose.pose); + ndt_ptr_->setRegularizationPose(pose); + RCLCPP_DEBUG_STREAM(get_logger(), "Regularization pose is set to NDT"); } void NDTScanMatcher::service_trigger_node( @@ -872,8 +832,7 @@ void NDTScanMatcher::service_trigger_node( { is_activated_ = req->data; if (is_activated_) { - std::lock_guard initial_pose_array_lock(initial_pose_array_mtx_); - initial_pose_msg_ptr_array_.clear(); + initial_pose_buffer_->clear(); } res->success = true; } From 5151a7b964a0e0c09fe441b49855669cb699318a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 30 Nov 2023 16:46:05 +0900 Subject: [PATCH 070/128] feat(lane_change): cancel lane change on red traffic light (#5515) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner/data_manager.hpp | 4 ++-- .../scene_module/lane_change/base_class.hpp | 2 ++ .../scene_module/lane_change/normal.hpp | 2 ++ .../utils/traffic_light_utils.hpp | 22 ++++++++++++++++++ .../scene_module/lane_change/interface.cpp | 8 +++++++ .../src/scene_module/lane_change/normal.cpp | 14 +++++++++++ .../src/utils/traffic_light_utils.cpp | 23 +++++++++++++++++++ 7 files changed, 73 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp index ca58144464731..6303455c03b0e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp @@ -156,7 +156,7 @@ struct PlannerData std::optional prev_modified_goal{}; std::optional prev_route_id{}; std::shared_ptr route_handler{std::make_shared()}; - std::map traffic_light_id_map; + std::map traffic_light_id_map; BehaviorPathPlannerParameters parameters{}; drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{}; @@ -174,7 +174,7 @@ struct PlannerData route_handler, path, turn_signal_info, current_pose, current_vel, parameters, debug_data); } - std::optional getTrafficSignal(const int id) const + std::optional getTrafficSignal(const int64_t id) const { if (traffic_light_id_map.count(id) == 0) { return std::nullopt; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp index daad5b1a40610..03a512a23989d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp @@ -107,6 +107,8 @@ class LaneChangeBase const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, const double threshold) const = 0; + virtual bool isStoppedAtRedTrafficLight() const = 0; + virtual bool calcAbortPath() = 0; virtual bool specialRequiredCheck() const { return false; } diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index 4a117e5350baf..e82c7f493ae9d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -96,6 +96,8 @@ class NormalLaneChange : public LaneChangeBase bool isLaneChangeRequired() const override; + bool isStoppedAtRedTrafficLight() const override; + protected: lanelet::ConstLanelets getCurrentLanes() const override; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp index aa3e7f4833134..202a5d3473620 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/traffic_light_utils.hpp @@ -27,6 +27,7 @@ #include #include +#include #include namespace behavior_path_planner::utils::traffic_light @@ -107,6 +108,27 @@ double getDistanceToNextTrafficLight( std::optional calcDistanceToRedTrafficLight( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, const std::shared_ptr & planner_data); + +/** + * @brief Checks if the vehicle is stationary within a specified distance from a red traffic light. + * + * This function first checks if the vehicle's velocity is below a minimum threshold, indicating it + * is stopped. It then calculates the distance to the nearest red traffic light using the + * calcDistanceToRedTrafficLight function. If the vehicle is within the specified distance threshold + * from the red traffic light, the function returns true, otherwise false. + * + * @param lanelets The lanelets to search for traffic lights. + * @param path The path along which to measure the distance to the traffic light. + * @param planner_data Shared pointer to the planner data containing vehicle state information. + * @param distance_threshold The maximum allowable distance from a red traffic light to consider the + * vehicle stopped. + * @return True if the vehicle is stopped within the distance threshold from a red traffic light, + * false otherwise. + */ +bool isStoppedAtRedTrafficLightWithinDistance( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data, + const double distance_threshold = std::numeric_limits::infinity()); } // namespace behavior_path_planner::utils::traffic_light #endif // BEHAVIOR_PATH_PLANNER__UTILS__TRAFFIC_LIGHT_UTILS_HPP_ 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 97e8a865e6741..1dddad3433668 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 @@ -110,6 +110,14 @@ ModuleStatus LaneChangeInterface::updateState() return ModuleStatus::SUCCESS; } + 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"); + module_type_->toCancelState(); + return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS; + } + const auto [is_safe, is_object_coming_from_rear] = module_type_->isApprovedPathSafe(); setObjectDebugVisualization(); 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 f35c2d6083836..40bf8ed0da8df 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 @@ -128,6 +128,13 @@ bool NormalLaneChange::isLaneChangeRequired() const return !target_lanes.empty(); } +bool NormalLaneChange::isStoppedAtRedTrafficLight() const +{ + return utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance( + status_.current_lanes, status_.lane_change_path.path, planner_data_, + status_.lane_change_path.info.length.sum()); +} + LaneChangePath NormalLaneChange::getLaneChangePath() const { return status_.lane_change_path; @@ -1364,9 +1371,16 @@ bool NormalLaneChange::getLaneChangePaths( if ( lane_change_parameters_->regulate_on_traffic_light && !hasEnoughLengthToTrafficLight(*candidate_path, current_lanes)) { + debug_print("Reject: regulate on traffic light!!"); continue; } + if (utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance( + lane_change_info.current_lanes, candidate_path.value().path, planner_data_, + lane_change_info.length.sum())) { + debug_print("Ego is stopping near traffic light. Do not allow lane change"); + continue; + } candidate_paths->push_back(*candidate_path); std::vector filtered_objects = diff --git a/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp index 9ec8531818d83..9069c86a79b29 100644 --- a/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner/src/utils/traffic_light_utils.cpp @@ -154,4 +154,27 @@ std::optional calcDistanceToRedTrafficLight( return std::nullopt; } + +bool isStoppedAtRedTrafficLightWithinDistance( + const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, + const std::shared_ptr & planner_data, const double distance_threshold) +{ + const auto ego_velocity = std::hypot( + planner_data->self_odometry->twist.twist.linear.x, + planner_data->self_odometry->twist.twist.linear.y); + constexpr double minimum_speed = 0.1; + if (ego_velocity > minimum_speed) { + return false; + } + + const auto distance_to_red_traffic_light = + calcDistanceToRedTrafficLight(lanelets, path, planner_data); + + if (!distance_to_red_traffic_light) { + return false; + } + + return (distance_to_red_traffic_light < distance_threshold); +} + } // namespace behavior_path_planner::utils::traffic_light From 3ca00b2533b3d5d92bb6a93bbab15e55258d2e74 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 30 Nov 2023 16:47:03 +0900 Subject: [PATCH 071/128] feat(lane_change): remove debug message (#5638) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_planner_node.hpp | 4 --- .../lane_change/avoidance_by_lane_change.hpp | 3 -- .../scene_module/lane_change/base_class.hpp | 9 ------ .../scene_module/lane_change/interface.hpp | 18 ++++------- .../scene_module/lane_change/normal.hpp | 5 --- .../scene_module/scene_module_visitor.hpp | 19 ----------- .../src/behavior_path_planner_node.cpp | 7 ---- .../scene_module/lane_change/interface.cpp | 32 ------------------- .../src/scene_module/scene_module_visitor.cpp | 5 --- 9 files changed, 6 insertions(+), 96 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 1a9b23be00a3f..ccda2ff35e682 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 @@ -21,7 +21,6 @@ #include "behavior_path_planner/steering_factor_interface.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" -#include "tier4_planning_msgs/msg/detail/lane_change_debug_msg_array__struct.hpp" #include #include #include @@ -35,7 +34,6 @@ #include #include #include -#include #include #include #include @@ -66,7 +64,6 @@ using nav_msgs::msg::Odometry; using rcl_interfaces::msg::SetParametersResult; using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; -using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; using tier4_planning_msgs::msg::LateralOffset; using tier4_planning_msgs::msg::RerouteAvailability; using tier4_planning_msgs::msg::Scenario; @@ -171,7 +168,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node // debug rclcpp::Publisher::SharedPtr debug_maximum_drivable_area_publisher_; rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; - rclcpp::Publisher::SharedPtr debug_lane_change_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; /** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp index 4b548c86e55bb..67fd2c1ba0c77 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp @@ -18,15 +18,12 @@ #include "behavior_path_planner/scene_module/lane_change/normal.hpp" #include -#include namespace behavior_path_planner { using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; -using tier4_planning_msgs::msg::LaneChangeDebugMsg; -using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; using AvoidanceDebugData = DebugData; class AvoidanceByLaneChange : public NormalLaneChange diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp index 03a512a23989d..53c42deca6215 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp @@ -14,8 +14,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ -#include "behavior_path_planner/marker_utils/lane_change/debug.hpp" -#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/scene_module/scene_module_interface.hpp" #include "behavior_path_planner/turn_signal_decider.hpp" #include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" @@ -27,18 +25,13 @@ #include #include -#include "tier4_planning_msgs/msg/lane_change_debug_msg.hpp" -#include "tier4_planning_msgs/msg/lane_change_debug_msg_array.hpp" #include #include #include -#include -#include #include #include #include -#include namespace behavior_path_planner { @@ -50,8 +43,6 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using route_handler::Direction; using tier4_autoware_utils::StopWatch; -using tier4_planning_msgs::msg::LaneChangeDebugMsg; -using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; class LaneChangeBase { 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 dad46494bc350..d2892691126eb 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/marker_utils/lane_change/debug.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" @@ -28,9 +27,6 @@ #include -#include "tier4_planning_msgs/msg/detail/lane_change_debug_msg_array__struct.hpp" -#include "tier4_planning_msgs/msg/lane_change_debug_msg.hpp" -#include "tier4_planning_msgs/msg/lane_change_debug_msg_array.hpp" #include #include #include @@ -40,16 +36,14 @@ #include #include #include -#include -#include namespace behavior_path_planner { using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; -using tier4_planning_msgs::msg::LaneChangeDebugMsg; -using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; +using objects_of_interest_marker_interface::ColorName; +using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; class LaneChangeInterface : public SceneModuleInterface { @@ -86,9 +80,10 @@ class LaneChangeInterface : public SceneModuleInterface CandidateOutput planCandidate() const override; - std::shared_ptr get_debug_msg_array() const; - - void acceptVisitor(const std::shared_ptr & visitor) const override; + void acceptVisitor( + [[maybe_unused]] const std::shared_ptr & visitor) const override + { + } void updateModuleParams(const std::any & parameters) override; @@ -141,7 +136,6 @@ class LaneChangeInterface : public SceneModuleInterface const CandidateOutput & output, const LaneChangePath & selected_path) const; mutable MarkerArray virtual_wall_marker_; - mutable LaneChangeDebugMsgArray lane_change_debug_msg_array_; std::unique_ptr prev_approved_path_; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index e82c7f493ae9d..61caf7b2b393f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -14,12 +14,9 @@ #ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ -#include "behavior_path_planner/marker_utils/utils.hpp" #include "behavior_path_planner/scene_module/lane_change/base_class.hpp" #include -#include -#include #include #include @@ -36,8 +33,6 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using route_handler::Direction; -using tier4_planning_msgs::msg::LaneChangeDebugMsg; -using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; class NormalLaneChange : public LaneChangeBase { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp index 03672aa59f6b9..08779e8baf757 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/scene_module_visitor.hpp @@ -15,12 +15,7 @@ #ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SCENE_MODULE_VISITOR_HPP_ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SCENE_MODULE_VISITOR_HPP_ -#include "tier4_planning_msgs/msg/avoidance_debug_msg.hpp" -#include "tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp" #include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp" -#include "tier4_planning_msgs/msg/detail/lane_change_debug_msg_array__struct.hpp" -#include "tier4_planning_msgs/msg/lane_change_debug_msg.hpp" -#include "tier4_planning_msgs/msg/lane_change_debug_msg_array.hpp" #include namespace behavior_path_planner @@ -28,37 +23,23 @@ namespace behavior_path_planner // Forward Declaration class AvoidanceModule; class AvoidanceByLCModule; -class LaneChangeModule; class ExternalRequestLaneChangeModule; class LaneChangeInterface; -class LaneChangeBTInterface; -class LaneFollowingModule; class StartPlannerModule; class GoalPlannerModule; class SideShiftModule; using tier4_planning_msgs::msg::AvoidanceDebugMsg; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; -using tier4_planning_msgs::msg::LaneChangeDebugMsg; -using tier4_planning_msgs::msg::LaneChangeDebugMsgArray; class SceneModuleVisitor { public: - void visitLaneChangeModule(const LaneChangeModule * module) const; - void visitExternalRequestLaneChangeModule(const ExternalRequestLaneChangeModule * module) const; - void visitLaneChangeInterface(const LaneChangeInterface * interface) const; - void visitLaneChangeBTInterface(const LaneChangeBTInterface * module) const; void visitAvoidanceModule(const AvoidanceModule * module) const; - void visitAvoidanceByLCModule(const AvoidanceByLCModule * module) const; std::shared_ptr getAvoidanceModuleDebugMsg() const; - std::shared_ptr getLaneChangeModuleDebugMsg() const; protected: - mutable std::shared_ptr lane_change_visitor_; - mutable std::shared_ptr ext_request_lane_change_visitor_; - mutable std::shared_ptr external_request_lane_change_bt_visitor_; mutable std::shared_ptr avoidance_visitor_; }; } // namespace behavior_path_planner 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 aa3dcb37eb76f..d1069e789edd2 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -79,8 +79,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod create_publisher("~/output/is_reroute_available", 1); debug_avoidance_msg_array_publisher_ = create_publisher("~/debug/avoidance_debug_message_array", 1); - debug_lane_change_msg_array_publisher_ = - create_publisher("~/debug/lane_change_debug_message_array", 1); if (planner_data_->parameters.visualize_maximum_drivable_area) { debug_maximum_drivable_area_publisher_ = @@ -785,11 +783,6 @@ void BehaviorPathPlannerNode::publishSceneModuleDebugMsg( if (avoidance_debug_message) { debug_avoidance_msg_array_publisher_->publish(*avoidance_debug_message); } - - const auto lane_change_debug_message = debug_messages_data_ptr->getLaneChangeModuleDebugMsg(); - if (lane_change_debug_message) { - debug_lane_change_msg_array_publisher_->publish(*lane_change_debug_message); - } } void BehaviorPathPlannerNode::publishPathCandidate( 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 1dddad3433668..f84eaa39844dc 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 @@ -328,27 +328,6 @@ void LaneChangeInterface::setObjectDebugVisualization() const } } -std::shared_ptr LaneChangeInterface::get_debug_msg_array() const -{ - const auto debug_data = module_type_->getDebugData(); - LaneChangeDebugMsgArray debug_msg_array; - debug_msg_array.lane_change_info.reserve(debug_data.size()); - for (const auto & [uuid, debug_data] : debug_data) { - LaneChangeDebugMsg debug_msg; - debug_msg.object_id = uuid; - debug_msg.allow_lane_change = debug_data.is_safe; - debug_msg.is_front = debug_data.is_front; - debug_msg.failed_reason = debug_data.unsafe_reason; - debug_msg.velocity = - std::hypot(debug_data.object_twist.linear.x, debug_data.object_twist.linear.y); - debug_msg_array.lane_change_info.push_back(debug_msg); - } - lane_change_debug_msg_array_ = debug_msg_array; - - lane_change_debug_msg_array_.header.stamp = clock_->now(); - return std::make_shared(lane_change_debug_msg_array_); -} - MarkerArray LaneChangeInterface::getModuleVirtualWall() { using marker_utils::lane_change_markers::createLaneChangingVirtualWallMarker; @@ -415,12 +394,6 @@ void LaneChangeInterface::updateSteeringFactorPtr( {output.start_distance_to_path_change, output.finish_distance_to_path_change}, PlanningBehavior::LANE_CHANGE, steering_factor_direction, SteeringFactor::APPROACHING, ""); } -void LaneChangeInterface::acceptVisitor(const std::shared_ptr & visitor) const -{ - if (visitor) { - visitor->visitLaneChangeInterface(this); - } -} TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( const PathWithLaneId & path, const TurnSignalInfo & original_turn_signal_info) @@ -502,11 +475,6 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( return original_turn_signal_info; } -void SceneModuleVisitor::visitLaneChangeInterface(const LaneChangeInterface * interface) const -{ - lane_change_visitor_ = interface->get_debug_msg_array(); -} - AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, diff --git a/planning/behavior_path_planner/src/scene_module/scene_module_visitor.cpp b/planning/behavior_path_planner/src/scene_module/scene_module_visitor.cpp index 42c8ae15919b1..6831e4b6b32ee 100644 --- a/planning/behavior_path_planner/src/scene_module/scene_module_visitor.cpp +++ b/planning/behavior_path_planner/src/scene_module/scene_module_visitor.cpp @@ -22,9 +22,4 @@ std::shared_ptr SceneModuleVisitor::getAvoidanceModuleDe { return avoidance_visitor_; } - -std::shared_ptr SceneModuleVisitor::getLaneChangeModuleDebugMsg() const -{ - return lane_change_visitor_; -} } // namespace behavior_path_planner From 6e2ab9688019a7fa1715b81ebf45dbb2ff69bd80 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Thu, 30 Nov 2023 17:42:34 +0900 Subject: [PATCH 072/128] fix: fix data types for lane ids (#4096) Signed-off-by: Ryohsuke Mitsudome --- .../lane_departure_checker_node.cpp | 6 ++-- .../utils/lane_change/lane_change_path.hpp | 4 +-- .../behavior_path_planner/utils/utils.hpp | 2 +- .../behavior_path_planner/src/utils/utils.cpp | 6 ++-- .../src/scene.cpp | 4 +-- .../src/scene.hpp | 5 +-- .../util.hpp | 2 +- .../src/util.cpp | 2 +- .../src/scene_intersection.cpp | 2 +- .../src/scene_intersection.hpp | 6 ++-- .../src/scene_merge_from_private_road.cpp | 2 +- .../src/scene_merge_from_private_road.hpp | 6 ++-- .../src/util.cpp | 16 +++++---- .../src/util.hpp | 14 ++++---- .../src/util_type.hpp | 7 ++-- .../utilization/util.hpp | 4 +-- .../src/utilization/util.cpp | 6 ++-- .../planning_interface_test_manager_utils.hpp | 4 +-- planning/route_handler/src/route_handler.cpp | 2 +- .../static_centerline_optimizer_node.hpp | 9 ++--- .../msg/PointsWithLaneId.msg | 2 +- .../src/static_centerline_optimizer_node.cpp | 34 +++++++++---------- .../srv/PlanPath.srv | 4 +-- .../srv/PlanRoute.srv | 6 ++-- 24 files changed, 81 insertions(+), 74 deletions(-) diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index b40a0d0473135..06d11133920f4 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -53,13 +53,13 @@ std::array triangle2points( return points; } -std::map getRouteLanelets( +std::map getRouteLanelets( const lanelet::LaneletMapPtr & lanelet_map, const lanelet::routing::RoutingGraphPtr & routing_graph, const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr & route_ptr, const double vehicle_length) { - std::map route_lanelets; + std::map route_lanelets; bool is_route_valid = lanelet::utils::route::isRouteValid(*route_ptr, lanelet_map); if (!is_route_valid) { @@ -315,7 +315,7 @@ void LaneDepartureCheckerNode::onTimer() // In order to wait for both of map and route will be ready, write this not in callback but here if (last_route_ != route_ && !route_->segments.empty()) { - std::map::iterator itr; + std::map::iterator itr; auto map_route_lanelets_ = getRouteLanelets(lanelet_map_, routing_graph_, route_, vehicle_length_m_); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp index f83c64192430c..f3a6ef9eae89e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp @@ -42,8 +42,8 @@ struct LaneChangeStatus LaneChangePath lane_change_path{}; lanelet::ConstLanelets current_lanes{}; lanelet::ConstLanelets target_lanes{}; - std::vector lane_follow_lane_ids{}; - std::vector lane_change_lane_ids{}; + std::vector lane_follow_lane_ids{}; + std::vector lane_change_lane_ids{}; bool is_safe{false}; bool is_valid_path{true}; double start_distance{0.0}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp index 144dad3b6feab..4d483562a2f88 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/utils.hpp @@ -122,7 +122,7 @@ FrenetPoint convertToFrenetPoint( return frenet_point; } -std::vector getIds(const lanelet::ConstLanelets & lanelets); +std::vector getIds(const lanelet::ConstLanelets & lanelets); // distance (arclength) calculation diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 763719f11ebd9..015826e908898 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -778,9 +778,9 @@ double getSignedDistance( return arc_goal.length - arc_current.length; } -std::vector getIds(const lanelet::ConstLanelets & lanelets) +std::vector getIds(const lanelet::ConstLanelets & lanelets) { - std::vector ids; + std::vector ids; ids.reserve(lanelets.size()); for (const auto & llt : lanelets) { ids.push_back(llt.id()); @@ -1274,7 +1274,7 @@ lanelet::ConstLanelets getCurrentLanesFromPath( const auto & current_pose = planner_data->self_odometry->pose.pose; const auto & p = planner_data->parameters; - std::set lane_ids; + std::set lane_ids; for (const auto & p : path.points) { for (const auto & id : p.lane_ids) { lane_ids.insert(id); diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_blind_spot_module/src/scene.cpp index ee19278d5654b..27f2a23e004d9 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.cpp @@ -629,7 +629,7 @@ bool BlindSpotModule::isTargetObjectType( } boost::optional BlindSpotModule::getStartPointFromLaneLet( - const int lane_id) const + const lanelet::Id lane_id) const { lanelet::ConstLanelet lanelet = planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id); @@ -653,7 +653,7 @@ boost::optional BlindSpotModule::getStartPointFromLane lanelet::ConstLanelets BlindSpotModule::getStraightLanelets( lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const int lane_id) + const lanelet::Id lane_id) { lanelet::ConstLanelets straight_lanelets; const auto intersection_lanelet = lanelet_map_ptr->laneletLayer.get(lane_id); diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_blind_spot_module/src/scene.hpp index e738fb2e7618a..bb78ed5771d2b 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.hpp @@ -201,14 +201,15 @@ class BlindSpotModule : public SceneModuleInterface * @param lane_id lane id of objective lanelet * @return end point of lanelet */ - boost::optional getStartPointFromLaneLet(const int lane_id) const; + boost::optional getStartPointFromLaneLet( + const lanelet::Id lane_id) const; /** * @brief get straight lanelets in intersection */ lanelet::ConstLanelets getStraightLanelets( lanelet::LaneletMapConstPtr lanelet_map_ptr, - lanelet::routing::RoutingGraphPtr routing_graph_ptr, const int lane_id); + lanelet::routing::RoutingGraphPtr routing_graph_ptr, const lanelet::Id lane_id); /** * @brief Modify objects predicted path. remove path point if the time exceeds timer_thr. 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 6c70e7a7f6dc0..d55dfb5de90b7 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 @@ -105,7 +105,7 @@ std::vector getLinestringIntersects( const geometry_msgs::msg::Point & ego_pos, const size_t max_num); std::optional getStopLineFromMap( - const int lane_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, + const lanelet::Id lane_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const std::string & attribute_name); } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/util.cpp b/planning/behavior_velocity_crosswalk_module/src/util.cpp index 47bbef7111da0..ecd0bb95eacd1 100644 --- a/planning/behavior_velocity_crosswalk_module/src/util.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/util.cpp @@ -209,7 +209,7 @@ std::vector getLinestringIntersects( } std::optional getStopLineFromMap( - const int lane_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, + const lanelet::Id lane_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const std::string & attribute_name) { lanelet::ConstLanelet lanelet = lanelet_map_ptr->laneletLayer.get(lane_id); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 71883973d9f35..5ddccfacfca6d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -95,7 +95,7 @@ static bool isTargetCollisionVehicleType( IntersectionModule::IntersectionModule( const int64_t module_id, const int64_t lane_id, [[maybe_unused]] std::shared_ptr planner_data, - const PlannerParam & planner_param, const std::set & associative_ids, + const 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) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index c794ef6c53aad..2c862abc0cdb6 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -259,7 +259,7 @@ class IntersectionModule : public SceneModuleInterface IntersectionModule( 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 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); @@ -273,7 +273,7 @@ class IntersectionModule : public SceneModuleInterface visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; motion_utils::VirtualWalls createVirtualWalls() override; - const std::set & getAssociativeIds() const { return associative_ids_; } + const std::set & getAssociativeIds() const { return associative_ids_; } UUID getOcclusionUUID() const { return occlusion_uuid_; } bool getOcclusionSafety() const { return occlusion_safety_; } @@ -284,7 +284,7 @@ class IntersectionModule : public SceneModuleInterface private: rclcpp::Node & node_; const int64_t lane_id_; - const std::set associative_ids_; + const std::set associative_ids_; const std::string turn_direction_; const bool has_traffic_light_; 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 a43223ecac102..63bca9d6c0577 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 @@ -39,7 +39,7 @@ namespace bg = boost::geometry; MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( const int64_t module_id, const int64_t lane_id, [[maybe_unused]] std::shared_ptr planner_data, - const PlannerParam & planner_param, const std::set & associative_ids, + const PlannerParam & planner_param, const std::set & associative_ids, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), lane_id_(lane_id), 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 19e7b9201093f..3d0fa818c42f8 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 @@ -66,7 +66,7 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface MergeFromPrivateRoadModule( const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, - const PlannerParam & planner_param, const std::set & associative_ids, + const PlannerParam & planner_param, const std::set & associative_ids, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); /** @@ -78,11 +78,11 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; motion_utils::VirtualWalls createVirtualWalls() override; - const std::set & getAssociativeIds() const { return associative_ids_; } + const std::set & getAssociativeIds() const { return associative_ids_; } private: const int64_t lane_id_; - const std::set associative_ids_; + const std::set associative_ids_; autoware_auto_planning_msgs::msg::PathWithLaneId extractPathNearExitOfPrivateRoad( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const double extend_length); diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 093f90e4b3df7..19fa5a790b491 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -117,7 +117,8 @@ static std::optional insertPointIndex( } bool hasLaneIds( - const autoware_auto_planning_msgs::msg::PathPointWithLaneId & p, const std::set & ids) + const autoware_auto_planning_msgs::msg::PathPointWithLaneId & p, + const std::set & ids) { for (const auto & pid : p.lane_ids) { if (ids.find(pid) != ids.end()) { @@ -128,7 +129,7 @@ bool hasLaneIds( } std::optional> findLaneIdsInterval( - const autoware_auto_planning_msgs::msg::PathWithLaneId & p, const std::set & ids) + const autoware_auto_planning_msgs::msg::PathWithLaneId & p, const std::set & ids) { bool found = false; size_t start = 0; @@ -684,7 +685,7 @@ mergeLaneletsByTopologicalSort( 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 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"); @@ -1098,7 +1099,7 @@ std::vector generateDetectionLaneDivisions( } std::optional generateInterpolatedPath( - const int lane_id, const std::set & associative_lane_ids, + const lanelet::Id lane_id, const std::set & associative_lane_ids, const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const double ds, const rclcpp::Logger logger) { @@ -1315,7 +1316,7 @@ void cutPredictPathWithDuration( 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 std::set & associative_ids, const size_t closest_idx, const size_t last_intersection_stop_line_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, @@ -1496,7 +1497,7 @@ void IntersectionLanelets::update( } static lanelet::ConstLanelets getPrevLanelets( - const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids) + const lanelet::ConstLanelets & lanelets_on_path, const std::set & associative_ids) { lanelet::ConstLanelets previous_lanelets; for (const auto & ll : lanelets_on_path) { @@ -1541,7 +1542,8 @@ lanelet::ConstLanelet generatePathLanelet( std::optional generatePathLanelets( const lanelet::ConstLanelets & lanelets_on_path, - const util::InterpolatedPathInfo & interpolated_path_info, const std::set & associative_ids, + 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, diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 0ff35ab5c0c23..79ccf629d69d4 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -40,9 +40,10 @@ std::optional insertPoint( autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path); bool hasLaneIds( - const autoware_auto_planning_msgs::msg::PathPointWithLaneId & p, const std::set & ids); + 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); + const autoware_auto_planning_msgs::msg::PathWithLaneId & p, const std::set & ids); /** * @brief get objective polygons for detection area @@ -50,7 +51,7 @@ std::optional> findLaneIdsInterval( 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 std::set & associative_ids, const double detection_area_length, const double occlusion_detection_area_length, const bool consider_wrong_direction_vehicle); /** @@ -117,7 +118,7 @@ std::vector generateDetectionLaneDivisions( const double curvature_threshold, const double curvature_calculation_ds); std::optional generateInterpolatedPath( - const int lane_id, const std::set & associative_lane_ids, + const lanelet::Id lane_id, const std::set & associative_lane_ids, const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const double ds, const rclcpp::Logger logger); @@ -150,7 +151,7 @@ void cutPredictPathWithDuration( 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 std::set & associative_ids, const size_t closest_idx, const size_t last_intersection_stop_line_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, @@ -166,7 +167,8 @@ lanelet::ConstLanelet generatePathLanelet( std::optional generatePathLanelets( const lanelet::ConstLanelets & lanelets_on_path, - const util::InterpolatedPathInfo & interpolated_path_info, const std::set & associative_ids, + 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, diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index d1ee4c2f79410..a324cce06c18f 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -64,8 +64,8 @@ struct InterpolatedPathInfo { autoware_auto_planning_msgs::msg::PathWithLaneId path; double ds{0.0}; - int lane_id{0}; - std::set associative_lane_ids{}; + lanelet::Id lane_id{0}; + std::set associative_lane_ids{}; std::optional> lane_id_interval{std::nullopt}; }; @@ -175,7 +175,8 @@ struct PathLanelets 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 + // conflicting lanelets plus the next lane part of the + // path }; struct TargetObject diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp index 86273b1e35e1d..636dec3a2bcd6 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp @@ -224,13 +224,13 @@ boost::optional insertStopPoint( @brief return 'associative' lanes in the intersection. 'associative' means that a lane shares same or lane-changeable parent lanes with `lane` and has same turn_direction value. */ -std::set getAssociativeIntersectionLanelets( +std::set getAssociativeIntersectionLanelets( lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map, const lanelet::routing::RoutingGraphPtr routing_graph); template