From 3239b9912401ae4d663a3acff0aa12239c69ae63 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 18 Jan 2024 12:58:32 +0900 Subject: [PATCH 1/8] fix(behavior_velocity_planner, behavior_path_planner): refresh raw traffic light id map every callback (#6061) Signed-off-by: Mamoru Sobue --- .../src/behavior_path_planner_node.cpp | 1 + planning/behavior_velocity_planner/src/node.cpp | 14 +++++++++++--- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 9b3fbedc37203..3eb5eca5954fb 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -784,6 +784,7 @@ void BehaviorPathPlannerNode::onTrafficSignals(const TrafficSignalArray::ConstSh { std::lock_guard lock(mutex_pd_); + planner_data_->traffic_light_id_map.clear(); for (const auto & signal : msg->signals) { TrafficSignalStamped traffic_signal; traffic_signal.stamp = msg->stamp; diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index e2c29ef868257..9fa5634c6dd65 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -323,6 +323,11 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( { std::lock_guard lock(mutex_); + // clear previous observation + planner_data_.traffic_light_id_map_raw_.clear(); + const auto traffic_light_id_map_last_observed_old = + planner_data_.traffic_light_id_map_last_observed_; + planner_data_.traffic_light_id_map_last_observed_.clear(); for (const auto & signal : msg->signals) { TrafficSignalStamped traffic_signal; traffic_signal.stamp = msg->stamp; @@ -334,9 +339,12 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( }); // if the observation is UNKNOWN and past observation is available, only update the timestamp // and keep the body of the info - if ( - is_unknown_observation && - planner_data_.traffic_light_id_map_last_observed_.count(signal.traffic_signal_id) == 1) { + const auto old_data = traffic_light_id_map_last_observed_old.find(signal.traffic_signal_id); + if (is_unknown_observation && old_data != traffic_light_id_map_last_observed_old.end()) { + // copy last observation + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = + old_data->second; + // update timestamp planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp = msg->stamp; } else { From 1f9cdfee48f3ca14628001f6d9fd18a9c56e8198 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Thu, 18 Jan 2024 13:23:40 +0900 Subject: [PATCH 2/8] fix(radar_tracks_msgs_converter): change default parameter for twist compensation (#6080) Signed-off-by: scepter914 --- perception/radar_tracks_msgs_converter/README.md | 2 +- .../launch/radar_tracks_msgs_converter.launch.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/README.md b/perception/radar_tracks_msgs_converter/README.md index fb8f117c82245..fa08eb08f521a 100644 --- a/perception/radar_tracks_msgs_converter/README.md +++ b/perception/radar_tracks_msgs_converter/README.md @@ -23,7 +23,7 @@ This package converts from [radar_msgs/msg/RadarTracks](https://github.com/ros-p - `new_frame_id` (string): The header frame of the output topic. - Default parameter is "base_link" - `use_twist_compensation` (bool): If the parameter is true, then the twist of the output objects' topic is compensated by ego vehicle motion. - - Default parameter is "false" + - Default parameter is "true" - `use_twist_yaw_compensation` (bool): If the parameter is true, then the ego motion compensation will also consider yaw motion of the ego vehicle. - Default parameter is "false" - `static_object_speed_threshold` (float): Specify the threshold for static object speed which determines the flag `is_stationary` [m/s]. diff --git a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml index a6a3f394b1f40..cc2bb80c6f4f7 100644 --- a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml +++ b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml @@ -4,7 +4,7 @@ - + From dcc29f2887eff1214d42fb326bb6af0a4aa342fc Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 18 Jan 2024 14:28:40 +0900 Subject: [PATCH 3/8] fix(pointpainting): fix param path declaration (#6106) * fix(pointpainting): fix param path declaration Signed-off-by: kminoda * remove pointpainting_model_name Signed-off-by: kminoda * revert: revert unnecessary change Signed-off-by: kminoda --------- Signed-off-by: kminoda --- .../detection/camera_lidar_fusion_based_detection.launch.xml | 2 ++ .../camera_lidar_radar_fusion_based_detection.launch.xml | 2 ++ launch/tier4_perception_launch/launch/perception.launch.xml | 3 +++ 3 files changed, 7 insertions(+) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 10d1ac034d457..d269144067e0e 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -267,6 +267,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml index c227298c932d9..4838187ef8fbe 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml @@ -296,6 +296,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 87616b9ccb122..4e9f0daafa736 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -34,6 +34,9 @@ + + + From fe9e11549653d926448fb8f5d00662fe8181c857 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 18 Jan 2024 16:14:22 +0900 Subject: [PATCH 4/8] docs(crosswalk): update the document (#5583) * docs(crosswalk): update the document Signed-off-by: Takayuki Murooka * fix the spell Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../README.md | 359 ++++++++++-------- .../docs/crosswalk_attention_range.svg | 229 ++++------- .../docs/crosswalk_module.svg | 98 +++++ .../docs/debug_markers.png | Bin 0 -> 220365 bytes .../docs/explicit_stop_line.svg | 71 ++++ .../docs/far_object_threshold.drawio.svg | 114 ++++++ .../docs/limitation.svg | 164 -------- .../docs/no-intension.svg | 193 ---------- .../docs/stop_line.svg | 149 -------- .../docs/stop_line_distance.svg | 170 --------- .../docs/stop_line_margin.svg | 204 ---------- .../docs/stop_margin.svg | 144 ------- .../docs/stuck_vehicle_attention_range.svg | 174 --------- .../docs/stuck_vehicle_detection.svg | 93 +++++ .../docs/ttc_vs_ttv.drawio.svg | 210 ++++++++++ .../docs/virtual_collision_point.svg | 157 +++----- .../docs/virtual_stop_line.svg | 73 ++++ .../docs/with_traffic_light.svg | 97 +++++ .../docs/without_traffic_light.svg | 67 ++++ 19 files changed, 1141 insertions(+), 1625 deletions(-) create mode 100644 planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/debug_markers.png create mode 100644 planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/limitation.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/no-intension.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_line.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg delete mode 100644 planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg create mode 100644 planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg diff --git a/planning/behavior_velocity_crosswalk_module/README.md b/planning/behavior_velocity_crosswalk_module/README.md index 5f82fe839fda6..37c3fb58049a6 100644 --- a/planning/behavior_velocity_crosswalk_module/README.md +++ b/planning/behavior_velocity_crosswalk_module/README.md @@ -1,204 +1,169 @@ -## Crosswalk +# Crosswalk -### Role +## Role -This module judges whether the ego should stop in front of the crosswalk in order to provide safe passage of pedestrians and bicycles based on object's behavior and surround traffic. +This module judges whether the ego should stop in front of the crosswalk in order to provide safe passage of crosswalk users such as pedestrians and bicycles based on the objects' behavior and surround traffic.
- ![example](docs/example.png){width=1000} -
crosswalk module
+ ![crosswalk_module](docs/crosswalk_module.svg){width=1100}
-### Activation Timing +## Features -The manager launch crosswalk scene modules when the reference path conflicts crosswalk lanelets. +### Yield -### Module Parameters +#### Target Object -#### Common parameters +The target object's type is filtered by the following parameters in the `object_filtering.target_object` namespace. -| Parameter | Type | Description | -| ----------------------------- | ---- | ------------------------------- | -| `common.show_processing_time` | bool | whether to show processing time | +| Parameter | Unit | Type | Description | +| ------------ | ---- | ---- | ---------------------------------------------- | +| `unknown` | [-] | bool | whether to look and stop by UNKNOWN objects | +| `pedestrian` | [-] | bool | whether to look and stop by PEDESTRIAN objects | +| `bicycle` | [-] | bool | whether to look and stop by BICYCLE objects | +| `motorcycle` | [-] | bool | whether to look and stop by MOTORCYCLE objects | -#### Parameters for input data +In order to detect crosswalk users crossing outside the crosswalk as well, the crosswalk module creates an attention area around the crosswalk shown as the yellow polygon in the figure. If the object's predicted path collides with the attention area, the object will be targeted for yield. -| Parameter | Type | Description | -| ------------------------------------ | ------ | ---------------------------------------------- | -| `common.traffic_light_state_timeout` | double | [s] timeout threshold for traffic light signal | +
+ ![crosswalk_attention_range](docs/crosswalk_attention_range.svg){width=600} +
-#### Parameters for stop position +The parameter is in the `object_filtering.target_object` namespace. -The crosswalk module determines a stop position at least `stop_distance_from_object` away from the object. +| Parameter | Unit | Type | Description | +| --------------------------- | ---- | ------ | ------------------------------------------------------------------------------------------------- | +| `crosswalk_attention_range` | [m] | double | the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk | -
- ![stop_distance_from_object](docs/stop_margin.svg){width=1000} -
stop margin
-
+#### Stop Position -The stop line is the reference point for the stopping position of the vehicle, but if there is no stop line in front of the crosswalk, the position `stop_distance_from_crosswalk` meters before the crosswalk is the virtual stop line for the vehicle. Then, if the stop position determined from `stop_distance_from_object` exists in front of the stop line determined from the HDMap or `stop_distance_from_crosswalk`, the actual stop position is determined according to `stop_distance_from_object` in principle, and vice versa. +First of all, `stop_distance_from_object [m]` is always kept at least between the ego and the target object for safety. -
- ![stop_line](docs/stop_line.svg){width=700} -
explicit stop line
-
+When the stop line exists in the lanelet map, the stop position is calculated based on the line. +When the stop line does **NOT** exist in the lanelet map, the stop position is calculated by keeping `stop_distance_from_crosswalk [m]` between the ego and the crosswalk. -
- ![stop_distance_from_crosswalk](docs/stop_line_distance.svg){width=700} -
virtual stop point
-
+
+ + + + + +
+
On the other hand, if pedestrian (bicycle) is crossing **wide** crosswalks seen in scramble intersections, and the pedestrian position is more than `far_object_threshold` meters away from the stop line, the actual stop position is determined to be `stop_distance_from_object` and pedestrian position, not at the stop line.
- ![far_object_threshold](docs/stop_line_margin.svg){width=1000} -
stop at wide crosswalk
+ ![far_object_threshold](docs/far_object_threshold.drawio.svg){width=700}
-See the workflow in algorithms section. +In the `stop_position` namespace, -| Parameter | Type | Description | -| -------------------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `stop_position.stop_distance_from_object` | double | [m] the vehicle decelerates to be able to stop in front of object with margin | -| `stop_position.stop_distance_from_crosswalk` | double | [m] make stop line away from crosswalk when no explicit stop line exists | -| `stop_position.far_object_threshold` | double | [m] if objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object) | -| `stop_position.stop_position_threshold` | double | [m] threshold for check whether the vehicle stop in front of crosswalk | +| Parameter | | Type | Description | +| ------------------------------ | --- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `stop_position_threshold` | [m] | double | If the ego vehicle has stopped near the stop line than this value, this module assumes itself to have achieved yielding. | +| `stop_distance_from_crosswalk` | [m] | double | make stop line away from crosswalk for the Lanelet2 map with no explicit stop lines | +| `far_object_threshold` | [m] | double | If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object) for the case where the crosswalk width is very wide | +| `stop_distance_from_object` | [m] | double | the vehicle decelerates to be able to stop in front of object with margin | -#### Parameters for ego's slow down velocity +#### Yield decision -| Parameter | Type | Description | -| --------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------- | -| `slow_velocity` | double | [m/s] target vehicle velocity when module receive slow down command from FOA | -| `max_slow_down_jerk` | double | [m/sss] minimum jerk deceleration for safe brake | -| `max_slow_down_accel` | double | [m/ss] minimum accel deceleration for safe brake | -| `no_relax_velocity` | double | [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints) | +The module makes a decision to yield only when the pedestrian traffic light is **GREEN** or **UNKNOWN**. +Calculating the collision point, the decision is based on the following variables. -#### Parameters for stuck vehicle +- TTC: Time-To-Collision which is the time for the **ego** to reach the virtual collision point. +- TTV: Time-To-Vehicle which is the time for the **object** to reach the virtual collision point. -If there are low speed or stop vehicle ahead of the crosswalk, and there is not enough space between the crosswalk and the vehicle (see following figure), closing the distance to that vehicle could cause Ego to be stuck on the crosswalk. So, in this situation, this module plans to stop before the crosswalk and wait until the vehicles move away, even if there are no pedestrians or bicycles. +Depending on the relative relationship between TTC and TTV, the ego's behavior at crosswalks can be classified into three categories based on [1] -
- ![stuck_vehicle_attention_range](docs/stuck_vehicle_attention_range.svg){width=1000} -
stuck vehicle attention range
-
+- A. **TTC >> TTV**: The object has enough time to cross before the ego. + - No stop planning. +- B. **TTC ≒ TTV**: There is a risk of collision. + - **Stop point is inserted in the ego's path**. +- C. **TTC << TTV**: Ego has enough time to cross before the object. + - No stop planning. -| Parameter | Type | Description | -| ------------------------------------------------ | ------ | ---------------------------------------------------------------------- | -| `stuck_vehicle.stuck_vehicle_velocity` | double | [m/s] maximum velocity threshold whether the vehicle is stuck | -| `stuck_vehicle.max_stuck_vehicle_lateral_offset` | double | [m] maximum lateral offset for stuck vehicle position should be looked | -| `stuck_vehicle.stuck_vehicle_attention_range` | double | [m] the detection area is defined as X meters behind the crosswalk | +
+ + + + + +
+
-#### Parameters for pass judge logic +The boundary of A and B is interpolated from `ego_pass_later_margin_x` and `ego_pass_later_margin_y`. In the case of the upper figure, `ego_pass_later_margin_x` is `{0, 1, 2}` and `ego_pass_later_margin_y` is `{1, 4, 6}` for example. +The same way, the boundary of B and C is calculated from `ego_pass_first_margin_x` and `ego_pass_first_margin_y`. In the case of the upper figure, `ego_pass_first_margin_x` is `{3, 5}` and `ego_pass_first_margin_y` is `{0, 1}` for example. -Also see algorithm section. +In the `pass_judge` namespace, -| Parameter | Type | Description | -| ------------------------------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| `pass_judge.ego_pass_first_margin` | double | [s] time margin for ego pass first situation | -| `pass_judge.ego_pass_later_margin` | double | [s] time margin for object pass first situation | -| `pass_judge.stop_object_velocity_threshold` | double | [m/s] velocity threshold for the module to judge whether the objects is stopped | -| `pass_judge.min_object_velocity` | double | [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV.) | -| `pass_judge.timeout_no_intention_to_walk` | double | [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. | -| `pass_judge.timeout_ego_stop_for_yield` | double | [s] the amount of time which ego should be stopping to query whether it yields or not. | +| Parameter | | Type | Description | +| ---------------------------------- | ----- | ------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `ego_pass_first_margin_x` | [[s]] | double | time to collision margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) | +| `ego_pass_first_margin_y` | [[s]] | double | time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) | +| `ego_pass_first_additional_margin` | [s] | double | additional time margin for ego pass first situation to suppress chattering | +| `ego_pass_later_margin_x` | [[s]] | double | time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) | +| `ego_pass_later_margin_y` | [[s]] | double | time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) | +| `ego_pass_later_additional_margin` | [s] | double | additional time margin for object pass first situation to suppress chattering | -#### Parameters for object filtering +### Smooth Yield Decision -As a countermeasure against pedestrians attempting to cross outside the crosswalk area, this module watches not only the crosswalk zebra area but also in front of and behind space of the crosswalk, and if there are pedestrians or bicycles attempting to pass through the watch area, this module judges whether ego should pass or stop. +When the object is stopped around the crosswalk but has no intention to walk, the ego will yield the object forever. +To prevent this dead lock behavior, the ego will cancel the yield depending on the situation. -
- ![crosswalk_attention_range](docs/crosswalk_attention_range.svg){width=1000} -
crosswalk attention range
-
+#### When there is no traffic light -This module mainly looks the following objects as target objects. There are also optional flags that enables the pass/stop decision for `motorcycle` and `unknown` objects. - -- pedestrian -- bicycle - -| Parameter | Type | Description | -| --------------------------- | ------ | ----------------------------------------------------------------------------------------------------- | -| `crosswalk_attention_range` | double | [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk | -| `target/unknown` | bool | whether to look and stop by UNKNOWN objects | -| `target/bicycle` | bool | whether to look and stop by BICYCLE objects | -| `target/motorcycle` | bool | whether to look and stop MOTORCYCLE objects | -| `target/pedestrian` | bool | whether to look and stop PEDESTRIAN objects | - -### Inner-workings / Algorithms - -#### Stop position - -The stop position is determined by the existence of the stop line defined by the HDMap, the positional relationship between the stop line and the pedestrians and bicycles, and each parameter. - -```plantuml -start -:calculate stop point from **stop_distance_from_object** (POINT-1); -if (There is the stop line in front of the crosswalk?) then (yes) - :calculate stop point from stop line (POINT-2.1); -else (no) - :calculate stop point from **stop_distance_from_crosswalk** (POINT-2.2); -endif -if (The distance ego to **POINT-1** is shorter than the distance ego to **POINT-2**) then (yes) - :ego stops at POINT-1; -else if (The distance ego to **POINT-1** is longer than the distance ego to **POINT-2** + **far_object_threshold**) then (yes) - :ego stops at POINT-1; -else (no) - :ego stops at POINT-2; -endif -end -``` +For the object stopped around the crosswalk but has no intention to walk (\*1), when the ego keeps stopping to yield for a certain time (\*2), the ego cancels the yield and start driving. -#### Pass judge logic +\*1: +The time is calculated by the interpolation of distance between the object and crosswalk with `distance_map_for_no_intention_to_walk` and `timeout_map_for_no_intention_to_walk`. -At first, this module determines whether the pedestrians or bicycles are likely to cross the crosswalk based on the color of the pedestrian traffic light signal related to the crosswalk. Only when the pedestrian traffic signal is **RED**, this module judges that the objects will not cross the crosswalk and skip the pass judge logic. +In the `pass_judge` namespace, -Secondly, this module makes a decision as to whether ego should stop in front of the crosswalk or pass through based on the relative relationship between TTC(Time-To-Collision) and TTV(Time-To-Vehicle). The TTC is the time it takes for ego to reach the virtual collision point, and the TTV is the time it takes for the object to reach the virtual collision point. +| Parameter | | Type | Description | +| --------------------------------------- | ----- | ------ | --------------------------------------------------------------------------------- | +| `distance_map_for_no_intention_to_walk` | [[m]] | double | distance map to calculate the timeout for no intention to walk with interpolation | +| `timeout_map_for_no_intention_to_walk` | [[s]] | double | timeout map to calculate the timeout for no intention to walk with interpolation | -
- ![virtual_collision_point](docs/virtual_collision_point.svg){width=1000} -
virtual collision point
-
+\*2: +In the `pass_judge` namespace, -Depending on the relative relationship between TTC and TTV, the ego's behavior at crosswalks can be classified into three categories. +| Parameter | | Type | Description | +| ---------------------------- | --- | ------ | ----------------------------------------------------------------------------------------------------------------------- | +| `timeout_ego_stop_for_yield` | [s] | double | If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. | -1. **TTC >> TTV**: The objects have enough time to cross first before ego reaches the crosswalk. (Type-A) -2. **TTC ≒ TTV**: There is a risk of a near miss and collision between ego and objects at the virtual collision point. (Type-B) -3. **TTC << TTV**: Ego has enough time to path through the crosswalk before the objects reach the virtual collision point. (Type-C) +#### When there is traffic light -This module judges that ego is able to pass through the crosswalk without collision risk when the relative relationship between TTC and TTV is **Type-A** and **Type-C**. On the other hand, this module judges that ego needs to stop in front of the crosswalk prevent collision with objects in **Type-B** condition. The time margin can be set by parameters `ego_pass_first_margin` and `ego_pass_later_margin`. This logic is designed based on [1]. +For the object stopped around the crosswalk but has no intention to walk (\*1), the ego will cancel the yield without stopping. +This comes from the assumption that the object has no intention to walk since it is stopped even though the pedestrian traffic light is green. -
- ![ttc-ttv](docs/ttc-ttv.svg){width=1000} -
time-to-collision vs time-to-vehicle
-
+\*1: +The crosswalk user's intention to walk is calculated in the same way as `When there is no traffic light`. -This module uses the larger value of estimated object velocity and `min_object_velocity` in calculating TTV in order to avoid division by zero. - -```plantuml -start -if (Pedestrian's traffic light signal is **RED**?) then (yes) -else (no) - if (There are objects around the crosswalk?) then (yes) - :calculate TTC & TTV; - if (TTC < TTV + **ego_pass_first_margin** && TTV < TTC + **ego_pass_later_margin**) then (yes) - :STOP; - else (no) - :PASS; - endif - endif -endif -end -``` +
+ + + + + +
+
-#### Dead lock prevention +#### New Object Handling -If there are objects stop within a radius of `min_object_velocity * ego_pass_later_margin` meters from virtual collision point, this module judges that ego should stop based on the pass judge logic described above at all times. In such a situation, even if the pedestrian has no intention of crossing, ego continues the stop decision on the spot. So, this module has another logic for dead lock prevention, and if the object continues to stop for more than `timeout_no_intention_to_walk` seconds after ego stops in front of the crosswalk, this module judges that the object has no intention of crossing and switches from **STOP** state to **PASS** state. The parameter `stop_object_velocity_threshold` is used to judge whether the objects are stopped or not. In addition, if the object starts to move after the module judges that the object has no intention of crossing, this module judges whether ego should stop or not once again. +Due to the perception's limited performance where the tree or poll is recognized as a pedestrian or the tracking failure in the crowd or occlusion, even if the surrounding environment does not change, the new pedestrian (= the new ID's pedestrian) may suddenly appear unexpectedly. +When this happens when the ego is going to pass the crosswalk, the ego will stop suddenly. -
- ![no-intension](docs/no-intension.svg){width=1000} -
dead lock situation
-
+To fix this issue, the option `disable_yield_for_new_stopped_object` is prepared. +If set to true, the new stopped object will be ignored during the yield decision around the crosswalk with a traffic light. + +In the `pass_judge` namespace, + +| Parameter | | Type | Description | +| -------------------------------------- | --- | ---- | ------------------------------------------------------------------------------------------------ | +| `disable_yield_for_new_stopped_object` | [-] | bool | If set to true, the new stopped object will be ignored around the crosswalk with a traffic light | -#### Safety Slow Down Behavior +### Safety Slow Down Behavior In current autoware implementation if there are no target objects around a crosswalk, ego vehicle will not slow down for the crosswalk. However, if ego vehicle to slow down to a certain speed in @@ -207,27 +172,103 @@ it is instructed in [lanelet2_format_extension.md](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) document. -### Limitations +| Parameter | | Type | Description | +| --------------------- | ------- | ------ | --------------------------------------------------------------------------------------------------------------------- | +| `slow_velocity` | [m/s] | double | target vehicle velocity when module receive slow down command from FOA | +| `max_slow_down_jerk` | [m/sss] | double | minimum jerk deceleration for safe brake | +| `max_slow_down_accel` | [m/ss] | double | minimum accel deceleration for safe brake | +| `no_relax_velocity` | [m/s] | double | if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints) | -When multiple crosswalks are nearby (such as intersection), this module may make a stop decision even at crosswalks where the object has no intention of crossing. +### Stuck Vehicle Detection + +The feature will make the ego not to stop on the crosswalk. +When there are low-speed or stopped vehicle ahead of the crosswalk, and there is not enough space between the crosswalk and the vehicle, the crosswalk module will plan to stop before the crosswalk even if there are no pedestrians or bicycles. + +`min_acc`, `min_jerk`, and `max_jerk` are met. If the ego cannot stop before the crosswalk with these parameters, the stop position will move forward. + +
+ ![stuck_vehicle_attention_range](docs/stuck_vehicle_detection.svg){width=600} +
+ +In the `stuck_vehicle` namespace, + +| Parameter | Unit | Type | Description | +| ---------------------------------- | ------- | ------ | ----------------------------------------------------------------------- | +| `stuck_vehicle_velocity` | [m/s] | double | maximum velocity threshold whether the target vehicle is stopped or not | +| `max_stuck_vehicle_lateral_offset` | [m] | double | maximum lateral offset of the target vehicle position | +| `stuck_vehicle_attention_range` | [m] | double | detection area length ahead of the crosswalk | +| `min_acc` | [m/ss] | double | minimum acceleration to stop | +| `min_jerk` | [m/sss] | double | minimum jerk to stop | +| `max_jerk` | [m/sss] | double | maximum jerk to stop | + +### Others + +In the `common` namespace, + +| Parameter | Unit | Type | Description | +| ----------------------------- | ---- | ------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `show_processing_time` | [-] | bool | whether to show processing time | +| `traffic_light_state_timeout` | [s] | double | timeout threshold for traffic light signal | +| `enable_rtc` | [-] | bool | if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. | + +## Known Issues + +- The yield decision may be sometimes aggressive or conservative depending on the case. + - The main reason is that the crosswalk module does not know the ego's position in the future. The detailed ego's position will be determined after the whole planning. + - Currently the module assumes that the ego will move with a constant velocity. + +## Debugging + +### Visualization of debug markers + +`/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk` shows the following markers.
- ![limitation](docs/limitation.svg){width=1000} -
design limits
+ ![limitation](docs/debug_markers.png){width=1000}
-### Known Issues +- Yellow polygons + - Ego footprints' polygon to calculate the collision check. +- Pink polygons + - Object footprints' polygon to calculate the collision check. +- The color of crosswalk + - Considering the traffic light's color, red means the target crosswalk and white means the ignored crosswalk. +- Texts + - It shows the module id, TTC, TTV, and the module state. + +### Visualization of Time-To-Collision -### Debugging +```sh +ros2 run behavior_velocity_crosswalk_module time_to_collision_plotter.py +``` -By `ros2 run behavior_velocity_crosswalk_module time_to_collision_plotter.py`, you can visualize the following figure of the ego and pedestrian's time to collision. +enables you to visualize the following figure of the ego and pedestrian's time to collision. The label of each plot is `-`.
![limitation](docs/time_to_collision_plot.png){width=1000} -
Plot of time to collision
-### References/External links +## Trouble Shooting + +### Behavior + +- Q. The ego stopped around the crosswalk even though there were no crosswalk user objects. + - A. See [Stuck Vehicle Detection](https://autowarefoundation.github.io/autoware.universe/pr-5583/planning/behavior_velocity_crosswalk_module/#stuck-vehicle-detection). +- Q. The crosswalk virtual wall suddenly appeared resulting in the sudden stop. + - A. There may be a crosswalk user started moving when the ego was close to the crosswalk. +- Q. The crosswalk module decides to stop even when the pedestrian traffic light is red. + - A. The lanelet map may be incorrect. The pedestrian traffic light and the crosswalk have to be related. +- Q. In the planning simulation, the crosswalk module does the yield decision to stop on all the crosswalks. + - A. This is because the pedestrian traffic light is unknown by default. In this case, the crosswalk does the yield decision for safety. + +### Parameter Tuning + +- Q. The ego's yield behavior is too conservative. + - A. Tune `ego_pass_later_margin` described in [Yield Decision](https://autowarefoundation.github.io/autoware.universe/pr-5583/planning/behavior_velocity_crosswalk_module/#stuck-vehicle-detection) +- Q. The ego's yield behavior is too aggressive. + - A. Tune `ego_pass_later_margin` described in [Yield Decision](https://autowarefoundation.github.io/autoware.universe/pr-5583/planning/behavior_velocity_crosswalk_module/#stuck-vehicle-detection) + +## References/External links [1] 佐藤 みなみ, 早坂 祥一, 清水 政行, 村野 隆彦, 横断歩行者に対するドライバのリスク回避行動のモデル化, 自動車技術会論文集, 2013, 44 巻, 3 号, p. 931-936. diff --git a/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg index 270a61264fe66..26e6118756bd8 100644 --- a/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg +++ b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_attention_range.svg @@ -1,213 +1,132 @@ + - + - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -
+
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22%22%20style%3D%22endArrow%3Dclassic%3Bhtml%3D1%3Brounded%3D0%3BexitX%3D0.25%3BexitY%3D0%3BexitDx%3D0%3BexitDy%3D0%3BentryX%3D0.5%3BentryY%3D0.442%3BentryDx%3D0%3BentryDy%3D0%3BentryPerimeter%3D0%3B%22%20edge%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20width%3D%2250%22%20height%3D%2250%22%20relative%3D%221%22%20as%3D%22geometry%22%3E%3CmxPoint%20x%3D%22851%22%20y%3D%221780%22%20as%3D%22sourcePoint%22%2F%3E%3CmxPoint%20x%3D%22890.04%22%20y%3D%221780%22%20as%3D%22targetPoint%22%2F%3E%3C%2FmxGeometry%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - +
+ target
- %3CmxGraphModel%3E%3... + target - - - - - - -
-
- crosswalk_attention_range - [m] +
+ target
- crosswalk_attention_range [m] + target - - - - -
+
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - +
+ NOT + target
- %3Cmx... + NOT target - - -
+
-
- Module don't respond prediction path without attention range. -
-
-
- - Module don't respond predict... - - - - - - -
-
-
- Vehicle +
+ crosswalk_attention_range
- Vehicle + crosswalk_attention... - - + + + + diff --git a/planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg new file mode 100644 index 0000000000000..18225f188fddf --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/crosswalk_module.svg @@ -0,0 +1,98 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_velocity_crosswalk_module/docs/debug_markers.png b/planning/behavior_velocity_crosswalk_module/docs/debug_markers.png new file mode 100644 index 0000000000000000000000000000000000000000..15645a340dca83a14ba136c0192849ed56ba887a GIT binary patch literal 220365 zcmY(r1yGdV`v+f|(%rcrAR)N2EG69`-5t{1CEa*m zzQ6yyGnZio*kOQk&htLcrw-w2DssAEwGV-0CV$hqy}&atcQhg3vA{k zU^kUofk0r80z?w#{%x<({xgwf=HX38GW+zi9Z)IxaJTR0P5SF{1b!HKKrpwwvDJ$g)#l4LQX>0uMR|z(lT-2SD;Oexz4lDU`rZ8E{e9D- z=D)6gR|h^FsLZ5=cEi z>Adoudr#ziFhiJ|hsUI5z%|&1gG5GBEUOFniTaC1vzT{2P8-4 z`m+=fTyNeWz2}REQhb_04LALLW<2t*6W@59v;EA=Gw>B*{Gq7oA}KptpD+=t{>O2LgS&J|)JHvAK>+8OnH-(bIdK(+H)XoXW&?fyylVtU4`s z*re-ZNmK~pfSBeuB@E1LqCC5g@^YApiw1D=RK7_q+pRkNxnuM_&I<))>vQC)=abtl z=^gMYOJMpPf5BF7j#^k?`f0zZmXC}xf3fXMQL58_E`|0FW4v7g{k?$w$3La2-kvyu zb_>5MidvP>5TPsW()fmi;TRj6n@~2=JHv<;bJv5paPOP*k4Bp(9#OHe_19ubVw@mw z`oLo?pU}^Zf!Mweo2;$J%f1|Em3bnqRzp`DynqM2(Gfm&5GqcMS|!_W4ZWV)X6c8gIwI zoyouZyRYf#Z9R#M+=7CeGpm1dV4ffay+@$9A8$|-3=moZXBU^;f&$8Tc|4O+v3;+J z9YPS8v>?2wtl{~H6}46ox`l<^^;N+o`gBUS*d+6zxYma|(S(2XS0dY(Fwl%;Fbbs~ z^XwghP!T~$7#_50i#8ln;{GZtasLhf48hhJe6#OQnFlT?Tg0e}Ehkx#VgF<{KSpL! z_MG+ZM4O3JjfoVjKuE8E4pIgQ=vBj~s`QG`K_(;QwDSb*IowIqDU_34dg%r_CHv|w z*y_If7m*O!XEt24q>&$+8Dr1lr?i@zw3s3S!pDe|&`3aa|L&R>y|<25yJkWOA{}dk zY-(i%yQL9fz^BJw@(&b={v~&_}*%@qhGWXQ6)R+uK0kw5DVReuW_s>OIN$d0n=i)R%W!nCfDZ=EsT{J_*v@PV>%#>U#RmXZ?%DkSQv2nQm>4itU((6*o zAu1(R)z!V}a{cOk0aTsend&Q8sSb5=N>=toeqy);E((MnermP(3#BKV#h^h3oF!uP z5uWcO-w~s3G@;eIuII8j<&N7(d_37LjcQfCt3Q(6Wveggi{ zS0hb%Mzc#xV4xnVr;-idSLzkL53EC4qnEt6B|gG+!+pc;gT7u?`uNY?zJ0TgmB&^1 z@~dv7k4NSmE{ugmJ)bxvBt(w`NizLOYu2N&y<5xsyrD7>Z{0s&+N&JNk-8{}5dh{9 z5s5M>Wzv_ojfzhkDoE7TgD~V$N(P69?FbafUct^B=HK|zmOd|Qpa6ZoawH9IHJF;T zkb%rs*-}>7&UQL~C+zw`GO~#BE9mMYVlVkno7~ma1ssGlP}0vM}nFrqLKB>~{MEBjI>d!0f*!s0A3&Gsg;4%DmgPDnmXW6fl%EBO? zI~Ws=9xAgTY$btgQyj#u32`&|WR80+gc%-n?L?G>-FyAu((h-OKf(24^Z1?~5pXl_ zb;lRGQ^ilzcw2S3e~;8Ge}$W;<~tBiyFdAH~5fws{dUTE69q(O|G*q#?s!FF0M)a07L><@a`D?vz99}2>e#hAuM8v3qA@;B01>|qij~anVJaXLp zAOr$vNup_=DWcD5Qf~eU@lccCuijZWymMY?G8J|;bCu9zPrZL3h(Whd3@bCB`b)}6 zCrY5qmqg#=NSy0qE0R^O!#3&MkhP^!!3v+7{N!D<@?>0QA}MTp(x%??%v#P4COA2z z)IMa`yMmW>_j}wmEdnWPdW&%tql&p7^7(s}pilH+ zIaYcYMY~HG1}vBVHKD@Ku$?M*3oVE_Tw&TFYqWjUVZUW!`*51$K#C^Y^BrSttIiej z`Xm4G#q9R41=Yt-o_uGDSRY!wySbpFid|ie6@M;s|B*FqJ-19p$6Y^V`&Hyb88rOw z%tzBZjOJtUHZ0YVw|4`4h7>+M=XwEbT8|C3Fs+Nvp2hmRQg zKKdvzk(TiR$fWeWoe6m*f6t74f@v+hIelWO{Dc7aB0t;U1r-%(u)1y7;_3}sn6%9V zO4I*UqAEh&rML~8;XWKt^Fpu`#bH&83=E{ik36Hz8mhmaOLqx8n5`}u3`V(Sp-*1u zdg_IAVKvRJ*4X7Xhpk+AN#wO?aN!C$i&-<0$WQxgnpk$Mt88Xvig=9fuX{$Met~5} zB^de#N!5xtfW2UK5Gc@Rg+67;IK5xRpvrODsU>!8sA@aXo9m`!m|d5Q3pQM7aNdz+ zsEJ>lK{-ccCI~np6p!9C-QQ}pPqssA;DTQcw!Vy8nBJXU>)4d{_4hvo8kc;+T6Z)K zpWEq-KUQOH!P~jZ+)8hR*Y5DU&})-uEvH;=AMc;>2DfZ+qnlZz5tsl*N!l(T*$Ief zRgwhi!nUiW1qAeX@^yRO0IsH?){lk=vSG$bNdm7k+Z_uz({0E6@84&JJPDx2ozE0| ze}v&`a-OfBcr;urcqQYdSrLS4`=`DKwxxB(GT<-Ou)>z=a1oBh2mfz>W22&+&HR%z z_hN`bMgLWhpsvXyjzMJ&Dt&TATCC5ctZV1C8Z?u1`-cR5jFP8l;^k@KGcyjR_t&_7 z``7nvkLq)rOia<^Gt*`{!*qYxMO~b@K2EdE77XCvO`yjf(IGxLIf)6jT6kN0>Z*g# zC_K7vmoPy@v0S-)xubkPLRr*EJvi69daYqfYvb)KkU!3uN~rD;ak+j~_WG%?L+>fySgab#agZ| zIq$BI<__Cd4!D8Ms_0b7F)*Qt0^m6Lix(p*LBYoM&skU7_Y-_)a8}3}u8^vk;}LN^ zU+-I6P1$+j*-Yh3aEo+1!K@*dHFsZfPSABQNs2okX~(tySy-pFUc_{RVmZe2S`Ikb^Se9%;?s1jZbf(P9?VikFE2OdEMKE0P}^T%=&A(GB1Rh< zvJ7vcsXtps?D=?H&W5s(kcc)yo!#WD-y)5CLKG2(E|ZoN(+ueYj`b!VNONyBSTWTh z`C4QR19l`>4G?0*N<21h7AqAn6++xDQ6;Yu?_+ZY67rPp4*?m_egFJg)}<$`JdOs3 zA=`tmZ%>A1Sz@h23^6v@U+(k;25cNGmkwcFniAvwrgLmnJq>8gVY>X=h9`X|>=Ax{ zhharrJHrlCk?a*RGBUEi^wy-b7Wr*xQwVrO<&soV+oIlyP()6?M8?av4V^f1)WNl< zW289uWf=nIcP0vIi-rzI^DB>LOp}>It?c|g;IXYnd@ zjLzceI==D=W^8Qzxp{&SyS@!Up^A;T%2^-HQa%ab%0OS*ci|M?YP9J2Co#nmI-}>P zp}e`QdGKa_a}SMDS7(d=yLIm0p?k4sfeUn40Q!a_iHL}babFHV#sQM^;o@L^Yk%LR zgIhT=Eh4ApToAwg7;JbG)$&TG_!k)auhxfs`>vQ*Ck`^p!Dl`RDtSly_P&%;B}Vr3 zw_{qwk=3Oi$DBacS4iLojm#nWB6wzb4o{EQ6|^VG1^Thh11My3oC-M~yX4nmk({!r z3kEHy=eM(WO%&@W)I-CKH$(7kEp27V8>`esVix!vPGxiBG9z--*+PPDpZbw-SBhv$ zt#3C+uRJN-$Q`wDx}MvfN7nAXWz$Tl3BR<+Wk`C0lahaYAeMiD50X!ay16(szIMHv zcuR$j%3-Scyo{bA&csT-o|VQPN4O3RP%)V*HjskYJ_-ODqVTie#o&S+ED7vimVhdu!7nXVV=@6&Rck06j}t#0x26Bvq>~wQT4e4-?8L#tp6x z%wcN!<}A=B&aVMxn9Bne@9s_>4v~sF4kgcJ>&edQrU#-@v zb#I=;P4&72i?{zWmsP?P%5#qRl=8$iQyAC{L+TQBHbG#&d_;pSo6h-9yLPL!wKRd} zI^S*vjswDbhj>gtV)ey#yVU2{mo@iH1@dJknni&Srvo5Y77v)(YLT^{xQ2qR{$X#h zBn%#-*!svRC>(G59wzif1#>^^w~Z_uU?>wQ&=a->Q;K|C$?uf-T z5<}FL?ueyDS-hL4j}|45x_HW zf+yGYOro0KO4fkLo#p+<_X5*aQzt39n+LG+8!{rz>P42APwU{TidFLw7IrW{UuM#h zO^!OxXV;m!k^HKduw=D-H-us-c~d6x1$Fefq^CDM?u4}%%kS_o)p{s{LThxopgzG- zcy9HNB>ipvQ3&i>a%{U|ReUc$pLuA}Ib$PB$ab3$t2Kft35W9o#o`pvV*+@R5!yn; zXS;|GYi_-pCz-cmr@L%@Jizw+a#)q^9~fAkt92^Iy@!12wkXe}N^#%j7#ALy|9pni z;Lp&4_x$;_o^>80TyZ(WZ6Uw@v)kzww6xhF2n$K=d&}+D$-|TFB*U?y2w!)(T#1YX zS;xTW%BFjgb@Kx#BqI>mgxBcITFbGz+AQ{)Ig}>m^;nGqb4a_w*idrv?PyxUXmn&a z+)UV$8(yQ1(0SUZdeNt4B6c@ZyrXB%N)7KEbn0@-SNaRJ?j_FkA_~Y17e=k zryxFJ`O@BQAx(L9IF$s{dJv{*AVC{%w!oP+^j)W6|7fQ*`W_uTTzm5Z)SeY?de`E) zVGA++wX293pewWegZ2wKpxgL!&4yesW?EmAko#{enIV`ksQ6jq9|O<~Bd zC^DFcv8#*@mlRd#m1V>#{-RqcpF?68()ygMlUn+EO`Z=`OA$dmh~?2L6M3kv2(^sY z{||$~`ffFNnucaqSn-2`4eDK&kJtOYW|0w)exNA?Q0gslO}_+&T#GjWeEqev^wX2; zx2kz#E?s1$I!}Sg&}Q#*LODe(3|I8fVw-qM=k|T<_&JSLrJy8h1|g>ULAmcgpNBfx z(_KvzUnVV-oI_Ob!e!U8XS%k~jfeG*?1+3{KliY8qUjH3ohTY*Hq=v!bJ9oqO6WOI z1I2D|ve=LCpXiWbW9P_W9gQx|TRm@wqfpUOTm{Y%R;B=fdpChd!?)!Hjyoc3u|FE; z4cSq7N?Es|au`Iju2VHwzUt*ZuPq8@vmu&sfZB%DbpHcN|zWUk&#l@jVg=`9(Obwl1~ zu=S%s8cQ$3|2=wxX8Zky7%+RfPEVaR(BKjas@-1LOU>N}jDSeczPh{9c`frC5&oE2rceF`@*MeQ_k zd#k-Y$c8q`koYwc717h906gMd@U96WdIES$n*kF>(O^I|$eu(?)`^^vIv|P!4c^(! zzE#;xg%Qy)n--Tgw5i4-`qxXrRx&SH#YL`;V7Gh&%;$)xa>PX6hs(_1l)TF;tbxw! zWsS_}K|S=x3Y20mQWV|YORRcGyjM4#Da$hy!|J6_x&+N|O1QCByEZWjZMv)f%bc z9sLHXLrW6*@K&BC`a}gl8R|;*Q#7u{Y$Toz3_@{8Xi`UV`;c)(!~=uO_9`=*1F1#^ zdj~+bcvgPyI0=uYPg{y42#rB5Le`=>=)6uAkz5H>g{8n5B}gH2ev$QEjm-+3VR#0v zC@h_UlkZo%IT%F=A65$Em}6fOY`%V`7~ys(JwIDzFKl)Z+9t%j2(W(R}3bZpb3TN#-6Tu?<=?@eh`?;wEo0l7Nhp=oUnX0&Z) z`3{~rq)Q6hmrsAnzPH;;YTtU-1$@(^3pcvYWZv76@1;VzXI-+)c*3g}JaHLSzO}$v zwO`s6Xv_zA!p=%RXV+l?3&_B{*-_VI&D>a4gwyv_u#(^-G+em|J^Nz&;-cZnxYo8O_U>pd3+b7X;LnxT$2NQS_FS zsiyY!ZS0|E301%N@12S57708m!rG9EA?uFIm~TmNMj6lPMtJ6xTqw8<2XX#?k=M;}ntH9V3qXksH!6NbZBf?+I}GEk9$6+Bvizv7}z zcmo5<&~uyN+Z%^~g8yoJ)?kg$T{RE;93bVRZGL7 z#+sx$*w6)9xi0Hs>h1cfv2TK9T+ZoPutvN*glIbjjrgbi$Lbg6X9=@br#S@~o8iIG z?IcY>78+mP*jwd)3zlr*|6fNYOMwjmriEbC;iDqlAKjN?wT|@oSXzL8(s_H^fDe5n zFC2R~HoT&RZ-A7zqd*gDrOU9~?s_9IU0pU^xY{)lc?X(>*4xesi2S=faX;OPFQK&_ zmWz*`6J_(S)1X0TQDc=Qma;Z|S5HJEy|!Pc`Z`gPC$+tc+Bd4U_U#l^*VY~6(2)%5 z+i*BH;kq2Ze^)Up9IpAX6Hd{|rY`JGb2{UYTURUQX>0L;LRYIr>VHjbfGd2L)V3*Cm$)k9biz;in8t1{ybDAu6oHaFusDK_OLu&J3kuz$fPg z+$(1xcG;^(vW!uOV{y>?>^e1nS%QiDzsRBTQ`48}q}t!^IZm5ql<*g-?Xz6tcJjg~ zlA9SC>qCbJ51&|kzjzA@lg(W*S-vi!Z;5?+Rm5au5u^}ZAH z_r)-PPXLnf6q~wG$tboRc4KMNS2{ry~*LKjz1>S+AOjXmJbdJEL76Mu}BVGW+{>Cf^o7 zH+Z&Mw=eJjo{pcCszqdzLHCO%n1)7ewsP3&mCrm&F|7`g7XYOg(Cq_(K1AhrQ6kvm zhuKO86zUDt@clui)(`dk&QIk!PmkR7zhsJbC^Z#R9bZXrIaimzzof|~6dGY?`U||G zVzg(yIm*nlfcM7@Q6^hBP@|6KgV1Owm-mRhD3@*7mkL_YVSD_RW7hTI;K~fj$+7cQ zQJSY0=i|01YMGq87me)_IfF>|)s1K&8vd-ITs5{D+Lda@Tof*g#WAlxw?Y*$w2>oD zvH9ENf{2yg`U6jpFn$gU7q%#hxY?s#QGeI(k9Gg7&;V`6Q5+K|Pxq zj2~zd^Us970h-;E%O8SiOmx;HMMMnIUPg_&e^0r?+o7K&V>I%zA})BME*rEo5U8yPil6B+G42 z1G*81VMCa(+rcGA&c?}A3oa&G7Y{-HM>o~_6t`c0>RfEb60sK;{q`jaMwy}D^=A)Q zXm0N1V5Y5M&@RcT4={@3frfi<2U!vWN)%}5VW$wb6cx1JpAoKl+r+;TuC`qtHEQlb z1b^Y=vBYkc>K6fa)C-}Qfh3g?4k+yp!^=H%Gu@4}k@Wh^0-{glS(f~{X2V>>P{6wr zv~gtJ+sGo+)B|Khbf>+U%6DN%wCu6Yi;r8SBiW>i1Xg5p#>$|lIT9ZjsmDKgBvJ8n z`W~&wfNsllilhvssSw6?t)8mcyiNdnkp`;yC(mS1+)S8HL-HFufF&`-9s2FpT=yBpI$Gqd zY#&-#Wr5HD%ur+>RQV}AV9=w0WTEHN;;S)h19HfZ#@!B)@;9|~B@ z94P>Q&twC0$F%?rlJ`V)C{x_#G6edS`EsF`0Y4~wdHDmVWo_-p5bO3QAqS!kH6U;B zzbwF)EQxxxKz$~eKlN_*^HUa>EnpmEOGNo(6l>zT7(YvTc-QKmCT}kTjq4`wo1M90 zpK#E!jgJGEh^mc*xm62$VgGC=3d6!k)9&K`Bv zdlA<{Eo3Xc%DrGe0pHOgWwybXd)^RiX!y3c{lg27ojDlU)l1<^10fklb*~!+Wb6jT zqy_z{0MXHzxfNg$OMcfG?)>W!eIe&*&7c*35av2a*nSZ%M4$;JHY?X1dM>8mpOh(8 z>Zg&FX+kO=f8>4qm;oQF9}pS1#Kk%FkzynH01&7k;@RSWfn21Rj8#D6xJXGycLGW7 z^Z|i8(bHo2?Al)`^7P=ovdJVBeWcsL+{nRdN|+**Ad(i9(fwrQ;5%liEBm1_T%nRS zULK2P0@Mhe-)WRE&iMahpj$(gcimn*?8Vi)H{mVfr&27#3pX#AGa}A9K1E+VIycA% zHM5Oo0~I|uDO=szmBX!cYuBnynm@anTY5c1NJF9%Y%UA)AGuD8zSwP6#mRP;6(l|& z{kvYtS!&)#YU?E_;xh#q2gvxE42%sIC|0F1qx z=Ki_j+V|nQAgl#1$VJuu>~jxY@C4hxaioM|k{mY1Abzm={YVdRdeer#3mb0uS4d^n^za3;o5?J{VA*QjFQ76(=|0;5W`QJ{!&r)K&+Im@VHHD)p4cp8_*6 z0DL-X2UEBBLG~!O5qf%litbm0&I0JtX&-(%M~H~GC{nSgIpvfE!C0j@X}p*t%bN|j z)i+K&_PsxR{>=3`F@1jb$t3l$x`g?97JBFZ0Qnoa8nrur(n-HT%EdgI)L6^GZ`i?) zQb=E67dp6VK5fg94+c%Pbsuoccw-)8&3nDXgmt;-Mp>D(DE{A{KBfGx9%!^rf zb-wuXVl|KEMXBVC@F~S)lk9!5uGHf@Z+{N}uO;-*t9*Mypoaz@jyYruSo$7|K%4Or zr(3-P`D(K`Kq+d0Vdw#GFvz#VYIIf1vl3)c^WxzDF34dzKjQ+*HqVdigdc#rs1wN8MMELT%1|1(PdXl4i{;0!QW^+c@V=T2u9!eA2zF< z6vrnNDs5L;5-lXhW<_Y^=H|NJ>{mNnpMKPy>cJH>$Pf3&=sj6~tQ>4<$T0mFXt;oX z`KQOhycUWkv6J%aJhc*(UCTl@PXNfpzZx3$rmv$uuU1y73(2(g?((0^2oR~ATzxUP z_l;Bh`JaZ`z5hf3nE7SGR#C^Q6PP5ysR5s}a4=qi?I)!mXO9~TN;JBFnX+-jMXZPx zO^a$8Sy0Rs;#AMKmq?zHOrAp1!PNBrv~0P%O009B!P*>XXiP;x(F%-?qxBRc>&4vQ zaTPLXG=|&4A?|g;SFQ*X*Urn2M-^kZh`l|VecBeUXY4?HV(l*IR=LV4JflT?FIgoz zCdTB;mzTiu$zQ$d7#}D8`Sa(T0o#*t%m?pGUbP*%O0;0mEk^Ahg)J zhM^GJaF{jg%8^T0$2GWb7vTR~x6|?Q@pbWU8znwAOwQqg~`u-WAm4b?Smj|+95T{Qk)Nw#4CX9oBK4y+g3eG}k zcnY$B9`>PHyFk-c7!a-I=jW3ne|{@0A#p92j|P*i_UMQy^J=s7D4D;_>2ZBXQ{2p! zGtJq~Rb>Ln33)-34Xw2a*k641!t&>dYR{!uX)P`W`eqo^$KE(vW|lqTqhRZn6y{Dw zdP{`PYMxrAJUv0=*@Sm277|E_N;sWk8QN_(uzhTec;-0czyGpPypJ$M=tJ=vElgEZrWrY6zi?bX@<2)ldkkS5O~KE zyKFf`xXb3j(XelS_xlJ42!xcDa)bEM&X$a*+GGFC#-f45FBg45;FnS?EtU;{sb<$* z_#;>%nU#MFz{(vGW%F9YcCdV-R_XN*ZQkA7a=u35Ag?Q=>(mqupu9g!Da%I zkJ}+bPcoU|#~3G=^!*Ekvh=ZZMMT9@HYrvzmhWQ_*g{USMgT_yKjkVJ-A!kWuGY_? zwhFz=(HKB>YB-yGfB8RIV*kSN%WozQ`fd(4$;;tG%XC5ePNTaCqviLDCK$M!xQbMzxo0VrD9P{fX+f$U@n2~ui4qz`Pa?&!VU0M^B7e#+X01og6}XWaq)L)IZ$G= zeUjMb5XM4K7qy{a(lHJqm`fSzV(G{HzfASJ>dYouGhb{9yMha2$U zA)$HB!Uv$PZg9CLkY}swASUf8s7e}4?kNvI$80t z^vZ3fIB0SlLtIu^j#Z~ID%Eh1>)!>OoO+LievB=)4i8)Gdr5i}<&HG{q-Al)+UdI3 z)>jiQ!7TW@c{XKaY4Ls3gxp(gJv2-aciE20ESR5CmouWLY%lU}eBU|{84Y%~4gj0& zmmPEYpA+{5`B_tW>tg{-A*96skXchP)n(Te)&%HU_5Y6o0&je{rXX$f<> zg)usM_FhX#RI1>wN?|OUI6D&q6Z!Yn787XclCkS(ds`K)FpRPA_y-`c6t{0+=4Vy139xl1Y0sMR{Eud_->qG(yn6rTrI|z}f4x zTCx2lt!-F7OlnyLt^7jkDQV&Dr#!N~Ks6q7U5G8*SCLFU{FuqV#jEPmG_5}Jn{o73 z6EF!(zBFS?x_(EG_CWH7>`!F&e+B=oWdy_<#caRVi#+viue+A+P2 zI>F)+jkptgQJz3#K}Df?DS$1xNSWvt!>mGSI)_=KJ{;k7q~v z-`(9YrSx?h3_Ym-gJYFLh5VX4GT^tUi-X10DgjSn$^KMKzt#-&V?oNr)%otB^Ln%1 zgs>U5e@Pq<0S0t`UqIc!P2n`^yluF=agx%JbG{4VIKj@uJ);cCz0Dtg{Pek<@q!jp z5&5VbCWUu3gjNJ4OWXSIE!*I`TuTGMA*zWM5K!O7o zR2+tsBrn)_whPv-u)TRlE*3gd>TLZGdCtu2oG!O~zo^?1)G$SK@nV0tNOgw zO#o_{u+cuc4?SGnsVs20_^@t6XvvUaIX#Hb*a_&ZbncB{tt5Jv2Uzo5-d=jM&HYJA z1Yu4S>{E>Rg`@erc|%|~_Nh}bSq-*`9G!cETaMHnA9ZiXZlyulf?ExfEHc2`X%X*c z`Ul7zi|?@cJ^ktXpYw9k(B(;R86ai%&ppvxtat1(%6Zcp1Nu?|j|62Pu)E8q91$sw zl+c`{%1WVdO>nR{UqsGQ`r_?tpNsm%*bt@NjEKK)*);VSROKNJo#N>>p=7u!IguQ^s{qe#|H-X2X@s-KBObj|qa zDB+s;a7HUUUj2F1x9Gt z-(RKAq_u*70IXxK^9IdS`+*!Bf2mb@x|cM{OgjkgGcPo%rvmZOkocW9kYl6P7WKA0 zv0gS>7|wE*c!vX_`j}I3s;g<|o}?7hyR`z}fX{1=bA*PeRv zk6Aq~eZ%*RSV=-E>}!#6=W7pTCe0+dZi|0dnnmU>dycL5tH5up!+)tCKKBm7C2Ja< zd@AAe9sQR9kk&!q$97R3t5n<0K5n^J2%e&~W`U!ee!ull(&8{z>q5=@S%$z{zGjok zPt$x-u>c~rq3+@Ye85%&rj9bxX)_F*?r+x}-K%h9jN*jOZ2jQ zaNq$PE-!bB73@|_1F(zT@yq+=dEb_d`tul8t0=`hoQ{CkCTJN@A(Gw5%Dp=7z>$+K zN5nDHYuZcEoQ0>rJsCC%=^w%Yz##j$VFw@&j0r%B1RC~46OaXdCdc{8X&GbECcQC9 z=A3Xb-XpII_f$vxs(IG*?inpgEHqpK=LhgRfK(n9dKj?C$9-o+Ri!=IOMJd#xTD)s z;6B39ZF?(^95!yA^b82wB;rmCh~_obn(7b`P4A^J!AU6&`r3kV{5*y$|K}LB=y3z{v&WDu?vA-Ubh8zKT@-%X*6vPhU zkNY&FQtVlEj)>7AWTFIbX>)6$OaG0(k1Z#_1u1>`E^cOi_qaFv6fX7;y^#cLj$rI- znY)dCdoE#N*4|u<01&P0RndpFYl2)eR{Z66(4^!iToqPi?TP=~zr3ol|K~okl47|_v7Y#xFh-uGqbF*dRwsmPf_8IO!nhTZ z4ddU(brL&&RiB&gg__RT+L=LiPWaDO?_^iE`NpdA9QG``KtbisI7@Ut&^wD^-VpRd z0+;G`3C7(5t%5X4&4eF6?O?1Jjm|7?{Fb#6z0XxRevO#k1qKEd`@}e3oSwcM#l_)+ z=z~ce9vXN+DEYcz?EMdZWNX%9+$Ix6w7`7H9R9w0x%Z7g!*TDsnJM5Dp%zEemd*Ys zvB!Qw+Fz$`9$$(4#QVE7Vo3N-B5}xQYI3lCt}p-pU9z04Y=xf(5YXRO+grtKm6=Ra z&kq8eT?p;>eN~BlNU_F6dG?#sU_S~rom6+A5=4i|F-s?;{Z z)!ZhYcUetlh2IOZ|2TFBE#2qX0GNQ1aIk1jkU@VS$*ZtNK-#eS;6auSLJ1@u4nV4egJp3mlpnYqm z-A9pB($7%jMbvOWw5ETTG?yh->L#p_H?608gEWK;Y&tQK+S`Z^{co8%1bk?RknKjV z3*Z`_NQFjetTu)ROc;weQU-GEp09Uv+w<9QD~-cf3slhIamL)B zxyt(?u>%MouGg8plaz*STP@Yx2SW?dxKWWonqu59N=5x@9Ly`q7MDsRF92bf5l>wAIp zj$m9ep@VYyL$h;~jyx9fw_JO0#gpsXu~O=o<+-)DW8#M)Ah}JOgd=C3QM~MRcX9lK zhjWwp!Pts$#<3#K-S!=mvW|O~_pL?@AoMzXAv#7+N3Fwc@)H4ZtoM>dCQZGLc#dhtg{QYRATihpy zkQ)rtdEG&%Mq=LaL1Hs(bhuan2ogUDtH+SSVGLzLS1Nv1;t} zXnr;p5R>Bg<-t8^#F&HQAPL5zHc85Q);G`i@_b%8LsDa?ZVh`XYdT6uY1MIiHShdcKW%QMQ9WqC+s4ii3M{^tCviN@p zJy<<%?PAYtXi;w*@UdFu$mOoOSV+Dd9Jrow>r97asLd>6sQZmZ>9BT|#Mp2KQt=JD2 zo>Xe2jWl+aK=;8p|K0;ZtXlo&5jlK!ZxgZkJ+!@>ljjYg(^3ZsCrE0gK8Z+y&FS`NgY2x98zRPyE5( zf<7ksR_JxacgQr{@kPzD(@ZeU{+d^n%4q489~Y?kt&W&{dS(#nd7e>j9nrMI1VF zYrVK98Bucvmi~)4szy+kb(ZQ=`Z&Om2eepSp|hESl4T%@_R2sA^Q#l$agl#!Cu zhzE20Sbh8KNRP7dRVG3sxE^z@xi=IgzhD&+JSV#tI~TgC<9h)d>ho|s@WU3E|F;D- zsFm9F^_eNvOk-d}#!;GIcXn3J-*{T4e*Tjl=rfoG*zY@#-fWR-NFg|`5~0562VA7f z>8DNU%Yj)ha4BqlN57R3pS*0!cxcQ*b4tn?D zt32%zgARZ=!~zs*a-LD%T*6bwT-cL9ErDJGq0!~z`c&c#AmZOkp+- zVq%=&x*XgobSp3zhF{m=7M+X=Opfa3Q zI3lj+B^Gg5Z&F8e#A!$)9bEeL45%ajbL?8PxaW7!DKlbwZ3>&~^YS+1#)8@7Ueo=* zSpdMQIK*ya`lo{kC{@JV{NeL*?pv#~Jzk8chF7kyZIdfV@Olj!bRz|*d_;phCx2e8 z4y`+?X=<{j9Y<=JJlvEo{*wRVl>E&!X)F=X34b^8S8G)o3Q^PF=1oesbmZ4l_eo%T2fV3DkDZ*HZ0WMm`2lx7DP+&ln?{!r z3ncfxz^RXJ|2>QjCF% z0#O%_a-4DgF2HxDd@Nu*h_0g1e62=O&%tkEfpe8FQ}{8^2ydiP6h_GY5X&qJO#(y7 zAN&KuJ1Gkb8Tw?>l&!Y(ph_X1TB0#dNGrcG?>&KrE^QjVY`>{%lz4`U4dV?EdYXBI zbCpTW`008olR=9Qkc6dU{T~e)WSD)@7jGH@cEJGI05Qr0vIjFZw*(xHm8Ehr}G+~pU9$F-5SPPxyyXH$s9yW?C-rLOV2OS638yP4S zaD|;!J-?u{|G9n`@$x~luF?AW z^iHl87MIjdC2%|IgT@nPATv)X z@Cl?wq}KD~`N!0AQ))A8qzWdcHx-IVJJ09S%g=I4d32-!TT=Y*kK1vzs8A26Ot`jN z$AQO!Bl*vO+&(>!6IR-W{V#q8+@5bV%9i^Y9k@j-3D*>2=)8F^-FZb6PEQz45BP{P z&1hBG)-V9cH~0DJ{btE16J8Ma@FDC`?oorQXr`c;#8J_?_4|qlUdxl}V?bofdH1vX z-JT%hX-I6NZNK1#Lbf>g* zOLup7y@TI-f9t+$xfXx9U_LW*&e`Yey(c)e>hr!4x=!_n(;ZU<;4F zlHP@Vi1T`atPhVjpWA`F?MfYf97zQ~GUZ=S5ztc+>@FpvpGy>QvY!_#ktOFSI`$}K zb7y)Eg;YiDN6wjQY%u^DF&OaXF|vuGR8olIPD$oOUnJ*_nay?~{rdoK0<-S2CTMxV z{yX&bany498CVQ>AIV7GC&b)*ij&1pDfM6f#{B{m-YBT3iSVUm)P9YJVFtt|)#?8FkA8WZXE>LbwMEV_bZu_=?!f z{C9}`)~y7GKtXUd#&@rHx61cG0dT8_cE&Bd-DF(dvFs#L$22D6dqDd$L8`8cV?8vy@(Gd4F5?|whCrm$W7By>dE(3w<2>1 z0^YtdkM7e08~?5e%NLGbK8;`cn#y*vJKbt0795x3TIPN#V6Lp1h}T!u4IC$A=9yw8 z%}80j_$GzZ0RgFTcr!x-n=+_Y&ih@%zB@|&Qxa8}AEf>1XY08TMV*AqtLG4P93J#; zm40uW*^6S!(-^>uSV_1V>-n98%|F&e&rvaz0L3gloF;`#GPelu64h!LeVdyn)T)rS z4t2uRiqJpRpslpr#UJXqUWq_{m!;jqwp@A3W-+~8?)h#scU7Pwxf-Xo{hUcM_Y9V7 zKbwB2LabI~TZuxnSZU>GKx?xh%}s$z`IkxtV?k0RL6C4#`1vbMyPSpo8fD)YVvt!) z4b`iid^G~|UTAL+cLV%9kB~K3Alt0{0d+i@*GFMpz-8@}hzqt-&F6_;s4aR&#mZO0^P>UnzTr znpb@RT?F^fSrDMfxr2Y$_5K)WlBR{Ai|utBGRATJ_<+{bq)_B(3;|vxRYPy&X=x&F zjD+1)?9`?3o_Mj*7nhl&hq);+`#X}#xJu#{Z;EG)>Y&@+o5h=gs!yMWA?$q2V(iew zS%HL_dI8m6dx^aW+44EJ!M&g`_6tGLNYSUFJ5-sLgQt|lpeJmuT1qk(2%%AM4`Co5 z78}(+_v<{AQ^Fcctm}(8>soo=*v(j8TRUVGuM*pWfC#dNKWcE$!=}qrDyrLkYWrid?>)MDdN7YC zOpmZ+9#I%PVDRRjwr>p72)=dHLxi4ZLh?-g&wZiWFhIcuLh4kDH&gRv)1yeke#_%! z*419c(8xTofQ_7t;r@P5MvFIFs@q!_p6#x=IammP^h%xzF7YqF+`#8WF)-6XExH*l zEakn?MKQ8X*PAv^lOI4xx!RWV?llUthH4em13oSuUp#OD0kg;HzN*fQ1YtPM7*5bjbKFjY%m^p0qBKQ>k;;$-AM$&;qAIyY)|q4mB&3+YK-mTMB0yI8 z?fo$HNcb@3eWL>dnJigs-1`- zHL`faxoFte_CHizn<7T8^HRv|)hYkeBChp(cUqi0e4nzyQ~4ueMxso-s1}0{oR%nH z$MTDR$NO%vrA^NJ=Djfa07ZQucU8lan+;Q3TmjhIs23R9;r4bpu&w_%f-#2@|ApC{ z0LqRV{U-`V&3u2X25qeEas@Kviw>7aa;{+|={xo(4}~HF6)kx{VNI`J+k+L&U0Q?v zfuR8R1q1V&!o#s2Tqv*Gm#;q*IjZA^l=*>2if?~mV*Ru5ip`;w%o9k9yET}X!ZHnx z6FE3;$NWwJoiA6OLC2JxLox1OcfA4=$T-&AJZ1{zi4}@`y;28_B(YoiKd#>PiZ7q$OR;oScX=DdC>3-Q1EcwBI?}Hceu1c~p(QU*LY>gW zzH2!`{G#r+X#7}G-4*Rq$@=E%<5T)sIrW2^+dpjomwzfD!MK3W;0%sQgZ(GKB;FZQ z1cou7VtEHf@r6Ik>k2EMs@f$-RotKT^|i&hDY|vC=fkVpjRcFo+Fr`fYa^sEnXlc9 zMx5LzTZ#mQy6pm8*+-8qlyZ_EHi@%p%SR9)(FU;fdcClNG)bm?i zUER;i_rc$6xzncQf;%&5URR9~59&91`;Ck!01Kzpy3N#Q!00N=<+vj4k&uKZ!Ec;t zvg^E|e#Gbm?{it^-;VJGz-oRL(TiTYmJNHSm48!aK~aG*xHBH*D2|%FVx2?oTbwI4 zG#O+ZZPvMGV07%R7aizybL`pDTOGJW=!i=z|LD@^;7x91;OLBbf9Q-O&PA-^A4|9r zFbfAY#)LJec%r<6(Xj1$FSg<(xLoD*HDGQ;jG*_;mLp`827*UO*d9e827&w^AS@VX z6w^n^<5eUWy`rYA{TC@GsZ32lA-|~6CU%2F*Uk=cy&Q>?*GD{i_BgQRhry(*9w&a# zRXm)u`9&)|@QT_m^ZMe&_X-YrS8DGo^Audfk1S%mi=eHb zM?yrR7E!h)dN3;oIF7~ruxv1~npV=eV^gJi&rUbhik0|Z#reIcFX?Og8Ca4xQedVFe57ZlyM&eK+xq^wG*LlD! z3ux&pOZwJd;*7iP>;i&PR^VBY{hp)~;PnH2=wDZFkR^c5yZ6*mYz6QO6u3Im!OfDV ze_jnb^B;2&cbvO#wyU%_Tm-Ph?Yb;FZVrOE%nz@6V=X&`{VMYGROks@1jhtXJX zMp0~iM<7}}!D1)89pkiR=Umc#r5;`a)ZFeDSHfG*cHnB$pVT^&K}DU2)(!G7x`zu* zkSoL=qSG;zwe%Ssvrv$Pty^@qLsrn}lgKcfW{Ypv;l5 zxJ|_DQn^0vxRjg-=Ah;IUx&BJ5$TsPG?mGsq~Qtu{keH~nz9};-H}vO zkUyJX&@d`Q##API0Rs#T64KHx&z2@-U?%eTgEc?Sl^FzVYyP;k_{$13VX6h3rZBx0 ztv(zd5xqE?1BVgDpL3|k5q4en)Zg($W$I9oWM60j1X+9SOAZ+?6%7tVg4xV}#7?oPgS5Uy{Q z-`g*yRg~v?V%RBjDR0K3N)s=Y(Cj&nJxO&~whLxb8qGhWLZau4pVOqcpAIc{Y;BpE zYUWSm6zl?0Q7zP<46o)slp~_Y-C!gk$K#2xD4W7D5r^yg#b1HMn>X!WF%Pf(d7n)V zbV_k?j-0E4|0mI48wggw(%hs^&;rwz5p!(CLY1IV8u&`n-|h3J=Vj*<723!+fGQ0r zvb|Mz8o0Al6Z$lDrYC3zzB}0yFXOwHtJ1K8 z;jD@lC3(&N>Afwy$%S-@RY<(KQgEKozGEZNI_WPJJ3~9nk!HNEXq|S>{IuPRPuSw9 zsHmJX4-+zkcCNY~wUg_<8s>c2jEfi9#(D-#5I!0;!^i5zO$k6sKUfsNTcp~WZ_~5Q z7#;fc9rLrN3S*(A^jZcI#MxJ#4j12z)Uql9@$Pk^wEj@)M-ID{=K$H&+AM~N2c`>@ z%LO&a>V`YdvWFsN7abYa1s@!c2xob!d6kDM7uF|m<`pqN2r>^j=GHIYtZ_OIG&lyc zE$BQs*+o;QtU&r=fxE*8Ppela*F5a1v`m-pKmN6OOUee=`FoUlI7d&DnNdlllw4d&XJV)iLOlczw9WxJO+6R>7+8UYh{?Des7^`t-XeQJ=O z0H(Yz*ytoOaMg#s3Bf{P2gUZ(S8xg~LtUoh$nFxHqP9a;8|f=wC9K{qKJpHxehi^g zEv~)5AvY(XR!uMsk*cjE;}Ul2h&Er7mdEnzu!L94NI=fyd9!unQVNDU2fgwA1G(YJ`m`FoAIKdre;xI~`3q5w}GD$7c z&Pkhb956&yK!5Ys;U0useipxs{bfz)L7$W^P9=I#G~SFzSMV!LxB6CcfJWTiXB47h zuxFgUeOe;Qs*QZt(LD?Y4e++d4}sreh92IHFHgwJPLEO9Y%S zs_3kqEFkzgutWqt{Fp!!Hhr7pweRw>cwF@L7~OJEEa%o{4-La8FiXe=lrkn;YvR;_ z(+=NsWE zv0Au0-A=#fZj1jrh?N@4$5Z>om|4#Hcvfg6ob^)4iDdn{E2P3tKb3RA<{M$LoO)bF z0qrSKD{aSwjJv>TAEfcOFUm)NQ2eyaTl09OMPp+%dU@!fZ!8Km6R zd!R5IetrrZIDtiu$8jevP^3#Ir}EcXHUmL3@l&w`8#zoOz21+JoDOowaLfCmvZZBsw&;bCvY8?aGQ!*M%i3>@;Fcw^ z@i6^8g>=ZAj+oHRtwp|!(T{>OKr3|$4h8rm5ep02V8~0)z+jdb4*1_cTDe1%m{hm~ zl$BMxZ(&wP^99S&!+drDiGg26ni9=$S<Z^f9^IJ?DF1Zeh-1)_r0~m5WNuiG? z&P!^Gq?XYBTlbHwJ7NBh|GHe)p+gwprtNtd)HqL+$kQ*4=K|V3lLJj8tT}8!>@(FB zNl&YXG8L`~iPig?FXT1zs-ksqUKuW&FTZfX557PAUMtU}-T24C&3`xtYMl0o8@Aw& z5Vo2xN3nqeY>)Y8iKH5j(a6#wvS!lAUsVpd29_D(-s&Dtx^LmRW$SYUB4;)OZ{I0rQmVn z#@KPf1hf@Dqq@~YxAWlN4`1g+zY)-q_w)ut9hOoU!IU7XSnrj~@QA2R~_6IGn7+sCewp{ldl{rrem>4-bjO#1}RH|}ohK-=)x zHNaC-l!x&CfIljL_T4i&gZMk{K*n-e|F!gbb+E?2FWC3XaUB^&?OywM-@^aLxIueZ z7XW$7`r1LZVO_V||B^dSj-t#_Z!A*6;tSz)W$~$#ZyH0 zK|w*$?Tcg36uSm13@xNRxVT&fjkucqmms0~%mg0#qY@HX=_p`n*4nn(aWvBRO_doS z6kE>(uFe9h<+neZ?^*luQ#AA4#qxgO`_PZHG5Jch;E<2f1i!puwoPU1ds^p?ARFjK z;nqlue~o=b0M*7;`nODS@-s9cNSodkg}@&HE5DH!H5iL?LX(*v)PZ4kRQsci;g*Q(g%dc;OLxp5_LZ)i- zt8)(Q{_AX@DSx%?sA0k6qBvan-C`U5O^EX1?~lB^;lOOnNqPZwYcncFD-2G*2?CZ`$QrK3b76c;Y~y3(P*~C37uTa_N-+r@Nsv(HuXt35H!n z@y~Jp)g^|&csHX&Hz!~l$uQl+k!)?+7Oi$~qP%jFdKPiY@MIYTeIwDU8p zw*J_{)%gH3)$>f8@DQPm?&qk!X1!Ijt4kWsqXJw9H>4Qr-->ILeo$@D zH@s-(Wkym-LJz1{E~-PmF+;M7XRwid$*#?$)eVdkSex-`Pc$n zwjkuOkZvybvpgoM?>9~uFn%}=Uk`NG68(_IHS=(pv^xOia-}b!95|78gm{Xk2AWtk&;}k*ror{3ovb;{8ZNt@k6Z&)`eCd0WpJGiCNK9PU{o zrespN3wNjNRmWarSNi5o`8(6DEk8i}+iP&KKg)H}btYzSk(`vR_Qex6!fO=0HiJ1& z9v?DuVr!(0B-h)QEluj~B{&3yGjo->GBq$~BMe#knI{o3puqsYB2swldGGmkM>ktU z^hA@(w^rV*wst_UBy9oRl{@z9!CM?xDF7_!T-V88eWO5_KoRu7#as3_NMwxU0!)a; z$K~7p+q%~(Czk2x<~TIECCc+Jl$Et;QZk3afa-5#^_^rLC*d^o=0M{cG2AhOeyZxZk&J! zRn#a^)3tLxu%i;<>-w8u(dO-N)TX~-2Rs~mayudWUq*OWwqCgg(`_Cl72cfh-~XgH z1i>w|afeJ>;U=bws@cmAV8r-43mh$B<7P7bTME(Rn(J8FGK0zq*0cFPU)gWpOYyh+6jY#fEDOsL2*aURcM=a^fG#Sxb^9O8XZ$ z7To2jWUuGaVM7Wg%-e@pEmy5!TCOK-0J-MV0LQ^f=7|L{8!~Rvxf(Yh}?KzF;=}9m==hk<|HWe3WJef9I!< z0QNxWlcwmc^ zr9@^bx&AK~K+bI4?%P=5dpoK0$@Z5}zjqs5tu1VF%}*yD&(hl7INRMp*--jffk zvn23=b?3HTubm-2=Bt#hJO^jBa+58vcpNZU%t?!_ zk@KF{kmTa40C_ENm#a)W)wp77lSMOUodM!fMD>Tq>Ccz79|pM>A1M%h`PE>buNWg* zqD;YC2Euf6(1*Xu?Q~9=wU%}MF&t9kfBF-0VYx zOvC)!LBEZS8A@mU(p5qZcy4Ag%dfRl(NX*_BwG0VP4L2uv!hs};S+{-JCO(O^;r9P zhCcHy9 z==n+@`R3aXb#?W@Uv$VX=*4mR%liAhdl|{FgK%CJg~DxNb4L`;Tjy%EjRfz1c>8-O z!618pDa!xy*=Ruin?}+=bm=OzPZ<;D+YW^iBmCbpTPsbte#g$Z)xXN+<-|U>OT1Qq zsT+>LdLyKyUj8OiTW@O3P7l?~AZUw=S-A z5Ig@m(&8epmRUk`ad3Fwl!C=YvInaxc$!WS1~Z^+&CZ~xuR{fO zdes*k(LoFTbi)9>vm`k;d7&Qbn!Y+Gqhne%S8oFYii?AJsRo!dw+sBcy-mLF^hH?Q zxcN#UvOy^Xt?TxktN_Mom3-NjWZS@7w&hx~<>I&;vnvu}`7?yhtS(cXrNH2B`{gLIew{$(OmIJnjme&L*(Uh8v z!op+{5)yp+)|XMvBm8O)5Xx$0v$x*HVUtqc@IDVzePjIEoOeS2n;gHnZ{^iw)$ux$ zH-3Z5;ZJ1okEeU@r%vZm6E?>}MfEqyV?$&`7#VArxf^u~Cq}CnHY`SHCbN+xcCr(2 zQedw@e_O_~E( zd3|ga(x8t1Zh`}$z`j_d4)pBuj5a_r)b~PRMy`4Bk$22ZG`V`YTEHBw%l0sf$3 zJQ?xZkXG2l1l=ajo4!N(6w-0P_1by`2bjufXe5e)QBSlFEiEks0>my~{@SD@3riNjgMF)wDZ=?h z+(kt3_wTRs&$T2UonyTI1TSBqV6!kOLH~63!a-LR9D|9GNJ5f*G$Cx-&v;KR?biQ> zt{uiie`TIILvAH2XpICThC)2ThMgKOdOh0re3TdsyWbE~5o02Q9l27dGXl!*uuEW} zQGq4mp~;t{I>?mh=F~k$S}O16y&vyuA0KXE~;-{`zb5cVbGkmlm znP0V?&A*9<$o4GXXBZJzuK?1`a_vE&6tiUAu+j?UzZ*uDHS!{N44);YWn{H=A)h9h z#V|AHozC2cHN3JiGYaBpUGN`&XFRjzARgX5&-?WY8%_-gF%g}z?4&F>N;W;0jP#Io z?nRjB*AqG=l3ulXXdMzy(0;EzSIY`2V4SE3v zSV;MlK2D_hp=o!;&`0E&Sz;{PPV%&$N)AyhmlVpwg_FA?5;E`|yb*MW0w$t_jNdX9 zlayqn+i$hLGpd!SJv%t=AJSjg1X~*v|KHYHH(wirr!88y9Z!nKwvN*$*4qfD)tPC? zs;aFSKF+&UzY>d3$Z**+pN*0<2SG@Zihr(j9u8~V_{+Fx1VTyR-LUcIC>A%<(i6LQ z^DdaG7K6?stw}DQ1CL_hYj4bm+8;y(DJdyf%{*b8J~%b{G(S&zUOQiFvT8=1mA7${ zdhf{XZLnse$|Ga{fSneHH<;7N17|r%D?P2?wlj; zn!#fdL5xoGm%U>*fs90)C93rkhjQlhW>kRwVoFL%IRzUmv(}Lh$0f|r=uUcH zla$3(4Fh5`!{UX^ptYs##qgNbS6L!yI^?<%+w7aYH}~q-oaf03o?g*5=d}f;r5G-Y zp6p%^r)gC6G!BA$w*{U060SS=>Sc;jQpm(esPb^xGu$(7ljz2dx>7}6+)-+t#{4r@ z&pK?<)C@>{VAJ>Ft49KN=gPXjwidt7Oj(=?5+iksNnNP2zZy_?&Lu3te=gtZvrJLOO^u-y(ghP*zZA{Txv_ZHZV&!iQ_bl340> z@7}^nzIO{D^ndBv^E{>1$F#8%KEKKQnf54q$NChjl9BIUSAoC4-Sr0tKx=z~sEQ5~ zehgBz36QFWT*3zL@=x-Mj?F$w{K>~~QEICwgS``#fJ~NPstAoWt-CO-**mH0_O{phD_uQ4nHCDae=<|L%6_L5=0 zu+*uY#2?Xg%K2#uO&=Pk5cy7S>IvniCFn%@*=65IO(*|vnZCU}Jpv*kaA+hvTkI`P z_Ahf$672@Ox#Ee_THnBfCC0pc8QJSK9E@1-l1(kd>56x;?B%j97U4>gH08U*xa)yc z`;0E6^m5`ahU)a(7X3B5PzVxNitLdm%ZOk9OUf03b^8#O&5HS?vge`Fkv%F=pWp0R z)y7>Gpu+5)6`*=~Q}ExXc$y!Wa8L5S%n+X|V&TUYvlPQ5YY5&b7pFYcg~Xb^u7l>x zebCjbiYT;N)-(}5cRHWC4ok@^DMWbZ!cR-qA4@?0XjU7HARa52=Ef`KpI2^3DZeNG z03terwaXk#ff~924UAHLou1VP!qM<*gUuuA9b#E`UQ+2WBUAX>W#SST0@W)o`o);H zqpf%$>}{GDvHOBm(_O<8ojTdFS7mo4e8nxVN%CJNY$_m;2?Qd?=3k>h5#Kr4xI=tw zH%&Ppv8Z&3!{3|ev96K}_1lzB5`CtGeN@jsGmWMpYTj?Kx6o_~U@MfY4&dO1!3C}fr#xtPJ5IAEo}7;zW=3~CHRs>;h>0uF@2z7V~SIZL9v zh6cg8*Ujy%-Ete8rliVh70M2b)?qRP!s^}xS&FBMEgb%?meKk&LqPRoz(EGb%K*(y z`t2(cuPeP4*}LWTfO~k{GLE;`+^bq6^M)+f%B40|R@gbik=ki+O}rtgj0_AwU#}b* zrj@hldD4@X#fvt1-u+NaKtOOu>)W++$8soF)~Nlhnv%!|DNyGZyTS?mFMp=@=&5W2 zw%`knRShK6=fb7V7`vMPSnlf&V0zED#Tz`I_2)=->Eif%o-^w3DYzttu2k~-<->d~ zp=llPCg>kHKHqJqHqe7hG|Gp+fY_3zW-kBT?>Kurl5cx#rRM83ySWmtk}S&b=GWw0 z)Ik!g1~G;Ga&o%qq>s(>pdbjVx~DqTXS~O`3{L zS?}$0kYZq9048-zADeEe8tm4xhTjQgjeINOw;`@>4=9OWb-glnbcg73r8m2?Wm`3Mx+1o|& z(P2R4bt1~rUYnep$jZxmaXIfo3K1vCu79h=NWw)J4O!{R%2Or`SoAd+>X+yb$#qo)?f#m;z2QCA+V`&jDKZMJORWjcm|I~w<1QtIxOBEV zlgnTJQnB$gLvq>5T}Wun&zFmvdsCPy4nJ6~?Wny+N-{YeWVV)VH4FLg*c?o3wj>Y~ zv#XRJ9<#!QjX~3oeRDkuN;*wTHFt&^EQ3zlZr?}lb>5347fK^ouonMyavNW|$r3== zv^Rd3aK))jVhUD8vr}IQD)do$qanV0ug`6at3fj98gN;$Yj$K-jGI!fUFNUFPYVs& zmNfeDIvX0}#4GXd+KXdjWB&m`t^M=i@?S%?i#0r9xV*Ii*3(~l^hn}CBN9;>yeehU zy~w_OmI*f}qd8Z1py&?#R28Ll&-E7)Yq5mOWNX2aI6OBe?HzEu$J4<=svsglyf4g# z$6~h{=Hy7-g6AgRj!0_sWkoGThh|+Uti!K2Zk)fs#LQ{DwDQkKLGN&!gmMAuSEl8y zCPlg?)HDc#LFJ@bt$`D&L$|FX-xK?6X%*Ghp27U8`NqH)^pdH4;s_K@L#TdFkXG=Vvi(;9$v@PCLWk>a{>@Ltkrs1>kXuBbHwsy%Q{`Vc z7bwWf;}4k)yF2|jrA;)yl+0idj!F3A!|0f_53LFne}AM~eyyHw$8Vz#;vc8RziF9Q znL=WTlZbbHaaHv~UD2)*hyxxTyofmM-!RIKtGTEpV8m_Ni$vh0 zN8bu$Ld>(>q=LW|)oX{s3L_|1M6xsEK#&7i;YS3hahH_P936@akzjUZ+z~ z&=!z$adOEhytVwZ-x!jASC-n@_iV$>WTO+Ql4aT4{n$Q~X3SM9FDejGb>grEPk-N! zviJ|0n=UWbA2Hm+XIE zf$QhkvS$Q$@wHse#uZkfPfW~QX;j<#FSG3_PM+YE1#Nc{oe`Q0$>;nsN>{v5J%%TJ zlM=-fu2@%kKlK7dkbM39nTFFO1ZbEcv<*wDdDY#8H&kY-nF0dYdUruSxg!w8>IS8} ziWrFEN~U4k$kVp^6$h+VKfi0GhWTL$Az)g`#YZ059pBBPq293!Qbb6#Fd3?Q_+@+s?p6DcZuGeBnny(=JIye>b@Ib0~Zt7nt3EqtY?S+k-bM%$?BbfoTnncbE3 zU672{E`x;ouWxa2c;IDs?1sRLBW>|(c?!FXF67km(|CVm=`6eW=%X85>rp06-W`P1 zg&v)d*6|`pcb}7D7T_(;ubEmT7$pkUzrtpg?n8 z8$XO)ggfuKS)-%M2d$vaO^ulH-)ZLCGmieDRQX041&}=-)-SqPtGpnWl)!6R{LJ2H zY%w->9#f~fqk|i#sqf#zQcpi-?sJpCWoO4Yuqu7hc7LF3+1^LD-qd6o*?bG}NZakW z$K~y=UZvV{vy!AtVk0OX;KV*`#h!e|i-~Twf@i3$6M#;7@req@jb?Sd{|$yyU)=2Q z*eU+QQNW_Grg-ptK2rBSeuPI}5Iu@079&69vu?HDW8%JM^m92GG3?A6@rR1^ChLOo z26JH`1GaBY4ZT*SxWBkBB-~6>9O#*B8-LB8- z!1p7sX=cKd70~v2A^xkRuzS#EPuNrIBLqJiNrCkp+gyxRx!}K2rc>g1x;4{>Weqkq zGMs0b_Slj7Z)4)2g9-q&BW>%JzAjinaVnnuOdY@Z-sZ7p4N~AVjx;%LiTwuvovT)* z*Tv(meAGECfd;Tl#=J_!&Vh)~X>aeM^vr)XIadsL$Fr#DdCOI21!lmp81gi(B(KtI zy}L5ol&)6^BJBcP~t*M(AFJ>4Q ziid0q3%Uu<{K1j$^+R(vQZ@H@^HphE{3)Dw3IJqhEu&%}7Y?&O!)iHSj&0L?ZajXA zs=|*XE*D#?YxX47R_%h3F zLxomND=*0l{Wh5VV-J4G*B)s!u#E}Cow}33YGiDG-Q_E|`JGXD5;)T!pI(3hU8Qh_$+v~jDv-C`CK@B_ z9@IaTxcoEum>n$T7-d6RpnQ))fwrq=zhnCgXNw#C)Miu(6@lzr=$rFfzr&MP(eRJp zeV{J5_opSJ?D`5Vy5l*vZ|AMQW*m?I^;^~JLg_b4^?Rp9OeE0UXyM%U@s-|MDHfjh|&)py??8oBme(~*`3#QL)6*9G+I%t|4%r~t!$4xK)0 zEQf-Yz6{tWpQJzJ5|%;A{Ip64o0E$Vz;%?j6Wj@x-{ptihqr3l&2u&j&A1mZklrvj z>LCXH%V8tOPfWF>xVte89$~?&I{SK*4VEW;;v#kW1vrPHT8;KHy z-zp*!5LgS!4VeKydh#=P`k-~_TeJ~1ufrg;^%79F;U$ZFKaBad*}(o0<7JZQzhEh< z(Jx`1ZqrQD9r-o*1PQOgVaqLuqx(&0%lSNCaJ>$1tt66$vQE?Q28Q<~|Gvn&VyssF zij+7^zBrc65{|X96Ad?A4jLV#_Mn13L=Rdm~<~Ve6poJ51Z|X724F|-kWMx-0 zRQyT7+qdQAEZ~V>T}Np(U-arJ^qyV#dZ}k+i&U2KmXp?~_}N-`wxf z;`ASS(5>qG0t){*X0MkMjK~FAIPUn0Uz6xVsd83q2WdU3O_|XM^B2{j%ngCN?_VF79;+_a^0IXm&+F2Emqp8_D#ksZcvSJu~jum^YUPMpImK z;00yKr$Iz2cZMbi#GrcQ(1j<&iEZ&hq>}g=V>SHffG;DvG(wPV7^=~A(a2w{)8s@`eVzBDvUWUD>T(uyy zgM&@K&6Em`AMUH2>7KJ;9W`Y=J5?@nKnNWBu;JCwYiC`haeqM=cIN)^-kbh!9mVCd zvKg@pWLq7R{uyGA9ge@g;ReKK31Qg-k;M6T`iqB&XqStS;vQ4wovTUhg$s>V<~s1a!Yg%@GVj=ld8&dOz9HzTwE9qm+5N z$+TQxK$Mhtm;UNKT;kuyc3Em{B#--$n$?Rc_SVg3qpSoT=1rmFz4lv;NLW+(PPk^! zWw<3}h;|L(VJf#@W)V@0;b!Z8;?J31l7fpGMYO314hdht0^Tyy8 z59aE$l{}t_-HjdUWNbceJp`2H*W-APoZuxFODGi=3E%G!9@SXw`Qs72P`b-t;fXrK8 z-=L4Cn1#5CD|A3;gYa%w33~+!XDswcK?BY4I_z{?mN()GhnVp+Y(^)*WnZ+^k%DfK z9Mku5Zh3K5S&rrVvcX*ZU)g(-vG%i&*|sf-4i&3UX5-r2^3DirZ22CjoiQ!$s$0^V3eA) zBW7kawnoRwx-`EWHa#4=Ue3`pPI|&y^h@dW_IFLU!dTMk_?gTuw0e^~VjOz7M?c^@ zg$m`%FG*or*p6M2wl=#g{_aCq6fwRb=ee)4SF6?4^5wtVwEf8CCg<&@>7l8entBeQ zKFHG4DJ;>3gS7DE>*r-;zyL4Qi(QUK&HXB>kwsv6#82e^?AbHDI%Jp~ zk9Q8mUAsJnMn<~8O!+IU0OvLl^Wr-NbDyk61HNye^JcbY#zq|;PW3RFzYfk7LybD}M2kExYXet+D5Rz6Nm6LRIA~V<)zU ztJGS(yXC-rC1PndT~|jus)Fj9CR5!_C?(^>4t@=L;$$wGN9zF2EFfF=7M8gw;7diB zWb8?z%7ul6J-sF$92^XJ4y&YFJtROBFd}I=X+pi3=`@A3TN>+}8QsQjh_A>PFEz8- z!~efrfRjPVavkP3Kk3+TishQL(c}BDok`=Q^wYSjXA?YAU|Q#ggo(TJyhJ>SCl({M z@-wi*>0&kG-#}%&K76Bk0u7YW;P~<+W(!K`k<3)h=^4U*eGM9ey|J-spK9V#4|ryS zvbw_u8B2o+e ztQXqOop2U&JrjDygo?7%he}v>IDc>Zndj)Hacid~uznQ#oyq3Pl%IoZ_O)!|QS0m< z$;piSyIil?9}f0*W4+28obLFbNq2PPakZt7ep3>D^~)v8jAm{|Nt)J&jm_fd`WtZ_ zFSfhbFTC0hx5O!XJHif5#M+!^Bviup=QWSG)sG&yAAS{!EFNJnMksXGIXN*rtPUOO zZN@d|`5{q%?e|`Pce*6p@x1GyUr1PCqqi6|k7zz3fHqseg zEarY1P4QhWcxOI@ZffO~>cV0{0WDr z%|RWK4g3pg-7Nj7h~}#)w1R(pIw~p&n)@3ew!K)0ohDxu$&J-`VSc_L;=_7}%}vCo z*#i*yYgp-3%!NgdSzNo7aS0SO2?Vm2dA%t2RPwP*XQVzlTizV9dOVrhSYlbe`9Z9dC)*X zn2?y#wrtBWWIJ@<{rgL3=$ZsnR7b__N_nu*oSYm5zP(I_XyJ~*?q2^q$PsRzitZd+ zkYfBzX}$-x3NFs_&z!!IN=wS5xL?9rBP@HLS1-YvwXGBbF2fkHf0mOvHrOo6TJGPG zm^Ht0DYEL2bYQOj`(ep@t`gHJr|)>7#~=ZEWjk5__HJP2ZPA}kD3fQb#Zx74mDd}i zNGLKg{86H)wKxnK-za(6xJuOC*;-+NDt$6Q?0CG1+xF}(_sU^19};Lj*wYy|LwHt51kCe^dCNV}e%#X%1ox4D$*XrHJ_|8!IUKA= zx!V7Ok@6vPfzy{f4gGQ;xdNzJp#9#G9oW#Wc=XtmNfsz2IXbO^j0`Gx=Nhg~-auXc z4av1UV%|qk{TVL!zpB}Gv~n1}`&lyt83R?AtgYnS&)jlJvv`{Lm}i@&E;NJ*UAA!(*wLR~@NnfMjdHH{XTRMf1j(-4 zlo)C514ndKZSnYXzXHM2{6XdPUJ|w4bN4}kb3t70$L$cNroe;LVH$;w!CacRwiLxf zx^+#6fAnD)K~oGZ_iMPjK{Z2aIy+I&enJ>rQK$*poGo_9Zg`ze@ownQeLs*lw7~n= z=ip#tFE`&FJR@s>ewE0hi}hePR5vopL4m?i(~O`-Qd$%jcJBK#3I*&FUCY(6a?x5s zh>+6lIgi_vi;%_fE4QzDQf6Twv^g)ww9&n;HY~-DZFo6DL$bz&#;j`$baf$M>m+!N zm?Uz(O|t*!x;~kDLE`RQ?OxNp>!)4PeS%GQG(@^5W^T{Y8+r|LS4hC*VlZjbCBaSC z9YVZ%qIzxcv?tfkw`Eq!#2@HCA?A(+VgDreST~VdUK2T(v-nK%fJWkRlLiAZVQ5mT zC?XQ%L(83p0h1qrrZ}kzFcxGgXCvT7 zGur$?@#mD@9VB)r`j2&uSn_1F++Od+u@cyPZP#VL$lcDD=^t2G1IyEdNrm#ny%d}0 ze*U)n_v33)Q6#5K?6Xb%)D|TaE7PeZRpJM^0Q9b^yeN8W)CjcInp^Kpgxa1%Qy6x{ zRqx|}mGN?w=@%Cn@gYl`b&)P;2pO zTEz3c*Q^D=XjSD@uUPV_titwt!M{#R)~TXyhA%262IqHTV>z=G&%FW28MRX`nEdIh z@1a2x3d>Sd=?aBqT}n@d6w5+l55vttouch$n)tP!C(2i~mpuN(I_*bO)V!Q-FE0`c zR)J^0SkMi+izj}X$HLduG^f?54Q{*Zofl831MGT&qugtDzM;dp+K(hCGbPKzeie9) z*6oW$>JfY?X#;w0E}j&7w7O8{*@HGS$_vjUoaW2B_gC{#U#WZOgw=(ej$7Iwv4vG* z9nZehX$;47%=pAE0%i5r<)XhsTjEk&kA5&+BVV_!a7hmPil-!VDBnvNog0+k-K^nh z#@9~i$l+_OdC97FnOmY9&`OSc9e+?W+3+g=l!|5ATl^1(&HW(p$;}2?&O-t>yIhSP z=5;cd!+iK*)mk3`24`k2vk&Z-tDW)W2rK^|Q)d|!W!Sat8B!WaDM6Z{1*E%?W=LtJ zC8Rs0MY_9(?rso}2I+2)?ymRtd7t-N-&+3AKeCv)@9Wz8+{bxtV?IJX7R@ES%rC9) zI9pe38YX=l1QzI^0Q4Zo8(A_pn?A>Dmt6E3D4Tbk`gXl(Dc7Gs+j7=lzvdYgAIfbL zHtlj)Nmrgc91>!=x9Kb1;Yj>P-xm9Ct54yJs(hymMhJxc7h5{0Bn7ag^f>wPT zU-`Z?xs?_XG1?Pu4sQ$Hg6Q#3m$W?4YUOBt>Lz(neAQP!KvubFtHc^%v^wqoN%gl~ zLQsBTG^6jhLdaj(^U;ilmhOpSe{_eR{Yy)j^vx4`1(|h^mGq)r?XH@q*`i=09M%k8 zeCK}SPyGY@x&EWZ0h597co1Q=_WYnk+X-0 zt1zH#4|x4zp}0C{WZhi8S&eY-a9|!zVQ#OqI;iBz!Xic+XPnl}8-9|(zl?bb%huZc zW@2EbQ}$saN6p&W+CF27qI&TN9Edc3<3%e&bAv*ZXa5m%H<5->{-5mqt>ui-;him* zfh9gZeto22WlK-7+cX3?iAZ@IeKX2SOYvx4ih7Mh`If{>9pMZHhbbp30!>)=8(KMQ6SXn}%xge#{!Jvy3 zt0S`Cwv9}<T6&=PZj0S+ zu{%$pmi z#bwqFXLfe=Yz15D>%Tp}xNvirz}aPs27Z0FVm~b><>XcCQvR-Nv8%xEd+?n_!+)}j z?)M`NGVhp1u%8T5uJm3XWnPEv7X)?4P7G+f3|@Kg}q);mxwi% z=werzYetSF{Q+t9DGxde{Wf_h+Hx8?Tyq`BceaQx0og3v+WV?6Cm5e3_3QH&57s9%x7jsPuL8SO7jM z5K$Qe34Ty+=yal={2L2a!V4ZYR#uq0h}@50b6D_0Ob*SsWnJT(NA#?lwm~x-Z4F95 z?Bl3>eXXRr@`1xQr6W~PXNYPrXC|735MjM=BU#7uHP&f-rXV7SZJHAdVxq%DS!mF& zknV}Va6DFBbRxk}?wQ#7MJ<;&T0paQP#J`CSN?wx)`d&a^jyBi#g1^DRuBk8Fl1&# z&Y@x4qMU3ipIqs1b9`!_ggChwDXi$DC}ES8LX3Kz4(P6iL?l^#e`tmTI;!}v&UmEQ zTy+lLN=AEp52E^tVOhUaN1C>0r?B)HmYCTjn5TlVVM4k%|RhA*T=S(?}~rtHZW-saY{!6Us~YY|Ke6W?2>cZi{ zXJ{-RHxAuJ1sOgBES~+{X#s)8TAx-g?+a3B=gKd;h2{tyJ7{B30G-3acR$6xi;viQ z5TObT0sdDf4$?OuhNL+3*ihmxI!uJrU{w^6ZAJn~!@?xRVTs@~_|BhX{5)uKz16;W ziN=UU$;QqzzXYV{?T8hO=(pwBVRsukByp^zo@sr{Xl=G1sR2)QreJvoLV8Vl}zB`On@EBy2Xz!KYeq zVL-wEUO?cxLHnIQ7#Fnx-M`U~!;_D=xuAJ%X>BbDw1ObiEE@nMcG3Hjs5&BX>iWj* zz9(L5!tk&@G++5MqVq3O?AAz#i5A0lJ@_nmYdz#ghcV(npspEzM^!8f8{%&em(E!i zbVG(_^5RGvJK{eKIH<01xsgko>@}dkJ8_ry0QP^71Pwl0XcA(;4wVT0ImK*&#Z#Ci z*tds0)tB^Cn0vKl`?`{1U!4Cf97qc)B`+Q*DTG|z=KR&ij(`87W)`3qfET~R6@3NN z_5{ZDOb5N@QCo6jFf`|UNVD?j7A4Lgd8ERvvIylxUsbF}I=1M05X_fT#1bI7=mZcS z$&!r)*YZICAPEb7v(^WvdO;@sqa)Z?4Fo=o<54tY{Pqy;J9$T3Fjhz^jtLoLH21Y6 zBa+f|Ni+v>5%@ww^q=K~k6-FecQw3JD0H{s%dL8}xZk28nU{FtgK`^uq$YY%J~N^@ zZv;k~`ehjZ64nEGxR*n8qvW=jnfgtfkXi$`!6Nvt&>zeoaUa#6R>GmbI}pwbM>V75 z!p5gdzmFn1v_i5(jVKnMc*>zf8dBwf&c|~T zF^2~~^0;EbmS2IEU3N}*!qbf)il8G2gd0eBLEj2I;hz&bsniZ`HSq&?3B^}W(Bd4^hMUt*`4NVRun41ask0R}GF2M?9k#j{HB7g%)vXoV};)@G+DHlQjAc z6ysH4FP{EIfEed}*Bb~2EhyI1q!PBRzoppQm4t)lqu2V5A8o?v4u6wpT5K3M+!j-e z=xiTNNlB?R>OpeXL4s|BqZPc554ki|jr&K4qEfPhEP?(79SJ@iiwg=aat$0ti`IHa zB1XP&$o33k0C`CneyUfWh67z^@&>*CEY#lejpTXuQ-|Lb-_=cFaqQWzHvX&&$QryI z!$7#wbU53&1^@Nqy>O*iVQ(y!H_7Jg(XDX55+LyEeRlmiX$p&z^PKZ|{c;(+3UnZh zj11T|oWu3Jy1te*^H~OYH}Eid>1yS``*NU?0RCNwrp`qs@E2KiF-{IxBiMza0^ak7 zvWt(*yGeb;y9$qA%ngC zRdP0Pn08;{m~XlpQ)Tie2_p&C&l!nlB&8;Y+gL=bdRzi@n?$XCHiuxwb;b=rcM{D6e4BcM1TCt1Vpg-el6i8vS-7SrzE4@Qc z3DE+@!<8@kb$;!1fv7i$V!&4hD)I!7>WS(Y6M8)jVm4vbEQqtvh*prcLnxUFw>bwcw_#|j$uJ(1L&&@YHLc+<5l+@ITnHkzac9Xl0NJZKIaSFIj z@$rTlB%}2JJt&PSP$uI?;cQ}9w@v~r!x=~Z(2|pCVv-;e~dh&4kx3LOi7}nD7+|93O9<>0%>!}Gxx~k$ZOkef z5?oh1gl!44c#6F*doQ;n;IJWh5Bc^6zccc(xI9r!u$Gz+3>T# zjLACzxt`eZOlX8T?`Nq{33GyK-d;G^EJA=}%&-j2=}J@&)+am-#Q65?82DddDKiw9 zRFQ%n4yT9hX;}vn#4}2qoID}fU7{Usz$j)Hp%}ESy6pf9vM;2?DX2!CI`hVq%msjL z%87mTl06tLOH+Za<6H-}ERi`%C?y(QtMF?;g6hT9u$*+HXKVx8G@#8Gp_TT)$5?!# z#%b~Tg$^~)jQodi14aOlh^;LvCK=!N`ucia2lA8>R3tS*KAHG`6LF^hZ4)HHFcALW z3sBv?6Xq5+2Q#n(_9gKhafa7>2)Et0;7)T+N*bEL3}<;B9{xffH4j`;7Q*&Q<2rH) zuS36JwldIf0^l2c?(cXau^E|J?>k3j`lS0K(>c9AK^~+1e3S09qTz)rYjX1w5b6iY z`l!&8s`QBP$>*Mmp0+&O^odz!l#OzESE@P{;)>5Aa&&Scz4u3TB@R;zf4{|eS9=@c z%B3kVauvDWn<-6B0=*#*kaM-lr`mxv z;&kRWB~c&{>;JFdAP@(t`V4thNnMe!kDnU8N}lwtWPzO8@uT3nKhkv)_GQMzz_sb0 zAS;L7`fk@3>v$Gb6Ck_uttX}Ydgkc=Ype>2I#$n`D*N@I$R#9v3L(~j8m|^9qTi&6 z40##!bL+bj__$m!S9(Bi9hA8F6rYJuK}W(5+)FP89pbX;%%omsQOR2Yw2b7a)&ySz z+U(?c*6T4)?me175RUwSf9EjJ)RDDgod&E7ppYkMm#>8e_*|yGEOSNhq!YpQ&jpGM#&klccObcPdM!OW5uzcDd#N!(+Y3 z`npc&h>1d?$L)L=THpy)Cm5>8YP!n#KaU!hmVf;&6&u9B?c}A~@_`f&CU>_4-l(-* zoUxv(cOnrS8TR2LJQlxD@C+;@fXJx-Kh!%f3vgm!6~_WBt4Y2IJu9=c#?B$dGawc^ z=DWoXeE;*Ob4hMpP7X9}TC?6Ai001^Ti|2{G#|{Qe@{W~L`Ys9_2>~4g19U)HGoTV_4WpSY4t{tT5XJSLc7b|${Gj<}LBImc{$>DuA=)ktmq0*6uK(0q7 zEv~|@c$3!kON9KHmWwQ0uH>7Q0tTiNnV(#)Wc6nR;0LmC`B?=J8j+BQS*`#+09QS~ zW1<3DI$D(|O>8yal$bO)@gPxbk)y-I?>+1&W{U5;HAMquHPO}9LmTw=kU?pqm*kH7 zSK8xy)ocQuyob)=MOO#2lVrN4T_JYVT)sMLY61Bl6La$NzGo!DoYgfn{>;t+d3A;j zXf8Tv_)JXIMIP;udkXw(L&GHZ2LYL<7_EiP%;+6~jY_e7rKgPEw$b=#(3Eto>+c4u0>Q&xwKelqw;F@#g!ZYK9^m6-47!G7FfV!o` zSoO^BgH{+0shqgF9D3u@vhJ)vA)7CzBZsQ!>HT)MT*=UKDTw^#8ZpT-MY-du@6(+rAJYXLJI7+K> zNd6mkxF_suq19p*hk2uSw8t+jCcvk8@B4ldxdP|3G^^S1FzOLvfLQEVbDYHyrkJMU z80dtqw(}#Ea}q7q&ps*zgF{bda#JI{(h#TL8rNN?Z zI_CpZ_G*vvW)pJYRq3iSVB3jZt#Zu40U~le_fr+NV`l5akYJ#Er9JWgV*$41+J4#R zOHC3y1k2rmWsOsXXQ zz>eC8%FNjtkIaSBWTsp6)n#87^(rxilw<9 z`U|HQFo(1EhXAC2{R9K%w>pK?0`cuZr{BMSi&pco-T&NECTsKr&z56Mig0N($@D5y z&+5_p4&t@gfTC_6#>KD`8J)7zT>xi>RTrZM$m#Q>6jWV(eWN#=9Uca_1TRzn$mGu+ zr~vL9r~cx9Xr2ES@@5S1BZq&;cet%Pip4^wKKVHBI(+QKxE&Mjh^*Q5I9+(2wY%8Y zd2@(sejhBomXT2~>rsD&<=XF#!P@#lfcaL~-}v*}x3_nZY@9s42_28`S4gTpPxtXx zaaoXhZO*dCrGz@xp(f>|*=m+*KK?wY*ZwEzF7CXf&wc$cXMGL(*WJqf!v%Uolv)aO z8;#p=?7UwcIydQ#TRM$fKHa#?Bn7XkLvxK?v88r-Gz`ePo-)02y$12Ub$#)U)DnadNIzJnvVGPfo)7%BhS`ZBO^(0?-@Xnf7s=YFH)~UH`J^$DQSGuIbLG$(TcOGUeWV$8&r`NIwfHgy5G2FIcn>&zJ^y+wRtRo# zjH(qd;=ekU!H{M!9ZXKq*bY3VWsMmTqTch8`S1V=gtK~I^m1Z`X_DKWQNFGeysh4l0jI22YB% zC?%IeL1|4dp*1m&BULsAJYj*K6CNu78FHBgs7=rV{Or>q@z2Lz@sLnw7%}>tmTo0F z?|h(Li(aF>iAZfdIJE8f?Mr6l=ci_Eo>`!d*VK0lbn$9gR!ntCx_MVK&tzGysr^j( zf`uCB|E!Pe_M-G1C|j*W83{mj_9ird&mQniNt&9{Vv-8@{(le-wEq?NmkcFpa;w^G zis;s}ZPZPy8)hN5042Wk)yBOKo<;T;?>Q~Bto8jpW>$Z2FJNtE14nU8+K-mmC&cIG zGlEB_O=ceZa@-Ge_d-{>?N)ur}$M zn905&`}W|w^{0{w)$**#WZug8KD%`>vu?5bdmxMnLq=v|Q>xy%{-8_4?^DWQPUHN=a@Fz$q7 z_Ji(F@c0Aca#Va_Kf!gt?XTt-uK-k+~1UU(emTVg>{;v`E zApPM%Z2FwvzkK3T{kk`PwVPwtmu^XjQh-x*iKnIT;UP+AyVrpx@s!yG3`MWJKeJ$d zwv!t}fzA@}SJfxM6}NxQx(>(mOp{y2z0I<$RDL-!D99Qcv}Y7L!aOWY=l9T<>c|X1 zQHzIPK4sB=`+h33b4nuk{u2`c;8Q{{tw|0NKf^2m8l_&Zn`LBQI2d63CCSb0K6#lC zqYCa3C4tjrA#BUEyPr9>;5G|`6a{K?^diE~Z=jvH@Q~T@JgE&d>at82<^RW|7xpHG zgJ!4c^KmeWDjgjVlTZ^K6EoP7E*JkjkD7}!g>!3%;GJ;An^T%DqeNXxgdOkO z1r2?TpJast6P$rgmBHV?SMC6`-Dg~|ZVdl5btK{Rn|dit@Wqf$ z_6_1CjA`-^n{H9~Ve2a;qcc#{i zxSW9ys}sFLu(_3T4*3B{LJ9XG+HXhbjdzf_Qf2_fH4WKKJLA8t2J(f2 zrKRX*V;Q|b#QNm-x?p-}SD}m~s${Z)X)^^Lib_PSOq_idNpbS3Ds-6`*;z>7P*b~g z)0MdWUb!mksK!eu?!ognk~-9a62mSJJX)JPrqh`$H6rBL@}#_mv9#EZz}z zd48toASJ4QGT|Lu&+eVr(OvgZVEGtfGb`s-W|I;^(E3H-1tG0MmNJ)LWMMVT?FT2w zFz_j$PT2W(dsLKn`L<_Zfmq;03kart@e6%-wZI*_!YyN0x9?H66ZM4L@cWJQBEhx$ zqB8S&c+WT0N4qEYwDqweH#5~Mu}*El?>Z!IN_ zd>QNC+pDktz=s3DVSl(4*?71^6GdY$^9RuCy0s}_$Rp~6qjM3F12+|+KvI?GI&;Qh zX95CNHNPPv!Jj@OviU8Lh=ZY=Z1l*$z(7w=|0*SlJc}e2(dU?YQ5H-n+{>FHlzzL{m1&k7un)o)O0f-aOyw_`UcNWxv1c^plBx5?by!Snw{QUeq`%AzTKkh3q zf#nJpASD2gmJ$uehc<)a+2ahZ%s8QsGD$QyC4 zab}CzJu-vp>`KEKqp5EK)&(#HVip5g%()MXyW$aJ$TefZB%VS^>?GM0pfwe626bnu z1h0}Hq%*f*2jARFDqa*9yuOSZjKY8gEYpA|F(0Tb`GR40IYJe=@q;roYwBUA|SV;{s(B)h+&m>5A z{!+@E;dNZb?7UHKN%Gc;*pD^BJ|FY%^eIcB&M)Vp^CmS-mWB;hTVeSATb=}FqLAN$ zZ$sw-VZTtXkU=MZQj(g~nz|o8<7sVvz&t$)9TGG#&HLgDa90Y)k*ayZMM-%(GEl2#+6IFD6H#NYZT;v}a5fUdy zLv~yN&7+Vk6SuTP@@%(o6;M-Yh^$pWXRm0n{?uU9e@%8-4J1~s9~iv2LmzhSrR9ol zmp$;ba`>x0`hv7bY=%2YvSIwWF){HC$=Q9AEj^OR)&?JN!U`gv!<}f2D*X51lpUqO&2Fd-X+W?}PJgzVwgl_nk}v z%Xg{!C!T!`NC-R+t+P+ohQmhm!1b_UE?zK7-lU*cW*LzBe4u$!{@x; z#mypSk=VW;sl#;OQw@O>B=ys4P8l|xBaxbJiDA%qOkf`gO<(O&_9pyH&uUJkvpI(ATgW=)V}x39lZk07=s??P6siwmZ~;u*}D(B=UL)8^NiAc=of-3+=(v zKR0zomx`uK$|suC2HekLlCq!Aey7THKY+*IJsSs4*Voqmi?P_WFSS<1P{Gph%Lrj?%}l~*G_+(gGN}zSarLQugk|Tc(uig& zcOPX0iDmn%qNs=z&&@8^mo3`8B%T!RA~I6omp4KNIMkp6VG)h`c_Xv6r~vj~^wJY(%kO=5a5%wV!a z76acQFS70Je1NO`%ko>=#rth_MI@DnCuxK}tIpCCh~h08Xo@&9#uDhme6Y%kY{3$En|Sty2$n03BS58*{o3phG=96w1v!xZJ4Xd|Vq~Z1iTr zZ%Ul@wowyG_7wUH{+fKfhBolFROZZBGKFvfk3tU~9j0OAYWd+($BYLHJ_AZp9g@&VIy$}Bu#;6U@()n;o;~~Z{)&z;VQ+gp?lM^S zSjRQ9qrrZEL#7W>hu5Pl=hIr1?-O=o>C7%AZ%;_=6lWg0{c8nz52GW2@2MXd*|Nui zyZBMc#sXF|lAIXdd%HT;<3wHH%!E0~vufjGumEMlnmNBN*;7jco$!^_Uo)Rtub z4F}$6$?2G_+%B#9@D5j*(%S$fu%|%$cEb|M7n1f?*kM`$b!Jg_QLuaCE7Zcbn~V!Q z4tei==qTwRce>>;KP-`k6ND3IATnm=(^O`7e8tyutKjW|$-lM&%&<1y{<(7E9$5p3 zqPv>p5O_%UIm!}U2!utahxiGo=6Dtor3lO6M0SS(c z)PR8<*6-95ZuX$1fr*gw0*J8iJ3eI-Li<`Rrq|Luwe|IX?v(!J1^zRtpRnU5E5$Mj z7q6Zt6N7ZU8nhai<2JmG=RPyEdpj^K05P6`=9%;M^XuM?rF=_!%E3s!J^SwU%AWPS za`uBt#J;5;N!#CmrR)H`wSTY=25KpnqlG}A=yT^?<)tp-7c1+hF(qcp868!;yt%m` zsMtS9B`ZW>wxby`I2(;6Qv%%nGp(AffPCutv|f>0QGs=R5bYB6%e^uDN;$GVw?JXi zSoSQ&7fy9D1GvmHDp&hB*3Z>$yf8il!@rydzxb+T`pvwwkthh?(iSH&^|VDatW9_c zi`z(PfF!oz5`Ou~Nl@hLWQLR5F8JF%Jxh98EE7iUIBni!I{$lWqn|I{+`y_VH_2|1 zKSQ3UF?HQvXh;v9f8ZwUpNC}ut@ie>cO7@xpyG+ORfdM2I=o|_Do-GIB0x%{Az6XF zI%<>i97UZ%kwnd_yOP_>+s&GR-9UjK^YD!l8f|8DEp*mJMcJL3p}2InA0kSUc6sn5 zwgU>gIvFMghD~Y%!esVOd2q*&a z_*s^QDNAxBnG#0*O93+0d!&n->s6b#=OLq~XTr|40R0LsGL|TR9cW2{vX{v!S@?^s z3|r+2pCGp~3t?b?yw?TXxnBEu@Tj}aYD#c$y>ipofYA3>Mhh?@ZoTaO=)EX(HKhi~ z>rI!c6i$~5Y57@j)UtLMi%dfAl20G(uu6fXt$l25Zzx_@f zkfP>DxD%=`5_Xp*Z1)#L<}Jo&-C*5}A-xzW<@v*0d?yq~Pb92}M)G6jmjN8&te^uv znhpPZdb-^xDqQGi{fUVjmFSVvQPSXzpI&5s;N`rB(%|FqwqANvt*(uUJc)UX6xxP1fh4nLm7C~ z1Nc+Z6}R19L(uTjg-3>&FfMP-M=m&DG3ulrh%#5T4cM4GpGD_gC#wtrHo!_$$<6y! z91x#3jz65m7{v}Rp@14?p;}sjn@bdb)uYe?7H1PY2Pn*F?DjZiK$h=t+`Jrp*Q7J za-ucNNw_saBoc3bPY>R|zdG3Vge@;G%Ubuqgzc%GsWBXSSe&Z7(_M|@m;~bca4}d4 z7Y`rj1r4%VvqBn#AANmoPZzKWlv?j$-8ATDAt*wx4I> z@m$=QZl<@|mj`k$rZj!t)+vCSJbXBPQ{F0eUAj7qh1u4Zkt!tVrOoT(H8W!Ff%amz zi0M7y9h&j1_`F)yVBeFA_1i{`qWc>vr3B)eqoa^JZG1w!1Ju>v+saR9S;gxN)F&cI zR#7SD^c^_5EK`|v8uYpE(?u*S7+Rc<%ynr>b6hI0`1 zyx15d{5ge29zgA*XyFu%`m8NWG7XO=m(eQ>qQ~b}3^a$L>o`s=d(Amac1&sQC4%=G zaS=$)#E-8)!&=H}Xw7|aSvuJ2^NLF3)R-zJNkv*%vBvtOA&~ED45+TC>vlGjq9Mf@ zg@?1|AV8>4o40RL%gb@j`_~?xR-JM?$}VN^ZO5Dk zYT`66HUx)`7zAZ&*rjU6e5(C1lsO5N8h_swPu{6X_v>Ok^DqX%(TjHS3*Ij{Rq529 zv~?qazVWIE392|E=_O}GCf!lBA{-I*;4?NeY7U|aK`0{`oZ+Ba*XEiD`85%~earn&&+&B?+D;*Sd zLO5F1@1|&#YO>*h`2TaJIyQ*a&QqoD%{U>apO zJ*p1&_Mk@hE6eUh_G({fZH|OHO?t>kJ?dt4u?bXDlVd&A@DF#W&jNXkGL*BIk%EST zO^CP4k>Yp8z4hZ`TR~dYI+kJ%QX@nc_oONnzNKS-Zp|=R5lGy4bXk~k-$A7%2k*g_GiTY&t zMg-B0$KH;|bj|$5H}yCJ?e=NI?9h=9=%&I=5w!)wG#vM%=H<=&rzPw1zDNJ7HHYiD zmmOnCRpTL`tJC!!qo2gS>LnTzi;Jo6S)kjpS7@xQ6ojEE&AaSypPVfT!kT+MelD#^ zXbG!k!_@9d{tnR_4kx^8&K6UI&D3j@lir)i5r(lm>OH7PoS46*5=maTg=gk>xHP0&-CoQmR zaZngTImjy7GU|uzy#$Y@7AZZw!1N9BY>>G(_`jYY=C%0HrzDC}^LUFaxFJKDgf6+$ z{%1Y(1zHpyQ}2MQ&VKWsAE`cGPABcZ!C~QulVE3P+plN~>6EWx*qg_N@X=r&i>dEF zT)%yG=5v3RVIB#5*i4G*Vt*IlgDG>DtPq!40Is5lhsL31We*NbU{=w`D}(hENfi3Y z9xpaG9)KuAsOoEogCR{#bN3ulDezU2$Ka-Of6(Swul7-aRUS$O7_I&BGnVKI_5eh1` zhVu&f*^`G~&#L%!a;mAtHiL^fg+kg-P*G8T4-W(QxTt~?29Ocbtl;#;)KpbV`SCw%TIU_Uwy6tY5(r{Vyx z_A6UF_=|5!Dx*Hy%*@RBfRcAiU!N2ZU-)}uB;Kz?h1Ww(RJBT{$T#KvQ*RxTD&f2R zoN`7kB)G%TfsFy0{Gh8Q?<4p68Qb{6Pl^q8TXXWT_It&Z1uiRIhiiG@C41g!Yl=oA%*Lg30vb<1Y_+WMHC5xISz*zBJjjThDoZp|-KBpOmch zb3}|{(T~kLFyf=8UEUK;MaLPALAy1#QpZ`CK>5T9W-;+`XF>)MLHh~GMWxLoLG_Ru|8+WrP4 zI}WS8qhDOZ?^@UuFW(eT*qZRIHuh|7Nf^M(e6It%VYtAlA5)kc@fiq=1R`nttE#H* zNcEwzO_ioHvD7r?!mR@7_wf-FLP`A0GzB zAt-h{5DFf)E#e|6vA!MJYVoQ1e)FvKjz;hUQ3`Nf*kU4?*cEF4FIJy;k9=DanM;~* z%eM0_)t>OMz+|PDaYO24{$6oTa?eRFZI4OPA&bcSb(7Ap|_NG>QXREi%cg zj%3(v+^I!jsQEt@fX|>-cl`@nK&)8M&UxS;;H4rAm`8!1UbFNo*u?Zcy`Yp2piTM7 z|0S#Vd(l;D+XWJoS)`oY2-~;)T^{#;{QoC>9=gNtNK7gRB9Pv?dTX+TU)CQ&u!s()|U{n zfq!%fxVn(2zEqQ)U4(XjY=VJ?p6{+FD1ZJ?$@XEOczVKLs0-ma0v* z;+gy7;v?C-5m)0Phn^C-CdsMcTF8Eqc1pO6x!oi8oX9h#Pt`=9^Vp!~Peh4WepVKk z|45JriKN?8EJ%n0sW-n#wcQ(eP}9*FELJb+E{HgLy1}hy^yfCH)jj8F<>m$_F*S%-MBf92WEnXEEU1<>%c`w=Lb3n=t^3H78yoj^t(JH+YE;6OC3QVMm{|Xj`*Rz zmU|-P4P+jX8zo){)~LwEUPuLsvg85!4RqfYte7(~L?Y^bV$v1koQ0DEbi#MC&&MavKY{g3aFr+9 zUail42SNOd($dllEQ-TVqzdl7iy>yzhrB7CLYYRL3j4V^IsOw96WY@8U5^3!%ux`% z*pWI$byn(G#@xOSWJ%qYBb}C20~Ah!Csc3H+1#Cy43%3ocwC+XlAhvN8O%oZxj3h| z?Jnw5&mNw(c6R33% zmqH7Yj|+OTyUTscE&O=zV>Y`(a{F?<5I`Ir zZ*@9lw$b}E^eOlTmtJ?!%*yI+_K7t(f|Z$369|v@8G1YOwLNs8J$!3wDP(nW?8~Yo zaGji&MhOW5w-KT|TXJ;2??c*-hvHU^{g<7P&>iHKt#L0|sqIlgpJz{r-?Fh(YR`%v zTy=6!X_EEN7nskkh#|kstA=%c{C8;*exV{q;>#uz8A1}rx7Z!?}^ozfre|+}< zaD0hii+@{UT@Uybe;Vxf-QB7ec&zvq74tYK*sMumnA-ajFoi*)cz%i=;%o|JGUe${sU zsn<*t@<=UOagf(XC?0>&nA^>N9p}JfCj9FlDA{={RZB1awgM`zJr?T zB3tS}sf_kr03F;NDgOJvuS?neAR>t)Qg(Hn6F=p>PpKx-E#JR;*)% z_;tWO<9TFd5Np&Gt0XwEh`gGx_+}6D^3F4epD$;Zlz3Hy=mhs z9tyRDp1b6dX1d#3_Qk49zmI^JUnMIYuVq*_oGW$QIn8-G)jeo6Nf{w&$@K>|eW7V% zJ~^N1YUqAoF8lJ5>6yCta?Ed({ZQU~)Tl%nCtTux-;#W2Yu36cE;8)1KkO{EC7fOv zVmNq$;&S>1r6uCF^pdn6>jvxmcju1)_UIfn_nwRV;&Y1bp}Sl7(SZT8r+atMOohSE z$>e+w^qW;5;fmJtL4Ofw8Knvi8{+F6DMmcNm5<*>boY8_SkH_LO%fj;@7qEBC(vJV z(zVVOWONU5cl8dpwEGc#;`$%bcwx=1OtIXVOmX27d(qH0#l{2{a#Mp=O`X#Z32e)p z@OjgBN)7cN9D4Rl-P|DxUwqH0%y!%a2n$FXJjK;6VQ!)TSXg?pl^cho9)5oTH-J znSZG>pQ&L~#PBOeHIz?#`siA#eRzG15gj$LXQ5w5$(H|$$6sZEhyNo?0Ls_{^}S9_ zwXprV6Hf5@k07qSt5m?)zT3bt*42mc2^L~4_0bY;C1u-`wbv2;Pzr*4zJ-i|3Cy#b zUe6hcr=4&0e6*?s*zv+pU%3+Oc#YSP5d9EHG9`5IvGC~Vh*ZEe>iXK*Q%wlCt8WWT zJM&a_gJV>i*j~TkZ->4mq1Jbl(_3?4=})xm*OStD`*YY>o|a=0Os-je$-&15*%f65 z$`;_T1#NF{JG!_`E>AKGkM-VOFVzJLx*SCps?oey* zN^_<(#7%pwW~Pm=_$ewZ4E5_M&ill2qr5u|(s&XXrH_T3>*K>d#Fr7VD$S&9uP;Mc zkaAUphh2`BXr*Zte##4RP#z!j8AkPq_$tOS*i0}uRZ%f7dz`eLKkx#f1JIko2?&e6 zm}FqMdWr6Pkt^4}TVVgr+Y4jEY_U6<*&@DKhR#HRlYt7eO+IxiZOQmUF>9BGF)Ml> z%JNCAFpW2ZGV}X%Rntm?HdC%3e2I*|n$5~b9CykA7HhME;bEh0?xe+MO9k%t3V$Ms z_axLWYx*N+%^Elo#@QO$Qi@F7}{nB%IMV0Oq=4G$={m-cE@|4MbE@UP0d5iDB6an6L8L!b+3T)Q9(?XJZn{P{4PGKXw8Stz;|(SQaF{5 z;csK~B)8;=azXp+PNiYP;$2$aK+4%WrAALaK8Dk3$c{7wlKv}?%|jJlU4UC!UJc!i zjuRg9FHe;1ki@Ivc4&4U1fFm7^aBKc83>B1xi7GIR0A{}nwg$GI|8Z~blC zJj(QEB3`v`?2;Er!#AF4ADs->9JkHh<={n&CV5KL`{4N#Yt|7bXo1I#r<(V3)}wdq z`aVvQQiY28Z)1zvEw(aA|6V2 zA=+vUT{G~L@fKJA|oV3o|pNi z*`43e&MX>-TK!}&4HaQJqcGLUEaRK`jz*YBxUjK_V>RsqS$8}Nq8q!SMCS5Ro_$4b#;H!X2IUj*! z1hOPPUUtyypo{a(hI8-_#;Cowd3oxe^bb7)E~rrz6n4w=ncB$UGJzqSvb*R%P_8mis2ZI$B!RPzfe% z52wQx>%Pe~>2W2I-R_FdxXWh6Q&g>22|D?fTN{O>ls6iVH%p4zjZK{UmOSLa4uEgZ z58r+aLu!-9GL-)+vhmbpNF&fM1lChRZts@=82vUx5kFUCy6PohK?n?6%n`cgLW^&~ zCdsXbsk&milcU8I|GM7wtVjR^^M!Gw4dg}g?x~LX;QpZjQ;d*GSbG;Z%c@C`PZ`5 zy^fKp4J<%D_3r&@ii$8HZW5@dZ$A7~Hw=M>bf?a`^Gk^DCvt6024n9qn~KL!4|FvI0&-?$uh-{q;- zb)_r8IOXUBNHeg-KbDR^3s~tj#L#wR6^8Hq175MRRBgnmqE_qi!x#MftTw63N$u*3 z;>Ii1gi~0f3db&6opA=Jd7tD*7&9^+^)A)bX)}qz8@->x~9`7rC)a1k&9_* zw{o(cP=WH%yfX1$G~~of5_#0QBT2mua4i_eeMQ-2Rd>0bS8v<#XQM7KoZB7t_5u2ZR;R?t$qC5& z4$=`NpnbKz9Sr1;4?~nsaCg2Rt2+3;UXtJBoI|j|tz%{fDk&`v*wWMLyE#U7yIEiw zLd@SZU&Qk-YFZyf4=!2NP96~!nEr{xl_#X$*2$JSmGI$c3_JHk^{bK)EQ1`YzKU~6 z5Pd5|U{zZdTi@8^*%i}?d+JBSFD|0opvBL}qN+ay2(;sO)zc1(Ieh%Rrd|nVsbWma zZwu1#F?68=2k?{N%a_&Jo^YRg>Wiy_w6v!Ad7_D|Rcleg(g_&VHf@>n*?Wt3*$*8e zWY<~fc!mT4!9E_*guhy`I;?>+px95#MdpvGqD zsP&}9XVUqZe0uKs)%&TDoQq!_fGSJ*J2eJO0n^h{kbS&WM@cmFm)^4J}BR5mV z*Y2d#M%1{O?wyG<)VPjiFD3y2hu8+Dx(R+r;F`|2fl7X>O&pn|^E6ab*S$^6rt4rAQjMJ;l9PE~ix#MlG~MX_S25t~>5- zLCO)xSXm>gtH1Q<6f3t+btazSEP!4yvq*Rb8CD$(n&dsEF1fOF#!6aM%ZPA@uc$B8 zCXE_INfrF23PuSYplAR6z(8?jB8G-y$N67@2JkA7w@h_~|;ZRUCSuHw-&73+< zRtb1}Tf@Y`{KNUfxRi>lH!1Xkvxy5QzkEh6A-A45*E;0@AEkk(O0CtoSTl%c)fD+; zu&wy*T**{CQJTCE!nohyIeq%di&8J;pF#q>5M+~uo4^Souqcb3vU_7scxGJ!1+}}B zaX6|35`HB=g*I43gl$FP7#CSW{pg&Ec0iSgzjmIA-7+ZYF#;bj z)Wu&Jbj;=?T91$H3rTQUzJk7=b%+3WA_D6?!B9?f-O%tXh)HjSKP381@_L$W{DdQK z+zAOGnx$CsVpShuB2V2xBgH*ufl6WpM_CaD{KRD;)S*y%TzPC7kZdrvUq80MeqD5o zA85b+a7=t`?;t#MuQ)Z?lbH}X4IUE%S~Py@CQ1Cu#<19n9BC)icqfM1eiKI$^`a@R zBQ3;OAdZffiD_@wnsW=%L_<%LUzHtQ?_doelGrXuX`!K^cf?;@?tc&-65h=kt>sn; zKI!@p!GJ_}|CSXOOCF?Wgh~z-fx4!am$gsYA8kHD8Q;qSTj>&P1!-@2=%4uY{-G^Y z|In6iZnPaEth+4g3a}*%-|F}Ixqv@xdUa?f+I<2Bks+3-#+%hEo{amP%J5$9(#dMc zm1)<7O$@%V(NgQF9!se@VDlizDkuAJ>uZ zJwxzfHqMv7@VC|L&Z+&iKwulcC~68I0UG$PTUw_f>8Q^-+Gq07>UAVtF$0TFa9Ubx z1;;%uchiSjy6&e=Pnq7pn2}6yFc5pvxz+H;dD9CbO(!)z)~Bf!Xlo@JRG8OBoNv6N z+-iX{_6u4puS%ic5YyLQ8@W|aY3N5mDQW!<0TV=rC7eK2AbP4S@DJvn1G2pK(0J~n zsM!Ur&6@;$I-FHa7`QU-m)-V=pC0BaH!cr&up*1h`f{O9BA#A%avb-|SZ81m_Dqse zXIM4k{ich)nJ-p(yfBCy) z?0FWef|Dt|?&!t*d(=Vk14y$3RnpjJ+vxIS3*uMe%0dn|ZC;WMM#)FA`lOv94=+Sf zv|rW*jU_ug(8G{b_2rLyBfI;DUgb_iOH8qh6sc5}JOm1&rz~Ewh!C3*ue!%1BJt0W zAZv&^$dy0Gf-Ccr#Qa2QpGFcFs?fy z9kNcI_S+_fOCVgfTgZYwr z5lX_9kMa&_tifSYz4iJMnv9??#omhNNlMbe$%#po952#lhRQ>s=Ut(vM!8xU9^HZY z!7mh1aIOU}#v z)*ViS!ixIKJo2`BOnYM)GAQX5gTJ>fCs@^C*~^ceQpPxhfGBHSCaX20@@fC|&oEnyC5K&W(GLNy z2jr`FR}My_+~~FG>o{~!shS1Xt!evA*E7PW1B|R~y_=2^pQl~45h|RIV?_KOTh6-X z&oD5hVy*Ad7ysselTEfVryq6xwU9E3YN~}I8+l$*mv(pkvD&|UZAwA>05V48lT@E) zy9Hg67n&h>!Z8BCq@Q*fAe}06%_f842>+E!CyH!qsgI8w;h5RG5T*qG&KsFry4E~s z7{0EnkWGu_9OJzgF~4UrKrm`XDMXzB3p}gVf)W!^U3s_OTvuDnysgka*qX1tHRa3H zI0Hj6rInlI6@WPp;F+1|GFm_BU1i!lpy7D+r<1KTALHF$`?+9Httha~9rPKccvg)M zrYYcwI{|kOEOiwfW^|W1v{S`5YX!n%3RU|(^>6+vT|4eQU-2$XV?hzOpM>JFjeb=q zI{qYxHcuXn=U$IZ2=S+q{Hb9R`O6#5D`n)ZAQY+4U}4z36>V00 z?ON?2y&v9jk`V3$zfr#Ak=ZYa`1vd@zYYUOq_1U-o9uW!*zE27Q zFLztKz`KTIsjd)Uy1CMMXO?5cW!``t92{Wr-W4~moWw7lhGRM@(Ut=OpT8~)IZG9% z!YrAyl{(|I59Jq*!v}bgL}|3UaaO;d{^N?BsjeUu;hzC{h)#fb0S+_Vkk|dqO0Die z4qxHaSpT-;#q4b?`_9<{eWeY>IPrfcX0m-Ec9l*t|r|*;_K;8^T?OBWW3&O3GDT!I;9`kvu32o z3n`Iza0#e<-J3ik^B)yYb#!&mJotvC(aQebXFI@OIMignOUD$s?U_)2 zr zB@2#;WqwC+XK-u@q7@55*DB0t_>KZ|su#_;B$fP>3Vwi5^)1>y@)=PO<$~sD8)Ox2 zGJYP4&S+6%g@E`_S>-5vH$8=?EmVkqbng^1PK)MWXF5p%@wf2P5xZ}s<)&Kk-U(C$ z(>;DD`Ae}9CnmmM{Yl!jW8z-1Zg&*%v)p%LcEyD5X9J{SoAL|DcWs0cxq)tjL(iax zZ_SHUZLgmMlj-W1@_Y%UA$O-3uQ{IQUhAE(Vovi)hJRdNg)est^q=&Ry^j7g`|xD1LP zQzw}xAtC)>zikWOW`{lbOpg;Tk$%T=5bjEhL&@0KSUe0=>#+@>%c2HYZIwc+{vGVy ziy3i!rN({dgoohP-mSr)k-hJGfbLP$r6F16PjU3U=;Rww6(~@r*h4c6-$Gr6BpM_f zxf?Iu(u|Gm^sH7?SyXVUm#yznufcZ)gnIDXQ#|tX_NV5uq{=t^@!TMCIc@ymBm=rz zhfqJmKmY5FPCM@4_&c%^jAb-+e+4{Kr@3CSc8tHiKFG)-!(Djwofmaa@Z!L-f~}B=!yEQLoq-J+TRT^!PrXk(e+%8Ns4kj$Aw{Z*vYGvrh2+3fV?81f?NVVZowk(-+~&9w0U$X8F{ zwJ#=caEU4D#jt7JfvHF@Y=%7I*WJo6H9_HQSBgP%!F;8AlqjZo!ecZ*Hz|g!=R!u& z+LrmHWC`bmo51XwWQcp7G3P0wo|IkrJj3YDHRVa z*xwky=F&a71TP1?$x2S0PESA8x=56dPex=}6v9X={_JqY(toay6>x>fue7TMJ2Iq` zx#v#6?6S`f{g9WtdiRA-FMn&sA&2p<=qeUyzrN@^MM^WP{$`3Z08!yI-OR7St;H*} zb7lUA!A78*cHrq3Ojlw_*I_yp{8J@tJfjDTcuN8iHN>kJqC_s(Uv+BS(E!Z;-`SgH z+cvmRUxT#{wzLv25|`XY>Zwr>7&g7}M#8+z;=fz}LB#E7HoMhG^0|qE4g}gZ+H-d* z0O6t)OS3?eHQ7q0Ks0$FdzKwcfViL_od6z|WXSmpqU2}b1%-vG!Ipd%*+mV1`>~B% zT3tOUhy1c8L8+4^0S1aabR8LawnOMr^=idx5*Ny3-4^JwBp_T>RQ;JJDb!q`Cy!#f zCDFclZd7&cbHy^;Y(mrB!Gs8S4|j@(TNqHCmC;w~yXlg5*zos%LtfjA(diiN`0K;< zF88JI`g2y>f!fP41C}q}ug8Xi4fq7*B4elCx-OaS1)&rD%&dtl>mCL7n{uUvBq#@P^Y>>(vhn(`?=jx4GY) z8Mw7D&Ph*BQ3wgLHLdK?(!Zbb{_JklBk2kqbAmelB#3DMuk0-aW2|SK^;-#in=5G+ z1VaH4uD?hc;oWa86(V~}OI8=QwxWeqHG$Bk<#ETj_AS|=aDrMoeG8ga0l><75Vgav z+APD~eTqmv~N*Gt3*p%>*&%4mmtuoSIIZk1!{5>z#mQ)Cu(}8TLwBd{AYnp}@RJ*sv-oA_A{oshglv zblzE#_|tLZu&L{h;#%jH&+}KbYqU;T*pk4C`OL6MkasQS$?w2u>|!-FH3+abbv&HM zDQ5~q|F0_JfvRjbsyowg(|qdZt}}W>zdxY}fl<{2LK)pCk`kGW_4R#S);u^1gm+aa zN$Ez=;xA?0?RRj`njXZR%d`{*&M-$sHaXfS&!i&jeR_B3;E4{tj+34?rYTft_e2a^ z+||5#1{oE}L*{1F>=P4N46uI>|IVjh>2mR*QFER1FZQD7slC)RqCW>^pn~NmbUKFX$Fec{AgirZm6Ff3@i%+=sCyW3qn|h^3x8-KYr(|B&jb=O&AEd*1bND9Fxc+94nu}!(?x4}`RKA;GuI(^7l|c6E?`13 z7gd?rx5YCeXrKY+Ls)-;8K zsKYNX`j)%Y!5h!+J7?V0k5hw$v|Src%DfsdLj|PIcI0hXh(xXn~P#=%Ok2kAr_`Y!rMR$3pK3T*5jS*Ni5i)q^ zJRdO%4d|mkIt%x z;<7DFm&)VBXmBW8pvr7)Vxn6q#I9G9gsuN+^lBy}%7;%m@QJ5kM9@X?;!|@iH zU04|O@jf1J+!J_#zYVqX-GMHlV}8-oN>tGbee4wiuJ`TbrpO_*pDvy>4O5FIY*I}Q zrlkuc16-P15J{2{PCjR=HQ3G@c;v>N^^q6XWs@!Yv@iFu31P^JIu*E$+H_9WGn13O z`^CwS&6mg1y@R5x$QF71d#a~~H3>U6o%tsKBm@*EkUAsGjROE2yfO(0_WA}adO$D# z`HvyP^L^=pMQ`;Wvw3vYQm;vLVn2fU!Y63CbWpW(oi^YGKpKaf63r_Abd96bs7;Ra zze2KQFz4}56v?$cis<(&EZtl**-0Kp`Zj~;ynxO&ubGQm6!EurVQ?t*g=3QvB93du z`Y2Y`fJ0{*DvsOw=#O(N%=}F`>^_!ojFL|+Y!R8}*DR*k70+7p%2;_ivM$RbOMW9p153Uo`B<#~vDN_8T6 z#GN1&Vz}Q;ih0)sGnMYTtfrBmf>B5~;i3 z5NK{ni6Ss<=N#f^Y1{OX*lolK=ER4^%7iY7dz=m(tahV6gmLFp6xGSsx(y0Xi+Ud; ztXt-IJvklOZ41Xa2Mf3=(~sTvs))U@Vo<(LI|4qm;NmsJs%W7J9D}D zntWrwH;KqpJ-ZpH?`@+w9!*}BN}ogwUOlSw`Gfy(ld=t&kqs7Kx-g$;%f`kS{jl^| z>ytSy1n15P|9dvT;RCKqO&mc%-BAnRRTpN~_CA0nRc}2CiHZaE^O##%#j6O87=uuZ zSKcKrJ-6?RW(3M2NY)@$f9tYA41Yt9=O?Hr7$RBJLBsdpxgTlYv^GuwznP^FM{(iL zof#G$wovVbj2^s?!Upw?*8*aewzs$KPVyYi2?wIFA{C+rjLf+G7FLNleq|@b01;S> z_07faOBZA>7p92#y&cuIl=cJwIl&$hQO>jJBc?#yAUL*+ z;@JGN7u9d|HC8JoELcp!f14vGo6a~IKkyvxuLAS@`YKj62g!W1I zF?bf96I_12_<0kw=F$~>q0xnq{`%mub-3zriq_I}@juBG!K}CfKN#Qv_r@E3!_-v( zCuH?aO^m_g>{Rep`&_R7r$kjS?4J`G&d>1zsWt40M^{B_j9WjF(y=P0EGO)t)2c;r zyJ&Tuiq*nM#bYH>P(G2bMN}!$3Z_!&Etg#+bRRL$jv#rdm?97G^@=DR#Bc}X_!hq- z2!8G&MeLHzXqiM#s#Pvc7YF~+>)tD`54Ry@pax+kwx}M9qNOQ(^+_$qQEkh_`<(V^ zx$EP`BG`-(l0!vNeoIaan*8Ncb$f>9<0k9{qg}FZ)c8xmITz0{u?hrs1f^l8XJRL6 zR}`96#cC_OX(Hz=8O^S--%5~+M_IL;1 z^}8LJ-tpVI2E9GIsg|D+QD4~E1I-;JBLgrYCX*>RWln<6yv4_%J;$av?9+2HY+6)lb{c7M$(g?fWrKn2*bguF=Dvs z=|F>kuFsvFtP#)XlsfvWRMwvYn_dbbUpiVgRtd;{?O$4u5~rayR99D5_WBSb5Azc- zQM_yC-WTEy3yqf-bVFV|%F2C&a9ZQ@=k5(JygUKR=EvnjmqEJ@6 zdzOO1<)r2~LnCx(W*huY*~=&fA0l5A7uId{O9u4aHMQZ~83rzHOZGn<80S9?CT-u`ZwgGDTw`hz6KNI(y_$;3url&gQxW?}LO%Oywr1uwg6)5!A zqXHoGZDJXB*6qc^aR(0kvvKcnip86Fr3x`;M11ZrqkQ&SF0L>#UrbZwN#Mx@^p|SEI-Jq2H!<#^jgC5k$rfyj9!#-u=573&9}_1N#E#!L_ES3IY@d_Fc%YnT`vA})Tr4|` zk2;5tev|5p`s|8M3aF+gKJUmM@9&dwa;gWF02@Do;8e?N-#Wln;geg$Vk5w|P=@rq z!$W1g??FI8AjdSB(Exvn)i#!ne)!#q38US z0m*~R5ZF@)68jg$KX@!#H=GY^SC>2Hi9xEVx1<3}7w=go{DlV~UFUs$x>QoIGYY(r zfl)07;zq>Y_h`|$g3NVBx$o~H5?a8OpYbhJRe3ya+ds@WJ=8>BUbzF|WRyDss(8`R z4}>|3IQRFm1w|@<@OgH`={ccz;pz2(%f)ZiEjrP=*v^*N)k2UJ>k>;<;6A^VMT6v~ zqPQeTGbL$I@4xvD7=BC$pw8MXn5svbO}x5|9<}@l$|BQd%*Xv7niThBss*!1qYYX4 zjqx(Nutg&pDr&V?#D{`Ge$zj@94C>dK9(}Kug80Ywxi^I7rr({mBcw#Km(_t8&}s2 z5#kgc+86O(1!J6_!DGPMy-Xr{KZWBr{_!R+lT%Z}V}@52A}owdwq}u4-IHOcL$Xgs ze1O9fr%(Br%qofhlux%ErB0>n z2yJamPit5iIXs+krEX3C>LiTMJ428)eQISaioPt-abBDrw*Dtagcq3V9SEGC?I-s4 z_gkAODiPgyGnrig(FKJ*y{uEqii57B1y(K@55~aQtOFoS1B<$t0Mt z++^VkrDrTO<+Ye+2+WWe_JI}v&Y;va0ZDoDg2I~jWDImkW!)@Io$o{JW>gz=oQo~I z)IJsre>C@o|K{BOS305)D8;mzfZZ(#Wze;VSkuipKAm2|)i>s}GjBi;2q67*3Z(p= zU*VjC8uYN(6}C?vxXB`g)yP^-$ZIfm#h5jQd|%eHwD{2J!J3a6)4#pc|o5z;#I(4dPOUH)ke( zdxQ@rW1-zME8D4_4WBdh$HWbxd5`!>w2h!PP-wd985c1(Rd(a~Gn~@QasFIQV6hgI zW9G|eZ4*0mo#Gl;KUfpxdEqC;7g09w!hl4?=(bB@^ub{FZe6U4+Ecq6-os|3T#3eU z?M03*hP&SH_2+_vr_&#SD7bJY4Jj9`XMmDZu-PoII36*7Os}~UXZ(q^hXSfyMh>i! z1u`Yy?*Aw`#C)Z%!Nl7XFt4Am#C`qp^X;j^4zndiMmT@gxZPaQ#N(LcA41zTF*@!U zfj{GoF1x$3_puP0C40gJ%>_@pO?bw7z221_`49ijtw`Mxy*6k`#fFdPt&gGxnfL2I zUl(9T*{j9;GoW<26WKb;M#_x)X$sW1a-!+8hleUNDy%lecEAA}C-rU*9}s)@zDM}d zK0i31I^?ec^9lxcVuYCz@dHJqCExJd=chQHl=2#Tv*oQ$>r-hG&LK4}ah79&&Y=XH6-wyw5xFVQz-`!b+38#{B;@HEI>w zQu1RXrpDt8CKjTeOvf$5=V^*dgwiELik?>`r z?w_8z?!zx?Gjml2KYK^1frpOyqn5mcj3QDziwAhS%TUErTE+}LUd8UaSvC9UU<%YH z-iql|isj}W00{ZckhIn?og+M0YJo&y1WtvD?3sLGga2OCTf2B`7zH;uHcWPhmSln1 znA)AZ$ZY&POvW5HWKv6gg=+CaV@U;27E8g>iBvY^>*aWG!@DqxXczkCDwCJ!18En_ zgKRbJU^9@~In6c8^@Z8-%7tTmft=?oRYe8j9c1{oga zWwSKmZMU90f$#iA5YujjeF^NJUZzD@0F#~ zHK}Ly^#HK+FFVB6LrD>QVAbFpOK0#ldmg|kL&m3AonkU zQ-H?Z@z#-$pQCL{M%2AuT}7uSZ_O2)sS8A53#5*3O3bBxjt1f8vJ9aeLz?F6ti`k_Kk!>fi?2jjxi@BV@|(40lky3Sb_5B zxjC4Bc55JNT!w#k0S>%Vony*-2 zf^x11s-@y~6h-}<+?j{GJx9CNA7|)~J&9f^@>UQ4UQKlkSjj{fsK-f>TeX#4VEwgyPgrrK#DevDE3Tt2ZQc0Z_n`3I zudD-u&Cq$oQNaKb2s${BP&Jj)ngULAY>@#Z1rH(E<&F5Yq9H$B>Ms{m8rw}&TzKYI z{1Ar!tJ1V-LLNLA$c^8m7|~juGZOsPP8w^day2va*rM*^B+9AYgAk<%uGhPGz|y}P zR5u5&2pg2)g(X&S1vl-=@-Q2N_521G?vzPxZ?7o*X?Q(>qRP0eKLS}P{{S+OjY%0V4h3;oOA5vaSNc%+IV4F zWl~^*o4$`zbL~(%`E9AAyb6{Q$IS^#RD+Fmfdi0f&EMZy$o0_!Pt#CP@ZkK#U=dZSdv;*`VPEdv~R_Ekz zW-AIv^S&P>6lQue*ATFxM!*!;d{p>!uRwWVzt<0!f-P8Xk86~9^;>ZI^uY8`+Qn>9 z)O`>_^~e}h&a>bW15^;iwd3OJO@tepL-}FM1SecPBLw(FZFg>=0JCjvTwujRy?SQ$ z4$1r-!aiF{cbGgSsvN;I~ zD1yRFll;Cw#_`KUa!(V zMRM@$lT=qbrKmfs?d)(k?3JIwRzWoJ@fURn%0C%5EK!8XOR+?t5578S^%YIuE5mZB zgFfT0W@RQa!mA|{YM6u1NihdZ!I|LXG~Nn3Yk%Fe(f%=o5uU2TZN)xO7R~t`vV$@j(+QSF0YWZY{M_Si~6>g zXYHH}8WX9I=Ubp;w-Dm5=Du+eyGeOr$>0kTYTC@*WOn&QP(jU|`TZh`0I@}Vt(8zc zlCtbWyq3_~R}>-H+1d~e;LN#M#^&`#wWeOh_(mo4-(APyoqF~6?gUI>gV6a-TWt@T zkd$TfX4tf>z-+BF=daa`HD1q-CF89!EsB8{!1n{vh;JbCqutV0G!1xNXngXBTIO7~`r6K6w_qYZskrKVSorJJ~F2 zayzxb4kME*rT<=y(vS&1@^LpQA@ z2_r5=qYmjQaC_l5_8D^M`?r;KR*X8u)$ueR;=`o9x*&lnT|b%eEq+x@xyEXjU`sOm zr8nT65*bK!_{qb2XC3z)nqH!{goAmR^I+W%12tPpkxOezR3yh-#?1HV?Z+bjQOVHZ zFLk~X-Tg@EayVqHQ&xN!>j%|MhN?PB$F6#oSg0R{aQ&DRw1U}5yBOTF1B5;r3~EhP zJK9ak5i~D(U>~0j15DhX<6EhRh%M7@+6C!F0CD!$!<@9k^&DSTUY-g-G;oRA4v8B7 z*|F+Zz8Za+Z*tf(ge^gw^n5SSJj;&HJX8GKj-s?DNF@W~p%#5*Ri)7vyZ~&~6YMOi zwWSArOz=5zNT06>25JQ&A^w~A<3?oWu&;)hNxSfFX=&-f;YnBu*t25l&1a}3JE^6; z(3jchVHv<0*Vq2p7euS3^r@~kJAK&6kyud8)dE{l!Z6cggZkGu`6!A;Co~0%){-N+!>bhA@auVzz#g}{EA0i1}@6>K$ z4hBC>#fcf1zA0TR>9f6@sNN-d&H)@=%szF^iRq|3B+4@}+;dBqAcPmAK9F`{fgrNJ zFkM0&V1CU8b%A|1V&-2FCc@+gy{J)CsO2~!llxvj=Y`1&Sp*ilI6D*I-IPz)k>qBE z0J#gajEsfQP~fp8ZUzW2s4VkTe5C!?Qs)s3lv=7?j!JY$$<-x0+yN6B zux-Ys+86xxx1`JVHMGgU1hah&AYad1d7HgYfm{Tl--%egnQ!n~P!vWJqgg+rbeUuN zhuchlFOcnjf&kKM1_pzTXZa$Pv54fdctyrU4(sJ!z&@DEn04d`7dj+~pM!O;(O|WZ zi^@oc3Tp;CotTK{$xnJTS78b`uu|-)P!wkr8B?B$#Jf+}BU*aGMEc-Lfb%DENb6&x z@V0$fK>q*Cem{TrKu2akJ4P9$(->L?PwxCRqV4Jczdzs56q%Yi{5~?G+TJz!8#)QX zdi9*1!dz^6z!s$G*iL5XXG2bx%KzGPesJ+>{7VVVbqV?pBL<3TpU;U>(&0B7NA8bFdAou ziod)2!FpYNPfTvsi@@5g_4;Q(F=o4*ejR!Uw5g)slVP7L2~%|_6slV<9gOP4e`ziL zt#IT3iaS&}qwuK&u6CC;t8L7Fxz5m?uz(I%ze;(;X;FPT6z02_U&$mylVBA&50XEY zgiXApcB$5G`b@eEL_s2CZuIIiR61uCR4`v~9@aJ3eiuvlfL0h#f|m7lbjaA|!a-uI zS;eSH+3)PNkL`=2Pp_3x?{}l_@901*7)7FN{|_pif1py_D^9`L%Ry(YXFI1l`JwV! z=X$}(0R2G)QPT^u!`pCWH7 zJ}vxh33@=v^m@<)%%W+SQ35YtG5GJY$+y16e}S~D{7Td0cE-~wiD4lqgbG1_bvm{F z@3b=UfbpP89@z{<2+3g*#)RX?5!MGl0T3{2!(;H0y;cE-KqjC@4LN&>P!C#gctT*_ z5|t5^roop1Q2xfm=3Kl4X+WTuy>|Xl#(e|AO9|HnY{;Oj0tW|D!ztGF$H~5^zr4+zd z_e@ke0j%dAC6zcZEbX9i>h7h|pSgk9G5NO-4>bEnd56nfiH^?wh{f4!5f<2FW*M}f zalv?rZ<~|?HOQa$wG-b3MAY*W3_HrEDFz(Tky)e(@EG!cMpkn0W1HzAaW5`9_PrWT zqZggwmTB$!#bX|lN^>>^&z@&afR$?zctQOOt<5^uT#=%+qqrvEeA&J~V~a&L(9ZNw zqcC`5`9p^>fuL$sMS`L?FkVMl3mBFhn6Kkya?zb}lJbrZc4;#U=_uXV&ICH+EATpC z!0a(KX(-K5>b-97Mf?JKsjNjTfoTD?30jmUW#ryV`oRQla~6s1e^`{J0S2?-*q(mG;v-e4uAFScusmSPskTAG?t0A8WY%)W5utzu$g z0(~;oK=x1NYqyuuLwG0e?(Jo=4-(AZC2i_G@##EK zGL37f1&myX#b?0`hAQx?QcA>bjc zbO+M39Y-m#6U0mnRR$b4-U@oXydE}R;NgFy&%aKEI00&H;C75r(ULkU73fuMARY%+ zbyj&5eCGT+E$P!+j~z36D@})gcq!n;Zz3?bjPiSMDCRO9w(Ne;2Qq%ZdT~Wwlae8& zON5YU+wJq{g^(2d+V44W$*Ag$6=bv8ngWcXQ)!vw|IwKv+bZlX8GSb|;gIA_PXPDS znw=@jgF-WomoSu7XGkV?fn14I&tK6p1D{}<|1Wci@>DtQt(*CJo%LkK7~HmgSW>+H z7fQfCl4XC%Q$)33SD+A-wLoDgR8HS#>qo+zTKvy5$jdeYxSo5h_J(09aj4RnGm%$$ zlYgVNId_7&H`f1@xh5O7MmCJVVfnJHKDaMIi$vb0W(#5(Kw&&NZsA~7{N6Pe_MJ9z zM*F#N|9~-U;U)W^r5>Fr_lX%T*`yF&nWvAUbHsC}CVHC%CAh5X&!y}Bf-$t`tv06o zx-rt2Jk9Jm_M45`PHX0V7NK*+hKa4Jgw;F*AjlhSn{c+_p{>uN$g1N(kpZ}%6N(hp zmPb+)zko1rr3M8NDSsqf;W`I!DdoYLseJ#@c+{)(3IDsp%*|0^<%QGHobQk1`7ZUf zdk{6Uf_QC)$QwO!rxjXe`;Yl-|LHe3IH zUbB{kn*;R9IS~8MDs)8jXX||3xy96Lm0Iew>A|y6vF`h{Q^aSAu@uUZ@r=BZ>}=oE zLxQ)cZ@HdU4T6GdqXJzYHIAOxXPts49vNed*8e{}D=?;7N?6>$hT?WTH|EWm&8sj>+33Hm|P*m%v zW)iO8Jn=U2q48|v3)idpyarQvr(<9JiuTthI+&)6$KI~0`k`?U-be&>InIu#f?(GN z-@_AUhr6~O7~W-p-xTny)PJIutaxpvZkLGAGHq__?ZaJmZ?l0d0puO=rj_$5aGBDJ zUPV8GU+e(4A_wvKb|7{52kW71MI$~+UPM-uO?X2zswwuFBgZJ|F%u{DgIFgEuW!5$mtKD>x-rUVLGg>}Igb&Pe(4 z-(hi5a@I6EMG4lW#J*RQ5MfeA#Z((cg$l`k(T8H??oMtza=}2lcm>eNs1X!sFW|Gu z_F}h>Sg<7hc#_`{2xi%mw4nQyeE-&k3FNDe9|RR|n`RuO?dQwq{;R}8XeD99dwxvDR$W}>3&%S}*mb49mTu^eTGHR=3=BYfp#jnHs9^KZFNVtS z%CJt%*A|^2-^W8X#q0&25uMs{3YU4^3SmGKvfYC0u}d9JmUGo(Q>gd}d%6~5JsdN( zn_|j?s+}c>Z59Q)bvSU-qVOdPwB7=fkuCs&=k-*$=mhWS~eLX?bPOD(DvS=X{&L&W&c_|IhYTekdb zKkFkoCXPiPT__QXspT^|OIQu4+Gnz`fdFhqIu5YW&l53qlf^CEV^g@8+-|s3J>u<9~j}vz7H(s$G8`U6Jth zE5bnI3mCW{?eU_$-B2*{=@y*q{OO$u)5%27WY}_W@~2H=g6)p5~oziZ36ywVm_AN~hZsoN4o z3yAh$tE!w^$K26O+d=$_P4L_iE+6v3>tFBXx?@HdS@@Du@7tC)zT7gDGmg;GQkjO1 zjHY~mv?Aj7`~Yk&P}(biMyN^(PM2Vh0@Xqlk?l$K$FGWk!tBi_GgN=+T)`hma#PHc zq3PfX0Bq6CWIa{yc)$h7k|K*0`8+J9l#g~o>nI0*7!XP(Od=s^(xWB=d*IWk*@_co z7*&*=Ms?pef~qY7!Zi5SFD1HF-wrjDbU9;LE@3{1vMLUK2 z_Yd$iSC7?xxo1({0_cPh`)ol1Q3dPfB|az^k*)Z!3Q^mP0|##5Rb))a)<$u5$TZ1O zZISsdnHh;AQ@<`C^OKXzEF-PKmTE2MMFRD?Rh{D|({&9=o1w2QC{cV?5(9+Ja%b=L zwTsn>-i0I|X%>^(6Ez4vHQK;O&{pyBlP&2F!T7QS)+jD$gX!YJ31s1DO0>Zz)?9)h z$8>2c>bU{INkR#~SgGB;e*0{QKWq`DE>h|)l87Mgh^%{54JeY?|q}^ z!H4saAJoxsq{czi$^Ky0j%j?DNx3*lPPtD5yph7gC@ivZk{oviobG~zFc{Vo#JT=8 z?^te=QcpTRtb|)Cal|Y8J5U8U=%|PY9O!3*zR=-xf}AvCp0Xq}E$d=n!P1!Q1il0j zzd4YkD>k2yc2AQ!!4mtN`1yxaV{2U$)=}#p_gEX5cKH7fRbLquW!QB+L#LEMBQ4!9LxU(KB_V?}NOzaCG`zRZ^S$d`-;Y^~AH-T**LBW5 zd+&1&?|=#V!Am>SkBeGuV_#m%nwA!ZjMHI`rMWMLZ^E-qNEiNi9D|UVFNj~S?7zVA z(%+00X7Q94C)5$Br?x)fd+s}p#6qPAY$?CAr+#1c%3>}3!bA(X{g4!`My%&Un&vlP zCtnruS;y@}TTPp`9b#bL6=;HA_(Exwy?K6cP!HI{vWkTP zo`k(Nv)YVw$Y3_D8hs?7SHAsF=p0a0IMA0R#`2D&x^&%BSn8k~kPO1Nljxb?vNokr zX>(JP%i7ORrE=_H>$jl9I~axVCnKZFwJzfVxv;y+%Jg8?$hn&%}BsO32D_=eqm z!kbS<=;5E#Imd#cOM@@Og$=!9yC*BF#c_I!Jjmm_zJnX~{5Ngma$#2ygg`4xny=rY z6|Py(-DWj|zv))l212bMz2T@AC%ToNF3v zV4bIY~%72gF&qMxsmWfJz~z0JhL&jyh-m9y zSJ>t7q^_RWC_;Tc2k+Esm*gule$<5Lr-p>7R89V=6cBvy>u;=A;f&SWXjq|#Sz&!g zMfMRMVB7oYyI+7*`Ics@YMO|~ zk3M?)yee9=A`z1tfzHzH#(;Ozsn`$5QU1~79VKYSpIa04g$;Cm^1g46B?~REf>c&+ zzRHbcwPgO%fJU+XVR=1iaMuXm^^(-^=|z6+cxGn z=f<4x0yvuBC0%{V7q&;MG%57GmQVjmJ-w`x`tXHm1!Fw;?piL-O_j!r`Cfuj^Ol!7 zmI2pmUJh}4?cIJoQ#IW?(WztMY@0{!Gn19^VbN`cAQGptr)X7QBa|CWgHfDkqU%ky z#M)RY)}HlVMI4!4u7epb-8VP%*#==>NgY4~!O8(57rM8L#bJ!rT4MEK`}Wwc;CL~R zt>%Yi4&tR7ZZ;;7rb#svR7iL(f1aWu++;e#t&TBg!62W51b%m$mZ zz`2*jPb8?_%Fs?~4xb;kS9ln##Q47bSWYanc#OehdRV$;ZKdtM!YLj*AV*B>w=;d; zS@c)!;)o{j1FhtE~RP9V9%t3grS&1e)_jpNm=BG3w>rVlw62ia(WZAOEb z)MISp=?+FIaC+Px0OM*uHh-NDUybQ?Z8?%aY!9(fzSAu-Bli35WqdFfS>f&c>VONh zGdJ>sM6TSy1fv+jqn`%BLgIgviXljUm%E{*KJak4NF?nLiQg{lb}N>Z9=l}2sv_&G z)*Y*T#K0-ZXZD4Ll9G~!>65^v{-~}PN2FKq=}(h%0tD)epla?8kE;XNy?FZ!{prCG zs5ye(!@`0zbx=$hs>7->;F8jwZH}gYGBf+YKZv_2oz5mMxx$8aPfgtFbWVP{N1Mu@ zsi{fIb$hQjKaLO#VVPHfRpDq4Y!*oC1H&_q+S^J0GWf^6v;Z;9A3J@iD$~Z+R2?gQ zwXObjr%`iUI?8I|IGLyBme3aX+*qH@sSzITwQ&}_E7oe*@1Lr%mYaF{qPsaxCw+-~ z#Kb+%ZCB1t5OhWfhJL@cxOv@*axL&1rHw~pjH|cHlBB8N&WRz|T=y}abDsxQ(j)L2 zEJ@2}lW@fc;=SW{Kw243g=*t+WNe{hl8^jB8H4H??Ail6g6evh`t+KGD;K?Df4z7u zJlBttLAm(34qC7AzRr|AYcm+Bb_em~GUkth{)iD!gy{$riMepkbWV$(3#|PCG08TU?`(HWyZ7E z*f?dAu(oWA9d)rR2=8N?{>eCTrrzXi9-XFO*tIh3szjBHUVae%>Fxl57%!gjNfxP#?RC@EN_ushk|+pOy*qqmih z4~_Ne$maR4ht)}=>gzQyur7afGe)%*bsM-Pv|_XHxe;MWQz~n3O1;ttEa4R zCWjzVeTQ=%``6C)k?8LFw7s{f;ibUR)Sre8nV(!zc!UFX21V4jm&TqH%JFsQTr@Z#aLO1@1mFsct&oHklZrh#}O| zd{v$w4@?N4&7%o9)l0Ivyq_<&90s*^fsvrYT_}|q!Ju{jeIqeswG~rxV4s2b=mT5ZF+KzcF^C6|Ct-9r-Xpa=)HTs++ z;P3%Luxl-44zngyS9_+dswm90$ju8zV&Je_q~D;J&K;?$5z+SWAthuP7L#Q5$qLal zSqVU^dZI8=d1C90MP zd$DGC5wNf24OZ#)wVy?$Wv$F}6q>zP>velFEk?;p1lJlY>!;0VIMsuYkRtxWj^eat zU9>EOL2a%g&s8Iff!e+qtdSbS+u-C7BcMVTa~caybD(x8hnXv}R!A|>FWu<%;hQCT&pw*d-dQsCp4up%>*c$Ti?Ytgs9FTmwpe173J#am5XC4Zn zixAD4(K3o&Ws_f9i{g7Eiy0mseo?rdSeot5k1=j%5@v#cp|``^g{csbH!PxwmnD9T zJoT;^Sg+Bd@fa5tNpm-MGm(SM$Rv^lcGVe!P#T1?&Md)xH+V7U2CaFV9 zK-F_Qy};4Goz}oz{82&7EbL8$b7M0rev~7=@DQvSk+J~Cx7bm;^bWRV>BK(YaMY8y zFrp;Mp0TGpv8T(r+r`AgjaTldGErkJbAX(xq3y1D8Fl2ELSafrgg`Low zAO>Peh)Bn8$N7aBKZu=Uby=j42ARZ)Oqx3vayk86z=;#@H5de?i?NCUA70bq!det` zxu^BDs>7EY_;Je@9%1MN)Bdyy!riP{eH@nOK&pPA$LFla9gpPT1X-9MtylnaF9B%w z`rB&DzRciH2+P^<*Jo3c+MSNN_3o;;iJ#L4 za>iUNk@^M>)>%< zPK{#YIevG+_(m>-8>~HHe|K{^Rc(nWB`qx)^6z+Af#V%krsJH!de)xX(#ZfIgZM~g zSf%ctR3}SIR?rffa^HOJ$@)c7f*Ea&k!jc*&$%`zS$Y{x@Ol$gbu;E8rEg?H)ID+5 zQtQV*^-x;>Yr?C9qARPoX;_LSfFU#v?!>HQeEGQ%kW3L^kJR_40_j8IWjLiqOZJEd zoofDMxuH`5TaU$<337hPuK(&@2so;pi=h{@vZxM5v!K$hPfemQiL3PT+PcYvf@qaG z9xVL`7YE^C!rfzVfmdt87;WOp>LAk$pLnN(=##s(+jgVM?Qz89W)t$Evs2f?1~?rA zD`ho1rV6G7;jP%Sr)|0`USptD-oRpREH(d1O+%EDkrjvt2QxM}lU$Do+QPk=@yph6 z2SR6FMcb8%EqF%Fns!BwTkO_R$mJmo!YPNX*Sn?4chg7$$Jvt6LGtb=`nrvst3d zDs^Qy=Id1bI??b@navVNARG|!tP$JY?&EqEfWLBg!q7Ll>pMMNXHn1X1ZV^*3RLho@+_D6tSe=;csK){{ zd>9IR5Af!h0CWg2oK-u4yx5v2zaHuv-u`^@A@Qi;Q1`K@peO1W-o3=Ffr)Egrto8T zlv;RCgxLSJm{eWbt;x*v`=NlYweP6DF|3uva1?eX`9Lv_c1^pEzOvv_QoGKvH2%t; z(fI2x_F=9m*$l$D_JT=TGdZAQKh*;o#B^?w-b1h7M3(2bm^X4}AOY;!Lo2*u3?f0w zcY5!>ejL(N<8DhiQq;pR*m?Qs_|6W5nh_$iCho)@wSI{p$hBX3Xyzk)jFDzUje zN2DFp=;|iu`L#hi8MnY`3Y!3Iap{}S!ZUpM^hesdbSGmqG zXeu$(6DstEIEt@zRx%+O&aqJ30{auNk#tttv}C@)7LjcM|{>f{=Z&;j*t7A?(R=o%sj6J zijbhvSQFeGhaD@N(%Q5{&+TWa%%`SyVd7EZmh#;7`tCx;j*vc zvZFD?jn%IH&u$RPqj0m`0)0E0i zJ>>e{+rsTYX4;yHl}5zL{LkxoLlMN9{lkIi4dn8 zW@1xa*8-NsA&jZ)g~HDlZ|$^mClSEU_L!<+)-(9D%t=I4z0X9I*dGyMaSFbjWfy#F zNk?=Z*Rn^M!m#%+mJHPv);PSiWz+iYSn4Ex^7DtU>#484ifJTVy5EGaE4>k)Ck9PT z9y8n(ZQp}Hqo&&}uFY*n!hioXKR?k)+>b7aQ;YRI28vYCvdSu!%V}O>&A5&8_<@#kC zzOKM~0S4E^RsP}6lnNwZiu)kS6&<6rIA_oh4Dvu8*3ItkHGZ7B`-GMP?KM6)&wT!7 zv8k!)u)ZpQ`1}pYeT?&TEw;e-Q|({Z8StA@K$`is804=$E8!EittKQS6yi>u=Fb28 z!O0!lL4VjIJu_fnxP<>-UKk8^I8h}W$O0rVrC!d=Qhbf5Fpy|=#kzvQ4t-hKQO}M8 zXn0)LK}?Jz9d%0v$TK|0o#ZZj8t)onhwM%?OZu}i(i0-_<7#Ig&scN3`O_8X)RkG} z_Chx*OVaW*&MetO(?;TRBGcwOdbt0|YpkjubdzSp&zkauW9mcitPvS4N-624N{{8A zBab3?fwzIBr$1oKxdFgWRWzYMML@oi?(dQCd4aI`;uw3R4@8cdLR1uV+W)NL<$jO5 zrgwY0q*k%L#o|3m$@W~qlfLg4j_~Ki&dW!bX>!7Npq~fZ^73y5eu**_?$LenDCo%` z6s4QwHmJ)Bc__(QX#bEj{6tqhPy3EDicAG3n^sgvBd3RaaMb6M;WKVNArMH;-1BP} zXs=05c$F4phWC1TGe%OyNGU=}HC%2@Co`jnPJ_EGsqXZ5sBeT&**YqEXuE+$U~6gSxUN$PtmYOvh2TyJ}}X_q>zNZbBM5I&#K>k~)Jb z2f2JZ^mTWB|6jT0oPiJxk@)mxae4Q|X6#y%xJ}nA}u)8!YfnUNRVc+UQ=P zs?YwCCN+NUDbQcNF7+(j72|FsXbP5cH23e8pm*O3aNq*V*tXi(f+z=f>B42ZBV!it zp4zqH>S_|+-;+zFcr`PId-05(z@WbKsCzjpE>>V!^v}v?wvuG!GoU65vSxL(uav6q zatdEJ&y>sR=UIK zDt42~48#`RYr=leR(mrCP$x6GE^!h@NNDPK#k3p#l*q~V%61#K5m|AqqkT)K?lWiG zk-UzRVj#U18EnKEb2EvhTgP!FRB&VZ~VHpELNX!)_Hnqtv(_kW-}e z8;Q48rYq1=I$$%KK7v(tFDhc|o8Vt|GM@+zR39bis|FLej6DWzJP9R_{sdXye9B)R z-Jp3QQK?I3`3*HEX7y=ie_tq=L{9i#FyQ`2ThDCP+vm~rn#{d_(_b3~{!RmyiLMc? zSI=_HG!|mM^_HSEEmg>(Blj*Mx0~^C;HJ~$dzG5F_^Qa1rZt6i2Zjwwoh{nABsL=< zvL^ZxHIa;F-2Ca;{%IF#{5%77n--x=`)YH+ zuTgv7t9dP;6_^PQ3?!uJdtLRr!nmZd4bNcH zXfW@4*|XD{kUa1y32}RhLnvQzV?(-25o&B}>oE|uI82fFTn-94#Q^tPZr+yty;gXP zxG;ajI5Ck|9UBq)ZG5#`={Ux4rJ}5v>6&7n(ntt__S__>>T&>=&Ix3G9+cB_FBcva zo|-kwG4NPn+|@e+*cUf7svq_#?|r&HIsB6x5@L$*OsJZS8_~wqSl<>}8Nc|`;LOT^ zK%U8sKF}4Ku&S8M>*Vv`k*$@FU+s0jID8)`NbL`2q@Drxb8Z#>1j!_G&3nLNvi+MF zMa#GVilsjWc`-KRHvHEWqW*&G*Nc)`($Pg>-j^~aZ6}eAAgxC<0~nn zDjpF{K`~i@;xtd*)sN{7&`Y4?@hEwE_5_D*wv`q{%yMQdFD6b&>Ro~n{VW+r=eUZ4 zMDKz|Yhrobu%}NI8zC3CZfcShtmj4#n~nC|V{*RRUgG}eFDQBcLbWo$ZkBcKsFU&W z79aG=r|E(vW@V$0X~qi=a34H8fv@Wh>mah!q-;*$^&;7$z~x~((XMaOj$@D{KQj@} z)-^GaS$|mwVDb2@EWX{Rl!<2UzKwxVN=By0N_^^|(;v(==M#G2345&lZ=j|(uG`|f1>eR_!T8#nI&~fE%9PdCOG3HZ;5lQE}MV`is9YAmxD7vwN zF>Cf_D{ykE5EMJu%M{_N{41>hIJ0%}_yEHf5ZwW#M$q)BXqi0ZbH4^OnLO|PQF!}_1UW7e)6r=Goy2I^#e1O&IQ@GsZQjgE!ie4`a8`RBf?wU3YC z`JRbnDzZDfw@ItpqBwo>J$;9TN(S|((3yR;ce77I#v@c%Sa7w%;d8quo%dXFuo<<( zq*d+(Lv9~PiocYV;3IB{VuI}SXeuo3wk>P^RKkkXE^8^ORKA|9-lxBbv;l3q=2{w4 z=A4^*K3HJwDMxLk39{i{F{vNhdcxsv>v_HT>H-vWV!vG#P)YCEWLoM6u$z&SH#*!t zJJT8Aecw-XoeKKwx>Q5K8p^Ag?~AcaE+zv)>fT&gl#V^&z4losY%qp30FQUg^?N!) zY!340P)7p?B^T~^GJ_+T>vy_l0Sj+D*l$TqD~$!!ZqJ-6+K2~fFTbJa(qJ~XuR+Cn zBGF}O2O#8)E&_~#(v+eG#MYbiQyI--*XiU@*`#OGDb!lF<(Mql!Dt=4V&Hu~#&Fre z*ABi3WiGHEj>U~D2Z3xf2Y@_DKS6+9Pd)GT^9#6lS_XE1kb(0tTh zi92d zS1_x7ez5QsLns`Y2<-33oN zSJ3tBdBJbfsGNIX*BpV7r=Gr zvP5!o93-ew(%M=oV%0(;gUvQyqUc~+n$#a|Va`mX#33kPxlj<2@*2x{FfXmx)trT; zv9hrz6tI^0>}EF?6X(9bmcd@3$nC+<-1LiRB~97EhJ_0z63X^j2XdcOyRrWzIx+m> zJTE08F8577ky}P zpBhFj2APCs-!QSi`qm`CDaB--Ta*{^|t?$IJO*Tba_JcAuqV@Ni7pvTo1^^0naQuDF|dg_V+ zgzumq*Db2QimxoiM)Mq&V>^?l+Bwj~r<&+~MVMpFfSDRLM3#h|J*5$P&$nMgxVpgxe{e z*ZDyYCg!p#2S}!I125aeJ?y{AZJ{J17z@6vcW_v3_(r8REU$fS4ewo&`H>=zznR$Y z-{sxR4{kzCIm3`91`uity!n#*ll`CPDdf;16Mm}f+Fjn4Xa(H^$F|q0JdIk3-o&dr z`(85Nf^iYZ&^W)8J;F0|&+OEV4#NIFl58LQeF+ zk=Q(hpI=#78RwsqXjTkAfWsoW!E6Gd&uTGQ8jm-K_GE?&x?qs=tNlsV0kQ73g zx_>4X4UaW#JF|Fj;n&yK%V+PiJ~@9gcJI}fEnvRtX{n|b=qY*>oW$_WXMeLAB{=sg zRsC=3!~$^ayt_CXJ%sVIfY3U}X#0u$wEBSF+DuZaS?Xw+ey9#~*03+(mGq~*vfcV( zA$%W%;F=8h$Ti8(Ve7Pj=i@h>6fLGhKyXv=7|$+aYF3+(tY4~GAg^pUVb3qBpJsBu zTaDVcKb*z$;Co}~rSUh^XkcX_`T}2~ND)R}G22SSvZuhI?N-24W)jPB{|%p*`0OXJ zBDNCbi83isJo*iV5oF`g>G(|7nUJ|i&E_GQszu(qef++k$)Ie0EHe-0=KiKcX{dWxYyv=UCVZ)%Ww3St+f%Jji5ratYAu8vCNTi57>o?iR*uqRfdZtMiU3y z)`EtZtgbHrfu4@D50E9am$@wBqJc7ul+?-eW%y^S%r`U@PD)eF2TTjcKtQ3{S1!c4 z@Ev-lzwy0-vJ~B@Z9E(4g3OZS`s`o;$@)Yr_2_0gw>vpqZXpzfhIly>b&;q~2ro{! z-Dw%?M0LJXV0bGN%Oh)`*t<1Bt+3mQ{FKd7Z{>=;BR+lt+DYLv_Oae@3*S6LZ4b)p z6)5_)d2s+ZLP&KAxJD@qZ{`}vFoEqTFUazE^mtTaxDa$|nF!KcH!$+iWJd-&DvQPK z+_v~c6TIIGE012>J+lHP$0;jn!fP z`82gV`vaiE3KrSq-Vdw&awo8&{pnxO(8P4makYX$#EZG@oN-*ku{4+g*;)H7$X|f8QP6UtM z{$}o!gxI|Z7X19rb=60q)$P@WYKdCOIBi-v9rxaKRar$@ z>UPez44cp#$;>GI?6`Oq-t1DeNiYFtn?B z1n&_jQXJ!U`jOyKHz{k%Ci*IbBM|Lx%m*k7<~Jmd}AL_jO8!K{%_uct@ALnfU_n;(z8 zjKzbovllc0Z;v3c=V2_5IK8*`z4MLIj&n=ey{*~yQ&50E3-kTq=p=w^#Ko2t-^zxN z70^OG01Yvr;i%Tw7HS~%=(c5H#97nf=$9P=e0 z3w5>7qL$3>Ralx49|YH1hJXi?#n~*Rw6vvDUL$y=>|8X;k%)tgn``nl|FXq=@_5of5^zg`tCQr-%8n z$fV8W95vhsp~D1~VwCyyfD{RV*MF$7;XcytT8eQqBuKDQbZ2$126$U4^0$+w{_aG3 z`V61SQspuMum0c5pFRt()UA1~UAxk*ThF3bo@D+wiUWVaH!*=FS%na;hp7WR>*~vt zg2(2=1IGMe$PuwD44_n?GT4b+gPI`54FyJ{2AY8dJ;19jqst{9(2H+68?2b}+tmNt z$^cz|O8sqzB5iha-d*d62;Ml;5cG&aa`^xa zgD$4eMe!}-o`&|1F!1CNCT9er*d^noCjOwR)1R#M}v184d-&IGe z!S}%*z=!Ud#GtL`U>Smz)YQ=POf>&E)SOx1K=%cVUzbftd`GkORPXQKP=U6O05Fuf zIL~V)7oT3^a?vrZ70_(~>2ml;(Vu99b6k#Kj2T*N>msyS*F;REiX1ZG#r-S0_9N#^ zx2$*8_X58CT^5ejyuzc;-k69);?xpwP!SKO3cpph23dt5K?qWK_cyj#jS;-mOP$PD zR_NVdKb!>SdyI>5iWBy0hzk`6$3ePm7}|Qx@b0b0nC2uo z`{V)vHv~ujd2%6_`UKBHlnReWEKaVQ=l87OAxeB6?|Rq}gRUrfllG>Su66mpmo4JR zFCI@m24KQZ85vQbxFnERN=K>s0+Aad4JBGH-gF3p&dHv9ItR%4A)f&X$F$T41kp0~ zr=Oz;uuU*aR9SX>6jlnQDRgsx(u(rpw7$+MJ>EK0|k^>)(+ zW)Tl^-6*f(1-7`M@|uM_|JdkK8%F|lPKutfUSJuUB8(UrCRwQs$k(fL>z%i;RD~FI zW67vVNrLuYfjT8n&oHh={dKSgHdDZ^cw@-$p1|AnnLYv zTm8qnAuuD4&=XR?+{FR`y}3Sq!H!EiiTkNN4N3P2ZOMSW4xPlkqeM<&nF%)yjDnC;o#23FS{E)iBD zEE6d^aBO&l3=_4Vp8%%CF0{n9E3lb8QO1WL?6O^FC@5mnV>)1~luac@S(~`1 z>-0R6@Tmgz&WArR;5^kNgpWiQq~0dIS#Q*`#mMe?_K(N$yHSL2o)7*QdQsdhD-l!7 zD@SJmTe55B$Qa<%BUHyH5;c{gY-Ri)C}I?N6lLC(%wu5nzSKd4GB=sfupp$2-CfkT zPeKj{ii5%!=>=^8*nTMkJX~gHLCHa&(|F#)0MA86TraLA;_tMXN zjv4@Jc3?9@Z=l5blNt5iWQ8d%=whPk?8(g3zE@Ie@{dou7DM<}VAL4CHgnLHr7rL5 z1;P&`%soJXPeut{2Ru<(jOl!@ZnR+{S>y&7`J9EYNj2afp(>iJoiLny1;|M)HBw>* zAI*phts*Ff>2uxAxl({!4M-1d(QR#Q=3hdR;LhLZ0fLxpPzSoWg^Qe2Cdwzr{imM~ zGRbvei~~@S<^(No>ZC{f6};iu_sbjv$~FB#RvFpJC+*t1#dwjCW3b#O%De)^bHMBJ z+*6g?_*l+LaJ4YpT-i{<1OE~k9c4X97#w~aD-41<_Hpdp8rl3H7JA7m)?i`=XnK09 zjXT?oVaB^}<-L9f137%T*uvx-naNX9UO<>Z!l>knySn#1GbQr;*ljq4Gb<6oRbOH@C%Rq7VuM~KLNrDyi0z-t*Bjj&-^<1?l0{%a zN63ra**<>!=PAgYFeMUMT}|q}7$}|{aNPHKfl^;#n2y(&meL{yr;_}egAGx;YI&bD zvY|DF1~hL00ZC!$ZtD>}rF>m--19zY({sbJdwKomE>ZJVBOn4~;%I}61fs;_wI6B! ze$g5lCW)+xB-EKmId*?l!_L~5(6zvfW(pfZF-8)<{J>^`GK?)VN|TzX1k6qdYOdt^&?3h$3>TCbI zD5bl%u+(%JU2eb!bv2S@?2^Y~e)9Eo6JUE|%0+#*8l3+Z_*Xl!)J#gvs;GhDKN6(( zARA*0=q2<}5A@!Q}lm<=4Sn`JX0>NlvtJY5nJM8yiuTS!Z ztbkALd9n!-U<#?!Uh4v&&%q$ZvcKX3T(=!zRx=uCIhdYy>Q)31O(I9771yxxWZ-fz z2V5$F+Bau|-#w!6{#bc_ols#|6(1u-ncjD!!zxqM0m|@sU!toO4k@uOZx^96lroqv zawsz3zV~?C;PUF11?AF@i5Lp%SH0w^kPy_HF$i6$J0w)EUI=8>h{XEo07jic2s}iw zVemhi&T67rMy!tyG?AJeOrubO_W!3mcJpd;e>(QdI}HPx`LL&6j^rVeasa9|=65ng zZ$%(r|DWa<-VY_azKv$Ph^t; zlD}`q54RLlZQc7|Z?R3T*r{s=HetO&<{0sS+KqtA#pIAPtPFNd;dp1?0v^8$@^vZ4 z(hNb`vv3pvN)ABeZ#g)S4nVOH*R8FDUmR(AT8>LWkY>3bs~0EN!C0hHLIP#Vrsn}I zr?b}}konDrUbv|?I+i(`=2-?e_795X%_muM@01!}s;H@ja`WNJQ@06)8^r^xzo3Xr ztnW)-vN&#JehYohVgM24`g{xFy2D(FcGLcVclEl>#akGU%EXQWhY?&WBAY%1y!5P( zWIkEgd7S$2di1&8K?YMgH$rN5i5py^Jv_cm`SqkET7INb*fo=9(4g^c@m}smuKUj?MN&Hv+(FU%ot)_S&;} zqKyYY6?c7fgal7fYt$(gQm%1Z1XcI^k(J|kzDMB9 zlih1vEXL16h0Kc6=dFYS&IEpw78U|{#A$k+v>T(#npFI!PpnejTr7HOjcwU1p6BNK zJ($f*76+O@3UK(ET{q@I+DAn|MPVT#$Q&Y1hld3=Z^t9hA=EagYNahRcrs$e^+F^p zs23PpCTsJ>fzu5>@mOnN=rLG}B4PZ^t>AARwN(CYbTW_Y)^J{0n_&SMc?8dY@KYLY zja>@(UNMfA2eH#8pL5^q63bv0Q|FSul2H5SE?9&Ax^o9ZBwIIXrHHcpfIXs~Hqt&8 zH@EN4h3sMS%Jv*Hn9+okAhWCez|!69xX?4)k?JEBPo4s&4qNA#q7o6WdBny_$yh)@t00#*d}1GYZGa2jt2pzoSy)nu5wFJBH&&(x#_vqEp zsq5+5xrIr=iB9RWS(+u6g9U%l5HmLCr;yk?GYXx>}KUjvGS%Q8cJh z3=idt=0LG#ZPmN&oH&&9^GyDDSfQw#=xa!m337BO)H8cYsKW) zZM3A}NPqRkAK7qBB(UCHL_{R_`*+6FEGIj6V2HOGelf7}BRsM@xd|Zfy!f|))Ih%H z$UU-`#u15Ah;q#%pd?h!0*E!X&lN>XKR>DA+1b2?ti}ibSM7KC1m$d3U@2;RPgj(?Sc{TG+%lytCo39ku>g}v}+(nD;;MG62! zrlZTPWc8sQE-%Z&+8kE(lWc5R0BiM^C`ozN2bNK?ak$$5)qO2$HaoUxm6~E)BeV^S zeTQXTR;hjmO10Use!UfA{>D`i+E|Bq?Y;K_z@b-9G9{kS;CQ^Rk(Y>}vYFOqJJxI@ z=h@{Ve>Z*`mD76{xvBR|7jV#Dfb<+65woF1A1s!PK1f%3HhC!C+lkn5GlJZeMBfLA zQd0krX`@jY0KNI;|C~>8y$MeER5D6HG$+=MN(pu~S<;FK{uxLsK0Wy8f7=bCWu_-| z#^#|gqHK&Bc?#L0Vs-OAry1uy+#%+etL&=tJa1P>b)3w zr@Nvsf3obBN%u>)K3JQ4qk#M}p@l}1c~dki5+@h3KdauL9iozk>Pb$wEuOmZ$=`O6 z($mx9m;ns!-F~gsYW0@#+Zcaa6L^w&IC4>*FZi%Z{r*{^>x%Nn?Q$(eaV>`2^QReNPMy~WANt3hKY#A}CsQglHK7owis%n}Z#oK|8+Zd88{!iVm1#K3#1Tv{s zo#ru>iejGoFM!(o*+}5`?Sw_xGd`vzq>&4%#|eV_f@1w*tfbKd&0LZ1ib4(OP-3D$ ztJ>HgwXO5YYuYr(raonV+rqU6zww_cCDAg+>TBs{cwG~Ypx|Z6Q24Q?J&5oMR#PoN z^u7@4aOERK;77Xn95$$!1V!$!J1V8@7&9Px;J-7qi!QpW%Lz5!t1g% zzSo6qG6D9Wsrxq#-aQ^`IjD&@+y~6*znDv zoVb-6!KB1@bAUr1Xa&V4orXrf5pcQ{i!OX!(;wl!l1(CRVf{mypRQ>R>oWF!+XkN}vxXr6B) zK1ghj@K_41r=h>6XSg+Fs77-S&qhIWzPkAc#a}JY8-JD-YJej(O$ zgZuT9Deq-T5Xh9#i;{nfryJve3ZrWC`^0sP{8{#DZAaR+q;Y^T<8DhkmOat>T}J~V zJr!~{MIStaTd=VtKz6z4G?{<&N^R<9A4S#05sLcZR z^#HBeln7t3X5i$Kg%ZT@02gr2cG0aIU$x|Ka%f*u4S|x&rd_h%3S(IcYv=)icb-qr-mguz%6+Uy!&_9zt-x3 zos?G5OqZo5+t}J?E`})VQirB@JD-9HwlLup`aFAH(&hR*Ev-U6fg_^YEU`lij~D5g2s_WR^lKSu)Vsn*)}2uO@QqGOKNEEIrq>t3h{noI<+GX!4V!|5%*cK`}VOLsZ%L{r~mZxdN(Dvq_u;B;Ro3 znjHu>e3j!+K?HtWfU~goeHd}!3eacUaTNKP1{|8SvzVX1aWGxSH@j?MuVNl~8N9c%bW{degY=2NFAv zQ^Pv+U)HdEgJ*AVZ)kEZ2@f63S`KHK*fDvBaE#y7Wpu$^dLrE0m+#?qogy-lhj%moL(^49Mb&=Yp`}DhLP|QMyFn@G z7?2K0hwct(q*FSiTRJ2}K%`rwySp2{hxfNW7X0Co8SdQsoPGA$r;3OL-@ixGz#(9y z(C=eSAd$h3@3rucEfBYFi}#8rlXuwA^YDj4iW)UvYcF6~IOhLGQwck>%ilp#wX}q( zfGPyg>+KFnl&N%QR^d9;F%n^n)s88l(YD&n&~g8-vUGd_+yKIJo%EGi(#3_^ge{FwlLX@iY8@_^b9#G!B$x1w;eBP88R&Sq zxt;vs4kz+74@|nhkQtO_$I^p;><|nFSN}U@b3f-GnSTCH)jE5=lg$i&#m$p<=ryL3 z_!TwRu>A5xo~4YOBC;2mQ-aG<>Zm^rDb2qzC@O@{*qyvUuF&wvBPJ;+_@vr_Fj9&z zURC_IixjTo1$~{s*Pp4r2o{To^oxjhof+BQxLdos?`)?`Go;mG4uIhQUY za=&L|K#n&1q#$D5i4LF@WN2DlUgyT6%@H(bKa0M~nde*GNrE1^dN#MxI` zdH^z+oD^J}D&VBfBJO$p7Rt-99+6Kv@ZL(=NMz~qmqkMW*()UGlO_{=b@X>zhwLL` z7$r3smsiOhe&=}jRhh{}WawqHzs1j!#m^-c`4hQfh|#&JsW9_6zO{&r{;y0sTIY@1 zxXIhB4nHsrVX3K5P}$S?>VCqF694h+9)8bz=5yx4A1PWj8W0h;4g27B^qoH|n?@F( z@`@eUCi;EznX~cJ(wjcL4>2#7c$;7iCadRXu$Ig=oWl5U`@w`Smb4G90mlxwaXzQ4 z-`nn3*|OYT{f_;ow1)dd4-8akbXZ3dxn7G;SxD4kUX>x2|EkpCbdC4McLrs3opwXm z2C`M=HR>$zhJWk(+7XMuGt!cwUL!ubkSd2fe8pk5F?cdUL%;qw_!0|Lc*{1Rh<{1? zIYDakZTx?YI3rwkcgATZ)9oFG&+fT?8d^ZUlV|-nC)9ZJ>hm~zSfaZ8=~(G~x<#4@ z0){s-VOm6Ek_)DjNaPy=-01lAzF)uEz+_Js%=q^MBy|Gjc%a6YjcmuH@}&l2m{o|? z*CGM)1aC!t0>;>$Eq~VD5JO_jQdZQ0Y_A%^)B+=pG{ag=L#{L{`>2 zU?Toof|jFo`q_+yTSS#X9!a0s0>Q^h(y33{ZDM!uuxo!CtG0D|phqh5nukS=Qg#y7 zh^~3Aq>ldjO>R1hLGPT(@G?~&Gu4jU;^S9@We(TNK*1gKN5t&5o10QXaspoR7iwYp zQP65qW;6WuMXZL|$TIl{%foYz>HQc-p_~?x%B}Pd^3lRKgf@?J`;cU0)y4Y*S92sW zATGuGy>Vc9>!ZYt@LiLhn&xv*krdTG3~2iz#PCM$a(!Za{PUMD_+M7b{z3-KoE^>C zGc5T-KEGb44XJq#*6mo;Wm1LkAEsAaPCGHcsZ_p;EmdAa|H2hBHm=V9N?liXz>x`T ztYpkQ0-NSBFt%0>dhLMWvaLLXz-!#VIp)!>`^^X* zEaUK}Q;bH01Vk9!%d9S}OiVXBVcGwzNrmSFm%hyUC2+a54xr9El#=hN5sg?4d`y+{ z{#d^p!0}s8b6z8Gr#}eD;mb}#pZHGG_XytXr-_ZV99i?{CzVSY=Dm7YR)nmWI{6Iq zafCA&<-^OoH!{?dbm#pmd}r{dmnss zS@o7?`X2rlW}ZcsfHEsh4JUaq?;At{`5O(yrA$We)rc<(Tbl&YMF^HIaQ8 zvE33&+cjpKH*e1<$(DiQ`titVy-q`YDS-)C8KKk-&Jx#>|3sAiQ5nKtNEv*>s8~n3?Aw09p(ppiV5oj(WYZZ9mRK`?ZX9fVGa+w@?m#s_V)c(a1@-J zxacq6h^fW9g^GUg*vxe}|GP#FN>+T_+sX9i^C2ZvQ=b9Xe&)wWH%9%5_Ef2fkyYo5 znzsBk-lUq#oOj3&9_;FB-q^idsgKuj_!Iuh;rBX}D3 z@3ka)tPp#ks;%e=-v?7cw4@y8n0QVBo>1Es?V)~J;s28Ur-Ch;oI%wJL6LcXjQ`%f zdO<>ND0e+fdX1pV5jDKd>q{irdnmP*S$&J&jHW1h^X$3TciNA>kn{Yzs*Nn1l#FW` z1}1YL500*ejN*#jcLeqYBg4u z(zH+Q`i*SBv9Gq5R zDrZ&o4lw|9BfTPrl?vBpesr4aQT3xVd9*{TKMkpTHdTbsmDdh%o zV^hnZeg-S79~OqoBXH6@r~XdBL!x-erdldF^%hu@qGh}GVVrzAw$apOZ+*w0wtI_yRTiSC9{|SiOm~ zTMP8W8gM}dDWIuX9EiF$$O^2(vE&Oua|&?szJRI$dljt#z4>*>4k!@D?q8=y0$bs; zcDAqHu#`>IM$K}D8nSuOc!2m_PfxEIGNBob|Ki><7g4#XM;pqi8|kDV^YT%OCiL7~> zUu$cGoX{3=;M1(De2q1hiq0-&-nn@6B-fKwnA836LJU9 z#GwL{5PU<5k`ASg7uhe8zxvzWoo#B4co1cOswLnXRaT2sk`5M&jOu9K@89$IMFM62 z^ob3LO`+gv*w~ftUWU6{ylLBm=yWQ}`%7rSMi-{? zX?kzl+*4Z=GB-~b77x9vHziEv^ep`ntSi;TFW%+`;|iUB;9Z(hiEeMs`QSE#%SVbD z+|135L+^Y_bEY~e?Q#y?S7;4Vo8HZWp{tc6pIb$`iJ1_>ip>ATHM3Z z6m}iWh+DCn!z(yE09!$MxW4UTsTQ)%cIw5mx_D-OmVp$DwHv~0VKsIi>gjcgo)r<| zd|*5~tmEv2>QK!)Ly8UCKa_-so3G2)Ar||nA{?J6mWI!MMQ2^znrN-nOSW8SyL0Jd z>O(`|HEv!-C}3$c>$@Qc*Gt4nfzG3)v0(uj7}>0rhAbi10I(Pt9( zVSg?TU_yMStk=(2&rd7t|~nHeWw99Qua%e?M41!3kmt-?)Rd>UHF&B_K{_JdJ-13SeYmNF22&QUr<(4$2pS=o82cP$!8>S zB^np{eD}m46!6=5K^i&Gi7S11ukCoE=7gD^8p;S5PEU?0Ne+=si61d}f@fBwKeA1CjW!`Y7ay3Bn5*=4e z*p)qAAx)I}^dqh12mC4*=SzN5B|m173iN`R*-B|Gzm{DjH3QEBZb%y+evd&vibjxO zsi7X;kW_cJc*)Y+x=H0`)kJ1lcqRl-j0~7ceT<;M6r&Y-MJ3bZ)=toCzTYL>17do` zfeEfO|6dCrJUE_9ncL{JJ;n_OmBY+ua;88IX%mAfSYtX!yH^_DGC-i>^<|LY1v{E} zqL|(Yv(S>M01ZJey&`{j_+O3t^%Xl!u^bN_{V(%=m4DiMwHS_d^s3Fz0l>0UPr9Z@7ELwNY>@n63>Dj0uWMp3rhu`Ii(n(-g)Bfec4 zcKI>zoPkat;~6GdP)QTEXz^zvMQx^#&QA(-0+oh$UY(yT)pA(-xI(1i!1;Ll?yU;F zJcS0NK!v7Yq!3KF(V1ucQ!fg0{1NQ0Ye`QZ_`b;v3Hz0M(BsWH4Vk81M7u2ttd#(K zD~_=wC%SfIFbmqOuJMl(c;tHK5+$RpV*C94J-M>GKc0)O?#Ykk9dOTe{vcbXOo5L6 zu1tAlZ{6DURqW837?K#}FM3YB4%R4QBryqb>`)1b30_JEmmF%LmPH7@Je=BVDXRPP zC_+Y)&;Ws0MUBfXDN-xHgw||&@p#->w`C>#GSAwmY_W04f>+b0PTyavyv-Vy?|H$I zZtQ^(;&Am45KC6r&=@FI9IIc{DTjbsSdCdw?Noqf1U1}AyE%T>;3y44gP2z)oX*mb z=QjU#ilsmO`1KUJmBMhRDiE;6DSuAlfQ@Vzjvz3(?z6q zD^1>-4{Waqc62^?ha*sDIK=MAI^x@M%bD%DH6b?f#^z^l(a$Z2b`x^3{+RhzLcRd> zLhpw#(nm}w?WX#vkz({!R!G6ack|u3BABbmH&=o+Ts`l1i1Z@Vt*YFxuDXJz9Mj4P z+E@(fTsS&;N5onE;-pLdJ_SXn9Nos*r}6Ert?b4;5Oi}=FE_m-5?J5bvKXq|V(QOr zcqrno8|V`=Fw*2?8{3_104!8ROQu=tIhL^Y4S9uucsy+ zor+{Pm_O&wiSyGFl(1!PfK78>YAh_t?`{R55a;jrn#^z|Ql-ld%ciBhIs5L)Y6iv) z>AfyLgsmM)oC|uR(n?WK^(z8-oZvR4ViPzy#^F1=yE6=f=n^+C$Mq9FElA}kzrZJ& zT>ZzaSA5a8jRfMN99Q%jhjeY&ehH=78!~jUgjq$%iF$aL!|eM2+SK4E3z55cbn7n` zT_21ptPj<7LiVa?MD46VMFvGlP92h-DNV5cP1S|;#~}EStx*VH^AD<6=McXn7HB{` zUVz%=cm8*B=#G~p6#Glqr{13TEz`TUa%x;WzVSF>686e4ru+`&aMKoaPd{lDi-`$=r-#9$Q?$1?U*1d zYOk2c)GewfmiY8GyNdAM*!_}?px$-^(U*AjpnO_rk{$AQTI`+qC@ZWbn6O&KqVk*bg7y}!55nuS+|&QcX9P5*4AdLtzV&cJ$xy^tsEmTvQTuT`Gx3z2a$1)o z8mIO3vj$9MB=j=YyQUSe(p_u;q%-${1=+h{Jty<=jnLQj1#d6)i^-5PiVaFeeNfxi zz1UvA{(SPqVaOzN+huMULp8^DwMKXI84J`imDiPQm)zhn9=XWhN(=sM5I2I5o$r+x zawvPo5%Rb%W#qFev#TG9p7GYtro_(GTytjPqZ_bRKmML~0ATXsT)HS0QrtF)D~7b| zQ{>O7a>YMqvMalfn)jSWOd&mi@6Aot+sm+jhOc2N_9FTD*Hef}Atj$5>VB@bK}xJy zbv+N$=EQBzA2fEm_CD=;RNm(ykLfjMm%bpIq)$q{&6;6(=`BUK$~c~ruoFw)63f_9 zZkRvki;-GFa;o$lOSL`y3}1axy;hq~M6bo)qLh{QQh1*shN{$_`$M(l+TNdnZ2HDm zfCSFEs*m^wY`+nzg{-OKYp@Sh%odZPptt`oC(<}$57gDQk4F= z9coCeywj5hW=+4!kej29*ZS3Xs3<-QL0ma`o1WF&4*lO7(^_HdXEXKP_ zr)#j10}2tdVd$#XG(S~9Kba}%b93=2ii=VJSJS{A=PBsQ}HH^gif8O%V!GIJD(hd|C;^SJ~Sq|SA^Sv5qko%nN+C`Tk@;-R>Z!-q{Ankd`d5r7gx z!&j$nkfSCH2c6AKx#ievV0~dS{Wzg2%unPwrmXPGiZm+#t_Ty8TX#Uf5sUf_JA)+I;;evL@;T-zga}t3zmkvy1m9tih&X9s1M(p?enWK8}0B{ z%JX!4$rOAjnDjYp)p_S6M&LH|V`<1DJk#;Iq>j%pNDy~K(# zAy0xTosT~A3+hpAYI5djpRkLEhJKCAe33IG z{PNQdqRsT>Qz;wsOwt;D&6-2iwcEXO{zXsZ&XpU2Vl;26?XIH0aYsR&2IPDQVbK{q zh8P1ZxwsW3=ee`C^NzmFjdi%k#tf2z&-d}Fesg{ZUt}lrh<0iH55ws(6VC*zK>GoY zD}jys4MoBcMD2S5jXbxU3FC3rR(UnL8WJj-I;7|VV0j;DhM0SO4_$%7B;N^*!tzFulqlR1smm7~w!p5(HwC(pi#==G+Q~+MtHo_+V z*;hMHwu<*8!QMw0%2;g*N z4O-rq1vm6B^xM?#t?=KRWUr>Crr3mpKv1eXd5?e^Keo*col3B~8DJL>tStZJBO~){ zbad3)_FqT^uUH+%V>K^-Jtj&2UW^0OdZ(8mP+C&JsdXv{N1EmR55KI&H&cv4vdT~s zyv)o@nM!!oPgsgdY)I1lZo%5Z`Y$xZEG?O;5{-{P+}3<|`uxdjp`dp4@%B`!C4qab z^yPSV*v8d%ue^c)su*Ab2t5SVtE8xj*8&3SA7Z2<_MI^xA5qM^o)2k=Yltj}tcBoz zcU~coNRn77KIxL%ACBv{gln`yaJi)l*|MP4FPLiK^+TihyE9;B0>3Erxvp+(ZLw$1YZw*ePzY& z;ig-l6jF@h>SK*hK@%w1%9^N+B#By0K!`-^cC(bbJT>Ueh$uN7EFu0u8TwYOZ9b;R zHUZT{Aoz?Jha2a``FQNo+g1?KD3JAr2CKfMn7nM)>rMT%3c>cB_fCGCsUB}psMG(b z`0lddneG|e&VY>=R&JD(t8YZbg4qa-u2(Haynn?D#(qdiU}J$#qF-r6a84uBJOcwN z3Wd;Iv(jdJ263t+y@Y9OE*LCvF)RO=ajHpNfVihBk7-v zQNHGtZy%^Ql7~c#|8NmRe2Ms_avmo&i5jGB-H5pW11Ngz3DM05RE5 zF`V(RW0{4YAoui}Fr*Gt3t6Tx69cPpJ3oXk)MZETU)Xzlk&xl zUP@7MgeYFS-L9-yrS4(@ZjMd26D@WDpBF{K&#|Xizf9q2dRO172r`w1J9}UfTcb-#eyx-f z{M@l41%c)WwbS{*t{==?WCp{3F7#a@y|0dTa?E1HL%X}bQ_;n=#*sY_a(GxEDNZuI z2mBSP{-KJ;71Q$cuT$jl5O3(>O`6RuT8>I))K~ZWZNwdxDazC5QfteBnnv1u)0PZ| zOgg+fjmer&=0QBOz0Q%DzPOe;Ge5NNR35m3QnuBuMK(B0crpm^&A+MQm$z(uNAnIR zC^dFtw&ih$p9dgEj@D+^?)U6`<(j=a{5>aM%Y32p3S%PiMo=(ZecOb)FY>QqCIX6? zBL&r@*KEDlV-^nTp`53pUK`QSIQG*#3Wk+*Tw%E~vbmZwwyq_@=8Pk(o8Nx?iu~@!HdpC0JnNWmGk|JrY?G{Rr)uKH zpn_dM(T(I76>ESu5FE*L>m?$m7rr~*TSOsYPAXAsp+d=`dilNQr*n;Nv7z3ItxLZC z{o=V@KC(;6vx$_AWn<~c4sq%lm}m}6C1(^?#ux`k+qI7lruly~7gZSxtSv`pZTXq= zE+p6lLsVnBnZvp%Kpggy{s-|J8ssy-=Uv3?ls3Yl0xNG@`N5Na&fCTfuVQOI&Ew6& z%nbJ0GxOR@bm}CT-d*^A^YZc{}W4J_(Do(DE5^`5@^KgnB{7jrT2=x z44xvJ>AIsTq&V--P$N&cY_u=YmTQkBNv}N)v`)Q$i{6E`2rhhQTpR`-aCev*LTktn zo#}_Y>tkr>UuW3f?YEy?7^Sqd^dZam`&JL&4W}(bRa72om7taL?Pxi9X}HpqzvSX4 z_`D2Iep~rVj`#fsqFh;9hoLP-rt+IAkFKt?+idNmr?A{ z`f*o91F<^M{0BqP&>d}~5>t0yH#c@8qwahE;&(Y6zhre{v{@_O>NAtQG=9Z69aKD3 z`~l_{ACX`?VwmOwx5S1cY6P=G{ug>ScdCDZyb%>zcz0{1F*d`JIX%yCaWMX@91hZ+VSS> z)6+^*aZ)M6@rAXUr+B&hp~zfy^8Q~aQsV4EqU!=#rCW6zC{fVuMn48zAJ2q zuzB(j6&H&wLM8_XBY_C_OZSa>ruk5EZ&^xBW3qQ_ zL;wQo_|~xH>h^YTNn+`d-R08iAi0|A7}D=CvqE+e8=>Rl2MTCS3uy|E8Q$m5pZNp@ z$F1;GCcbS9ByuReOcMJPH3_do8;^~TEjd%h9~ct+8Ylddjm?IGipV;tYHFqK_nUbS zgkqc^UQ^S2=vODwMcDDxTutc1*_(kOKhZl>;~lu4h)S+j&o@tyaOLs*@>}&w{XO7| zQPsxZKf}tdsfmw>FSK{OSUKBhXx=~k=46_)zDs_KkuWT1ebN_T&c3^82rwpYotm>T*1TZ^Da=)w@-BXp2R>~BH zi~Bx3Ikd8poDzFtYRd88E$uBjqY6!4T1Rn+ZlBz^6dc8rrTwl|=V*4Fzyj#i`^+Xb+>@xQ&AChx;gB)HS!uH>DbQ3 zXuq|`$>z75jmaURptyPtSa5yQC@n53TDm%3B@u86Eug(Uuo4Hsq|nt;K;w@eHK1Qc zFdGM-=@0{1$cEg2M}2_ATfNXOPXa3ts%vVd>nsVt?&Xc1gQiWgjp3}} zdh6ML_0~EK-qvtCGa-K+R@P8|3>%*v^(-xmS|p>LZ7bHHsO9*M4C3VZdw??3$*>3oH8hen-VCjn6d`J2@?nSgU{4-X!Q8FJ7I4i-cQcfOq%avKe) zVu-w+z%xnHD|Uzt&;#%M1I@Zr`O^RyXO>e$~yYOpkYW9PQg8 zp1a>ZH$U$VvU_$84l7NYnKc5eQ3GiqD+fQ`-)y|PIuKOl(gumdKC>ta}x%_Z@Kqn-W zE-G@_0~gut@bQC&ey}c!`LTaDXfLo^UI`MpI8X&1tfq!jj)2v4+PeSW4_nsrb3L2k ztK;K=WRU=H_Hl`czv!}T{tGh>4R3y^e*;${PfPWh}17-!-DW#}LMQmMZ_(1C~ z$cc?FLaaG$?vyWr-!p7?TW0f~LL)PRB4NW%O1~WY|C4~;&E-&<&d3+g4*#45TU4D< z%%e$itB(*B+4U6VoDb|Q*f3BXheqT?UYH~Z_6VNk{ zUfpg)bDq58vqa&#HaD6nHFA8hx)gfG%Em&^7V3GR-8(nY)Y#lS_V;hF%!Z%pcHf>PlT4ZV=~xO=t;KmLL`jd-(dHq()^>aFG%N0@!`&sCIZ^h# zygWG9WJY6o@4@fBei;r_a52hQ3Q!klV^dI87UBDFn&owWJ~f4i(t-HQd^mFuEH+_a zWo@{5NRrJ5ZuE7mjApe7s^{f_X=gAd-piL4ZY{I6?HTL+Usu=GBrGiG0q*3~ge-(} zq(r1}nxFhLj>aY+2!S$k`}X`gLAxc)$3l zpsI=^n~#$yD+#7uaim}{4^@6sx1z0A-%WxIO zL_U80(Yd*SC-ze_EYcr_OZy`A>(?Hz@@AmfdAF#dq8`?1h^nlVF4O^FbSzB*Y_%gU zjls)&C(78tA}?GSYp+kWtFdEykOCV?k-HDdESCDfDlvE-+V3!3+l?q^ZL~8pSuoq$ zF%j3tlmOLd@0^H;fO2rCmK%cqkSyzVN@qP;J-WOk$I&FxBnquoe=jN4?ROiS^#0VI zgHbtL-Z9{%DSA`i+-t`HWR27)#~Q<(-|1{T8-dON#gy1(tqsq7eSLYXqZ(;rh{*}C z>hg8@yay&OXNR-IGWsSc|M=m{IIA@Svah0M5Rf*8*%Uy+o1X><6PeSSENX*siESvW#fCh zQ#1-^zI1b-Un2KUO?~Yl_e}?$8H^?6r4Ma}O){3YWrD*)#B={Txb#NbYaoR)WV!}S zpxo6c?X3ZxGn{~xth%)H9Wwy|!AoXs32*P#Np}@(?JrP9nx)SuR|0G=T+9FN$$GD^ zefs6q;x^mhxqYB~E=pPgVR(%w<PS9mo9v{p~%~?sv zV<>B}qya3W2+FwgY6tbGA=ohqqWC7IZ;-V4} zM5{@@!c8qn-g#}jGf~{t)fJ=X5EQLwkXN6NA0{KwQYjeCoZj;-g+X^nq-PYD*3}Ry zL2aoq9~~dhi4sjl-9SOmy5QGdN$zMiWc2$=lQF!y$>|zL0NuQRSq7Y9nsy3uf=Y^& z)zn6&`v`8K)}^6!^aF`#TS|}nDZ&n?+YgVF0>(V;9TRCzmu12lKUEjCL*{(tD~(iv z!t0eAm(1&q!=59qOHcpXc#d%7(v|p@@3O;^~+CX#Vz6Sy$VCg8ubC z)=;e)Gj^9fO*Gcb<)7@kz5Xw#^Ofn7`HbMRh~NOR+wqlyK$yYd$m*7_%|H*R4&Fcs2;p3RT!XAT{Mh)R}~ z3nz#qqq{oScm2NArn~Qd+(Iv@f~Kc?Q;<%_njEh)5|X|iH&nXXiDL&Zu%>H9^Z3NS z7^r?`UQImn&sQYm>bDn8og!hRJyc!eyZ5aNgfZ_R-3g=cEzDnxu{@Kw4%KPSYU-20 z%~Al?6FmJ8XO!D^5-2JCG1rR|7TDytd2+k>n3cO4HYfH<< z7V~7K2?==mUdNILjjPXhcI16^(1QFIA1)f+=r+ax{`)TN6#D&SP%L~0 zj9`7e`-!{)PV08kOUJ;(v^tXW?%m1)X%V2~q0!Mj!^6=71M)TFZh*r=H8ixX(^67; z-(d*{PJFwp0{jPHJBz-)e#^tnuGi!JrN%7?A#%sJV`Q3D(|B#>{#@+OmS;DXTMe6v z6A=+v{rldr^NT83#Jsb!(|xb1Ct1Lmv9k4o7yw5>Q&Y;*?ey4X*7w}!eqzeNNf3ev za9HRRgMooT?DFLPLFU=Fv1r+!TSR`Noj0Ch78z>gUzg}c(~L?&R6;@)@FZvwZeHoN z4vItH7C+Ygg8tl-9c-K#o*7GIBylvhLI14&`RejS_^$zjPC{307Y3RJ8e~%S7kh9Y zI}^#KS(ECI4rnfF9*ex-Z-4%ttCQJds~H@2Ltb|;T_H#c0jGjpeG@46r(uiusfbU= zWpSp>^r3_;8d_JhHR6b z0=6mo-+Y*uc+*mEw10O;bWY7q?ChFl{)fZ6VCa_-z#y;V zZh~|H=RP$0GwJ$lD?aXjt?D$fGNF-?-5nipwzjq~%O4_V;9vn@ANYNj`apaqsAY9D{JWgJv=^h;%;eaNpHQqs0K?d0WhzJSGH}P^W6va z4-E|oo&9_#LygmRwS#_oNJ{Xk=dS5AEId57tR*7jhikP(2PIP|V1u4$V#a*4zve;YA}aI9TxQ*W!6oPWsXy^z-u!O;)X0ApxK5 zImbpUCP)?=(gw(*>{9QoP~8L8J;}_Lw{8t-gxD^K;IX`W+V5R2uUg0s$ReV+&fg0= zA8^qPXS|*GhV!}c6df^~~h+Ij+C9U24f%V&Bz4cqIrVpMX=dUtToeo-1%F7qJ zBL3Q)g}_({)-D@;4bZUAjr-P21R|yCbw90JW|;__AzN4#7BvOD$WNF4edE~Pju$dd zdzqpuf|fff1HuS8;`0KZLS)tvc&Cn6)1bx$3jshXh|nno1wF;WcmMs<1kI~ioHlcO z^)~Z;I<~En_V(0RIFYai7l4ty z*@ozb1&{ES7NNMfxF>aNdU|?oeI0<}02r?L!~xU_6}dY-TwPuN!_(be_vIi0K7iec ztLl`o%9@&?s>N&dvo^+k2@L6?zCbK!W1YaPySu-CFDIAV+??urziR+;+fV9;m6a85 z=*-NFtYXx;dA@3KUT!WzhN85VmR7s=9RSogaCZn?F7pctXirW~_Tc{l&I|^D^#j}_ z67>-ReNbl7XIP?lKfz{;{%?}uZac+=nhiD??(H2AsN8$B;STj=w0Y1!xZ4HY?J{#M zF)edMN>K=Dz)Xmx&n8Ds}sw-kI{u<~2l za8t>(ax_)xo9yQXlYb{2vJd>!-5&=9hNUQWFrk{7gxlNOp%RpBcPDbCy+==O>EU`4 zG>9m<0q1f(S?SZgH(g`znUK(>rX>6%4Pg0R1(`rEo0sj6!lIAY!$7j|e2URz^W%Wyc5rau zbKb#gznQGGuwX-q0>{_>cE6#&)b=7xGzBAKy|cDk{oniDZoCO4k4mEUScJ1<&=uZ|C4ZQ5#0=IKF`cBn&8J{`*M@ zuwgrefCI>GKMlF;4of^!xa@Jjs{@0Aj{CwZfp7Tz;c-UN`yB#E1)&8|snIG?v9LTR zwK?VCl_vY&2t!EoX$3CVairyP2)lhiDv9Pd6NJ>>b{aP>&f#3`=M z%gbw)Kk%{R4hg*Z>#zO50+!$YMT#O9Rdke_3LLfIayU8?A5$Gq2A6<>MV?piyUntq zy)shsjoGg&RQWW4$Z>PUn#Z3$z`fX4*>`pS9tC9b7`KPteS?}Yv1E3!)f51iWKdQ+ zIq-G5L+w^z4AWn zMgtRwnQlTTTiS>=^CVF<*a!7~g-IPM5J9Ol*_yzZLL`)NEjzZ1{}r0 zFY_q0X({g~uL+%{T!yQWfA~+pxV4(J@RINxnvOWM%m0$l=8tbTdfl=0g7p#GtKphf z4wg-b!OPiB($qN1MZ1OdW>UW&BM>qh4u$V zUBTW%#o8TT7;=&DAAO67-tnQ9`%J7v_1L>j4|4$lfsqSkj(Kt-f8(OewlAdLDB6C^ z4X8wNl78s_7!*TK-tt0nF{-i@oig?ra53TGSQ%1$EGNeCX?44XjXxAa-a0g;=jBm9 zDWk`$J=3+Ha6w*uzRi)F7!w>Qq02c(`Bbhje}DJ{+5Aa+TE+A~{z&M5fQjw_{3BR7l-0@A7J4VZjWgm;#7(LPA1zE-nT2^+{u6V>XMI0vS=@5_~Rd zvT}gmBCwF8#0G45gKXd3-F;pg89)mo6Vvr7`Qsmuegg`4#B|iK+zf3M`Ppbo83ydCy+6Cydk(; z@MPVcs^smwTDZx24*j*+yCionSawr@mj3{+To+h8vQE8^S-?|Q@`umyPssxNZ&`Nr^f4j ziBHkn?O}TsE}f!oLsb^=0%5pxE1R3rfRH_XJRtm)={Cj9%xHUgdmmq1YybyD0kRw5 zCUFsCUNR*9Ic$4%$h#PL;qrItFYeUDTjYXEn}KBZEvIIadB3dRHXFQ{n|eTpuo;2T2Cu;S(&EIMFb$ht>b(QOpunP*dY%EQ9oJ}Y-*R;l4hH%=F0UZ92(@ZfyP*QJ z+q?F`0y&qBlc}FS#mK-s#iYgh^xp+iz)}WHiYBy8H%ko<{! z`k^T+Yl>OFV@3|hnPvAD`Vlt}^xj(52@N^mbKe(Ppp4hN>vNBcaQgcEP6D|ia|}AHRd?0T~;bOX=w~81X5DiH_BYQIKh?GeYtnW!sqAn%O=KZRLtef zfyg0Cq%RcJ6%r>K!TP(S)26ON4FYW9{dXFjt$B!dVU7gz45EjMcUQDh(Y(wnRsp$) zVfbimIt~e~U(lZl7Y=fJ{s~(~6Y1|%zJredVYWFHHP%rm@6=m5gb&e z9P2gkR$t-y$-Md2nvWDPYIqQUMscu5VSP*qY;Do|oXDDaK4bNM9}E2jk-qF&Kt3VW zn_tWih;$2%%Q8E7slT1MT@Ep`FOZd#GF{k(KLnCA1*8M0B)e6-pnYeDk)ih0_!-%| zre_c876OlFQn^H#H?GMnZoMW2NbTC?1)3X@!Q&Pi9uZQuc%x-?TNzileue&bcX!D` z?i`e{p@9B7f{uFq_DUdY$S5iG7_w=8=ETCnQdO1D;(R*iYrXNUWQDD*8BZkW$tcdw zoWSe%nvp|PVRfm&!N{Nh7o>uAF5Da(I8;V8eH52eT9Q%>%i7}8*`3kcjypz=v)wAZu3x`bI6t*9_*+N`mfnd2(cD`xIXdX1jZOtgMqA2l<7TUh1!$n|o7AB2AJLf@N1>qtv;$Bi zN_VDpx)VLhA`7AEml zRu=7t>!BIQnS#vdLGvyP7~AlE|pF{unsx=!V)^}e|+&uwx8eKF_OYirMB_l@3Ay}sua5y_mJ(*?B@>IF(! zQL_0fXWQeo4Go;G2f9y@aAB6umr;wZ(a~7o0&s9}{&CrmSYnYQ=f+M%U{Ln;{qZ`2 z1B%L@wuJdZhs%zHJ$d=$KM~uUd|%z89z9nd8xtJEfCLW?xJ*jyFFn_}?r%up|Be=r zefS;_0E$v8%I1N}_ThRT0D^_1o;s&Xczs%$%%nx zn-%|}*DWTUVy0ow5Gf$uH9*EGu`F@lUjI7K10s=+4|CUZ?zb5vd~SYvj|-B!>U{QkdB`-A%Grf+^k?q+-y2_46&;Gz_m#+UI>q#w zIE zd9wGD_5SpqVNz9i5mFc)txcP$`QZM4su=^hPUr+wpR^LeM)m_^DU(Ibc=)&l*BD5p z>KFEOPU1H`5(?DB5*maPagCmqc8{WW5M zr~#Z6Wfm`?$f-2|>N;qI*kAAe(3xBD7McqeJ1Ul6aNAAMsu-eJD#_w1cJL3$6w$DF zYIjt&j*v8hq;;QuT$GKU)VibMh*+!n9|?^fdQ$xtrmls05`uiDLXL}^ahN>;q(pOI z>qz-`7hPP{s%7<1I`x~r8Eb(TU`6u?q8?1?(~ z&DJK+0L5uxVa;K;`2l1kO4Xs(y6ec6fahAFa&o%G~y*qc}f8 z>IhcZQ~7^Podr&doyHjcDmPU{eknZl-ASI0miZlXJ(k0#9 z^{svGy))m;Idk-kg6_Tl>s{-4e$RTd)BM`DtZw=m&PQ@}jOlzaiC$M}A%8?-Pb>CA zcCf`FSSLk z8o(m5q3MMN@2Ci6z9k3;PWAb zw;j^e2CtqVA3P9ZFtB)bZfrN~hv9X+di(%H7dt3H(7m-HXLf+oI2>0VVh6RXy)L^e zkerl+NW_~1A~Jw zme(ylTdTF32W|AVKF`BSixDOzC8gi{4RDc~4*Lgl#Jc7h^N%4olqEk|tl{LLWh(FX zDU48W%8Y7%Kx(4}|h;wZC>ABXcn6f=J%+xij-$!o>C2nI)YTqXR zqJy|<^m_g|-1K-lP5b`Xpnwh{&R)5Gj^@3{aF$T^rg<@t2LZ{+6A|&p$BR;-gv7s; z<#~)7c?Yf!+Pd{zz0J&4%B(~|T5>GWEY&ySNyEo^K|mwQu@t^^*v+6%9Xll41_{+(Yl zpw7Mg{nhjLfaXiD3zs~(R4Fwze9(Dc9izT{`~Xg2AJGu}x$SLv2?>dst2ZNbnM2Pw zI7ZDs59Z0fygmon&&9k<1&PFf#}@>WI5daZ{T*}JfwZMG`MJ>d{CtB)W!!ScYiH;D z6Rf4A@h5WWoIS@g-ZqWnsZcHIemfxjm$w(UdsBD~rFd%WZr?}4z%X9=oEQ@uADNym zFKsa*^sTr!ly_#EjGV#uUFYD**7^4Dhr?#Cl=SrE@~d&+q=hcGz@~tD{>>dy@4ej* z`pGK=W}p+~8t2mJ#(aJ{v3OC0*yemAPW9S{FI3I&PC=tyBm8xr;fDl$`t*#4E1)qC{Ii;uU>tZD;2zb~f9Cb6t+W)&$b`1Mka>7Qe^f>zN$?m6v_qFNAGllXKR19Yz6h zo)^oH6(8vm$oaJ6BCnzgX0C8$pi2&5QPY; zrm`FC>gu4ExgIQsv)c6XkZ2yG7cP)E&(Z$raWY5H+mklnn7%Y0qCwN*a^=j&`1q)W z+}5I~RTKM1A5~};<#-?r^5zy6_pz`{Pxlt#x!M_!X5O6(B%Q{l?1oE*v6&lB48p_T zJ3D`MSe8Rhnm=yi!xgS@yt3645Pl{iBHG#8%liI(sxaThW?=m=CN2(XU??ak%y2(Y z5~>{nF*@PJTa@;2((R*EB7A%?0|Rm(qu|bmBxa8^4m)31Hx8e6h#=m9?ef**+aTjL zocs&vFk%Iz`cqKQ9Qu5Jz}DfKQy?g!R`mo~G=TZ?3N{g)tRD4+6^p+GL;! zVOFkkn}lkitsSC-c+SD`I8lbJz`k!iHzVU2IXO8Tei5p*cM=2^8(jBGy7$pY(R`V7 z>u)CziTYMsjtPOmj84E*>HZlU-Heg-L>Qj{|5-e(d?n_2@TiX_w#=4nuS=?-=>$8b z*ZG*hkx@N%eQgasB9zdl!3Ry6Gv3U?Mi~BPXB~L>2c8cz>T(l7mMwSfHep)U7o&=u zTb+A{Qc4b1CVT@$8eFv(f776(eF_WClN|P|7Y;2dDjJ?IE-r@A2<(pCgM%E&;n*jo zgX{2JTKhW}oVnb$HZt^+6|==M2iFx|BkFIebQhib-gYssOMS>h`96Xox>Lq``;nsM z^_DvtYaa+Hk)1{-vI!kSXJ{HYRaW3zhLU!YPF>t}zWGyH`$J(7a}8IR#PclC;ZI!b zPxBLua`XfX9Kw}#^|}_n?EelYY`3}}Ubfdl>f$ghcjH30<#$@tCmp6Hw+H2f8%!Jt zaw?KJx@8ut2Y-g*aBv8JMh#m;NElnXt}{D+TI8UeD&^Drxh77Utz5LYj&&s#7>cg3 zvGKWO;%=e4?=Pycdik5vUf0%W!NR}iJ0)Z(DPG4`C9^%!)A>C`P;pItsvE!LBetfap~(O_U7WfA`ua6RCj1b1 zKbQWHY6C6{%;!e+V*je6$qx8$c5tE{R#(|79#LlgYt_@v_}TI6*DZa0{g+=r!v)ua z1vE4gw-qu#W6zH^=bQb})y{hWF@m%(4A#O&m=3}MFbXEUDV;Fs zzFc@%Rq9YzQBl$EbzY=a4E*VKb-g?TelqhB_+VvL6KvqTTzv${PAd^(dVB|8JdA{l zjPIs;EBJvh*m!E{yI6L20--RziQ(X6HpT1*v(L(vjY*lyu5#Mdr+x5!uG$w0C=LI z?9(fc8e#ec(9lu%S)m5Q7CuRTw2rQ>or6PmUEOJY?D|9(+_A;$76VOS;@q2e?+|14 zTZ@av$B%`~;8Q?OLj!g|2l%iN99-DEuB`O8ZoNHsHt{~o9$sF^AiTYtUw8M|!ju)S5rvI$0>fW~G8HoV z%}UZ_=LDd9uMt@VE>@bPp7-z0H=vhVxQ-<`8>rGw*a0$Pc^a`wiooc8|v zD=7X#K{8a?RmHK~)}Da}?~bAe{x#h2y514ElbgYJn5jk*D6fUPdA_mV5Ht5kL)FBs zNN&_Ph3l8?k(Vi&im`1@4jXDj=b~dZx}U53+*=hgMHforxnrl7Nxv#qKE>j&dXs;3 z936@bYwiAA+7>_AEYvWpeD6U0?JG2#iGfk2w7OHx{Fbef#O=%j^jo)4M~7AiHSLGF z7}U^huFq-BleBiwLa@VJ)$eL15}M&eof=Kh#}ME@_&hT4w5|s0>vZJ(`1F~h>eRE! z9G+lPy?V?tYR8+7PI!}iR@lirMwWDR)P`#8+Se*RPP;#@#H7=LJGf)}JiTje{%pn- zJP(uq9u;Vz%9Cz17u@ogYN2Z2&lLNYHI;lclcx9Bc!h6Jcw;XZDE+weWHT!Int5$J zdpjA!|0z1+-oV)bV0IV&#Tb_dBo#U&q~thh`wIg$MeKsj>rHL`qkI;AU+2&nS>d^o?eTc|VNv-ob9v)_W6h)Y1Atg0%iGxIOR+xF$*4OLKx4t1$ z7RYiAI9puxBlMg+nM9#)jl|5%%<+#dmV+It&L+k$tk4T?yvuatV0~?+^|a2_$8w5F z@ObP<|(A$c!bXe%|Lv6wcrBF|?P9KUmInHlhPPufdr6VBTg0-|%l0LIY zrNC^U^Cedqpn<2Z*>7#ve&^!7+xKkur%SbuE+Du^LV|)YeDx$yN3%w&I0}_0VtQk} z1c#~$Kg3uinga{VM};uhu~LH}L52#3LHjzQT%{l#rglpAT6r?=R=sj^-08_r|GKncQGcd^`9UOS?a(d$cFWy6s8QZr>1pb2 z39k+DA#4H}E>I;kiZr@|CUG`K>kM1$i;k+D;~2D>W!Wc1Oiih&_vMsI=<^}(bamy0 z&#Wb*w$wql2D?~6~3)if4?&B~JBs7%s@=j_5R}te*ch$g8MRBv%M8>Xm!&?Hi(~ z^p~X+nS^zl@Sd;8WrKIpJy#qaihWP^q`%3MWSn7g^w}(T$3ejThkf{3BG88OHI+bw0 z+Y3oPLB$#mU*iU$JwTvLC6>je25E2V%S(s$?01%Nv3+J&-yiy`POE9=ll@20kdj91 zj`TBIp&O##A%5@pA!-jhPbSH4*dX)nxjmg}i?xz5dFkXC8Z_LilF^BYk^YUv{^9!G ziT@gOdr7yO>YZJ;vq&0bIlij%DuYs za(+GYdG~~0`9hiU-m3}jNHo=ZT&gcv2}LY;YN;7xFtjihP389UXReY!_XkaStHa(vG;dAR_Ob*P&D~?>4Bs>z<)>|1f>!9PnW9{2&F!#Rc zoVe+HYWvP+O_Tm7bIls-sSICQap=Azo%SJc5Dh^2KF}<&@LvZg3lmk1+*$egfq-iP zAmsujQBp!;*86JNyLKtbqINYexud72ivA&QIuf=mEGlUp9E^s5f%C>Fi`mmeng4=2 z|5^bhQ`X|*y4!i$24k}ez~~!YUEr&aeKkf0Fx4+GkRraD(tR6@VoDUe9|qNbMn<@#p{ zPp;_s!j2TOS_3vK25QEt&|;gm$YfHElJa5pA?2by>bF8S8u7E0RSP9D#tk^!o9LzU zN!)hGSYNWV`nj~}DhVnjM83QgW8~_rE@tFY=y+rerEzE_Y5fB3=>!$^y<`t^ z^LeKCs(aBs|GA-(QdDY^BadaBUMV#Vjf9fxsL*rfVe=}ZIh;;X$YZbSXwTy-^H|5$~D;6#NJ*rXOQ$$kr_P zK!u*|Vm;Bj+;p3SyP21YDqyU_1dBUuXh;R7O_oGi@Mz#1?3hlMwVGOC4(8_Kdhz&y z#+O^@#Dn>=%g4#yeSQ`C)4wvazWQogfAc@7brJFvzA;zv8rO$z{Lm^>sUYFuD?zu* zy6;lWvG_8ZJsn1N5DfT6rT-B3PTVuX%e>a+Q^%uuhUm^eZ7ueFecNPgbO9+1I2)4{ z(InJT*-&f74>w&3d3T3T##@O#2>iKwlBh^W#IJdK&fDXjZ|^=?JvTSNC85JB-Yh;S^00TtvXUp&Bq_ZC!gk83ZSNHJ4QKwOsgDXW1CWtb1U4r zk`iAOoa^gW*>OC%ofh=?)T72lAvq;Ti#-t(5cyZK@;sqt!%do3%G_6 zcT|p9pQ+9N^o)+x!6TcWVCI{LbkiJY*K$qb(EdP@D7tguz;kPRJHM%EW~=7({C4?0 z^VNY|5a1p@ery&WS~#+Px@qHWas0U4e;OY~5m3J>ARCCZ+nSoLKSloovo5RO3{pc2 zARaTh@&Z&^tK#+Q3B0rLI0vc~Awd*pXLs$BlM~x1rxCkhkQ0z9`qWgY5~5{hh7_bL zaq+t_?D8BADLaQ(XfSvHfrp%YkU@H`gC@@|M+q2~xQRR~M(hQ@P_Mqp30nSH)E6j&w7!vV2GM+(S=J zT)fUFW{@_ll$2D?mzJJn_GlLFkNN4ITI7Ln--25EgUFB@)oR|4zsT{vQ}*M~W5wHW zP_FS#k+T$GxY>ARMq$twg<$y@T%^XpDbi3KtfX5h-7yq0HNCw?G~z(0-@rz4Z=vTn zJSy@k$kE-+oO{)~^U<_EL4lHV5t#>Wp^Ekc~De1(pQ% z{IJ;l69Id);LDfFZ~PP#w?f5)_4K9-hKqY=B{G6*f@o-HewbHbBCcXPjiBY--EAkm zbt~=~TwONECjcTODJx3}VGl@d@SShG1XI{mBllm1PVW-5I~oknhllqSbb04+d|kO- z8R?W#Q&HWqVYUINZi;sb>JfC#w6u(wIhB5s(RCMVTl$fFyu?-Gbzc=f<0SA|aYf=# zoRXiT@9phx+*1h^`^ct7Pg_BpsX+4_1<$X~42tm8)fHIfnBR?0QL`$%2#yUr4Du!WX9ICQoaNdJ}PPh(3fp@=sD5 zj)NDY)yRwv<3d^2ZG!>)!U!77YjxhtP_?XNquX@GF~!vnZKcE%{6DYW%_~2S>yu20 z`Jh$2Oq$@A&QY^%qR<$KBxfR*F(uVLwz>@Cc|s<8pIz4`2*O@k60a z)FM}y;679tQhiu7yes~6PsML^tpQP%B6|;KnS0$|DYG9NG53-nqISp+2Up@BYDkM6=+nk9twA4`=C(!)dfEJe z=MkiwDJVWdH^ln#WoK_M)vH%A7*E+AVq*&dpr+gXjpDOdcFcW@W}CjM5j|y0lExVHjRcTG)zL1cJ0K-!Ulb0Xi>(7$2{1K zZ@@Xx0Yc;AVwoTLYX<79i=u6GP=T!w5^ zD6PL)ua|{;P58e#b$vIZs07 zNHhs17H#rj#n`ob{nOiB1BlKPQsiCR#0<$dmuz3!n=;x2GGVv^u0s#^YaIHH5u@QgoOdofiF(mG3D&PjePGw z14X`ffY$sO9&UvILhd;h9qtz;nv-?E`xge|uU6Lnl{D~}S@Kbnt3GE~wC4l~Kt?i6 z=nCP{ihn7k(SEXMV%cO!3dT-E}GBN~|ID7osppejq{hE)D55!-|uEgpiHb*?Jfx!XEgcL}Kpaw7rlI1ASfKU8pYTOAR#NGbh z@RiNYShc=ew{F29k^wg-o9F*kU2(bcUlxCFnU@#E^&0PC*FWeiu5NyeT?oVXD#shf z$DrbT+jW!tSyO#j-I-kFT&7WL``%%Bb^^Uz=7zbc{Xg71D*4>+*{N&e=4a>U{U>I% zcE2#5Q$KgOSg>n6p>rQ4;uDVd`5MfMO(jdk!iW43w1HsE+n*ZGe07`)|3LHRshS1) zJ2s=qUiQij4`uWpIIgS6LRr!v*xt)tr4ib^EJ;Y>!%8kh{%m-z)31Z;KIVfg*%>)- zHQ~itd{I~MM*msWOU1I?nf)Gq2}?=pa>`UwXD@5h?QL3~2ha_Kp!P|wx}1tr3WK1%A!Nw(=mFd~h{k6hozD7FzZ7ta~^GlmAyG0-?cxFPGN)%aScy;KW+`v%E;I zic)O6w5KOAN#jiqZt8RzO>$*+8UL3Lcb7H(#$Tl@mwKY~h|HZFI8_g-(&M75;Swk* zGRU|P&tpJ)9+dW2R^A3{hKN^2S9q#yQSsTs0=~VQ_Fuj$%UkbC21+_UfAMiD{d{jy zns=p-$1jIj4<`2I728rC1Zbf#*q{{U}cZ*V>cd(>Ua*y ze$o9F2hAXIYIKl5!Mlw&1v@?D0ZEbP*}V-p<;YK3F#W)aCZNPXgV({P1vE4f5{GWz zy(a4hNN0bZea+a49id!xm`DJKwF9IB9X*z zaBwhL&>n~+d?&NFkc&M)E9-`NbO#DGpx&(^1P&J`cJ=l3$eETRW7zyP3kwUF8))$N zpiP!%iht>}rea;Uh!5=$0)fcP$oL@_S*SvXG_804wf--|@lC^j|2|Y)=x-!Iz=2Hw z#B5L2kTwa#Rp?7_la7P38`IyDr@p8 z#=!VESBIt@3$k9rs9SmRYZj$2vP0#KLZpiG5&6-!{)2lW<{zj&Y?7X1k-ur3AywDB z&@GnQJlMqDQ|E3kJ-A}}G?ei{fYrpv_WAOsN)0*^(_I^Fa;L#I`}hK-^`~nHn}YX= zbWR|zK?6$t{_=up_1YTcaG>SAD%WDK;N{yn4;X`yJtr(i(bCcaIg%XCG3YYCe*O9! zMOCG~Hp}xcTAptXj!9DhGcWeyn~*@cqm$F4$B#Q;P)&q`6Qs>$&?asGI1YCf{dzs3 z^9wSOG71V2IUU+H*2JJ^4A7C?6TN3(=51m^g?t|=DJemfd*Oa$Nlrl_ofDZ?= zVM*heInn{L@!Egtyg4okFR`GYAcKBm3V0g3tNH2Ux-l~@^P$Mk6qv#B{1o0_>wyZQW=K`>VAdS4%VQ$!U|JSv!|w#o*$96sz^#51bux|FRi zpq$%+6ar^gMEBx=$S!#P+3-D)%nrm2AZ&bR?A6W2w3mU}VC>yU#a!R^?$g!x?$MQH zys(HVRDt8^+mcMta4^h1Fl1BnFr@tWAfTn?A5^VXOvOU>h?JBR4Gn!|Z3}v#f#G3M zko%BOKstLmyk8J_eP?EtQTZiiA;(CqM5A*zWu7Kh3L6JIF_P~iyb8@iza*q&$T?{f zp?!97cQ<5B+!;QJ;^dA7jM;qM{GE*rH9IqMdSbCyVvwQ2S**7Qc?=#*9ky-Oi;K$w z8{8)!ThV!uHvF51nK(koZoEFv&5yzWOB)4mR;Hg2Oa*v@oY8T;p78sk_};_Bq@tnu zw3TKJbp}U>3U+HC17s!@iJhkR(NpExSG@{YY44w~1!^;QFXU+=ZvQ3d&yo9~o=s-q zjK4cB>EUqj0#($v+2M3x@pnQTQ;hTKM9_$wJ(sniKB;j%E2v|Xi@DER*CjqB%gh*i zE)b*`v_{=(Y1Kp3xjXcxsuANJj*_A$ok@D|=xJV@ekx?v-U6A4h(q4Lv2)^1lSjles_0nEftBX6In2W|OMI3#B85Y}{iBE|- zW=c|<^Rn#Kh&V(7GLz#&?oOPaFMnx$Wm8X|J^$zs|$l0I0-@F;o?QZ zT)b5J9=oV893g`z7pHyROAz@N&s4C5g=cWIC&C*I6FQK{dr;l%H%80fhVPn{zxj!R z1bP6{I2}yCdR0K_)c~&WA`r$z<+J(4#j#?~8fTv2X90p-g2~RN&+) zNx~!mH^01@Zg7Q;?>|?`-cE<+-t$Wa_$|4QGXu))+e*N01W94(X0SxtU(wMY3)PWF!B#4I2c>(O)Zo1|} z?r|DzaD52}y>sHlzw)OB2($tt;+_sJ zzm4PKiH%OSNFv<^7yb}}?f8zN8}MoM$j>e+ieObC4$1%FRH&l=k=Z}UpTdR*h0Bwh z_JFa$X!8;>OEEF=1LM@+2(YsyfPwQ13xh$xx*aO^3#_{ySfvxxZx+Ka<$km=hsaN}=Tanm z=gTq~|1E)nA`8wNxVifUlHG8by$KpU+$JhkI-;ztEe-Z4^e>i^wU3Z}m?s0@Q8#nb z0st9p2IWY6Um{l`>`%8*N=!FxboZF!QT4YZKlF{cPsl?DB&1DioNOXwPz0f@KIo_tPcxaWo#P3DJ^YRpO?0jVL&xSdyZNNWCJIsCS14DX%zL<^Xy<1c6;E#p^EA< zo4OgpUhUJ`+&CzD@}BJlKVxb#+vKNyGZAp|W@h>_DFRQ7`j`%g-Kg5p&6V^?^<(Jp zq?xo|8Bys-Ytu6~o?_=&M@Mk)AKqLt{%vd?71#Zh3PrllTGMa%48<1v#TcGAXBG$Z zhj#Y-{h~m5h5Sf|GqaWqtKR`8zjcd0JO~NxvZdkn*0*~U_jbHXba6GdO}68ThJwPG z_T>Wl3%7gaXe4QAI8jz{5R@e897^3~GgWO*ps%N`4@F zOo*_HO&){c{Tv%_7KQ?zqftXBBV}g&IC~f;0Kx78R%Q%xFCg#0n!~SYKXn=pX*K;9HD8>ihZ z4LOC}hT;lBN)IGSYoTVJ!mtDbROECSt#aN@P1B_;Ihz%-Df z9TrJC$4x*4!4_5-0K!QGJ^#+mPR6%y$zXuN%l4mw&A|&aL{Cr8@1)luaL_}m3vV?M zhwY7ArOxbdKJ)xE*eJ08MVOqLTAYs49DcIWpABgYz!iWBQQ|g-Gg_YaFeX*>k0qNl zS_Fh5V0ziz+4=G2g#sMhtSSa-*yVK|&pkqsa zwQY#muB{ku)7`^KK*EB^Q!XXtb5m1O&Lr}zM^Y@vwLi~fQiwa3VG}|ah@{Y(AtNFw zd^WIY02T`iWcTlo7R5eE9zc9c((2gQdK>L*OHq;Fz4pLr(~9U~?-`(ceu4h;^Yb5d znDW7)hM;IySGSqg7mr}+HKh!rfM98?U`mDo;1w7bGEMT7X)FcUX<@1ApW`Q8O$@u$Qg zaIM5;p4Zybby^0d=08@?yp(uu7~?I1(3?-`P`$FX+BU>2(=20xV~l4klb$52@ZrhN zGsbpvtJ`5HrZipq3qd_0;yi4vt~WQX44Ar?Jf-FmG2m7QQ>oxTViqh~er$G5wGp(N zwVM*R3qJw+a4NLVSF?T1OS{An6wQu^Y{X0vZh^I&>ObKfZ!_tVmh`$JXEv+Rb1aRJy| zsy8=gcKP)9niqs$vczfVGK`}!-bi!lU(C(t;E1=z3V(ZlD6AKg>w!&Fl;e|!60Yrg zG-b>YT9q`(t-=xc2H7?;DtOd;4!e5?l@-+!TBkRhnNzyA{2esyW*^dH68!_MY0G2l zQQ8-qf1MUr=pQPp4F)Fs;&uzw$eM*7#Y$+Kp_nl9GyG+G;wH1e<`g|K@G*CRV~v+N zlZIQcrj!|!BS8q0oE`k|w}giYx$sW)G%TUq>cwN1r9@K>ctAmW0n6s!+#J$21epLt zg@I8H4O)j14%fZs$PA=dc0c9rjb{-;=^lHXWl~b&9M<$ven`0m&{hgg&P0G(A@}zp zQ3hlRMd+2FhlWq0aM+YVxdKp_&@lEunU$21B4=QD&{wf615Od_gH3^$0GMd;4?AIA z1q_!zD%qfNWp#B96kMR@W0mv8su!K!zu$+QDN$)@OsP1K*@T5N@K{krOP=)X>_P%7v$j?vSPAXH186Y~;X)9fGvL_qO5bKG&Q7 zyp+Q2c0dD94$s+2w#VsWe70LSQUkHEVFrLruCyCwUvMOlu?AmXU$SEgu9&tgIedbb zt!BZh}IX|TDK|8^)Um7*ZyNZC$KZO551T^Ld#>D!2 zuq2^8M~XL+^o_a<4Yn)gqM~z?^s+C|U0oxy(pG*CpUwvF2JPNj{ke+mgO;s)wgsPa z_*J(~SJXxjN}zI421E%SUG*0z{d8R&g22P(#-+CYHCwG?%7 z>%)4-XT}KWSr<~zO?UuUgCF8WQQpiItA|aszBE z!TO9b#L5MgRUKoAXM~~7zuTzvxAGaP6Dl2J4`x13>pa1yJ-@j}d zUI0TRvYV#qRwE=bd^4CrKYv~zcz@xGWWsD__}1)M?e-{|?e^v$ggqavGw@m>@p2sg zz^j?!j%7Uc{!X3PM^=*7e>#gQg;WrPoAdnmw5SOBcJA;RT+Yp}RV-IO6Uh^+S1R;#TvZ(h z2d_t)v_V!^m^XT!8cREc3L9~w!>FO^pH{EY7y%xpI&LnPbc&aLh7zI{+MeCLJtUD> zRq^PX-8&?8y#xp1SxMkr06NTD$fNlL`1Rj_tG}`|ijl}8;dJw}3HNaK5qGn;70W}B zQAfZ1-O7aS^QK#KxgXjyZudveB8u^xVuh`j3*nZ}<`$v&h}aL^pHv=|DE&ss3CxK$ zlgqH&uA}!Lt{4bB+vF$U_*Oy`CV`qMp*n+juT`+NxZ2voKE?2;VC!O#^iE1oNc+ns zr-_p(+dJCisx4-{Fa4!*-DY{hx}$kA`cwY()a0F3l<%Q03Y zRsfHjjtRIcl7z8O7IiXJ=<0xWLS`TnP16Wfh8#+6n?pxiq+VK0p-=;#z=08@`TzqX zqOkB^2y^2PBUVM)`291@+$@P46K8ZkXL&U$AVcT9rlIGtEBb-lRwW@}d*3H1J)M8W zQ@Lo^veD)x+|R{xxiPq~h?Q>ln3%Zd3t>gTa|O|ZqoaRCyT)+rYcRwKcG-zncE;e+ zcorz%BPf6a3pbauBRPONLsu{ZqVHaZGo<#KYC(?497Cx#X0C^wMp{pK#V5mcvVT&L zJxUDRc_QW1&yeDI!`KXM81qqcw86ZDoWws7JK9uyESUh4FP^@`PCU2i1nkN(gyhX} zsFI`U|7qI2;iN3jtweqBaN%#GHIJ`BjyLzmu|G0>h+hR4h6<>ne>|niQi5*NJ-`)9 z)H2^m=D|1|J979RL--v}Q1R-3%MB^RO{}h9%D~#UQ`WvHsISE(U2$!^%6uuP?=U@R zK|x5`#e%Dl+8T0<^Y9tXN0>8qR-%<%j3=HydGg&BLgzuhyMZoOrtqf}1+^VhIs?t{ zbKY~d;Aft91viOv;_lH^q7~z((j{y*z8u|775Qe6F(joI_pyD#yVY>JyJMm){iZ7m z85{sGP(ZA+Z|+y1?i1r)3~=ySX>} z^W(-;MZCp`UiW|NZaNk^`Y8x(TMPpmiuF$9Hd)?aJo(i1?ghQs3-l5{+hnCKfg;H+ zS*!S>vNQitqrB?TO>TC61*L*Kc^oh0%5gOK2j$gOj=aV4jvaIUglt$*Tt~xhp^~tc zU#qP8Lquw0s^gin)HxBe2S($7S9^#m3;o#08E1gktyQwk$ujHXgifTx*fMgz_Wlql zHhj_x3JaTOX7rQVL#bYl5Ki7Md@7uY$PH?Xqw;9*%-PQ9PcgNoTtod(ELE17=>vNf z*epkX(3dte^Iz?TzqJy#9yJ69w56>L60DJAA&=UE@8eKKL`B)_ss4l!9X9B|lCV3A z?=g;B`E)X>=jY*j_R>CfeGZYW=$IH-Q_E{?Z2WO+W^#sk>|FH1vxg3i8nd^82t%aV zzQH!G-Hqw79ESV8EW1PB)bY;GBP^GT&i24d2DrB}n(MWb2$)aq$~u-rNEHkOLJ$Tq zI5W8k4ryxx1X79ATQ5HI4jA3LjpD?xrhLQL#ZT8KhSAGwVnXFu?=3s$y`y7_KYj6g z11R;{sK$XpIKJf^HVQs5bkC)fyum_>X)j zk~TrhT;UEn&WE(-Uw%D$&#eY+Rm%E9S_)-wL`?hb>do(d=_I*-{|i^+v^B#G`I!p_ zhAt9CPc&b&=dMaq1+n>IJIDLfRCED)hFE+Q5&6}9v~=?L#-PAG337!36zEYH7@-@QOkgz=HKwzb)VS=49w@&f`UZo@1LKXw zE`eg+PL6I~mMl|*{@$9?^M4&@ZzH-rR|L;DCRr`$ChCMMOj!i3l%rxAxN&6DB= z#ya1LC_0z3R*YpCA?`w@8tbRta)qB96mx?)5$dINNkt<%j8j`w3f{Gkw^QI4*(M&@ zZ~A_jYR5YrDt#-gaA?lY5$zx(cwP!h+C;ai#WB zwxW{5k~?5d3CjiE@|0;6!{Sq{uCph>0>y=e$eeXH%#vW$KzBrGd|8Lh%gd{xs*3SW znZH0`r%Vd3OBVTE^Dn%*KwCz2UMoQp<V63 zHhu9x#FwdV+{Wfj{SxvPFXOf_7oK1gj%qAC z(U&rmrbJOE5?|_kz-pRCwUR_U;F9KL_c8Sh_Ze+T*m~)uqfD2wI51WV_NN8CPpf|4 z3T>W{vr>A+;#-o&6t%W?lQ2X&?3S$p+4VG?JaIpmPsYZJuBT~Ne6!#MisveYp7lW< z<0`e@6)9CrdtYCopQSh~_fj%3Sr4_-Ff;ct^-W_e*Mf{vcX>2{l;&aC?C%6L^0xws zNr{oJk~GSTR)-xH{_C%_Rq5_^4MmI1CCRDe-O-X2(ePWhR*W@IeMaMy0vD;_=KpIF z{pYw|UAvzrb@=*3Dkr~41@X^I*T+FMH!m>9aD{yor=SzBLFIAxG9}A051+WIIS_ft z*0|Hu>IF(SxtD_rq*S|NI*j)O!*^BO?GKZR0E+c@oPe8lU0~&V`)ho5Cf!dCEQ(}i z^f81%5>v3`pq3~ozc(cdk-M5gy4{w0Yu6JK<36h2zU+cFQQylN>_Z+w%QNh`4x{$A zHrT!*3MsnoWbdiRPnDEzH_v&DpQgU$Kp8F(aRM*dorCgKUY51kOec|=5?VYOvlon|nOSu`!J zx{GAtLrw90P2*1vs-NzKiW!cixs_;?FFd4YCRJekv^Gf1hSkeVj0u({`M)YvSUAEh zOvh-6o&!Om8^VS1s$`0A-{2~3rF!_-Qn{Ec?vbJ{{RTxNc^bF=_g~iMnO`N1T?`5f zW71~S?$bx*?v-^ORI?2@o81Mr;WkySWVj7SJ*lb$?$Y!T8G4Qykw$OV$6JLe>**vp z3rhrdV#PVTC3r_BEBa~TQxVcc4!w?rZ%X*$eof76-16%VS2cfqH;`7^VLs3YoX602 z=Rga_GZloPf?{%mK*b;J;gcs^dE46n+OWUlM{8+qg$;6oPELmj!Nmd1xdk##aq&;` zDj(*(2&ZSp6I096lPVm_$$IX=tt*`8eCDi_z_HiNe($!q-+PX4bo{Z_+_pV8Z{T~? zKC}%rI5JSkMP6wOG{CKlqJr6`Y2M%L-t|+IhPLwqfiKDW70d-|LT5r9S|tiq00bv_ z5rGAA=#i$g-h0{<{6vQ*PR|FK3e(Cz3P7c2kIOG4K zBpK|?K3O|z2PuGksMdA+3R92qAtkh=-**uLVxazjQQ^xF?_?RtWF1ZuR;PZQBHf$^ zDc-DA|C9QWu6JCkUeF#>J*7RIIyAlZR`YkGii_`Usdw}U6QTQBu^oxtp<+6MQ|%w0 z%w{E2G>nolxH?+zL_aniv~esaRJBa0;;#SX`0-@z!JH+@CJmiEPJ#7jf-sRn#^Zn0 z``;cTK?Pw5J8`92%bcpu{{%fZ)x;^xUw}9L=yEqpiHX!`n}DIAck{A@CIUrpmvdT( z{=1&Mq-2ovJz&RF;EHNpsSFbJGpR+z8^MG6p&BHp&7$iror^A3cg4*ckuvLV>RbSg6wP z@51#A{xzib{G=-7THnrN&VjRtZ zrD|vv=kW)(HS(REtcnwk?~E8UzbJO3k|-ynRIV|Hf%lxJGB0}Xw?%=zzvvGqoH$F3!YESV81edeFt8F%3f(0iPm?=yrXCCja zIEotZvRxr2Rp771?5A*cagT<&YTd{AC%SWLIrVns6aeHRl=Hv7-=5xfqp{XmK&mcn zdK8I-i8->;hTyFceD8s{g)>9CedUS!Te3fN4~sVK=Njj_@&(EQ(mP}+1m?r#@p@Uu&o)XQ(~4baxw9$i6SOZzuoA&Zn|$7Ahl z^bKIYD+MRQ-+RET98_Cfb@HvyvFnfV4~Q(oZn7H;8bLv!Z+}(sN8KBOwGA+LV}7V^ z@^76IO_(1kCMIR0>2HNo{I&ND+qrS&Sm?N`G-nbDdV8LVw+ydL9BB7qXk+H zJj*Si>vxl8LiSKx7K4ls9EG|4(b`*_!iru$$}|hI{wXi9IA;E^r5P5DW|_ymS@;C) z=wN&*A1z2|YtuCTeIZ)VlPHBM$M+d&F@BTYJLTbNk3|u^u3>N9S<=F2c6;^Xy@9(d zb>wMycjF9M9@Aj<5?6k2p1_(p!Np}2WHL|wxQ2%vmRo$sFg?gCHNMEfkh*p8kui<ZhBle-9aYHAtV1YP-Sf?XK!&ITQHSTE9EoWQ2NwH1fkS*?k%#vVqsReSbYhc@CV0Rcq2IqVlM^nXM8j*DBpMMpQ1 z2)D0DIw;{iLn<1}V;HlK^at06t-Q8`n8o~5JX=&N?EKkrtD+Jr>bHm)dhu)R# zLK%hP&v3hO(?A4R;eFc3T*@S(=!TM5ZaUiTvwlxy;$kp-=FeUi&QYu4zoun|;^kz| z-gJ3F5*CU7N7Yw`MHzkHlG2JGA+3N&gQPS_4n52O(jh6`(jnb3bi)8Mlqj8|gn;w_ z(%lk6ND186-#_lX&x4=%gy%i`ti9ISYokB#h}LsP!8j8pCwA;a9%viet7aRtibt@3 zVXFWfu&nzt%bPE+9w+zUyNN^tZoMnZ!ArhEMRf;?HDbDGNNuo8J6oTu=_3GH8aGgc zRo&9#F0VLm9M`Y`pAyrk#ohJZdalHl5-=q} zTeCR4F>iub{qU(x2_}PoaIoi*jyAVtlf&rF!zz-V9XxH;=k#B`06L2iH%yjTA^+Rg z?ZIRT&z{GO&N58k?rM`darINp0Hyr^RAkg`K`ZH%N;1b zSUlXz@H7QoJhEB$mM>^cOkYWNjjx4JsRK-fEG9h;t{3U5<2$Q#7n5c=SnD0q(_zjh z)+J1>kE9@PHOpYNo$!d>=oj+9`I&A>F{``eftzy^$5gy5TnA_y)?a8X3I~eNt?G+y zzR>O`u#uku=t~|@P6KTiKVSy~I+_u2{@u9$^e}*nL}L{8kCXB}x8J>|`VtT%=u!p> z$2{3EV&ahMC(_%l6XQ_re^Z!W8Ne9PWS&Ury>us>C4k4nA{F>%2r$BGG;xnSqMn$R zp2I>Un;|Q|Lrj%aOW3-6FMF6aE5FS30v4rSmMC19!M zju{e>PNL@OzfR3q8Dv>vl(Eu$FJilvT&APnO@pyfyC5B}&#n#ab% z(w$t%jc4S@LZs6#>Q5k$!z~gm#z3s#(c-!bOy1xDo;?q-#SeZDZE*Hnwqq>0df*nz zj06et_SW8s5H11TS5q)taLs=nl~I_CV=DXA+;>xOK|*h*bS{Zsy~|H&+{^x>iAYFR zjEnWYH$}*tp3%n^Xmh5M<5}rT>0nOhvDtVPddc3A5neeKaI)d=6aBp8igEH1MHX$x zQ~lU5_t~sw*vDzXP`_^khXmV$79l+j`69=eTh7woMO*1@|$uGh3R(gPdEmJ{m=H=Pw~=O@q!%ZGicvmn5d+UV2)18!JLH=CWU z9aD$G4;58s73ONz_{DK-Tzw5w9SGSfe`;pMPKJ}aVm{W6_<8-FVO~l(U+3slB<8nX zXKU|Ab-JAQ%d^`qmEgr@>XpWmwpEb7=>V#T>u%%+q(fFy!I%{@8$)6$Ut<7b;{xND znpxpQ2=!y@RY*Cye)vWv79)nRN2Vxi8PeV>b3l}up9g*&Ut(N!+?Zw+Gy9E11^wN; zuXEca#7LkM|8`QTtEKmnv?u+gIc9S=XXb*8EEj(o#}o~<#=xE*<^mGMC<=JY09zS7 zRrIyvNHWoM@>(A}8j!|4pkhD+P~$?S93V|fMWy8JEuyYoGb-sC_kolj)j|d^xTAnQ zNOi7LnvCw?md|XJo;!IDgf#{GP}SH|0bDd=%RHSFJHSR;e-uj{8xZu8_K!YkZS`6W zW0z${Q0vr-dk;~M^Zpc3_0f$D#m-qO9(JjI?AW5zyBI>Q2Y#wP?@QRai#m)xtYaht z0KpAZjK$QnB4o+H)Xqkzjt^3gf~>GuxEV>5N7kWRL z*4)?}hD>m+OSLv|ulE~8&+>fPX{Vm{Rf3=w2wpM2pmyQ>{3R2BmGX+2T^%gtL0v|0 zXMasQPcm;x&A9WLob2$YXONjhBCBWN34QY*GGfC1qPyrLqxn(#^$NPi~Y<2R2h z5|CR*eq0{~pupXI)WAU@#DILp$OhDB><*LBI?H~e?EXFFLg7YY-BpAn3I`A8k!oQ= zekcG z*VkUVtyL`ka#F1^b2B>sWCgZ-y4(^sObIZEPoG^s20|$ib`p0P_ewq$pN?ma9Rx=HIjzgms(U0T{};z_Lee{(jhtO4;}t zaHIkAjxCT@Ub2b=>KF%a>*f1rJ#tY<6t1-ZP@uOn^KeOFPpj1m4{eNUt@jBabil@by5@t$n1u^9M~GI*c{3G+un+s z3OA;DbX0%Id9m1tn9Tn@>ohr>|7BjRVbZbHZhBYPD-{*}#gpuH0(XD1V{{`ArDqXK z49<}VDGp|6^ZJdYXxMx(4nAnjYRTP0-Yj?(gDzBHwEgI)8d)J%KE+;Bn|Uc!r4f=g z@ptm*ZYrU@z?rL3(Wdd$eyu!ThRcz$vs+6S=IHOiKVwVFK3_W2lA~7EvZ1&^oSJ$;W3n-@QQX+0VBzht@Fo!#YscvjP3I+* z#WL&t=e*MkV1DjnMGFWH-mc?e4I2*WP{A4HDUZF<*30G; zQj9w_^xNzg5s&oQ=>G2Z0i{*}bDLzfwpN`CWDu|<`g=0W6X<&O2B-Xhx|DqE>ZyjQ zKVw&6|M;&240%d_hnAvPnHbs&k4?L~(U1%kh@;h!40FR5xP;5+yulp_o^1^4__ro( z8;>;2&jV}I!A88#G zyCVOZ3HG+d5jj1Z@qONUc8LsdKfx0sEy>V?Q?a3#^&2KElm$^Kc)Q>Q*>Q#@wYXvi%=9IgfIJq4CJ*GF=7zi zS%v8s9p)n{xT7du_5nGS8L+X{PoKtp8_`NRR5!A1lsT$o(qxVzljgggUMk&<#CzC1jIs) z_|tCB6*+Iem~4fu(M`^-p2}19q!tDH;ixJ|CiHo2G0UzE`$dcVUV)_ge5<Bb;^^e$^|pb{J#r>dth=oetROO>z7bDy7iq}*n)VQ;dMh=ni1l{JO0b|QciQ%DKAEy z%pT|cmF7-h?Qwvf8@!KpPB~3?Z6+s!I}gBIt>bV(v05!$tkW0*K`1gkg-|;q*?_6R zwZUqL63DgC?Y%|yCxdVuKkFV*9p}Zt`Ndc}LQSas`no*^irm-Gz~9vS zWU76!9GH{;LpvYKku;bcgs19ieZk;_Q{<8F{(RqJ+OR{{2aUo&; zi^T8Y88m{$&S{^Uk!HJRh2FMG_`{a1hm+BRas&t$(U(n+nwfS#JTvV1J1O6H6Mc4J zS>a^T`pI59z15MLGVfJt3D24$xs|7ekp@*)`>D|LXnbxSS4D^I8@!%z0`Ic^$U*gt zOoE12uOQFA>x@>>=N0xAv&%BuD*qhii=-@Qp<6yvrjbzh<2`@ipTM0t@ARxnWke*; z?sxB(^XE4jN7(X_Rg;_Vv_yWuf5F>V*sGR~phe*ITOdC4u;aqy-_rX1j;BcBI^bNn zS=M+}@VQBeBR_-6OYb`ZdCUCB~i<6eV z?nDZIjNwj6fk0b+B^HN5pt#E66{;`Ey&U_1TASW$(QQ%3$H%9I@_m&zSV%k%zw9&s zHP!n9Ni>rNR7*Qz`Ql z45VvdTDF_`_mb}?64O3r2^D@HEBtT*timL0gmi$T)8Eex);|_JxS06ukeYF`c6#Qx zUo!hzzW3&)CsiEhqf&vY;VAHx-)){hI=$Wv`i}Z^X`-T_new2|sF|4nE8i9C&|D#y z#@Uv6shuj0m74ek@dNVdq=G*?66et`-L2f)T{G}qfR{MoEuQhV0+pk)vGepbxWS-H zulJ?iE-HtHB#iy5J`6bp27Hvv%*^&_rc>EtzM%-vrp~8!PN6yli4he~xSW`>r#}71 zZ?d7QS~O~so-gRjYWk`m`im3nIm<8Fq}+QiS*i9`XPjZi`Jj30)A@H8tu*s&)!v(} zu`!<$dCTmLSf~qSFNM(ot_g|hOmPH5HRkN>y*KVHV0tv}A)yhAw(gtd>U&-P&OMOv z1&7zey^XUc*kRbO0Met%V*8=%-%LUs=q5ApkZM`ajskmo3MrKx`2cIiV|<*9dX$p{)*$spIaf2aM}LjD>dz~kz5>Z=nHx}@E<#?U;Y zhd{A4j=v17!v(i&6$D=F{v|49v8&RpqBq_lw(i~Z%?tL{kSN;yb-as7bC&W@%GZYNrs%4#|Mu=vi-ey@>#pTTC!qIOLb({9AR zj9G}H5G%LSBcjH5;PI1FG=?h~9RM)Ix-Qk5_wm1#EQi6U zk9vHnX<0QJGOHV_Z5e!w721#+JU#*uO@M#SAJ?fJJk{i;Ai-H+W&v?V9dw8c4_K01 z%^KR52Rac845UtLiS`im698Lt94((8!|q0L!Fu}__6=#fpj%XNtga^> z1UrGR7sP8L4z0R!k+Xc&ld}IRBEIr4)7Wko^5shwoAjx8n)sj4v_#j4+hqFe5}(ox=(5#TI;v8vMKBcYI^C};jc;hCY&KCR4p_KY5y8QD)c7H zN;)S%cT-UpI<VfRDiu5iM`-kxQ?UcTF51s$y11^)WEQpb3V%q zwSW3*eOOAFvmqV4TJfW`>lc7^AIb!r2uK$`x4PRMTIQ^h0j2cW_m25uTkB-4xm7;^ z7J%EW(9DfA_Hq7R3M5uEn?a|t9j4e6~2pGoLc3*cYFrt_gq?NE%+ zNd=2}42*BdZORgN^q0J*y#nvcoed|#EeLVOaJR`DCzzm7E; z0sxuaK$TZ&tZ(I@CcDY%@}w)-QMIXME?b`KR{K= z(0U`qaCNz6D}b4w5Ev#M6|+9*G>)@*fB&ZZ(*1YfXmNAC93+Yp8gnsPzto2+V(Z22qf?W7D z2Sh;tAp@M(!9P7XI4P77=-a7eaJzH{r)NWq6A&r7`J7^gDCZ&&m7bbkhKQnf#1Bw})oa znd1a&fk#h|w!h7KXXdGlph2GbeK{9vB8J`ia&O-XF^!R)xwxZvl~{1!zm^@<2i|Dd z{MJ^ruej~WWA%OrRSwXC)D-l77_T-VgO_0VW(#Mv#-p_n&?q96{cu9->HY1L&k$X(2NU!)Qef>bx8XQ>PS~`29Ql%PT>3*oFiE1mHb#le#u@ub@aUTn?pR zHPQefDi!Voa)^i`DzY@Jv?30&WK80ZsMz2W2sOPu`;dHK&$6~LH$z(O1DS)F7wd=F zt0scqRY!BxU{m&1@7Hy!rZ-iy+;)LG>VA*6obF5|a1X&sH;88_se_>T5j+r;rIuHX zLMGj_KH=TT*4F(X{CHwAfFBQbwsll6Og{Jv^JwV`dE?!seu2n~84`*hvk)McH{vlc za9Wwjnv`E;rlxg<;2_B4&+)eSP_NmmpFBJJn(3opC>BE0_s0JaeXqLR>HbOrx7h>! zteOw$Y{;0=bgq5KUA|zb5nGw%7v#xHg9CuHFH*eayd9c+xsMA(GVz@{v?bp1#U%ex zW{K+FE*r8gX)lF%Np-as2_N^x|=A9>U~Eo`Of)%lj2VkR84dB!Zy}?yFVmgpZ-ca(KB&NIPZjNBl<)dkcUf1}Pp=x) z{~c6=vLrYa%7bOo93?K?G++8tl-1Z(_tBvaQ(L65p?XN9T&Wx+ZGDzEr>;>q7}3`opVph&QM;=aYAYk6>%D?Cc+uCr4j2rYzz8A1jv2br|tfanb?%$@wSfjfA0(qB5KJ)cB@8J z`RLLxk&~~#23@axi47+#CL=(<+X-h}EZB@W7nSfh`aqReXw~+7a52Co#YX@5B=!6y4sD?8HW>NsBdsH#W9vW>9Nc0p{y<5nZbjmO z62$|hhQGXP6hT40`@UBL!_t`YQLQ%Cj|vK|B^J}26p7z6K4*t%EIy9qe+k5_r6DO) z@*aW2Drjupejdj7|lSkdAN{365*WRz+5YwN<|nVxFzm zTf6J#@@TB(A{bw5z5nvvhE5!dTafOS8@y(#3UY9aTbJwbxEW}V#h9G{nAQWYeOGo~ z2%LOrjS2;k7N*HvujZ+5?j8sVOB9xrhjJu=*QaSsf$@wY1cLpj!1Dz)u2pb$i!?$e z@ErD5Y)V*oWILh(zATyQCiwsQ>XfB)G&p{nGBu$N$SI!Pe z_XR(pr)B2n%qNAU&!R_~(IYHDidjrT7;ywxu!E)vTlLO6bQZzW!X?j{$5MalGA26j zM@`#c&Vk$Hs`*Jzaj{F(i-*4d>zXYc@cb71L>DdznZ8Zx-#7wLi=SF84FN^LeMpj%|E;{hOyB&C*wuIFL zT7CP|*QW?9eT=TU>?GW%O-KVeMttWYCZPry!Wird2HE}(dANy+3&Q43GzTqBHFhDW zqPFEN;8E4c>AuR)^sKVILy&#?S+2$bjh2u55t{hpOjM6&=5vQt+yS>`vyma18$y8t zhJUCE2XSO`@R9>j!IqZt{rypRTVv^I76Q?1?+~OEDNLSnCFWc^Y|rt3*HouwXx=QK zpeVN)VUgJD zGxd|6Td~0I$ftKXdJnld+ zyc>{WxZlB!giusBJk&Ym&JSf#?$wvGi1itNo9RAuIJvoYyXunJ$;scUd6;I5_!?u5 zd~y^CH@CNrlZGZ9xo8`bt%*}LqML3TPJH#=2zSK?J7LC-$f;C)j7i!VF(S}%taaWV zWxNy^92&F=zV`TCOSDv`re_~Uy4j7r1kHmHsw5Grwt+DpAiW;X-v?j%1MuxdS{4>J z1fc*92Mxel-TO!Ct&qay!mRSpY`v_vgr)YDmB4hX4AWN>YJxF1>mQe9(+Zio-JN3> zSXzFnzjCVM)XL2oM}0OVCH?P1z^h<86K+xWV#NhlVrm`Tugni%Auj0sFLvpT#MWQ> z7=ymP(#uK%$4MtgJ&q5L{y9u~Ix=`MI`XTz<@CALrj$nBlSlFv-J6eA+$oedD-U(V zUwd54tC?il?8%+j*Eg1?MU41mN(6HOFiwl% z;^;mwqNC%(&}|lRj8){K%o7iSEt#mhtPw`*vv7Z|Ed@%&IO3_V-^9i2>*X)OG?578FK};5xu!uBvg| zs__li0sv_?c-U9(0OJpK1fz1mGCCybrW+hI1aZ`G6pPA!ZvsaS!;#3|M_sH;_SS-? z1PL5K-v*pB2;l*8%jez%8LJ2TD!gB7=Xr|esh1%vgtvqPgVLe-%qn(wyY^3%tvE7> zgoOHdyC?M}tUhVh2k!pM<5$$(1+CiuZTpI731zrOAP`YYYM zcfEk9;PX*wSnHWv` z`hu*slp%ihA&}zwP@hv14X-FRU%#8)4{?6ADEIe4+|Sw~-$vrY*|47VS@?QPzbdYy z-pW2u9``5Z6Gd*|2la?&ebFN9v1oj{jHOr^rWIj{mvT6HPIE*RJosArQKlM)3>4M` zBuR+^YigxT(VJXINVQNkG}AyC4S6dO6YZmmMlI~X>L=J!$K}<-^=W|n%2+^MUfZRe ztF$Z_mvR!003Pw2WyN2l8k~816~8fl#GtYL*Z*8#J}$iT=exCNo#2{)f$)j+!-R3- zlNuda>&Sj5gP&G#wCMah+r%RuV$$t`Esi9E=mgfE?Wuf|O!9W5#S6s*CycZF>S`cOY;vX z?04VCjno0VtgL18b*NaJB&xz`ZmW zR695>#7x-_-@HZ)3f+6a0U{>Y3P}WgKY@+aLvF`^r_ZG(Ncn)Q$9jQ#puY1Gnxy=B?zGw zTx5jsQ+4o+Uy=Sd#kMBphqU|1?9E{A93%;lYQPVDxj05h*Zix#+@J)|J+O>X2f*qs zYcX`=nw|xHZ%*A>AbYoAVPV81B3NeOSeM1HL-W6a>td81 zL=pivrs%KJHz9ukCt`8($NZp#*g{dDglEHb09Ky+?rdf)uGv*_Ay-%^rr)Z9>D&M$ zHp-*eujxf4h$qAdu(i+>VG{XaoC-i7*-D?>eP?FIwEtbmy^;Ohcdvor_Q!p)_4V~; zud=2$8#z@t@=`$WN`0iG_@ZgyHgm>1H zVxn`D$01tP+_JgCr%SOCUMlCWDdTQJ&M<%^DpecMC@i1U|v8f_v{aDn%6wgMr3`S0b5BTxgxsnr zl@VAwz-V%t_-&z9HY^9J_Ny~_?Iu1x9+>Er`0O`WzsF!d~Ck|H4ARgRRPlpe5vaOmY%x zqJq5NC*?)e9PG&`pEafw6A^K#sq-yS6?tB8iTtK4+0F1xVS5M)*X7jqaESY1cEW@N zep7JQK?H%|wU}RUQTfsJ6rZaRVNqF2%2O`?{D&Gt6D8Xu{Ldd%pV zjyv}Fx7M+YzZ-_&_$f9`3eQE%Z}mCqEFIOqsI>5xX2`bjJtnI`ytbeTpb@OLr&y2R z_V!PUkZdXuftl5MV(mVh`ss6T;12g1!Mn6y#weJypStWsQXqB5wyLo}U7uJ6Pa+wYn*2 z023(WG5+HQ{7YNGB2B`A^3WKgTD|^4N4xMHWXO=nGj1|74&YC7vKk;eX%fRVg9W>Zj zIKH6IRlAhz1Xi0J37Dib5YA4w3wqTt5=n$P5SXil?Eh|XJc>Z z#J$x15fhX4)!h(Qy*+=ULf+>LiJSZXmy_5opnA62a~4k*c&iJj^q>nB4JbjG^@zHo zm#~1q{xdPIJI4$rTk9+om_n_dS4ud`uoS)D#LH8sX(=}!XYZD9X!RnE*&^sD*QG6-mjQ~5!ybe~Z6 zB%g_(HvB)}+F((GG219!E>cgM{+SXYqK^UYKNAy3(Zg25lCZ)fk~SMe1>wozY)2)S z2}YnLeexriZWV95?uNH^>Q&kJ7;2*Lc!!UOh{*1^zKo-y`H)%ZaDz>W@!iN&WRVe0 zVT%k>nCzRuT=0wMcN)Xj?R4Vv>V<<@n^KO6BRW)?tuh*Tp6v~0W>P$@mh^QP^hM@s z(JwnZEuK_6s^wnkGA{(%w57*lkCNxo$=KAD2))H`iv+&NWQ*Iay%!_5CwRGHCprta zHfUmF3#SDI&v_}1#^{@|x}ZyE)IleO_x;=74H{~2tFyb4o47p52t++y^^%O>lhW&m zj@;W>cQw;pbClS?Z($O=2Xmx{cH0;E9rPElFYQ@Au+}`|pTvJA0(b69woN<3{8s4l zi(&;APcU>cmU%C2+S0_fu_gGV5PcWW>KFi0qdrt1A$7w4h?9pzclG~m94YOF{P2SN z-kLn{(_Hx!6Rz{3#BRXn{<23DQ0a@b>+l7pJPk~Q`vL6|?p(-E@(IM(u%MkV>o2`n zzJ!~CF=4!_!I^qJ67I<9%ez3~^r7R5gCV+5Xs0)J1uaSwAIyYri%Xv#m6y2i_py}c z4fDzRz58g;>JJoc%svPg8JJ`0$|b{3Mk>1}0yaXB$fYHU{Cs@lkhWgA0Rj*mu9Y5= zxl=|-S#ZW-3y@wU#+{lho96!w^Z~eO2kp{}1qo(Wf?Z5jas#;Rs{YwC`?5+c0DQxc zK=^eF1cY$lqG;r8@|Q%`)$tE&=OE+p!I)1glxtAw=4hFjO^+>{3Md71r(T8B{l8kR z-5KJG;seg#UlIS+ZczXNe11^2=6c75Tzv00mNR~`Y@8$+B3n`smd6j7xeNr?AEQ@Z zPkGW1@f?hGpw^QtZ)tKI2m0pypLBX8|57_CykJfwK2Fwrh~a{c3%fr*dl)#S6XA`H z|NUzblkP2LK9WH9wSphd#5*wx=kMqfPzv}~i}X7^Uj;i#Lk4XF+? zl|#Rgs2uuLj|?>qWlvAmU#DIqiGSBh0EO$79rZV(j=UtlOn_PgE|b~I^>1y?#p8RV z^#)|ImQ?mm5;D;xDZw^mfUl_yC}1RhQeStnn(*=DBclt)i$x4=f4Sr7WM~Q;QOchG zJ)6m1IpqtC43AzSM=kjTqlwm3-f@wYHFl&TItAR?Kk0jp z;MvkX-5$k>r&-p6*8k_5vwF|n4SBXR8gn_?A6~VF0GKaw0di8p4XBvV`r|}S0IR29 z14VFp#-td&dyl1JgXDME05~~=-0w_Z5q3(lKqahZSz;u4V3m}u%ra)*b8#?o+vIXF z+=NNM({^*Ubi?~fj3?B<5~ZeJ?yt7}<%+tJR>!CjY^5Ou1q>}fG73rQ7T|4Fr23?o zT5A|{(RK#QY4iZ{zBC?`V*n8|50Fe)({jL8SLF`5^XqZuN)r}n1w?OeYdj*X0yL(I zTY&^ap{#+Q0(Rao4rV)Z9B_jDr9H2F6OU9u0qUSvH1TTcj_r@GMH&nMnQe9*jj`g< z(!3upf*=0oY?{^F0@090sN~xMwhl?NZl)SugYEmj1M;ipnt?z)fT5QL_!hcWKhLcK zxj+nxuZ2yd4@W~}WlW!U267j|F!sJ-MJsqC`plRlwpsb4vMFarl}yyhjg2z^Wqr#n zD9mE=z%AyV&w^*|?p^8ci%zc?!=uNVpLz0KkJ(IThh`CEAO7s-8#4snOe$UV^p6Z2 zdzgJ4_+9lT0j+u=d3#1hUBFKc`ZyVkAX5g!Tr#t-o*{wNEoK+&EX?mfd)51!Y$EqK z#<#joVkWWAFq(|p<16^P$3}4Fbi#u5UkHgFd|z@C*fjJmoZ3aqdvZcWJhY}-Bd-_n zcK!BEcWyT?>Sn~)ogJ*4{FAtc+n!3^JVa++ei77n(C4t1zi<`&w$Lo$B7tzta zb%)uXGqV1)^<{=e!2L>&+IffOaKh~?dEA%p+e2norPjuk1Ep73S$Z$vZ+`&%9;YV* zk^|b(kZxxGtXC)LA(-5-aqZmi@mATS4DyQ?tw}+KndqVxQ}0c+ZY8n2z+!m-cD( zttopfpIM^f`0dLC^%MB*6=`S6F{knuB^A0N)Yzw#=rvv8UUs1#cA@^Alj{ECFpjFv zoKv+TlQ!h{4Db4GbX3cqUq~fv4GyRS7eGh|_5jQZ7lXj(hcKs5XU8CqhS*ZVaX{@= zxpdkqdi=y&|rL-JMGwgp|Fk0u+A za*4HgJC9b{G>-rs57t6S4D8C~k;9h6K0nyo>8EmJcN=oFUK3 zgV7^~R4f}T7FuFwzfxxBy-CX$);`QExj~I=7UUK;FDqS6u#%ahZ$P+Uu-(+7eD9Ox zf=(dtu&nRT0sJ{cdTM=Tr%rbd`CT**`=m9It|c|YS+x1+LByUN#EQgF(v4?yP2orjt^x&!3 z)dSy>X5L6_sllejA2-rhl$#@7eIuQ3T%00WT&WVStsCnX1Aq$hW3~BEy1W(_~wg+ z8X^T*h)`$kp8f9sr%+^18-yW}j3sb~+Q2qKVn*0h6Gs2MwK9i3(i>iIz!2aFxMFr` zFPD9+CC`j1)C`weL|%UZLa}Q#wMBFzN4E@NFa4j@pyVYqB*@AdTH+HIPccTW6`8t6 zc{}yQIdlO82myDmY<3Q1ZST2$8SM1mJj#b2yw88iAgYKYfvf|C{OR7fH+QzRm?%5 zTz!!RL)Ih!1?|JxxDr9QoIGV@W%)NRxHhTu&FrXfPiH+OPFiOI+8ck|`fR@F?%aFH z9H^-Y7ftc;?y2){J|VN;Dv@dAkIhm~z6i2M!4pTA{4dG*w$f$_# zER@W*G+`k>is!vs4*2Vrn3nUixZ&crzIoNEDHOoAOKOea;U3tR9D}8~!M&1p+9Mn5gt0aW99r$AZZsLKTwIbw zJl9le6f1kh=SCNrV_WJl2b&sJ8AO%BPZhBQ$bXJTu|;god%5iXi2c_}MEe+d<)%+N zus)6@dwXp8vW|b9Z2RY)8f%)!Qt-TILSn|fU+3}kcZn~XPw&bO4IxbjmTTYq*6urw zFq!aa?7bJiU0$sZG}d6TwrKwAhNpD@Kc6=TbYJd0ZW-ko2sQ262E+DwXpHFu6GFqW)B? zOP~k(*}sS+LfXbF@4#^;r$yZ-*kMi&AS;=hjhKs=f+ zqb)#6r}v5SW_Hl^BTlZQlwi0SpM@|C7}XuOKN|{#1VrP8Df}&|#T8t|ulp*Iyn>Z% zmgK|r;=9h3-&5k9s%chPB)ACnWHrM&c9VSHv_@tx7I=7pNE3HT#oJ-;JCZjg!+-mV zyj$+y4B)44Naf{ulB)OUE0=a@W@$hG$7xx^w{|=L^fAOIG;M9^f6_DO%Z!o_{m`a4 z6uDeJ{QSw2_c7d;bxzAeb_b)E19$iR-#V*3I(5Sa*v7{EG3Imgoz}&FU;kLY?8A$W zpyY$4>#VjXquu+XmA(u9ZV9V%?;p>pE`ERZ*A?hV5KFEClX|{mJ7Q7#h;^U zpVq?)%r<@+vaIoEJKw9n80k_q^NInseJ;Ba6aDo%FF`eWKR#Al%b_cCc+a^ST#yu$ zK9OCW>F{vjmec*Aga}{H)fMi)dWfv(=%6ncEmypPA~>|(6O?_MsDTK$+Eek`mbHQ< z6KL9{c(+z0UX-XLT!aDdqx4a~86O|xujl2q2H6phaY9j3teL?x+C(MWLcQDRrmqdwE(ch9@>AN&g{zrDGjI`1$A^!ixe zy9O;Dy}k57jxDM!sNSB~RBJ># ztK3t}Qf%(PeZvnG-(?7V>a59_7osu32y!{P!luS@Vfp(i{^qc>)sYuIW$5a8ANu2) zM93^Va^9)TfBxYhO|~n2P`JxiO+h;OlBu=d?HPnN;^b6Iy&|vWB`BX!#%l#l$~M+} z@rek3J%cgi@83%U8Ma@SZ>QgLEkIQIbFL!aF13ZAdc`AAb>ejv+ zxxz3#pj{cokp&2tR{OoZJ@7LC1S;5ae?`d|A+jFd@f;l9f0H8guR#A0|Nst z`5i7^#x1V}j1d5k1AM#v22KCbg55PW^4J%rqPF_S3byo^d1Wjs1 z-bV}@WRS_wkLi)#^)QkzcT(B(3@hE1yC^O+=W3X_Y9N_DHFYKSn~KNrZEyYj_D*)W z3EpDW`yV&9UYpFI1Ba?14+-}(qEvbx)xcX^1%r?!~>A`Ok zf8l?f%O1P*FZU^U!>He>$pp{53Kq{sQ~~m>hA-4dcxx33)~U z7T7KTow{#tcK|jI_b}3O-;lj}tR^XE^O*JK1|Wn|ZZx8!BDx#~-g zezx^zwf>cw46xBZj$y+Caw*?ko&l{up84L%&1JcwkK2g~LvBD)SA*2|WuJQifcNMZ zpVNH)tn-ijYiHKc|M3Dy^!+sB1%7E`{i(?;7*JU6JH{&jR>T;(2t-}(NkE`TU0L9D zw3k?C`6xNdp!Pekn}(qB6~q|?PKa^bVtMNLO2dM!7{GTy6wj0XF6wL56! zhi8vA7f*S>0k7@=1~k~4tp5_&Tck+F+)PjY3+v%n6kd^P2upz--4oB0H>v zoTzhj5)A;@~%#6sZ~=~M+4!-{6azvtLrx@F;AySR?dC1a&ipyNQJ0m zNF>oDWL6EL%uWpFo#D*+5*Yq=N0JifKNvAxhQd>ml*jlv7(DW8)FKl>pAD+(mw$B@ zVdn*i?!`#WqDgvuV7CSz|OC%xsBs{dm-oReMbh;0o`n)q?^Llw>bi2`2! z+qU0|!*S>Rw^DL8qgz}_zK2&YUc4Aq{Wb~61`_w)&N@02^7^GyK+_EUXYO`;W0^Xh z&|=Z%1I)fFb25F=r>nQebr?@-_kWIDRg%(4zkzuFnQ>SIH?GaLAog~5&D~xR+_rHq zN*JDVG0CA&_pCoS>;O*9Zdh23@XPWmt6I-NcQ9stu7Ap?Wm z>=YKO`FG;~638(t0Lv%BK*88KlLP10R*@Gw{2xa5HM0Eo4!slPek%sG|MHKEr6!yZ z8O!|QLzo``CnAqi=)&%{gk_);c}0`|5!l1UOG_f*>|35)6&w$iftL!VhBM~ zP9azb;J|O~7G+U@ZAcWbP?Xe{@xlR%XZ4N#`MK6!C)RW2oZQ?};0?lK^mlpFf5A%O z4jB(R)XbLCH)`Mze=E*b;uK${=->8A75mDH(SsRQ@Ni!K99o9=8?dc zoTH$7%-5Z~c2W$$Ta>IysZMZhn+A9Tvp@U#(#LcC0+?k{+e(L(2SIB%s+}_=f&+QJ>_R%9s+y? z$ms+@nQY`lwj*`*!!n+N^rQXUqYYlgd#vE{y#kP-Y29A#qhml+{D)Ms5k*C^z(5_? z6XwxjZeJ56UG)=2xXa`@S|jQ4d+B?kDP_qr`2Udg)pj=FKHie{ENlQ5JE*Iu}7NjN5Kj)_(YUFt(v zMA2T{9`3fk5|nJJ2)wqx|D*-cL>v4?uhob0PV=$~(`W&K;r(+)zNw~7?#pwzIE(_G0QbW^Jm(C|;1sPxE|G&mE8C3LZB|@j zU+HIgWCj#CM$i)UoC=R;X5&v|3A&7SMpPO#=Bq8~Q>+_J?A1`jyI)N2o&neYy1xfN z4hF#$jyW?Ow^@(WY*!AC zZuQ=(y0&$c)TloI!UDVI@1HbMleVIdTaL^S5V7j0raDx^K zsIJiHE`&N6MBnHwFphI0)4|TD$mqu92+_J`+_J@60!)GvjxJv@TX!I=m)XdN#X)uVpC)uWTKOl$IGko+ zC_Q89L)jWJhJxx7{-3y(0!hSpT(^H0Kn z-PkfePFvG~(fQ^0Q~qO=cRC=(BGFfbep!}oS+<_ZS`60(RNuhSbPI6_5dF7#ji5Omu-N0cCwCt4p_O zqVxr5(Yh^Ge@;pw#_l=~gD;LuGSirUGt_BJ(0~Y>T}BPKTNzF|T+94cg*$m&rH;qd z)ibd5=$iaY@r~$ukkXpQd{P3PUc;{H{l^mO@sL6zD&eyEEZ5DCnIwQX@0XGyt-;? zNZUFn+Vq8RwJ-`cb(tCr=xNLY>GSD#+ZX-0tajK4sG0i-=XzV}BwC|`8|==TQ*4e* z2R6iS3Z0>&)M!lgI1OCfJTBwdMO*X2@12w9gec043I-`#NrI9g61)4_ETsWnzvEFJ z1w2wN%wlD9$2b(ZgG;8}oF48rfwa#%V*eKQpC8x0_@k;MqX3C5WXomE=fAm~nBjb; zJhEk-7X^vZme-2L8Goch-+p5~8k6b+T5=1j;l?G&_Tl8zC)n7P?g^2Q_PZ0+?Ba#V zOrn8tUV8Pk&lramQ~9j(QGZ<&Pgaj)?_cfKlFrVo$w|mRns`<#^~Kpm*XhmIhR@LI zmzt&ZSUI_s{&U)#9h$Y#^kAL>HmUMB#Xv!GXI+qL{fIIeX$?Ll66%v`a%3Ve{LH3} zeYrjlI&$zzr^VG6-qNYqv6Q(gw^a2wZ;oUObW$#r8a!<5IEWwuXtFV_D*DjWf44id zveMw_ny=@-p8st04Cwi%*)%VIot2yZ`7@<%bqv^F>*$mQzz8=2_EL@1LFlQ-?ZBOu zo9%FazZn^MJol@;bH{cAr7?>;#}5#4v@G%S4AaLs{Y~MT9@J-@jMVi&rj9e~vN{`% zu9~)r`PBDv1#fe4j@3}DX|(5+b<+dc6we#938bG*HXd5+vT446VjhUf*_L5{m?H;a$sCHf*n;d(z`&tg_jmnd!U;tpBim5<{{2j!Us#yF?_TOl z>vN{GLNs^ErIfm6MwTm{EdE&>3OXT~Tth&Q$8SipasBrkD`8$nJB~EG1UWu0kC~bn$`5`@5 zR1P9s$Hqu9<@woPQv!N}!SMdmCL)>9th`Opf{)eFZf7ZSCqyebA9 z6+5~z_+>fuo&yPUnH~)>fa|}RthTROR{oQ5$HZY&EXFfoFULE_GvT+aGMgq#-%E0@ zs44U8a`4jmwvnM_WhQ23!7VwQ&qNz6<{xr)FLcwQ~)7mkQok z2j)56 z)|1z6s)Ff(GIrWUUE=c}vVV2?tmZ615wbC?@8jq~q7@tKfS{oK2tAb@u$Yh?8c0mL zK69i|XI{QL-Sh23(LEsP8dITB5A6x2AzF4O$u*8J6zeu@;6^OmCC=Sl69sg&qEDe4 zylt}CDgAbt{HfCU6I<@qfWwhigDOFRV(7814s}oG>jNUv1N1PKOnjmBL4-Yu1#mb9 ziJ@&JF75E}?8?cRa!#;?4HdlT_vriTFhnF{gKgnm^$SfvYvVs(cz2*s`tpJZ7l|cD zi;Y)AM2QAh%MIIrxxcF5T}&Ele^=IUo}=vJoZzg>hhJ)Sz~+Iowg*oMc~kWRJ4HpS zY-h!%Ek=(h722If?LUo)hc%=}znc4aM{*6>TOT@pRRbD6u%F$>QR805@Gtf$&2Ge* zgAq9jQmJdJFK90aok%`8N}a1F0@f$@UWP;ZZcK29Ek>XNRY;vBS^$1s(SDeJb2Ktv zV)XmUL>QlXUZ7aZ^pjzNj&}Y=%?SZ8hQLCCt*k+O0 zKcuWXhr|Yq9jg9eWX*@rt8c)J>xN~j3tw0xt!WwqA(&?aJ0*5wnn-_|^ zw%@_bu^1GsWFji6nZtYJioqHeD?~C3S#5BclJ_O1&8ybpclexs4`z*Hkp%bVo|S@_ z8kA5bz;L(bvRI29;E_o)G-&Eg80=f8^=xJRr4LJB^78E2LzP6m66i~^(RT`w9Kw9t z?Msh7sI(+JR=#^b|L&4N3CY+WHUQs7r!F4S`Caz4+7WoSz>L0!U9h%5z_zg~^p*h^ zgp76W?5DnT6ij^UQsyu7dBf4;j_gx{zTkNwwjL`+Z#KMF*HNrF;J`{-DoIRT7`32;^iL9NRvWF4*pDxTF zb(?BWSL(NwlrN>B$tORAZeMtG7=Uc@${jS^LU-RHR$douD=w~E*zt34-C0%0uqQ$a zt!%*fqAS&(g3ij@ogTIE*N^L-jA(4Gi)(!AV#C|`9LXE;X{(usBxW5k`SPEh`VrO1 zmy6Gj1{Yq^hQ4^X5(~g=V*TpcMZzjXjz|N(|^XRfyb8VEhUj(tRqR}q0GcPfh z?M1(PTSj?bkPIKuo=vtFq+3 zU=HP0P^G_mU{*#d#%W6F{uJ%A5I0dA8sx*#^QO1$!%5QHW4Ah;Hb9PIW7B8b1oS^d zl*RZmqt01H!ao1OQ1dqzR-)O?u>N0wgIf`t?54`sXU;WKOlk~eTtop0!wG5ODx5wj3MN1cd zSMGM}*;J562m7JlK*F|jJ!r7WCN^(!)t@8PL2 z-0&{^AjkJi@U8EGb>WE9nK&>1o4(k5X$`y2d^xU-4a16RvMlbMjjj8NFug+2bcK7x z6_{RFMbasnBK%IeGM)fr?N(M+OCuWE9R1lG{>slgn{nKed@lvmm_!kGbDu5_n|E%; z?p!vDCL;DP+DvtkKMwX^()oAS5YX`8V)1MT*B3C5e|YHmO#K*>_xuWH zhiMCHK--7)TXCJ|1(lDLzj7Iw`g6VP9IP#fbs=ApnvB>Kz8RPx9gP@^FyrBF^)VdJ z9}osPwO4Xf^3n$H@O=s7{KwzDGUk0A$YwwS@IS_wSXJk4#Dy$Y#s=)$9Cm_`eE4j*$0uF z7@(TI+PT@hfS#&xJn!dRy9wBcdY*{?NP{YO33)rHC(W}jqVLZR1%H#HnMUcF+!EEA+!?$0 zwi?jIRd8Hg+Z84%GJ7))9^Qsjux`4Y6^b`QlCu~IR6t1)MZsTN(8a^SIHtlPa`&YvbEM0&7e{^OJtgfwWI@H*|$GerJ$bQ&C z8Y#83xhQ7uK0Aoh*c$=e(oZC9FzDt`a(s0+h1VL+w-d6OZ&>nSK4MP zHDUxl5rn|OYv;`Dw6&#B9;u1E%Z4J_#<_cq`I|_zi*P#v;qGb18MA-sNYZsz;nck+ z0v~gs@HVNm5Hj>g2vD319_3Z9zM*tSIUWt(31jJ(lAiEraKb1ULU8b1nQ;mcUO<;P z4UOeZQ2vZjNK8>vb%inJjM1T)=df(3fcNzmmfG%y(x1IO#(Yys0u(1sI;SBk2k3~J z{Hw4S&%T%x`2*$Tpu8{4*iW(OIytpwfL1jW!t8GpRHtQJ`a5F{^ONnb?5JA-u+fj) z3QH3erxRz9kCGJ!{}x`gZl=~w+9LZuNF)N*5gxDz9xVSzD26dRj6u=y)%isEytTaQeFnd z6lRja3FpWwC6eiL#Hn<}k33rV$OpVF>>IbNh?K-SM6Ez*++T8MI%F>sll8EtM6qBf z9zWeCAvaf8uX3BP(&|VB)j7xn1$)`z8lT2cZPD&ih|t~Nt*6>Fg`W-zf1$|Jbi zjoxn>)B6GZcLbHvF1J7P{y^K^tEF+9{`2}t{(6Kd87VKRNtP3Blv2Y>sNX_l$2ykl zFq%-j2`0Xhm}~Ej^)B)0qB1drhDgan%|0`ZxUQdP%S8fB&Chzqa8z{suRsDabHiol zu{>VMz=fD1J{a{KyScj2cNJ=+1)utUwwJ>*>rV4WKOff2eLU9N#hXioOjh$gFW5|& z2LB+Mg}r8cqWd`-MV_v7ECheWcXSW$$h*5%IzjF+YFW5*ICNAny=BrZ=$6|?jEhz6 z9h!FF@FeP*W1+ZLp=uo(i8kzX+@iREiZ{C2(te&g=plgY#L$wKl$95D z85+nJ&wOt#$bQvXCFo%qbpsM#lY@hU(HI{SicKHXPEAcoNDusNA$spTWpkm@2~Fi1 zMk}YJUQMgz;`%`e=cZ?kjwo;cz*rD=*=bZ*V>!jd^z2!mkea_yVk`$&gNHeHRo9WH zy>6;1DNBJtT8mHUrreXIXNv9fNYlzw ziwBPv{Gbkd3tBeztZ?u1}dA`!9ErE-gh9&+=MT^my9Qw9`nnQE*oVA|5Vs? z>+w=?4o6PshgPx}G&RPVJY41+v-ZQ@U%$?sYn<9L!LbOwnMCsWL_{3=bCA>DHm}`4zP<4Mz*IN!bU|H+ zdIF{zOd%6rQ`X8$4 zLq7|%tNMI-nJF@o=&7AfN_>F+oHc=fJ+>0Yd3WC7b%lBC;$W@In%!~2cYS>m5Z%-` zIO~@yzLS4bA=4|rE2m%WN7kzJL1V}G+a-NdHrMG<;H&IsUTCOBn@NHeu|aA}jStd} zA1pI`gSpEU!`2X4x?RCVC%su|+;9G;1z=>V=)(86zyUInSX40=t0-O8r#_dHYX zSvXx@aARrJ88UOwl`-5}MJVX-B22u*-Ks{*eFs{M@4B8gY6gm1}7?w{dB7Zkyo*<#!Tk+LL$O$#3TP+JyOq4&r;Q#dn+-NO@hVR~b6CY#{@ zLrK#1K>MA3iIL@x^v9@P%}WIC?bt%znmrWRn2fO=Z(J~@i z1Yrx{^`GMZVN1?G7quHynl8oBdI^L{EP+x!P}P+Ow08xT3hMZ;Rjt- z<0-0Cg~TgWm6b&xfX>v?&Mq1Z6?-pH2}B_Xy2#Nd);(@2@I{ zfA^G43>rz_OCa2^q7bwv1$b!&x< znYyOc3ASLOCufDt=3BQyCV_RH9Uo?{3GQj+o!)sBSBngxUr?-tgY2s|;vWg<0hKV* zKv+G2%fI zFK@SAzLfMbtfs>&gdlg%8|NBZohV)jAQ15f146z$njk<$t$@`2`yrmO3%gDm*t6_3AwDsFk(3Sngx;yJKqYh~r7a^O)ZE@kNR(4(*p*A#t| zL%H#O>8XkZ0;ce%;@{jx>BiVXa3 zq3wJ{va+-MV=U&#L0I@+N^YHvlL_h)D7VpXG~bos9AnR1^ed3bw;g@p6a?75-%04I-WiWW}%SWw+l2@QWX|P z+;V+Rov5kxy^qgH&#yFLb_#bQ@R2b31WU z9pTyniGL|zx$jvksF@6pnL=?^wJnmu1&H;(e1qpwffQ4lr5O%#l{w|fDUAW$=^?Cn0<^NTns7GPYi$!mo zJNTr?Gv|G+I!GN4QZ0}F3(Xx60)4g9DHt#=;`|4HPp#=Fi3NGkn|?HcXYL zq&?qY&TSA?qV;HgbalYv?mWG_aM564ILLVF%LDg=n3PJm7RvcOds3;U)jA0U>OPNA zrIVvF!#nFR4f;?Lu!ii+B=>7bn-e?*g9ZL`&MCJ%BHScVR^2u*7^5o%{T}wvVq9I( zj+Jw4kK4KNH?@F~MulxBHqXXM7jN`>=@X|?<% z-)KGMYNF-;=;1BkSWC|pXGQ?A-!4sNaW-TeFI{CTZF7&4q z?-!KJw&P6Wc02pl5}Hhl`zQ&|%6P|a1+j2yupQavCl{$z2@@2q3mNw{!+8L>2Kcr} zN55_y#h|8St*M^L1l{dqbs!I$LthbkJX?Vk8(B3YM^O=PfA%j2t1Ux|2oXFa^=_QY z2TzO^iNC`AI2kL|Y!3Ln(rq#JRh+x4akI49|-Ff`doD&f_b+uf*h66J6SE z#&!KWah&uEi^ea4#3yt=e%(@k1#lhM!pkJ>KTw-tR%@L5KVuHzQ|>CPnO4H=cYfi{ zg++Oy7+-(<@N2Ao0dGC!&4%h^k{Ey4|sAg!rS8>wpg%H(KcMSzH#oj z+bx(O#k^m14e%5L3ga7uQ-TJUO@ffCp|LRuM30_)ouy7$f2aQlAiH90I7ic7jI?^k z)n7;xDzch0?)ds|sD7m(*Bsy`46Nj`Q{5A&`Aj0qTmc%WMi~36 zYT5e)xV~W4N@Klw;4pBRpULXSRuJ%4jIW9voxHC9@xjC||QmZdQ#B^On7<_nu5<6BF*k`~B&4H*~1 z_UasDDAe*<(tB3nE|NA*(f9K5lW36G6Dp_KS?vW-C5*zc8{b@avg_hhy;Iy2)Jf`10)JEk3C2oeWcUo3fRt`77Z2L$#9_A+ji_o+h zB-`gaKzH#cy&g8}hZ@~g)jH@jq5gM z3pkf`^*g!|DE-J$BzBL%4R3IXH~9^~lcG3js#?dxqt5yf5rx3-lgy0E2YUxw;*FNK z1d=aa^YwrI^8&TKnNeh)jobST@w+*GQ#Sh<^WQ=<-;trzx9;@R4O=J^!}(F2DvH{c z+9Lqg%Oo@VEggu4yN-Fml!YC4+|6}do05K;u0H+q{xs4MXoAJEboF&~1P(ln-`CAq z*x4z0ev~h#g90S6)*BzW`5n4rh) z)t0)+?Wo{}!Dq=n*kc>@L_mTXcHRy&8S!Fh@UU&>iox6XlPn<7!(r=u=-dk_yOO zX)}cJYlpa8vG@%uanB8PBS+mzH(IXghACR+8Qn59H72pjTmJ+a1LLI*o$?7BAPlQ- z~`6zgpJBz8p})cHe?+ zu)4?2{zk%$ALqoClyE@Ps@r=o3>qyAe=c%aM~&Jfa?vt=baH?&H`4gEGea^_!HMBi zn8Ytl`aPj4cDP7-@K|xUvW8(D!P&`Xs5-VKhvq`-lFI?RqR2RTL#+Bc0TvzJ5M_?# zEqV-0mu?c>yQn-gtoBia^{A~5&jwiM#u%3;p#tMF$~j5}&MX>XJXB*Df)dG$SNM8j z*Y<6uUqp1aVL!ef%bjqb6EpnxW_$xJ$B}>gvi7Dmu;g*c12=_C3<71PjajF5Q+fMO zH5dg{9^Z#vVUJ*xWL7X4T-x#{D>3a~zvGQPx-F9$uzX5s&M@`8#L|ak`zMTnDqEFU z*{L=*0aN~QQL%o4I&}P5lvIh|JZM>neA?`&2JZ&qjESc4hA_uR;td)a8cP+fVz6ln zeS#;7uydSkRCQ@iv(lc=6}1`}xv1Ob)ASQ=HOg%{{{#pBO1&US%z~a6hOn7eHMhaz zv4-A6sx!h~wpZ4#xPGwvVx3ptUa$0|sEQg)Ka{JQi;^lc8S+GHG6_>?y5;yl?gmk7 z`ZCgPoDpwwn&CyM>hqY~?&{@6B>SJp)Cj|ERGO|<|0l0}vU*x0U-t($+kPAB?nJWX zGClc2LiMY6*LAg4Y3*sUZ|Y04t=g-`yRWU3pJEuE#7l^K;g{=4LK8%3QlfA6+oC~u zvcXwRQ0V>UTi93bfHI1(l_#R-ls*h!Q#U7}LU+zu?bMrYh5Pdjtk3{; zE_9cTTn&MS$|8=-6j7%4cxPZV=m~3#00?#O@wFr@*V$x^(fPQlA6g##epdh zAuy`uxqB9i}G5l=O(#!UlNfM?hk>-!P!5cN6hMe&iM@Lmz z9}0E}W)7}}$SSb27v6eIon_pdjn|yHINn7qT;3kNYN7D!f=~L~9+4jmDZ(tnoq-9rs16uswT1GIo-=Tj7>dZc?FOa|%9 zDf?zI!^v7uDc5(;T+~^U1s9ZCeK&j9f>GN+E&Z^t;=D1rrN5eQ2IBfI>7(MsUm0hx zW`cJX+1_aL;Ne#uf`e>>o=IlQk2G4I4*^52BR!f(*6Le9&=jhpuRjVR4nDiug7KWy z-jFG(UgB~gV*qqDyhIY#){IBY?weKN=V{2Kyhsf*+#`TybrYgTgZ&Sw8Lj}RfW}FP zWN>5nw!K;g4T32)nut*oq~>iyxvr`j$W)6!(iY`4+xSMbbpe=@@r_ zg0-=pHE1eD*$r&{-g3*rNXv~|)$F>REy&{3@+_y<2$m{OQ7{`}a(b~`CDfSorOZlm zM1<&@e0iJ3ns;4eC{qrL3VzT%n}^H{c-PSpG|~S-KTZ!&YP)xohmNrk;26Yl?i@7# z>;pXBrMd)VS8FMUdj=CLrbMs$Q~%r}uEnUwb6;2nH>H|LO4sajuZx)+4BMYBViPGV zHEcQDcZ^HkWZxWgj35j%#@<_ge6UxD6Dz)7LPA0k z^5z*4a_Oj9uW^l09i!n+LaJ`4wIf^eUK#~GciV&6-{myymb?}`I%L8wuO2#K+YT@+ zRdn^gv5`*m;8w!=?o?bKj0HYeMIVL6=E%{;zNjot#hY#t)g8&<;9O`~GzvDmd4?&; zv3zIdDBk_NGE&(q>`y!OE|{Nu>-XQSZ3hK(Lsc5BFQM8c$o@2BLudYUVN5+BcDA>% z3$bU1o(Tmal8h5~p3^D>7Q$Mj*J*e*;DmMMrT!CKSN0B<^3SSQXJDhvcTlqxsF-Ji<=**PIQPCooZ}d52s57vZ`f5Lghq}+2fL6kIWKrQSdOZ zA-OPbZT`pf1`@d7X@~y5lmfJw;D(mhrfI;$b46^XX?vCltdYwrEw|8-G?u!C9XTyhm4!MhD38Dw2(hSN5Ee2cU3k=ugrF^6jKQLi>KVApaATY8l52z zBv7xWv$V8a{X19pPEnEL41$W>{Zg_*nMH-}-|j~U81fQ>a?jRVMfnuNr4ZTKbl7%? z?V$cInS7ozMqV4_&S?DOH^W+s0Am&|v%=Cnr4JDz`%a^O-L(XV{24=!tW#X_f`vEJ zufC(!ny(?w8P*WEzT1Q&{WosO={?sh_-{wV^fOEPZo!jDyYh;Wk+IZfG2j&U+B;v~@VjnN+1&bT>T?v2ug{ypSu8xq zV~={GCp#NKjq&iH1jRXv=jaq=aG)g_1GhjM31$GS0zCJ@#mU{CbIUN@GvroG&} zrSAAS5jFhEUjrwOxS#3SpM$3A7H54ee;74YMr0rBiPDx+w)izF4B%VMz10D!{tF3a zW{&PXN5D@ds0}}75V=!(QZ?*9mh#0;jw;pY`-rhuEBD{0UE{+R7k??{SI1mgUL9ay z6y*MiWRhYh(Q-rBsocM7v;AsgCzA}R?Yam8}j!M(Y zv|VJn5;ns}0N%ua*@>_ivK_fI6#sN$VOHLmlQ`y27z@~6u}68(ogJ^AEg@U|5q>Kg zDP(YUh};Vl8Rve{Vd!31a5Z_~xPO$0o*}%d+Z#Lx9Z{HnUG#F~4WFZ`iK&fc+y!!P zi9Eh%_rsW(=i8X>mhuHuBy^|mixc7rRM`4JwA1hJv5eX2x-Yp;R31UMpFu?5B(#MC zc|aebvdck7;OeybR3{%Vk_!SGJ=3P>gF0Q}bGdDpK-*`prV!)>)Y0M%YSUyZlYukz zhivZ@btlNh^3f`=8J=89OFwPEQZ^ckV#$$8l78E>YStrmCzgD)fheok?L6j!rjl zv67mVS;i9iBuCH*OTkwfwgsDk)xPh2n89HVGg+ghL}u~pPWa40PcTrT2UA;iesT-2f5NlD+KH0=h$`7ofBZ*~>Qg5SdqF0Lg=gTb zz5HCN@YnO^k*~O)65mJTU+qGME=%W1T=uK<6zlXbeK!Kc)`suNe8nqc>V}syvu~Fg zmrk?zAB$S{n(^pRN+i$Byp1<fl#qATsFa6N1&4c*o02ndVMJZ4Gg@)FJwj z)@4Z8e^}68;}w05+%HNhq-gSvg7u3|0U&_1p1HaVS!s##r==J1z1AO+%Xohi-N~i< z9fW!J6-B16vBV$){AB&^gsM0}x{qK5rw~X>#=Wk&v9Ph381stcMbYddaB3b{Memt%$x~l5&(QV_t#1+Y-EE2`^CPo6*11HQgju znQ(rSgtOAa`=M7@Kn9`U<`~TvzXDz8IUIQQ(~Nv`@(*shuoI4UP@x*{{x{3)oQo0J z3<481zWto?_uPHEd~v!uqtEQ%+y=8eq?;6Em0dybFaZ|wCZ`?E@sKa=$lY=|wY6~> z85H-Oh(~I&Zxci^E&dPAHm6{mBr7tKAA~%|yVJQEzi8XA<{x}XfBE*y1*dF;@8)<& zL;l|>#o&RhodHpTrY}~iICZumpRG9tTok#sBO?xW6{#MxMnfc+W9I8V;ZSGZhB_>`kF4iUEH7upAw#uf;sOgM z0QD76r-HmUo!<;J$3k3iGlr6@1{419eN8=qep!)9BYbeXxkq<<&aMr60z>^JWthUsn+P}+_x3FT z&}v&veR`)c8+^D9n1-nkv4m(8?h z?{7h?3k0E0^X?+3nI&zmduu?1g(FM@j!>Sw$0fszoz$}W`jnvlSlic13nf%;I}KWV zLnNI15+XY4z8dmJm_KXAWpB}T>({zB=sYV?m!}debuF41F9?$_oX=^fwW#qVxQmP& z$c?@*eIa0mmQ8;5^AQp?s#i6lNKE)sdS+UwHqzNGr=dpVK?p=cC&_-@yOGa&*(9&; zVjZX)cC2<^`>uM4TcZHyM9^jXfCf3idvw_=IsB{hkkTp2Nn!3ev@6MPCE6N797at^ zwu$bIqSm^!SUG#ru0i~c+_pVZWw`KH%T|WS=B=o54$&hGIxvO!K(EE|!xv3DK;4tK zxg9+GwH_^Eu$K5Or169>Z4BozVFKRwWCAfzy5~MGRF&w}pqRqELp)DoRsV9?l*LEi zFy0Cwp$GhA`}ouA2kt%TrU+x73kshS6>PZtf#!H$OYgCE_pbv# zL&!1^M>5?zAGxgOj18L0fZhoijd9tIFO@5Oq)d3Z3NfVFd7MHQ@b#Fu7gb)q#Hgqm zUv3~RJ>AlV=yRp2f<>+t0O~ZV9K@5SS@i2c)U*n0?Ppw6_f%Q;z)ipcSbDLpcTedy5*<1uN z-?gE;AMv`MP`A8mUA2|La zFCV2(XC$YGOjwxO+rQX9J3Br7F@bl}kVHR=eSU)2VX9;=|3#uh*>zBlqO7H_G`*QA zBXimqeh?DSFx($W&j0D0Ej~V8zJt(Tw0flZp!3EZ5Xs4&q?mNI&Q^NXYxMbEnN&M+ zXepB)9-12!4e`#*+WqQFK6&7xxpPxI`a)HJ5&G?hzDbpI-S-|=g98X9Yv_`q1P`52 z0G+6ZvN$&y+M=*dq_@QFYlf`ub{Xq8fz}KO#|*dZtmI$a3UaKkM_ZaZWx_;bMGxui zuC{sFG~BVH51seEIe+tzRRW8E?Mdth6O3VAa1@!CV zCiCD{-&6$(>uYeHVg?wO;va;-njz}p#b$cY5#T7zC09I2x^9PQ+J9m>B5W8YGKm8X zKax&QFMR~eE`6)!iF53AAExp|PSg z4OfsIaB{G83)>j-4jSzN;)}WtR5ik0?sMVq1Nx+y$uV7Ax`!OuF!6XBKs7oPMEV_h zXCe$hul(6ahCKTE`%BaARo=;2l*0z-^lvt35C4VOESf8p0Y!Z!`*&4_egNyH|* zvzHgy?p2{pKvcxVt5Y0@fj*APd7-hhmF!IR(nlqCw;aw-dcPLL`U>a-EkWa})|`L2 zxHEGyn@{yCJjHt0kQ^=-Z2GliP}!SJ!^>B=w5$ve_{!ep;2^SnW(D#%zyQw)Rny|@ ze~s@i{72rj85pRm|0jhNeG!uQbR$}-fVDx_@Ea)5{O!410ZuX5Px>p)n4 z*(jpDwk7$RHDh#T8|9+4CO*V&G z7XQ7LODi?%18rVWlnheC823x_naQI#_HLV{Pn@~F2Zi-j@(Q9IUXJf$;lnmeGkf;c zJ|Xn)@y^|R;RO4)-_d z6;mGVC+}4*iPCZ8j^%#VI>^^2f01KD;(ZAy3h7ajm5@UquQ_(ym_X%AXW!uh6hKr| zRLTIGblM)aLEBH+!hv3~jw}??9YaHZ(FXt!|Ni~k{`~LcG7O-h;pjw)4NZCj%~G9h zwbh0;2dq;Dbpf;qeJE%pRYvT#9M^b_(gDd;p(nOg57#Y&f$FFjM$J~vn44F<%7Y={ zXGZCBh6Euo^X_LwIlHe(clM6;j>PgmmK>C6SR&sIKM``It!{~+X&+fa|@mMnp< z!$5FB{-xXmtkJtMFc22Nt_xie($pKND*1id)m38}dn+S#-lK5yQO0g?VbZ_|=RFXx zT<^XdGvo?3>_*b=XTul`N+4u#MHfu+yDoi0KjQtbc=Iq_z7!te%n4x2LskJUx}rlH zj-xl8!;cv|f#XL6R@N+gJB28X7UswKdf9(vF@JgRb6=h{AcS(?R!eddD6FgjBBc*m zAuF9T#Lk5eqpV}CkS#V_ek+<{voMgZN1wYfxB6im4IHa@U?r~SQ4(Bvf-W8qA1dHn z#`xtv;^Lj-FG1-Kc(LV}Du1hr2SMR~d&#$i`bZNzhlS2^S6Q`Wa>ezY9k(@w27yK% zxf(Ps@JokfkF88borxa610^IRJi_CZ6-QH}8S%z&`X9M`icPixTG8Nw``M!3NwX_t zxmJwRPdtVHzWo2;>aC-yj^p zl8-6KRUj(__Vpa4qk+ixu=gAunEUBjSaQ!>bg6a}m=o=qg!q5(6_73wp(1_*0w}^0 zDwsG0syUDJ<aGtEz3pyje`AkIx2Y=3W>lZSF?(UcZ!|jJS&H zOh6yV202=D_ENuf;{ZN3tSanNrjCVPiqFO|d9q8%DT6(?Z1!iI?-(%3fOAqiJK*_q zPyi`Q(5=30aR>P5cNR8~8bT$d2oR$o6pgr`6nXAWqrI@hmGW18?e^hggyQTGTUpkk zJF#&fva+*Zu+2Vz$F1dU(5gQVCTRfA^1jcYvSfu_yw>XLXW#Yaj*`A4;N^DQIDK)) zT57M9YX2D1{nz2$>~l{p@{kic#7<;O)qbZ*F3X-@DCHAqqV)Z&6q@<+Z&{`rHk z?WFM3QlcMRK;Os5*{!wRxdCX_TD@UH*6U*EgzQu4yD-Y>`oZ$scPtq74v zxB!N}gV{@Mr&7F`Uq_x?y#>=99(rx*cD5LjZz>Q>J@MtB>KYnhUzR`F8Toqir)Sw5 zphdu&!}rBDvnT4o^&{BzVu&eRshkD~{~OUjYJM=5&*U>J4B0b$wxyDU;bF}LU2W8X z1+C<(!S@+rhV}gS?Bgz`uWR=*OvH|`ua-pghOh4jl#WR*sl0ak`Oi&ShA)rY%G_e0 zmAbO(UK~?MQ(75)2WRng1%O2(IJXr(y#4vp5c~?+N#k8>i>p4wb$3euZpLLvfk3V6 zRoZ=U^xseWl+S7H|HD$g;*q_a8u!YRoVcV64dX<(tcPEwE_O&q%}pbfXEZVoyhT1; zfp&aBbol;E$Bv5QE;q}zvpi$wokN^h-i%fa^d*uSD$z^x=z`-B<=n9zQsu9?d6)ir zz9D6mPZ>NM-d&UZUa zSifQ9rX+yQiig%@{4U)xWH3fSrglNn$%~bQKIPUAnN>GfEH)|-cK{MT${?7!DoY8(k(QkkkV`Yuvn zHUSnKWWb2GpGvP?K6mf+VgRk$^I3?EW}={G{6$oY20S;VButXo_4tj%owxAz*jliU zq6Xorj*zMvTv~E|IH~Guu_O*S3fb$9z9!QPdtztke|F9p5d<7{H2=(C32HM<2m)0oV#gxc$|>^bbmm)=}Y0 z_r}34P7XjjpR-yKN`N5d!l75sa*c+NP&Rh9|1((%N+na0Y@k*s1egFP0zjUwxm
r&zemmK=Fi%+B8^57yU&I2vJ^ImG(ZgR{ea#_fgHS?>^o1M)^oj zjPKdcjvjxng}Zpyq<5&%lSVos0i%oQ#g(OO(yA0 zi%$UvJJ1`yw;98WBZkcIr{EC{QyF}qgZ_FFdUeiH8GElz9hR)AyFPQ(`n0EhhK6ZS zK=hW?;}3#2-z!{QVZp{6M|dZ)99Q<$FYS$&7KR+1yD)~?%4B3N(vB*C{gqMxo?tDr zqFhW=830Ju4Eyd)JqK)0y|Dd>N66t1-%wsnPfuP&1>1To&uFI-xcWEO7A}d4{<~*6}=RZ;cEP0AFlE7TgUDnT*2`6+@m>Sco6!Tv%JT5*u*>F zf0b&6_e$a%5J>@A?n~9Xwg>tDhnv)!3j5UlCQsd2B#mz%OscrD(q38}J(Rh~h6rzLCi1?;|}R#PHLo6uAcl~by7v>_s! z-_8DFQ7oScqAVUbmG}PFg{b&nkqDy;4$LNwE}JCW*lTR+D*Ycs1iW+l(vEzMM7fZI%5LY`Af@gAw44dHp_e!xkKk0`#16C(xQ3J{rRa~L%8mHoSgUpqG<6AE}6x9-+ogWF0B z?1sOWx`I{o#_jNd%~QR4dfgGl1pDEG9q^hwKRpDD8R+kktyfB7bLaPNuF|jp=MVyR zZ)Pm9sP5X2MrklN2IjLk__sdMr=XQzM%W41pRfT!5ub+v@yO6CX6Li(H+tru3o;3s zffFA%#i^XmZJnH0v9PezV@FmV_DU8NQH=)FbD|%mUWihxTq8)JLt)9qkpNbpBBD1o zHo{3th253Rr7u@W9u-vaiAjl1*)<|c4n0|+FouUn%=?o8Ln(rQ zG>2k2h4A9RyhqASz_J3tu<7&noZMzugenY&LF@0=!@wtd@~vnt>M{AoaAq1MJB>Fboo1N1vv+O!Pf^~@!~Xh~o2+NA3ok3W3n*Yj0c zFv0~EYsB?l#8ypiZEtsPdzkTNZ}03V>=zW+W z^$9>cPh5bi3Ot48h^~}$-YRHNmpK0o1oovHMI~EM(vEEmlv;B z`*Q}jQ5{4(ceTxzS;W!$f)Fv<`=1b?Chq^kjjsI90Ne=yJ9!AGc1T}=K$xFF*L$z7 zf%zGXu6CQfXZ{BJ4xYSK7{MFO?o%)?I%ZP6zyFM#(B-2K#-mK65ax$rEb5ZzlU~;U z@l8YW;*g79>xNFE?88@??W>9`C3z_{ck>eqKLg8Il*9p+JDe4IitCjxv)c1n_-1Nm z{5xClSjE9U?MqHmy=GCL;mWhPy36wD-t)@8jr6?R6(oIj z5O!BfGjDK|w#YY@^_<}y?Bms7S6AMfeagV38)Z=3Q#rMg;Sr~-vV3~UVMWTo#PG_` zFYEBo6*IE6i~MU=IO$`%Qcd7flY1DMBUKlqeHX6(v8$y5@%lsHfM&0xl+mMyh;$mP!BJ_o0`c{wD_30QL50 z>u#3(C-6-*I9MlmHD&(j9P7P$jx9K^q{vxL@TtQ+%i4Im0QS9@bV-%AhV72yVDYFO z&M^4yCEQM1`|S0!LCDvM9v!Z&G`7PMfMKlPQpRI_4ZO3!D1md}efs?Q^X~KoPtV=- zMmz|Z9trDN25GD7jWfmuJC+Z{=W{xX!B^o)e%&`rjgtl4?c2T5U>RKrXD@j|2q{Z? zEo!+*^4W1I3CAhkoCUmA7E?MM>8g(Cj-Qu?&wF?V3UV!D6Y-?xJj_i&2PeKJC_`CU zZc7K5Fd4aD3W*7vu$&DKE&&0-iBW5qcBM3z`)cQ(vWedp8?ta7!7YEXFAvjI(pqKS z?i`h>FJ1Spbb1ky#U@piL#y!8$l*lQw2r>d1hns0-lmPL2^Ude z54Ag15xACLsO0GW=i7n84b01uQt{ytKpIAm-R`eZ$V^0cH-ZKqd*K{-XZtLZAFVe| zOXc5Zf(aVAL%d1zOKY1|a^GY+TcP~)Go*;gn@%^wSxwh5iTE?WnUmm{xZ_eSZhTEG zBk>@0oVITLXSuUK99CO$SQ9^NogmY6k%v=0LSwhEctQ~}ZTiWodG*kze_+JY&J1CU zXCW>?g)pRcfo?2&PeD=+>GV5P!kkiXar>7n*fmyZNedzMS$8N!yV^~ikh05 zKRT!MDN1ErT@UNM3RsY0LfU3rB~A~43%LhZE#Ds&+kTLm8=m_@`Qx93BTJS7MtY9B zQ=w;TIzEIWJVKZbfj+PAeN6e4#EooxwU}=pI;&SJ!C2TaU0%Pb4Eol5g1n8MFGNx` z8H=KbD;`+Z++RFLt}-&@_{v7l$HN2i;<6?M{r&v5w%!Tx7L@pGME&N(RVO%y{{7%D zEiGvU1O&iK;RVfjkXO*ag4gnQQCSqA4+JA$M>iAhZ^w>Q8hWafZGqhaB#q50eLQg^ zJ1|f-Md*_5Opl=}VWk1Xu-LF8U1pT+?2mDXH*Y`WE6K7>8$T_5{`7FWJc$M^zxz2) zFZtf79ozmIEY`ojl4sc+W&ADvuOnNR58H>WB4CvQCl}`cJ8?hf&Hy)Y{~)*7VE?Cz zw0@54{_*WUem~#UHw>_65|a{}j{8R6R3SK6n#+CioJaV16OvH#mFE5Uy{gwG^&sX3=YFR!ud1LTb8|#K& z-ZtCx5<($AFyB;SE&P7bRCx5Mp zlKpJhevq%!agA?%`?X+06q_SWm=2;x5HXXa+sXqqz)r1_3OrR1*DQEL?2naAdsQ2&`?P~C%cNeR)#sh;d zN7Am6)bDcL0Rn&nNLdaWO*w)22r0&ba?0J1RS1g!Bq*;Y@P6U`E&&V3Da8u$$274_ zX(Gv;OZ~jA2#aLfg6s zhAYS6&m$hMg%&1Ccu30U*k?RmPR++ZH5atBec)QfcQTeBY^@4NSyjw&*|pNy*^lSq zQqiFb-?Z+AH_7R#Cs@-q4kRaf9z*FzlO+l3lJss1`TaW0E1A(>1&Qt1&iL z;y*V;7LxYc59fisf~%;mCQ!elQ3tCfcVqjHg}}_R!nW4I;(dRrC|9W&V+c1hCDuz* zD^9HnCZ1X1`v7;f(l?tjWWnjYK?5mk?}iQgj3Z@b4}CheK4z|A&uEy=if>4XCXYo4 z`71!)-A=9@)VZ&zlwm|d>8q&tibLWYL`a&1-JX}eQ_fu5+%O&FE}D{SSz!IiN~D>R z!k?=$tW%@LE*!UcWO?N&2zL9B#zz{D=^^;ySy)@+x$L-LU2_=L&<&-2Nh^Y}!;*_D8&3nxGJm-Tqy9$|E{-_v%tbfz?mHRE2Z@`2JIt)-*m4g#AZTigC2 zpXi*mWb825PsBx16)=9hlftPL(@UM6nVhM5 zsbd&fGDSrahxn5WK@-ZPjRAxl1* zi)3J&N#>vWtvI(r3_>RXQ14!${tGk*AAlyXd2e(?KKV-bJx#ENXJl8QI=?NMP=}GC zU1JPHd`m1OWyKH&TOf*^aPa7C`_9o14w*MN^EqXcKXwvs`F3$?!GF}Bhoi+4^nA|t z`65Zw4%v0E>DXGvHct-ilHnWwLD^3%-Kk`^a@ff<5rG#0qH!|RnVFdumX@!0vpGCG zm-lzgZR}#AbDnW>aglI&aOH};={6Nl{&bMk|9!n+YIeDF6)d)T3I(S$)d%6-GFwhSpHLoZd;1d55$f;*MV6NjK zQw6D+=%x5ndfKa>9*!;s=HtZ!gUZlEQhn|;1xg4*;#F|x47tZ1<6)p>OAsUQ@;L8` zNu+yEtGm#96B+qk7RdlAE%N>zMS>6E6GwG=xZkCH;f8`TBvi}5z(5yVw1<~izgiIt z)ThgaKGY#aX;An<$8PE7=Ju}+!2_9pBTdIxZ^yEVbkY#Y9{jQEeBxd`CCNJO4z-`*Bh7X&hSXUO#vAk$|ri7edd$`LHpOMIAs90n9NQgWC zRqbXh=9XahuP?twzM8-5%@YWFUydlBJZ{5n!%do_V*R7>J-22Kg*Yr3XCo-ZYprf(?5OZp^XyI;{_3l@;HDw{58^HzuJ#Fl zxd7a18{fKgX|1KJ>X!R2!RFqX46y$UO$)or08|0UYTmtFzcotxAIxLr>NmEBUjWIugeqpG3b z)xPBYoF{I2yy}YBkAc5>qQYfM+&iiHcDnL$n`(!#vzj>Mj3F4MWyOQDU}Bkt?FAcK zLQV%SW<*fE0;Z3M@yCfEOg|A)5z{{fGsNHINuHqoYEPD4_&UEX6lr+*l4H^&zOzc>ltWtXGy!|) z<&0*C26vjt@~dmn`LKvdV3s=WIXKmXY@_YB-*@X92M9E-t5XokwSvgUU(!kzp;{T8 zi4PCr{FTXlT%5^`>Ebcjgq=XyH?^mz5C6D%dODjP!}FUYUEIw79g-5<5MzJc+baXu zi(6gnaEQqLMSl#(*ChmsF7vy72_d?0 zp~mNZ>)&D}gRF#U-C{NlM~G~JMj4$BJMTCf)aN{isv6dB(_hf=_H3NIk5con*4AD( z!7$QO?L4@C#7UDgbJM_bADWXyou;~?iGY7hH>(7HuEnG<4WU(YRJTx^7(Aer|9o&> zOpm_pL3-{eKkV56{9uyZ6pjn8xFOWMnNnjrptLGAhD1j*wkEQJwRZS)3nd-snuYQo zKjnJsNnWiIpyuvOm&-#%aX_n@;a8|>;KwJF!16+}Xz|m@`FR6~4}}Fv7NqN8H9XPD zy6H$r_P-Dcpu9c&h|tIhBv8bi<1y?%X~o(+>!sd-Hz$XSv=AHC^f}%;zkXIMhVdAj zY(3s2I}~O34^I6i?u~m(qTUg=k9+HC!|!g5$d@ji%;(PI^PX=#4jjr<)M8Rw`m->o z*xfPObT-G9bEy-%9K$R`@Xiae^A<;u-8fdR!)<-gbHvM7KALe3G^bO2z(xYrv;nx^ zG^>b%idY!}c<^JeCE$&31=gA$Ok>8D^Zmj(53|Q$jRK1Wja%tiP_<;)=ar3uY3(eH z&3A(b_7V2$ojGEWOhljJ^zx$xe}p7ZxR(7`at%3=%37YK6r68UQzp?wQqlt z$JXWg+%4FUQR4#Ap&|03{1PVeC3yy6auJs=%iFjn5Yb5xB8EQ}YVORYC<-?J+9)!H z*sb5Ki*L_@=nuv`!wb1?SW#D3z8sB4WSEPUSgt$E|udAw9KBvmoW9*`Ho`4ERNa4D%d#K5oms4U%6b-@zs*2Pd^y$xG0orytCRqSCcK!Mpl8RM~SjQ zi^|N)qf1i&zlJ1BG&D55(CJh7=~|PqlP%0lCDIhCNSJvRa&lqOuHcvO@ONlzwiz*# zgvAG}DPnAm=lMpF;|%^Eh=08%H(~Km_;8M4ms#7A}aXLWw_-%~+}d1~(GyRQL3R&Gqc!>l3XwroDoS>(Sv z5PQFo&l@%f#}I-NsVea0=c^iVPqAaHO|uI>D3PG&)<;^$T}WxK83!wvs9l(%%FWHa zxD7%^My_%0j$MlgtGE1+MWSQF{S2|rV4ZIk!!$v&k6y)S;^#=*7JnK+B1qkPQ}mLJX<) z9G=PZsN-i^Fu$bA{F>OHl*_~^yhb^fS3K`r*M%?Gh@ZsRQ%*Rw*!99IltZ=M=74Be zkuHDv1Z8?Gf4xQlBG@j}wRxzQrY~7i<3yE&dV72O`pbGulMVM^!&mBr7V9^wmvo^#m6}@#M$Dtb#5x-9}*z`(WvLu1Z;tRw=Kb2l|dqsa@$fwCBURj;L2-EA)6^ zV$e}@g2Pa7F_U%QVPQziBc>ZF;nd~%!cKzP-ii{#O{E66B27Z0(Zrrf4Wq-Hc-N|O zlpGTg6%ipWAt6ZxXh;a9OX08AIJcaZ#Jvq3%aE-MkenzHnp8@Dn^fl^5y|+ndc=Mm zn(<19?4S)HSi|n%-aLHnx{z6OxAB|^Tl5X54>s7xKGqgCrK-{#Hn#&Q_44va8Z4=4 zH`m+#y?;X%(zhw0YR!O;K2&GX?KUwp)0ado3p+2kq?E*>*NXp%;chiCQs&exyJA^J876v z;9MJ}39VY!*;hJaKi|toC2%KEc^-2X;4u|ucZ(6He54Dn!G?6sS)fNmeN;N(bHA&T zWS#Cj92);z@N`C6(PMt^7Os}yXyzFOB!MNnIZ=g&&QRsy)#5`2(_IgeIt^~L6`M50 z6K)b5#wo*^a>l8x*>B@8EnD0_60a1>o}{UNrn7?@+lt~SjGRfjYZ4{baZU$J2IhTv zhW;~lnRjb18czBMKe2()YTBj5=DjXW%KMsyP5b5Al5ruK_uc`cb9)DmLgBWxVk{V? z>7RT+to#;j*XHUA(MNFfiF?voH0t1h`{KX@C1rL|p3tRD?;sXhkHMr0I9M6gMsbbk z)zuZh$Cla@2>n%c1E`6vdaL)BReD8FwST|JjbmK3zc0-hq5nxYtWQ?N@niimh5U$} ztJ+c!+DxUG^F^B-(vEw=xv_i2_tRf(#n0->5GDI1c5{;FJ&mZQhSxJZMeQudC#P?1 zSvxi>VWMd?ig}&Kc?rQ6#;XV=Zs%efKfiUjZ{UfFsXJLe9iQ{1{MlD!hGu;E-Bx%k zzr*AIHt z&8f*fk8|f`8ETpx)r@A^TyEw@%6zAdNN}sPoxWtJ8ADGI@|EoLX-<0?qbG;s&9VH9 zej)l~Zu=Ga>5EJymBL+to2&#~IvI(J5DDo^a1*FUP5e6ums6YLv2;|Ld z*cHnC@r-+}m~mr!#^uM`29zBH-Ql|_VH=4!8BN$w0WbtVYqh%IHU@pHUs#CLk`u~9I$={0IER(sMhzfSeN{*g%Li|i5HA?1R` z^-sAk1dkYqWbfoU-_d3dyAO?`GKfTuZI-qNQnMzY>tnObcK_*u1_%l%`nV_Eud}8s zcxQgR8yn=g&(+eHU(BEUh!LqWyLU@r0V^1Gd#wVI*Q%3Zd~;b*8QMsr2Jf{uw?6D| z1e0?-Vg72B)OD`z_Ba^D)Hu{`EH*TapaSJguX-nA@$_(_&p+3+RED!WzN`Atz+Sb0 zoQ%d)WsH_V-Ue$<->}7oh!cYrvNF6oDDI5ngM<~lr-*izA*m107d(ILFesO4>>dsuT$eyMYTdMBw$qO?h>W}FVl3cH|8t_ zv19OH%t(?;mn{Dc)6)IHGt(L*WZT-hYDQ(9$obge#zR1pDrIZ4R1Z#PnY)CGy;?!Nq5 z&S~QmQNR{A{{rv#q#Bo_AqgL`>}L8Rd+_lTDlw;@A2qy5NC3ydYcm$Y_73tIGQp{8 z)fA0DDh~yAHatzdoXd-ZPp6R5(WD9r@J1nDU0=^O+Urbpf+4x34}05Q1dMge0H3C_ z@EOsL&j;{AoXAH=w09$jmEJUc?-P5-`W@(*17Og&u}$9|nS-v+ZvgLUB8pD|GQ z2hvyXo#q?LmSnXu_e68lA9N|+O~hiQl&5_Juhae`+s!cyQgVv4u6qva>(FIQ2gUR+ z5bap;>JnoJqhY?>LaY0WM~@!Oh;TpKXgZjmDlZB&p=jaY_xVFnu99na2J9^oDL921 zl^LMoyPTfgeck97Cfje8e4Q@9-puL2NR*aDA3Iq&B9U9mNU(#U<9{zQaNkdN$@MiA z?WR?`tn^ikD;^KzDo(R)<3p`A5tEwzX2G0E=^*;#cbx>B&z4sM@~)gmn1$(ZK>g0S zzc3fQ+IndrU#82PJhZ)b@(c#63(`b!Vh9;3PR^PdC_A=^!AQ_~={bO?F;5cIo}JL= z=J11X4a2+o#j~yT6jj`~xVOxAY$cJGk`FD2N^Ee)ID`2r_GCl+tpjt*dvIsk8sGn-9@U_Rk8{-t5gc>+E4feVN8g-&NY! z-`Szcby6x&;?k8X=&ZjhnD|cdIPc5p&RF8pL<_xv&_IT~;IsOMg)KOSM(?Kz*{9(n zO1wQA)iK&%Z$c)oSa;^b!H|6<>f%oV5GP3OMt&!EO$v~ypymJ~P@r8@W zN*oM6lR(c89G?v`y-0P>Ap8~KlJDM3{^@p@Pi^Vi@#VBz^<<>VLhk6FbG+%UOZy~f zHlMSVnb}Gkt(~P0zAnO4O*$wce8`dyGf+>!`8{9%e%+s;V&3Fw-c-|Nx208(=o*6% zc@{Y97xZZEdJi_~AS0PDSn&#vML5`IQqu9}^zAOAOv~y7iX6T*s-Gl9ro{+%O(AbN z!m0lJMJ-sGBU6Cj6aR#a>osf7z`(j$TJ)i7S$SE%1*Zk)bfX7r#*17PoM@?j8jp|0 zY^=&(*0uYsF)T0`04GivEaXQQ#mvAy+wH(CXPPpcH@{fmeN5416nPe8`RAEc#TOEt zCN=*qlAR}ew_yT53N^jPC(Y)rH`6L8!pgL>(3DrcZ(+8c0XEg+>m{h@rDOLHoSPEcb zm(};Kt1>`d@uE~mLI_1oYlBa;mdSm36XY-$55*ClNj=s||rQt3Y-n zxzu(c<%1zNPA?1^{Mq?vzHy2sA7LtR$7zh$bj1gE3RHL^!qU%|Q}l@wWRn8dKPPK3 z_VmOOF%ZUrX6bX`lUBpGVEMd(JrjHv`2@FoxrR@Nu@*QF^#K|;{J3W_-6f?9s+)v- zc_B}+*zS+!2o`fl)>Oqz)(*%UUjMmPM9ocJ(e!*-UZ7vHA8lkhJi$75jdYx>QeF$~ z2$qOu1P2n?*(nOr;XxC>Hjt9T?^-0!q)$SX^oCk^ciF4GR`K;BGcJ$+Z`-))X=$ly z@#m)>4tE#*^*pO z{kP7?E7Idr;iH4Ki?jcO%ATugwH?8ou*v=3-2PUqrjdfA`XIUtL9|~*ZzjAmS+3e~ zHs5(Ez#LAL?{>4K!B#L}mwl2d6zWL~Y#8V~8AGp#dy5e53UnwtSOvYY?QHj<9goGi z77({6SX2vqVn^*u%mp{c?vu>k>(Ux`7_)&$&8F$;BQ)g{55f4cRS5|G#~{8;AF`LD zNdt89bSWN=m}Y)>i0w*d`E9=5H1eA)NMt|k5nTMxs0cQk52EUos%I8W_%8~0u&KWN zSfTEYf7x+%H~N-UBU1~aJ_?~_d{Y2TGp$CFgJ=kyHxefFy`;x)vm)^;R-9a!7Fi>^ zJA)wYFg*n(3?>2!h-yL5)&6P39W!C6P}nniMSX#1GH6jr3-H5|gpJi5PEUiYg>#QD zd{*xrU!Rp z`BhpbSdp}!KxPlFDp4mQN;-7}EB`LvvoCioe%@6ES$lx{Od(v2_>EZ~1 z4&`D{meQ^2(6u$mGvdXlix#9=9)Q-#apm#|Is z<%*E~2)xe73L>!LT<>5A1QZTcFKAWOQcqyF8O8a@Dy2E@av?>!W;&XXau_6;hGyb} zlpS4o^GU1G6b(Ab8`?4w5)z4Y8bLupK+%2hzC^QVKAO(Poi&T=x-p6U+1O`cp=IXb zQG;*H?6sBptpRMksntnCw@gCkk9bkU2r)H}Qt|ZiSU$fzyuMMX>|)U)N_}|ONC)%@ zE7D$R=zMWH?MhEV=Bt-taasru`rY@gdUrM_e>b zbC9RY*0H8FH{GYoHwUKbp-EOCH z69@l$Gg>=GpHv&5Cpck0JY=}hh+sMhgPi#Zs*^si;~b4-sgqhwBV(fw*GNRXf6jaD z_zDH2e)}i){ojl3vd-=RRH*(*B;5MkBqP=-m<@V}>Bz9lrCKUwn?j>w>4tx%=`RrU82X z1mC&bPYeLN!74Q*-e^hiJo*M-5afSfMDuVpWYkm($i#wjxU30H1U!qMME{iJ|0yFZ zsyX*oE5e%PHH!felST%0T06A85%vCu4 zEdBxZkErBB5fRbuf1L=c~(0o zCMr6r#vNmu)t~%Y&sS6dxAARa4>yN0-UNGp$wUixJZK+VXvOV#6>Ab{GZ@$fc;k!c z!JQT+R#}K>+lU@wA`~$9IU4zuLm$(iUt| zOU7)aM6zJ!D}ixKyb1C<7o6#t<-?Z4-su$b(}Dq9){G&XwAgA%mXo)yA~hihe50u9 z+vg|s33~zX3fICisM6`**7?(5ZUF%~h20YN*o^DELDvE9O?xl0=&ZJxXp^#Po^m7V?ponwQhHS1W1lJO;9Jz zFtoB~g1>j~j(KpOfOOuEm&)?oQ`?xhvKBa8|CtV3;LSM;kJ;_ktt4#70+IAR7A2 zyf}qEM)DK+*L5ybZ}}2j%Ef2QrWFjG0d-nwSL)_3%Ml`!7XI7duxR7{u2NKwt_fOTg*=`7jbPBD8{PU9oDc6RjDN*3k* z0=1ayF2rFrHQA2z*Xbx@%Rz^-a)-TTs6n^UXr1?ybqyWK2n2*St0=op*77;Ca?iZR?_PXpVDt_fz5{~H)g?m@%XUu1uvJdTOc0>p=9uuy!8`5Z>ua685JCQUGHBg zAH0mw_btU6SP|D0%Uy4eQ227i8+|p^eKgZ&EwX@;vZSiCe17fQx0%gF)N1^nx}$EYd+LLH01PEj|M)TUAI;Y5`GVPe% zI!-*|B#uim4yTF4q(HF^OFmgnZPc;FZ5-B412I6E|vd z>8Mw6i}4gOay5|0UPTHLJ{Po%6qNGsGQ|dTLY&Ev(xd`-1{=*WCKaY7L$qk>u@d@r z9h#e?)F4P*Vjf0RJf!h%z)+rD_FuT2eGfRbAH^Au5@bXiZ`#hulCw@X%R6szfr_*E zhbIsm=-u)AdLO_2L*tS) zpoRcWP34r~%~@dRFRRU_c_(ul8#%zNnPP$W0WIoFz{PSDI9k(8b=HoAfNgFo13s%= zKP!SI$jkCi$<``EUXP?;+-L&~(cdOws5OB`H0YGl)aWByGRzIK!T%&<^Z<<*W3BZ(`8zX26gNBn*Jbt+4~u({>&Y{(k}O_(uIy5N9%)y=wZ zqY)FGMwgF6GFy#W2!N)KZVR0SywwhJE?u%~XX?^;X zf}{UEIJy@eI|nbyT7)cbh5zz(bK(zNXr2GL6Aq&%9`#t9;PD+1`a|I^bOmel{xa0P zQh=({f+`G<5~KfA)-h}SGg5ukxCg@RN_t*2|zOfVi zjqeeF97c@`Q&ZZF)i6@B1aIRcyP=8h?rtO|ReQY=+{PBq$5-#kA5CXp^I03$l1API z?E)QW&#OsCp+NNhH=GH>$nnRMnuL7O#i8GS2DP`L9rKBX>rH_G6k;RhI2z=U9{Qy5 zBe5rQpzE-zwYU{BAT%byYcz>BwgQo1lj_L^vYc)0?dMFQ#_2jxmfPEB4cfNd*mH3n zm{iiWhj}#bu4|))hY9Uf8C(Lf4d1UX5lYQ(U-BZP54F&b7E@mKGfe#X ziU?~yIc4&}7j9*ZBV7nVrQvMRn4znkCP~(MK%;d<79BAi9o>KwZu5{bJ24IMNpX41 zR;$vbUYR^6!3%?&o>hn|gQ%8sl3I55>?EO;b-6$bb&q+l@dud37>}q2`XCj7iwrax zrq!KH3q#Gy%GVDi{SW-x`l-jl_Z0L?rjWvEj1&!s;&%}HLB%SaH&>+{o%J6AyKZru zJQ|`y-L=#<()twnSI}XU%C1B)|36^9@kw-d3{cce@!y|I*zUsStfPQLl1C_uqEi)r z@0{QMxs$EdFhuL_t}n-tQjKUpL@$0l z0xf()29*u_L!WvID1*4PVX~$AW)27xXr6{jW<@{_2JW3un912rT_>^OYx%bp%aSd;6Ij)kq*aF@xQO5 z728GA^3S&wTpF`ot>y1Rd^c)7Eee6yI@(H4aED2V^_V3o37W^F&_g)H_qHeuh#8siDd7c+S1ZJqD3@{38SjzuJ-vNJ}Gdcp# zUVtKVb8#r$T)fmj87Utj8T5Ji)5pGfF3r9^*$ie?N9|&%k)><;%WE>EDmZ8@O=Wn{ z4w{y4=0VJ~o2g06W`4(SM5>Ov6zrheg;Ok%&45Xa6i&~DOz$?*wQYbO$o%YHS6^2L z>%?RKr9wB0uzvyadh{n*2+`+26)J|12e8eeY@Z7V+T+SY*UsYInmgA(qBdRzH+0U_`%s z&k+WTNgg^Jl_du*iaW7PY0gR}75hqYrsi;&7x^+`ls`1~Po9#KTiduKn!T6%{ETjZ z{rPunUiZhzh_=w2Qi`d(;(ErWx8gilkMxq+F~9hx+e)@945b@TwZwaAeeBPYV1H8b zE=ArNH{FFt(VCkQN3~#+%O;sT!=MKbjJ)%@1dWgU9>#zCe9(OcJ0)1O_2hvO&C#^X zn*3;pc?O5kd>)<%wNIl}e86{UQdBsAcax;iAbk2lHE-=}G@i2I)L^~Z(_q@RJnFQ; zCkfV>?})9<%zP1Cw6mqE2`bJ@#&ksP2Cu?LA3FduM_#^IG`{oi;j~&Yj_!v}wdp}_ zs1=*|Hts$u>-Y{o1iI_Kkt^xG#-NLEdbn9Lu8%tk=z=i2&<8o-+FU+x{^3dFEG=~d-{YABT4S{w{PmQ4|!3I z(*HlsGwH!{wvp}3>rWC!r(Vl=T0bojn^ZGcQh}LEYSdgTeD9VC)9~JJ$;}n=8l80} zrhD$_sJ&kHs>p_swHf1OI%+~Zhlogg)h<4EtLp-(tR{pr6Ei{*zIlkp+St}I0#-Zz z7P`h>l5>3V;|KBKtRCjXhp-yP&oB+$e9!5Igws;O`&4d?8vbfwop^DiM8yU*mR7sl za$ClE(TP|cmTMf%!NPY=0d`FN$YlAF{<5fF*yT$#Ov8%kJ!*H6HL3F15;Iw-C=1&x z!X(&OcAYlkxg@MssD%USxL=%pK59PKiBv&CCuu5GNE;%6KznSjl_9N4I#hqQ_W&Ra=h_<9s?_qHEcBOP$t4|K1EneK=ghwx1}c$3&I`p-uRx|X1&NU;b$p~AOI%FE{!*-y zfXJq4USX%le%dbtvR^saB`UchL)=!~TE~Uyl30u|O9PdZ-X0S9W0-#0j#VUr&dsyE zI{EzxQx8c7BSIy!5c}I=SFf%YI2315yZ?e{ZxFUJ3Ks2^5b#8So~3JPRjZJdM%Dbi zEvwIzf|^CUr^kv-3U=2&6)O8_6HU<$H`_Bw>ebOfqy>FX{8FqgDaoI z_T9@9Ba<&;rh6)+cgYq9kAcxnF-;}ty=6d^?eaZLDgq)Yph!u#baywKy(#H#q@@J~ z0g>*O-kTDT77+xIMpC-Fq#OPhdYZZ#2TEIf-% zrC_3^55SybYy&*O>Ka|GFw9Y3sE!bIb$NM|)LR_bwvhiNKaf-vm~C-DRKLw5Rp`XN z6y_-xelN?8``*y}#qWj6PkWQxnmH3FL?wL7PJN#ZN7(lN#mtawa$xxM()S+gP@~wj z@Tl`rSO)({`<<|Z>|bQI?Ts=*9{M0ryn43?YvX`EV4pt6Pwn;>a;W3_{ZGkZOXGDw z0gkk}Y<+JEAk+2KIQEPlfu_`=^tFih*@4e3C)%C_Noa8G*tTDv{ygWLq8wsM6*aqv zE<>B3s5x9EU)#fxLH2YGGlzHx?KLu?j6|Y2=(`Iqyzfh=Gy%?X3VDWxGso9?E2Xyo)77k`VWf6cDuGWUp;?Urh=TpC zs($<^zQXM~-Qk+O=km&G9Y2pQ$-Hc}GYso~*DhS?B)V3D6%@_k}#?b z(IEi*IlX7|ShrBRFQZJ>89=&QB^6`%ma!{uZv66LRUbRS;j&mJQ_>Y!*vLslm#3D| zsMO1oz-m&L^TYMO4v%}cDrgHBGn1i37~|~sFl_iVqj$mJ9;07JCN9dWncRW6d87_Y zNJ$~x_fC{#Q)5ZVyTS>RKGiI^6PstMD;$ip?sg~O-Q%PJ6FE_I6y#VqA#k1H%-;EI ziD3|~4f|loACT!gb8fFW()GYK-`eI5qDjmEoPwg?e)`qhl5yDwdPgDU6%AE4=VQL( zfiG;KLB;xkdad|H;I~Gw>XSjbPqU}=xHOuHM{0n=(v3rwDNa0AnfV36?Ta~6%i$p! zCntIBU4_^+>s{lnwUw>`LZdB(g%KK6Bi+nn|2pqA!gv`b^=nUR1eh#&M6EHu@*s6% zch_pHtP(9;HWw_p{v5_^OJ418`8A03;yrF*0=HDo3Q!X+{i0B`UJV1{T46l_1x7CX zc5@_)ihbzg{@HEo0&KUIW(pX*T;d4)d?>K!2sy~=Kt;3!#Sxj})w9vah8QOTTxm#C zw~Xf+f&LQ^>Y(cPKnVym2Kys?f4AIiGp+cOnm|+NM9c>5f;KjZ<)6#j&bUk-!$dm_ z9B?*#UkZ~$;DlV7acdb>XijmV584@)u!_RNS-MGd)T?tydr>(4&&=mxem6D~i`mXUJcY!M7{m>H|6F*O4;KJ=QN92{*B-7xJ z_GkkxG~^pHhSMtFYSorQ$~^o6GyMxSS8CCDh5^?>u&TRN$yY{DG-|AqrGwM>tP!^^ z^E?(_)lA{eFarA2x||h_$?rx{3Gs!z%&Z!A=o=#I2e7E-%4n*oj;_x5hGUI^`_zc_5pg}S8KU)SrhL7R!`x!y!RS?wR zh#^MH+LOs(+#~aifV$oOGCL8rB)|`yNiAS=Q4lc@4!yj>glI^NnA_plemD1EP~az% zJyPsb)~v-Vn4VPOO|zi!YPpvo=($4{V!{tA3^CE+(oh;H;;m#6npaPtf*gNAQ7FcQ z1-Wm5u6+jCv`z`Y)!dmrN{odi4u&szwdIW zyoPdGh|DsG{EU~Ujs2lWUOtLRQa8oP7GbkaC98!a|gwbzUoATon(jHjw4l$7vPt+NW`9IvRy#x*yL?~eJW!Mm^HrsU|g+0F3q@YA)m(pS~1h=OPDa%#K)tlh`-Yb-GUx)piT`Mlry=nMozA8tTpUZUv5r1amG{7Z7Y0u&{ao6kuuH= z?uO~|l%^C__6!u}etPq*?kb%2nF=41qcHh{212VB*3siBq=Rs10!#JtGY5fi8^J1# z?d`5b+sPZvh-lN~kM$Y%r(UC(FF*74@ws=Z2b9mGK7A^6#sDKPd7CV%^`)>y>NnIj zb+HPg7UugcxG8y&COWQarDL)3bezBdZSsiDvG(!3l;awY??mi3i@nI#Zm-kW)B=Zc zl?dPvUt5jst7&hzi|&!u6K3g+UI{5$rYT_wP0#{dUtc5q>~ynH+}s_Co(DgAZ#dVJ z;+dRGV(9E;Tjjc{dW*6KTnTG;s7`*@KC97ls)=fwF^v*k6BY#@CE@;E1>4aFYQV1f zqUrn~r0m`X*09>_5zpmkK5BrOcElQ*OpqafDz3a)Z#D@j5t{Ps^KD(F7j+{K_~ywB z{LKGaF}clI`Gjs=OLmX{q%0LDC-(Ul$q&RXU(CNoM|o%je6Sgr1cDaY`8&tV?=oNO zMR8GNnNWI@+CU_mOLFUZ2s_{BFr9vOYxLyvibC1M}U_25TN!EGy4Cy0cwDirq7^QcK@;p)pxlF zrs1`2KykC(?`YzoV|VK1ByEeDH{;dcF_!sj>f-^ah|mDVd195{Y7c!MI!P!Jd|CFk z!*Fn&^*h;XoV_X=@5aSIQ=ulqsRHM^!N(ZuInv7asP^0w@Z4$W_gPuwx-~e$E(WV? zT&{&}2VNt5teqZYlaPnEqcF$-9mVV$0U^Nv{+hUZcQPa%Pb^_9&N^5Usz0*a!D#?3XBg{u2UDJbZ{$MxrqyA(8P7&;sn>bt!sLZ zIxTS39`3PQ$&qq4)H!7+eoUS_Jluby3L=n>k`gRg*rWc|dbjzW4ju@;lne`J`$E`C14Ji>SXyaOBFJ8xEefg`g|m|xzn#|nG&Ibzhx~m@|y5H3Ub!n z_F)EjU41ZNJ`@)brTi1${@dyarzlrXN7iMGFPjrOgyBtRz0O{Wg44V z6^oC@gd$z%_(vJZ$-mv)GE|9xY*8qtom&!+3 z*)ws;J`-L+xasX{KQ%0CXZOnVgS=pd^HRA@Q09mLn6^p2gLWxeKt~_*-UCwE+VPC< z#1VThz@B9BFrugE%clXxqbMy48w=P*a$$xz)lZ0=P2Ovx08c-u zey^uhgUFDxe$lm0r%1vazFnls4}MG5MTx!al5pR#`Vx3PaJp@HpC!dPMfdekgtFw*erJC_gl|tZ=ag?usIE+U zpD&p%RgS8(gY?lO>MRZg3j$?&SzvfD=m!IF8nA@OW3WAesB5Gsx!|d)9fc=CUFm~r zB@5Uh@u9dF3n+(aPbn4Lx-K|=#PQG<2jwHsY?t3@%fnv#>gFgCMJ4&83t{s*jY}I# z7HnTJ6V`YxxYRRju(^zr71+GG2NoJBtMyC%q~wK1hgzudtwr>8SQ83){tk7* z*EU>rbMczIh)ebS`9ZU5P9RU(47CuwyE`0|-)Aei$A88j*{m-95rmobp1hHCSo8K6 z>C#M-l^<3NJP$tX@TJwwh&Nh%;|DI3RnyRYV!ndChRir$&L zw0?tpfO%c^u%|A~^g}2@Tr^AWplGcgn=4G=kd&ZP{YR(5VTr0>hUG=ga|Ak^hAPDp zW>WN2DL-{X`FVD#*5qfF&Z5+=V~0sZWN-3Q<%hFRDIH9!JccK%B8Gd6@~^R>;=D`< z_1;t?9T+_1LmWfi-l25#XMbptGmp`%^K)}wx7m}!ATMl~LSp1J z{m?F-L@c?`@Xd6JP~E@j!6+Q+9-4We{U9T#QXZWF_zXACa+r=nOk_YgC6Uks<66?x z%UvI<$thuBWma0%!qvKtVS3E!y9!z5-j}yibd4(ea{^QB*BFd5r$UM#XVf83U>L*a z!&uSh|2PMmTu+M-GD2m{T}OYqgA7~lU6#De=!W; zBUt#VVeqPOC*U5fhB)DDND|UxV*7K1I>k|x&Q-0Xq~58|3o{`}UJ5I;(l94VTA|jI zADEbs{JNVZghfPVV|!OsW3TS$F>e<=pF}Jzp$yd^L5q>MiZTMBI#h6!QlL3*9E6PUx^X`>{EssHZ7B%Gb_kdcDda^#pJornjc5 z;Sp6$8YUeH%?kLqWqJeKAN&UtoR3wv6S((PUJ`RhE=T`&aBB4N(jN=K1Hq^$?}?Wd z-y~vFiFHzt;EFh;cbdNTgnn-d;Oopk@$JE}!xD93tpJG_K)u7aUzR`X&Ilab%gSQ7 z`{@5CEQ4em@juDkd- z8XUQUn=0qgwwivg*drJoL!%`eMTh%DjzIL9Ni?5v3s-rdJ)Cy1*@UD=Q1Qw1Lx_xxgJk))=4tO~Zdv1X%pgo4~9MG6i=;J~ZDy znaSm>$EUjz#|A=u>>QDKUxd;tv~b~*9N`q}M~fl4pfVi%3bZ?3E;g?t%Xq;gzGH2g zJ?|#8P%#!dvg0)2aGl=;#U{{=2|JXwcG{L~+1MzyUo0R1e zg%;&#J|*%ZQ@vMyz9VB@;0*7sl99@{2_tSd;WDJhV}5sF8Zkt1HHp0Dx&_fg8s?~3 z{qKXi4u@GNHG0-bEXkY2Fbb4~vleptJ63t!e&-2<>HlEYE$ADYd61|KR6ctp-4^qN zKTQ6QJq5r=V%i|24etL9x1igP+i(NU{qJ7khd#;M}VbK&58J|Gr}5!0m~*bs{hp+wuTz10|vw=034U-APk*ofi) zFa(&D0jc;SMBfg!aZx(?GGJ&my&tEG6CF=2LX`uq9H*tMJoIg}*Wpvm+r76_XhEWo zdK+a_eOZiN=J|sQuzOMRRwGf?%}Hd^v_KmAG;yjF)fwA!ygj+uCsEDdq{K6?!8pdU z*rH~m;gtWan&KX_o2{WPFiz}V2wo`fFYP<~?(oL$aj(0jACK~KfOJ8nK*z@S=90># zA#ifBg*$xB8xy9<`0#`Jj{}9DOK}5tc77`BaaCC0!N(r`aT~1-Gv&kaiBcbP!CDkGN%M`$ z%b7(-kL%-l=B=IsG!Zt+3q;=*zp(&tBlSmk%_JOEY?7 zG)#1E%0SLY5A73&&5_$Ja4~~*v}55_aSG7dg*PgsGN@JNjI;`-n!9w&$_S_xQ_9ig zsU5oQ@<~Nd0{h_l#9K98HQ|6S=gHm+pJp}_5D;2%PDB(V;ouw8Z9(JPm#D|iB zxcK-=oJGFts{%5(~;Hf%4a$d1v^A_ZI4_01#;zYA}J zT?lxB?x;WA!Z3U9{f7fI=&QkqZm6##57T2*Z;rlBE~lCO4@L+a02o2P{MudyeZ#7Z zTHQg^ufM~)8DKwgrmzNuidg6RDj+1V|8>~0Gbh4Gl6YA`Zya99A!q= zU+bTD2VeGO~Vn zu%7HFk2K!x-)iz8Tu9F6?MOoat(qRrT z(Jk7EU2D}GX!ppt_t}U!idPg790DI0FNX+^3bm*TNWjU_$}}xKi!P*Suc_$htr!UR z2{8qP$y3ZZ?=5vctW0Ms*gN}tnUL~5xSjJ zN9E|`gdi-Q`P&=urn5R=5)nD(Zoe`@VF~nBJNF#{IZNzEQSJSYXo!n;3aWPPmAk)8 zfv*h=qZqnUyXT|kftixyjFx|;RYc;ghY{oCS+UMY%k4OJ<{2HpWKv@^3{Pn`Zu(~$ z(QDmjy)v_0QE_%CF$`&9hTCJ;l=KqqlM)iPq~S*v3n^{m4pH>5i)@e2lQVwStG(-a zCsY?p3g?|(znD&-Ld$&G3uSt+f-y56j~vEYsMauN0z)OEQX*~a0?}tAG@Mtc=?AlK zrO09k86o&cv8^|n`LQ=`$bCki+{AtRc26!8X-eP47vYCVD?&SEHHsD8$@$k-?O4hc zOFJu5<%#y(rYA3^1(Lj2`=fa}*H(EA;Hvr#kuNwR@k$}i;cE?DBb(YJ=PoGP)z4l_ zuyp5C6~BA+h%P2VgMm;T_I~DxNV3LATme?;D1YS-wJ8WTRmzS*)8%V1D5@s5W(<*XdxLhaR+d83QDyzrA3tJ_N>-Puuso6p zMQSM1sBplR%GZO(c3XsXypE9NiC0Xy(cKGo-vFsS^Z0saAKOUA=W@04_`0{HAf{;G zG#frMV`%ttKA0Be2&{E%TqX4ETv=45v0VqdDNbH`VkKb>J9D+eBT>JIkBEs#%;kD+ zG|$8MHyRG7+Ydx93|f=It9frO5-jh^*Na@m`yZZ!)}4GC$gN89vfT)}Iqm%IuiA!l zX1BO#L~yyCc7HNzNekGo!en!AFJEoHrp52{dkdniUC(wvj@(<`M9 z>c+M%vEr2CoH3Myn7Com>pL5CB-pX`O85nF;hb-ap&HK~2Fo$dV7yx9f@ouexyV?A z`BpQT^}O}KRkWwqmCuGFyCh(z&d)H(5;^)^C5(0>pwqS~^86C~!|nM>N$SqOzBmXm zs8_gitAHDJxUKn658Se^Wxu3b1x<#&mhlr_1f_3lon}d=G(RJoo3YsNmMk>)xmhvO zQ~;B3Do4l1``;+8qorGmdmfXMue^RBYW(tL-Og&Pz3^sCQD5fkU+g!-#6=xdg#tR{ zdlVFWn!a^cAH}LDPbLN*Ms4E&=1suri+Frk<$MY7Pb|*^$03+eM|VMFlEPx z??ClNuOOE>unb{{l!l8z#XyKTRrgG>-hS~R>YE&7>UoY-L~h+33BLCs;p)OMFE#a; z7#0dP4|VATU?x-h$#%uiHeqVQ98P|zhNt2A{nHbD&2=d5!CgbNRT|SW&5e{(n5j&^ zD*PU3nPm11V;C4r;Q1CTW@+m3NJe9A3*&<=rr)$dUASa>&6y^*_z$;J zN4P&V>@lfy+mL@upWX+}>SO;q z_t183xtA!qE5hOpn0ngeizdJR7^)Ca(7wP?OjN0`_qxmeW4Qhdd)b9l>OKL6HAZz1 zHFr-igd%A_$95=f0~+`oAziFfi#a^87&7)gz1Jf24r@&{1ufaE6eu7IOWFwq%wV_**G@ z)667;oSJuPf6J#v{mB4NX%W(c6Y^n9;}Inf1*?lWRR)g+#~;tkI5E1xghK73I5L>` z+Y^-X8e#aI3>gO7)(BaT9ZU2gTw~pbnkmj*`J9#m()a72@nktUW(Wri1P0l|u`DKL z-*orse1}UVy&dEai37dV9-rFcF9bp!nfY9jU>c8`*=c>4*-vFwfH{iNlRHUi5V9GZ z5v}%k&EF zswzjy6c@=9Q5j@Ck1D589}#S_DQ(ZVBVU?yp^&%Z-?|WRp(gdo;UvVH@2R*gZJ?eH z0jgTIA=ku}`|s_sD~ec}$FKiS{7S5~`*RJSi03t2MgGvE`o2AJu}LbJZzs4NNC=6Oy(~~NF5#r|-NqP##j;pl)ovlsci&{r5K?mRAk(X=RFrRfjfq zMo>QW(cG5gW=%zj`vtkoM&@+mJ+M^Afb{7>hqGmk+Kc%v5>*MSiyEXD_4H%&LhXdq zUSvMhTtb*S%R{8#S0>qy*kCJok&*CE8X7Ck3?IV3b|GuNyYa~nAGGMuJ0`)954liy zbD@Ez(_V1|%R6r-)FFJC56?y@iD4DnhALZzjE`&B3#rxXw{YivqP@>VggVA*mP(~O zl(#YACXL_o(B&75n5&2@gDFO#MYD`j-(DZK@n&50(*}%n4Csp?syt~btQxz#)*Eld zE~#cuzw=!lf#g}cljqSnYDF8S=e^CEPX7h#CCX9q(Q@pnZ{0S>;s?UHd&6@V&Gr-i zQ4MTGNk5T++pcBl|qL8J+}kmy09C zsL4(@btV@vQ>2g_0J7fy^JvYPKkE62O~u2j_e{E_3U@4qrw)6#f67PrQuXV5;4I&% zdzRL{I5c(Iy4-S&CNV_$@IAg-O8hp;a?aw>@!}P)m{@5fr zn-nQ4N8saZ(h%6ND5KJyhWqqt8gJ0lifv8x}cso|ckWfW{56>YLbEIZ;sX(8mlGu5lpXKv|QJ2qp`+Ge#&dQNLCCS*&=Z_T_hDcd5~H1z$F@ zLZ&-f;{=6IIy=^_eWnOX+AE$T)MU23x|bY&R&qonh+W`B#aC>Tr6O{eymDeFQ37*F zFetOiIr+3DG?>7E8HC|s7+R3EUU*m!f4fVl{EyA-zL$D|ixy61M;IA;YCZv;ULir` z$5H@R1uXtL#3vdh<{p`x?0yh%Dh2Qk(zkElF29LgqSos>j;zY>sM+ElG4m*_I|VE@ zQ$6X=Tru`)6LXwW-kU%E=Kt=^_4>UVlo9Je$=@Zo+&+TqQ$;N!t|sI+{)si)L;&ID zbPDN+F@r^4)BUxs$NG6Dt0le%GEDtV8|4%kOT|aISy#_9w527D5t6ZyUeN{RctiNH7>x2Y`nPA58PS&PK<7=39lI%gFQ#u9S zG`gV~{AA+f5_!GT#)0~5K&i<3O@bp7?`!_&L+M((Rio0TfDf(1Oz&e-u6p9&@DAc7 z>pS{m#D!f<2}L1g<@-%9Qo1djGccDc-y`DTTE)L=f)Nc2h%j|=4MIg)32Hp51Vzrw zl!d?yACiV^0eGY;H_wCC?(H9WbML@e)ivlRJ^g2Hn0fN0e9t9wg2pDACwzwiMEKo` z#eTXuKW{Pv(uJjiN@XWl2;z3x9*6C}Yjr&qX{C1IdGHl0T5!bcs}bMxY;uRW%c1Hb zSeEGZ6-#5*N8WsS19D3DWBugj^G$<@Nc7Q{E7MiN;)@ObBR%*eP7cL&U1l*mO69v+E$ZaMB$X-#)1 z?CCT)E$#pu`b3%M$7v7$_Bva77k6m>^iWDXJtV6Z%`6gRA*bi~W=+FZrC?)cVjczFai~bm&x` zMgNll$TyVm@bl{7%5Xt zcm$ROLF%jX1A>pQQn_Kzv~Z&EjfuV|rwBw*x3-yGd{n|A5_%U@HJmcDQgx!Q72VsX zS*lmpnh(hY8*Ct@S{j7GFR3LsW02-yLytlfSRT@n48I_I+rsXo&S0TH$K&=?rkc~E zTY!^sKnU%oL*H-W0(sV8s;tQfl(b0JryBF4U`GSm#`;hppSe?Puf%eSHiqvBtfBRe zsdvQU_z=x>&dsT5AR-bQ|8$K)WAo6m>LG~h935^E&lgc*%M*gcSvDhr;>QYAz>3$! z-ZXzRhny*1+Jp>X0?4v$Jl}i{G|F*sPkYm@GfX>I08Q|3qV?FBx#0Zx6F+f<+mn&O8r&xWmHc_>we?**&mtf7U=wpSg!5LPK?u>xB8Cbc!438Cw zf~DU@Zpq}<}C+?7vGY{p};ENba9od zdmR%|hjcY-%6VOWA8dYbi@plS;ZI+q&E8l{PmqHP%J+sJWnHng?9j7_)!96iu?1oL zN>EhImkIDzfPinT^+?>#ScJ!n3Ym%O!58|C5#*lQfCxdMnE?@nohSb^S${+7B9?6+ z66NiV6ti*6C2E`DTx+-6oHPJWQ0K%HVC`tXv{)%i&ckP1U<{OfCGA7_A@KzhCfMJi zKLhqIlePHzXU1$Unk%8?KcXWUtWbhAK!o584`F<}u+&kV{Ds3r#gX=#rjKRuoOQ?i zHKqG=M#7sg#7f5t10PtJU=q=i%K?-L{mo_$<&QoUFyhis1_mziFy8$350;|pQI9oN zZ-*yx^x}@#hFX_|=E$a`o<42xxZpT!2i~F7I;#{tyWO{w+WD<2F%5Yxx?1@&M9)=o zP%hJ~Ztg!2In8eN2WX(~<=(=b9r?{X@H4v!s9k_eW*yQHYVw^oRYT3UKhfvwxgdz+cZwOxIJ^We|gUk+j6&n-f6_Jn`=6hhCalY)KFGW2UT z(>;36DJ0Zgm$Hy`9vQlg;(Egx34~WtU;S9#R!!oo$1um33 zIq_$T^tS9{1d6``n+u3#f*;gU97m0biOeT8@}+*lB_j%YpT*fAx+2@u=;rg#GS3k7 zV9lcpV7nb+f2#QU{O5T0b;k2(lp}wM|4E(zrA|dnDXc+NGQ(arP;Fne85h~b_TLCg zLDedoxN!L2d^0iaq)f2IYg|JY_L79Qz`AtWy8AIsDa#VHr~> z9-j;x5?8R(I%Zi7(U3q3D|&Zi&U?51?DN?7C~ZqYo;})zGP6{=d3EcbSl<0G zLUgWSi3Sk~>YevV>8S&uZJ3lOORMY}jB3++C!C8sT`r&Xvj!Mx`I^cG;5+-094X{_ zE+vHUO*19=VYzdPmClaL!!hE!>@FU2EDaybLXTpnJspFAIq@3Yu#}p7|;%JJ9UIG zF@t?u2;f*0?}MK*=*d83WMDAt>90h*4W{@53q_JA<{SHS@Pvs|;@WzRF@=A;04MBa zvP7osy#B$#yw~GQ%Y*3@BnjQU3xbApvNVs5@)_Uxj~z0!7!wxiQD&$@YE;6P$vR(# z={sgh?ra$Zuyesz-m1zJ%N##^7}N=<&?i;vv>Q*a9vu959d)|-?lp1!%XLfmCqj6s z9IH6y=SD{WeJ)Ul<~9!v3mVCd`FE##F~8irYp8x!(r$S_T93UK_qNrn*3T9d^Zu^( z3GIK`5Otd8QQ&BMO#dn=MG}=Uz5+A#KeST)tS%d5_0#VL$-=43VDn?aVCG^e%#qM< zM6#q5>DgSQR4D*B0v}u$Z4eZZAB=!HsWPFgtge#Q^S(B4x%U<|8_Kw}iZ_DPBL0H_ z{w^q23jpz%uKq_^-{|SkmIsB)%uu5<9@A$%meU{vyTBU?ruXr~bBt4MJa#5z`XkXi zc)kwE6E#993Deu$!{e1sW}Y?=Yz)o>6n@aGYzpwRw+-{&T6^Ykvb{gnEao0- z_ifBcKs9`L)TI7jnkdU@vU@r5uEJYvN9^mEuW~n`dWAxcb`>M&w(raPgU7Gl$V?t% zf}XMa=ETFVpn>f{G>Td_FPMhQz8rk)k7DBK9FnUUus_RRM!Nku!8=5tH?9LzVw7et zP0V4|z8Z&_&1OUPb0}+V!|C&+7?SX@3(O+B5_e!EK(;39pM225 zu%^O~Aq=lnPuRc|N7l}^34+*=7v|*5adHZ`wf(}TRT>znK%E!F7}LcqGL=9uWiq&% zD8ya6q%@$6ll54*LYdLOoZANZN*E{654a})DxZTy|C(M(gD65gU7RwgRe0|uVehZV z0`ztH_XHT*AEGH*+0=%YeRQ!hycL`uKf0}B2<(goE?%%BiJX!rC1v3Os#Qu?iKvw% zpBqwFJ4ExC!A3NHY^K#~p%G;Nqt};^pGWgG-+YNSsY>kJ9&#yP7v5AkdXA4S6m1TU z#dGnz?e|amJ-O`(D5ddT{F6g(&<~27H2K|s5M7z&GZH|s#@6@y@)v0iOs&BPut@-e ziy1ZvzB)UO(y+>ZIk^Ey&6rQT|Ii+>TBg+laDxP!=3hmlfn#gO{`5=xUdMuC?AURU zZ8mmM+3-gNq}2G4>J`PmmMhss4CIWL-}Uq@;kJHg5|O3Jfqb%876~>X;aBxqPV{dU ztfte{t}PlTQ?_9GwXC}zj1QBe!W}5ma)4GVa^vr1HmT$0GZ+@dBW#l`Q_IQ-CmZ5= zh_N|`*iww!6@n%SG%X|Kozj>;J zw$Z6cU%_Jc-YSUnIOI|>#`{JC@I+H0GmpR3mMW1|eL19f%%_>Y!T@F7l$G-))r>%D~U<8HQjJU^%<_f;aJy; z|CiBlQ;S^zz2IMZI7S|ajQ?ve7V)U4I(7YnfwD|F5Nmn&ix1tKHoH#pYfwTuZLD%pyYEZtHKzFtX@npAxq^#nT&N^*K8A_;kldVu>wVz;xJ-_`nRp=$+w&F z&TEn|{n$Mege|0Wg0S@aRLOYJf5bMYJ8@?T-IYuuRzUrUbh|q%;2jZUfp<^t5(zFO z5k7nYj>AYO23$P8={2SeJO_-#(tUPa)tf`KX`^c_FowRKk`l7>2bt8dqceS-Dst|p zcF#r0`@=sZ-IdS4-d$~edvR60w^x3pMbdc{_z$ZFVnu_04|F7qw1~WXb*qjm^{Hw= zKvclsig(gIl9=N(dkoyyZPWnpae2rPwu z+Wx$uoxE`B2hwEJp;%8`l*qj~tl@TKh-VNX{Nygca`8qN3C*H^;79Mq;DLjWz%9+N znU(qV^bl>EahJm9DXpy@MkJ<0or%>ivSG>mW0oHI;Iw&7y9x~ycjs5}ghi!c{}Uqc z!?dx`0w}#&s&Iqodx;L_Ms!dpMo2?Jov2F~&IsjnrYsDK(jdX|(9FX!@zR(4J>@nW z2Z~2)+yLETQmqark?r5OJWm6CnQ`+aSAd_e&qVXuEfM7^d`lX%Hm~vN zDOU`+XvJ!c6!AS0>6Mtt+io5bsIil6{ty&*$7b@27JIa7^^^Igw)a{SQ&oU z-(r5{858ggA0+47SswMVF3$jOOhlc4w)*uv)&saMPnovQSZ?ZunWp;S?@cmKvvsNN1#jUmZ?Q|G0H{cuo;NQAV~&HUn=s zR*i!haW~C^Go+J$CMKTDa(bOKJQ<)k~k~Z z&#M0DFc?P!f1q*tP8nK-HB#fFb__=|Tieh`Xo@0?ifeCnW520h6Lc!9@ERJU1K zE}z6~Uwyr!G;AgpRnh1~JO{|mgN_@p@*l*E%N|mr2rV9I_)?bljOC9meFc?x1^Uus zrQVSki5|}x@lICOT&H+x2N+OZs%B{&!InRenM8Q-f?c_4C#YvjAvF6$&k9b=Dl8%w_bFKW~G z(;Kye!3jE+D~x zb6a5}PL#~5WTXAf>%9^oc}1`OdiTbqeaz;KvcE$s1&h=|-qk5!R3ZP{n`f;`K2zf;yphI*V30J#9?wc%Lv zWAEA%Pa$6i?PQ9K_TGmWcTAyOf(@3q7!2{@w1DAj584icwo6E~u=yOQYi=`oY^~+0 zGpI8VhRWtLgtz>DkDszGoS;ZP23Lpw`gP2Gc1CIx56+JSh#5X^uBCUvu@wpwkM{Fv z#A}rpkfqaXD^>nr7Z+cG?K)%yUSXX!C*#^Q-Ra|R^AN43RX{$8xFNJk^+7fsEmL%8 z_=7ukGp}l;TQkR-`CrCVp;|rmH)MqHvH#oFdrI8YxQCgICS5NsT83*rx$7H<2=EU2 zDz{s5?tPS41W<>YfuYSN7oY8mBmG~*@LN#4LtjFBpq7UBkCyVMBNgUxubL3QBVYY5 zOv4XbS})8>1O%$?cc7j$G7b5ktSW*_9yiDS+QiC-@f>b((&Hw!)N0Rj9tR_Z6i`hu z#mL9IbhfY+lY|83@W(4ztgP%~%ttHc|4?2%TNtE?)8t*=@5LOpt$t&WNo|zeQRBc3 zqb0!x+>#{5L%w7t%r)5vV-8s>IgFuUXPXWT57))-+HQqa*52Xc>-{e>&OKCTv9x}G z4NRUs&AgmzScjkS8uFV0@)1za4$0+xU)Re1^G+nOc=eHclg{O)HCiG7YExyff)VEZKF6s7$*KjdvD75y5)K_Ht>OE#g>P8O% zX7Dc}RZVv$5`={CjOq_;(a1Sj8B`Ap{KK7F}Z3SsgCEF5(7k%+;8<7?~c zwHw>^0eHb*E+ghH#oj*+=wrVLB5;9$%Um(00o?h!Z6-(AegQF9Z=7HJ_mxq0fWNIl zxnDVcHL!!&1&NO|_&lSyzT+)N-&$rb5aSKho`7?f)^S(7>)n7g`{T9*GL0I zZw2PmpF8ERffMBB1*HvZ&QFHP8i%-B)j|VgvDwQNJ^@!t*B;h5d79o^QPbSvKX7gI zV%(SYmS@|4GplpK(tu~yI2!h%SSOfTmQs@CQ9jT_m=ckQ0wWFBsNcLU6JQ`r$;imx zfXcVUwk_Oas*w@R>fpc*k{~b`duW->maeTa@QL!n3wn4Bzd?rKsvUf=ug4x)rPG+f ztfx2O<4Qm4w5!4O(tC+rTz98kK2edt$)Tt}^qJUNBiOX}h)shSYq+zAFo1-=8)}J& zDbyzbxhk<8#a-JXmH1#)o2Y2x2W4Q?HQo`q&n>22bmyJ?i_$U#0A8o4vZcC0@` zp0hmNuP;cyFeHT%-hn3ktPuaU{MWE>jPx7Lc00$f*ZMZ;gQYgbsA&EN1vgTGc}IVf zK42;Yd`~~#qFbz6Hyv*pZCY;`;CTmIOZeOnjdcSJ4lhe5-`nms|KwGm;clI=PDT(E z>XjO6>mvycGP-@EG$w%-8&ATZD!F>Bc-R=2!A$FsY~pew+|)6Y%P!;PlIZ1OMj9~g z-Zt!f8z;4@s`4jPWP}bv1O({Z?unrS?<{FZ9$yo?O_z0NRp<^&7G}Dj-}uQEciWBT zodFlhb6PjV2mGU7Kh3swCegvSUxLT!jINNhG0SXxSO3RzK)ifQli}L^K^eRDz}x}k z1zN?Oz7T@hQfY?}aTtNKbiJ~%li2sx=KDx8Lj#&N>2QTN299gwI|&jp^Ra{J7fz09 zV#gq75zqZAJX{F5g6IJ)-Ew7B@!0jOLLwC-=isAT0l_oMQ{x(xM2aOREzHO?Mpbt*W8rv|&men6&D0kk zOud(O&_YLiabnlAqHi&{aP(6C$vq6E-%++43Ln-CZ+$_4erqVCT$sri_@gLHUyA#3 ze$FDOkh-2YJsm>}xUkebrW>ES&1CZbwZ;h*J`{v8d#4VyZenJ*_&kgq-~D)M!($7B z8_7B1-ovS)C(PMsE7Bsfv~tDJ0IDgY-opYoK)S#Uw6l}ZX3A7%rVbaxs#3ep&Dy%P z#o|#f&N3Q?ryOgGRbgjE9H~iX6k$qqAM@<-)~^E13Rj&o=aqu76W2CNB2bbC;J`yt z0**StK6Qxg_}lK5H~zs78Mz&yZ<=D)0nI2N^r9xSu!!067h0aY1I=Fy;T9$?V(GUo zChAyl`r^W5KZNhCc@r|EICo%j=-ZF?G1U*yBZ1fDyL*nO!@pYi7OB z@c5p4^$9yphF)xs;pza~ZW7_Emq~*g5z7+%iaG(&J3LHdF==^{iNn&p@KcUL1|~6t z@<#Ge%c~#@0fz9P9E7x)Ly_Ja+iJz#NE~mU!Mauns+1+g1?=B=Br4O?s#(Za=Q4YgdZgSX(MBt6)6#U5fU;x#OP^_7cKX?~421u^&E~@~70U zwb3OSWG}jVPj4Jy6#V|Nb_UBh5kRFF#O>2&S##ddLxeZw z($uuP8sDjEkL8Ht)Zh8^m~z_>Qe2eMVLRI|x+_V0%B2E#{wcraup0XxBNY_nBN3b+ zX6OH~;7!`4U{bX`4(9a2gM)|E-?L+o?xjH5f7KqKbiCcutnvlSGGmM9z7&7TZC~7% zb~W~V8lB#8C3FQAVlOR27$&~?FS*p!wb}`NEB1J%bG_dgj@M`Xto8q>@7y^>o1Ac}zi}!p zE2i0~Sg>4}!L16tv5^~X%=Xf+NTlBtZV=ZF;YM!IGygP7BrKzif_@&f6)|IKpql=f z0+-QV?cHAEeR}byyqdx%20Ma}J8Cb&nf`;xWK zoMO^k))#G)d|38uPxOs!JBB~UTtv+xTU*oewB9~YJI8R<=Uu;9$(6TmCW0~h$aE*B zib{{E;5Bc=7E1@~?mKnfElTB&xyj65aq(7I^mRMLe!)^a8 zZhFTO-iLEuU%J?|e8b|tEKSl)K~de{0y`S*%%QWPl*H|nN0Fc=@MvgvSDWaN&yjo8Dch9{fV z%&Ny@Z_AAODr}^y@i4W_VmzXpJ;O_r(VdJfH-zb|r;g~CPKNVSePI@SeupSU;BETU z?a6KusdPCSpD4u}F1{roI95a~eQ&fl5UF2qAk1n9Da{05@@JlVon_xMRM&km=a=#} zV|LvG4>3AN-P}O0cJcYO$Je4ub<+(C?C15Kvx7uG+qv$pn=QSQj`gpcF5Wtz%yEcs zc~fL6c0~UO`@S;&VZWCzoIM+Rz(uP+N`)<`VHHn6tMO^7F$zVI%ab|TG#n3Lpm{2+ ztz$i4US-W&9#7sqJ()9~QMV*gI@oaN3D?>0!v)nA&*lKQ`}?S+s_@zTPiuZA0q-eu z@SQRO`YeF7s?nEnHC}#$X*!@-dcLt4w8wgHX?Cpn`oHC;FLO*f8Tggf!a_JIx#r{B z7QQmQgV*9d#0eU&thQmhsk9sSeN);~<|3^3Yw3|{n9#@G7GCk_+k^h!r14(5S%np~ zT+c0Zi6$hiScB86gO#xDCfe36Jx{|hY8}^}L4jfnT;+bv`+4wo9rY6zng2siEVI)EHa6g&^ znHnw1&TY(hA`5B%)xVHwg%aCpHKV_W`Ch)@7Q@2m@XO*$#~#CBql}@%yGKrI>dua_ z?Y$X`=}67@KA=z>Xa4O(Q;<$&p-J4v)2iX@q_JO<)As75nV#jZmC`h(;Pjqk^?QVK z9$^Sa8Hu2Y>XE!|zEa+_+J4jeo5hn3MsZUA=PW<)%#=*K;(7^5V-cUXRfUY{l!*!K zpX(yOpDv`-#eBCgJN-wsh<1=ky7PCLG3trj@Cb3A;T)!*%hB+nfkY8)&tJO!wdc^p z8@K9)ImsakG`R3c>GPYHzH0}$xZ?g2l|Q$V{-r8JJXa@ks{A%&dTre^DtMy?JOByf zOb9N9Uk;#5^S5_jgjK%~EZ1PQ$_vZx{eh!3DWjq|az!ub)$))rAD@$Y?_)xS`ED)SPNIU zt8RVd4*u3*dW~qwi&OS9`Ywkat-OnnFcz75NNA=c&S)f$_WfQ^_+_J$##YUg+k8bC zD05_SDOz{RHPATJk7s#t$amB-yCk%sJVjFgXSa?MyN^py?OS$`(_%GT%dgDh?VdcI z6i@S7_`5|}rA{>7xhidq188BwG0kSkr474*@%>r&F@&jLi%diS8riP%;c1K3}%OsDv5-$#{ zCDl|4x`~#?=WE-f>2Q=SSkLI2$b0T#%2{B*NWgc|L)gI6Vzpk z?BzGF46@JYsD0@hzj(hZ@gxfY1hW^9W$Q4heh?lvYj|-$1nBShS%)sW@kYZg^33$< zX|)(aX#euYsoa}(>u^$s;4hzWoCQsu?tpD9G3JESnCNO!~ z1KFhEN#u*YDemH*xNq>R`c z_eByX?GiA$8BPx_6cP1ih}Cv%vW20=&3JP%Tec?Vr1(QW{Wo^~8pQ(B7c)zZHCv_P z{Z;Gf&T4tf@8<)5r*qqJuB}@;d+5}96Gu0XvdjtAXCeENqHmp3*U%vCpb2&P`iczB zelBkBk5n?eUt>4p;k^nkX4Yu@u(;{f-Y+D@#FSK<);+eMw=X%5d1SD#)?f6ldcm=O zv7c{yzqZPr2cFdH-T&zEHAbuRQN*9p_>EZ&r=?r0uc5&%%WYcZFZ@kUo%1AYtE~W0 zLn#Ht4AQe@;_fOJe0gUUox@N4b6@(ExA9NjwT@{raYVK8{(MKhO)+EDc%8}@I z;YCp-S0}V)SjLAFx{T|V@avIh3f-HJ>LxOH-v9n}ybK#$_;uW6|DeDva`8?~V6_yQ zh$NWU_>=+#tLwT(%pOYS^fmXTbHksO*|{!@^thBrkGXpd8laoj9at5 z!NAagQo#k&AJZ)JuGF{R>?3idMm176TNmfy$@BQ~0neCbwogMds-#F1A|rAwZ*zj7 zXJNMTzdWMg4(`)~<3G+)pz4?WwR#R6tvEvBNiUkd2Wmb>AG_?A?G&gN`X;lhj~&bN zBCk`M%9vFkv7yz%*VB-LE8BUD_g4#6r*BF0)$wxAH)cpocUX@6mf!pXSt<5&fnKdv zOFi`!W=k{bDtrqT!!LbFyG;=yK-z5@LXiq@TeX!?l}H>!fQ(R>%-NR~-u}-FUu4w| zYgojk=_H0@u*GX4#;GK4x@Lwcy_?sYn!5f5Th~yLo2$pV4}YLcOgye>_j8%0d?gcM z&A-|)D>c^bM&x!Vhq~Wz9{kslMb;XtrnNoY$3m)KgmI}+=Ik3g^SabAJIBewf^O`L zz56}lC+56M`gCem{Y9q<$7sY1ptWBGbQ-R{(O75W`XANr?&f!YbaIUD?T7E^!W4R+ z+a)53U+5Xw1p^13H^+-wN_d@M2)VKAKT1~O-5TVDi6PiZgBWn7YC8#we)JkgMyzKQ ztOlnyaKd-a3|C&1K}`>Djn!?f{HLWK*PMx5Q_GAs^==j^AJ&Z@Z&>%-y1n~1*jRq? zwK8XvpwE3Sc@qYPBIKER~af1?E?gn{<(+D^7XLc~`!6x&PX0YFXH_ z@#LHvLv!h2_tLdPe=W|ip(c~>|GJ$=&^Gg!KH$T-lW93dd23E%7gufPvyB4%)Qi{o zi4P?Hk&BNPBRU_>f+~@H^ zkz4L0Ddwv3e5of0gLS-7w@VC;SdOq;gKW{Vyb-jLi{CMM?jVz-Af8TdVA+0YxfAqi zn2M)LZj0=h>wQJ*XXS>U3;(&Z-f9p7ZWzQek2>59fU_^i*xgK4e|=rH%1gHLJ}WAz z@cF_rttM$AJu+71lZZJ-DV24MM)LIk0-9il&F$#|4&Z0A8|-e0J&L^6Vx;Q_T*09H zKkAtHXl#1J#qgHN^oG5LzscMcND(a%Z)4`NM+QB_(qY3fbP!Q5&mUd-?TPg_z!>U~ zsXpuH_orjR&9`08;>7(fxMwBMt#d!_+N_Qz2gwA`sV{4r-Ca!g+G0Azi$DAA(*hEc z>*M2bxGP;MHv-7yd7u#++T@@B0o@C@!$f!(2B$2{ez_iT`qZi7cB3dIKDM{;+RP7Q z&Mj?i4gh-?8h1yvTC5B$y?if_;!{fcPx3XvYJ_9Dkl`Zgnnypqp|X4PX+B--^v2Rf zhl;E3C5?r{Kj)AVQ9+5k;)X)P)-z^4w&&&Zj?(yk!`oUvAP)Q=CBLKMJi`=Yygeh$_IPOZUjygJN zxQVY<2v$d^J753Wl-$LjBWoP@@&xCiVaI&mhg8|MXP<`-*aWLjnsvRuZp|^sAzRdZ zLOJ#-DWR(1@clUiRFSQy%To(`vE|_*w<fs#d$&esJ!+{|zbFZ0)n#{3h4$KqFiVz-A2?57}QI$*ZA z;b!6(%H@9CdzmXwbPn`7=bdn8Eb+Bd30hZiHtp3Sy#RUaDB}!|#*h2gGKX z61cW8WEA995Dd8~PfTe4Xq0RDxbsEzwFM$-ykAx!nZu!JlkZ{7HV**z>A$4T0U8ir zv@#qwzujIrKvA-JzNDDnz@Mh0`mlHE%TN)mpfUbLY3-J3LJxJtm=zsEj)Bx=cQ_BhF zIP3nqfz`}*y9yADcu1H(%JwweYcmZHRW&lncdl7lwio>Rpv8_+$J@ceu=9KpK__n z1|4P`Fh9B+b;rE4dD5B|H@86M4YfYf)~T?C4P3ci%<~oF{{3isQox%<;k%!oz-vk3 z{jzwhvLwwlB>T=6$#hs9J<-|_^{{H+#C-S9*2TmpOC!lKAEPRNaA#UuiznB99r=0r zqHu@#IX2aq53ZJ?Y6ryju(Ky!y-Y*|DTHu@x~3%vez>Jm16-_45tL+K3k@Gi&QyLTTQ}pSYPa$kIUJ9s<5;KtbaP*Q zyNz7w=`%`d8$SeYEqHL{_pAv;&L$J}iWX=!*Z8SE^PY2;4kFN_E@-`tRo>OrS29K9 zvc*`mx3|~R#Sm`W+1r~tI?};W1V1w9qU!tl`|068FXQ`!yVLeF{#rMM2(_})i-ef_ zhF5io^^c?pLC5sGWh1GSmTYD`j+%)a%`eo4>wWzixsEfuN`tj%Tpdc+fSVFk?qP4e zy4!`0A1xH?Or>Q>Nk*ns=P^F|L9P552kPFF)ozUi)YbG{jlsyhAIS1%_Z*IjKZW7v zE$V5ei@|>y91Od9>H}Qk+vAXpN{my7U(gnl*wcM$k{#rny<;hzt?<(3xQ+4D@eDZh z$0(p!_eCC-n=w=37hm`b*ZVwqALnVb4=|?QZ!RNLEgiz_-*bxV?Gfc$6?ig1O-`P? zC)An9(;GUM6mo1;zfN!1ibbg4@v{ZXw?6ux3_)0q{4skM5aHtKd;Nt@_XNwAFLiF|3HSTd`XEu zitbkRmkD!Eev;p?Au-Zk{*Xq?_jZ7Q%x*$sl$MhF3Wq9{Ci8)($#DPkdSY{(y8Qlx zAlFTs*t$Eh^`7J7?hZ`MeI7x2GG~4eCiIat+Jc|@<{PI@7SCPoBv4{G`KUVHKmUfO(B-`7XhOYNzTx{;XaO}!sV%-_Z!fqoY9R*qa)lbj{ zwCLF_CcDb2KPN5vq5Jc?RIF!YKeKm{TMZ5!V0!K<2&WH!$TOz(ZKms{31`d9_M2yX zv04++J+;B2w4&~o-{ZB1up!eTJE)NxMDTk4dxBb1AYrx3^9)M!thp~9MWNu|nxA&{@Nf|p)Qazica}Gfpk2IFr#l7*hs+*i>7;E%=8F!yC!AF}Pb;)t z>%02&vdF9Ci24FDUoT_kDwaes;=wpoaZ`JCzZGSoqO2V5w*Ya$k1Ve=kOqaD8PMJ{ z#geG_@OPmcRK5%kjslIQqia8oRtq1%$|{ouq~-W69H2+jYO)H=vISMrp<5j;Xl-%x z3i897?A3D^=jP^C9FC@!Lh0a{)YQ}<%g8X1&Y&AGC`SwxoO-F66EMInKD~$@z*{|c z#Yvy6sE)g?n-}Y%NuB1VOZ>Iyhgy5SloC-}Xj~Y3BJNOn0;W9cu-k%L@V@^xsIUtL zjqi^rOIcnG*oP8d(Cg|lqL0AM?Y=^@-M?wcaDCJD`OQ6Dl6x(A?{9V&bxY#qRZkqX ztCc3h4Sv~=pL#ly(J|&+1v5pr7#bA~E$!=>rHQ(De3RixmhZ+edz>G`Q>E46ugN&3 znxm3cTc_EOa3>*R6vY=zahhP}EsIL>U8#1iDvaUDi)TOj|8%FSr>4Vhp506)#!uv@ zlQqQG#Q3>HDF~=fUwG@5TMwsy+(%BHej#NbbC8oyQGus-OjZo~>pi`7T<&Um7Bi!o z?=3BUjl%NFVHt~|8m`i8S|wr<5>P0-w`xtHNl~DmgdV2Z4f9c#PUmE@7pwwW-Q0#J zcM{^trKUG@o6919(ki(J_YEBwg=JtnA(`wWM_iJXiqQ98^5@yuwX*-~W!(NZe-14q z${P2O4>#K1oiZAI?=2OQ;9apGeJ)_r_3(7{`TqJA_H<$`TF`AJ!E3PWLU3q)yn*K5 z4rI(NKXw}_610&Kn}mc!aaEP|ycQHn$rT!K%#%V@u-EcfEVzX!xXYz@k|URn{?v~l zUdD8riwP(9rErp-ymwu3Np|>4A06F1(L*=!IE8K&>28gq&t3dB*0_=sXDzp$`gNu# z7kqnPB1?D^^$%3ku1m=XN0N`Cy3_j0#wCT`QQYp3J;)pqps9jh=5h$R&sOsu! zcwZnqYkFico^m?>R9JPW)|KcpOBK+Q*jom<@DXg5aIpL`hTfr{Uu;rRZ~l{e4vSZt zT&rSHmQEYdu)Q)G{ayVwPo6=y!4&Go?XIo}zuRylOI8=S?0rM)!YpGqT9TxwhjZ;0 z4BJrMJjw?j@m+EAeE!DTsV>aQN_s0y<_{J5lgDD{0*;!(&9sYHTI7OWL8Y9LVvWHs z8p&jNdvC>}P9OU!YZ{}jo2Lc$M(bymj+1JwVOk4a_uEI@;zL_z)TY~*A@}BohVe+g z`NXT6lYTg2ft9VDxIF$a866!3#&w@&^byJKz%Qs%^IZ{TeHpr{(2s|SA@%-Y-%AtUqxfFfbfB0|X~0!{Wt6v_JeVptJo*vC zw2^N%VH=xhMSPPkzll+UVLL9FatfVQ+70i*Krjrps?F#=blh?hCBcQ1bR1$Fiy=Zk6|Aptap;hzjAMZY<-XU|6T zg=Alc3VQy&4IPct9j=*tRJ=iv(;0H>T=*@Yt((3W>?Yix0ei_ySYC4OHu>|ut76D+ zBMoF05Ja+SqtY`jH@#t9v1dd9Q%0kJe_U2OY>PZWXw53#vX`*YDt?ju;pf>s@pYGP zyna<9Eb@9m2sMf-U;LO;om{{~j(xREr`txU4gZhrQ9pPQM*TKQ$^Fl$KclUvxMv3- zzk|D1+F*VfL_NAAV`H8SbTF+amEyQRNV&B=6kp~$s>&Ja=Rs)GL@ zYE`aTzAn^qzAKeHtN)ymXRv7Z-F_{a^UZg!eXC~iaZA6nUvt42mf6On7<=`3qsb0Y z^!cCU$D6wB4XFe6747f2c^M514bQCZ#oV~q)YjOfo*+`d z>0`Yx`al=!_gU|qprCB1O-%D%da_OblCQ&U%F7xP9-qwOK94#bI8k}zk!?W2^javx zTLW}b_tBK&1qlOZ;_TZvuqw~LECe@5JVabY(B zlU@J&5gw0sPki#^-K$ptq-!Z1;0kt|XLuXbVj2V&at^pf&qU9}>3Ol}?w`g76-Fj1 zqMBBF*DK!|kZoPi*+2aJbje`d+vc3{GrsEDmRX#v{VQt7-9Ilf?sy@V>WzhZQqT;x z!mGeLKv21uIBVPI?C#2YZfjy)630!>&Ak`DUD)A7*-iDhGWvLBct((NoEuic+{`a1 z*w4ns_GMr|Z1ouC201iE%*rv@vzA~37_eKZJETb`Lv!H;`R3SA$MHt87j`{GwRKDr zB*4DwePWE^g?48u9TuhIi`1Gi+D<4!tqXO!!tkS&V`PFHC&^#sbdn!ODZ!8)P9?kg zBiD?>eLo5Y$dzXw97abjq5vkk&2iJiKU)0MyYHX^78l(YQbO?V{ewewR@M#XI%aUH z)U*DK$)SYcrTjm^F1ppvmf~h%SJE*#qE`P}^9e&?xtd*FX_lKwsD;Ajd_U19>dbj+ z&GR&x)aEw=prN~vV{Zmx-2)6I-S3bIBA?YR49hXy=h31cWK2&E`Au)gnl1|^QLRkO zK3g+Ze!djf%--eGF~R5Ke|mqT)AEbZ>Gj=Bw3^BNTJuG|1^1A(xNftyhBqRT9U~*= z&`ErDl?HU;SV%+OWnMAY1_M-vk^tq>FT26dS931@b3ESMsv+WCGDX1UfYo#r&KIc^ z1We3H&WP_FS*m*}$VuP?NaeMPe)@eu4=(JZkH^4vDOFi|=F7(~!}%Th?L%& zE7zAEm{%<#s3-hi{&9Ca;(Y#h^4w?rcSe;yw+t*u8ymN-2h9YQGe$o*UFbU_9^NN% zp?wVKX3ziI5S0P;?UXmZ!CZkW7_Wl<%R~e+8HG{KkN4fUjmePe0F@x6o zBe8FIZ=dD;nZqY$jqTJ8hepIxJM_fVDzb@A*K$(gfa!iy9oeWKo~MIDZQ@V0e4x}u zeM(W!FsZOS@see!AFtRWc0g-^MpK9NUR1S@TJ6UQbkiB}!jJYmyssu*c{wAFa7M8C zGVz|l584O!Pg~$sFw&3W2{3L6nj>DfhO>0g_L0@zlaI79IdEwGxC>cC%Kd%5Q)xjO z%@Eq6jEr3nz~m9sqU;|Sc>DD$_qtzQyCM%SV@QMf!Gi~{!c*ihgw6PCx>@9hpD#I3 zT``T!SB&Tz;u@g;-7oYjY0o}*1KbNklRL-A@_5Yx4812}3(0W)hjtSTLjltsIZB1# zZ)b9Z{KF>>y@EF(`cm+o34H!sA|nEgISP3_r`37uj0icPE1$A-E@_Bzjr=k`_}OQ& ztF8_Ey-xP2oa4lAgNC}dhf*z?D_rl#5M-deMjdX!y&qyu9dh&hliXTh+A~x|sg+8AgSy}?f^+k13eEig9OncpGdEf40=p~s2k^<-gwi+_07wd=kQT$y^S(0+dQ47Jgf z<4bp8C)}AfV5Ock?z!!6=g+mRC>7Ms3%bE1sS|$#^el%FuC1sL0D<;f-?FKutk^uOL5~GTatdnu5vb?6@{Og~S$ zk4+V>c}@ap;ZveuW7xh)Z*;*jWC_N+IUp8`jM4hm%V!s-P`amGMt(j)=@xBQyZ+?> zFZK(`ySna>&v^u2M-sDi{>tWjJ~r8DGqnUS5X*$}4c)!8hT@Hl=Xy3ojXe zU~>KmpK0ld%mXquGatSCJ_ zJ-UeZVaT^9Y!6gpVR?*nLPCP$WC#EAdB&*hw+qFqb8FlBAnHSqM@^hMb4Kmffo9#k zpZ6|D;O-IL*VE}9IX-hr`;Ni%mz~-EfFuCwnLKIr*|#4A$!rY0(QZn@C5;W7vMdTD zqTD+KGSI*J$nifM|EEp%{1u7t&d{OZ^R?RHjv%D}i$5Y*0G1DEm6t}x2o_YUUwV)# z9$AZqb)EWos4B}SfauAQ+ELGo@=5m_rfrN$^d`rSsWEO>`}lETii4>P^z_yNNFhhU z521hnCOFhBZl>kLJ4LE^`wN~pD<$lt7a*0d@$HJVIY06AG_7Xv zlNG1Mo7oA!p_*rGXU#q%BH6$iO}at~->8l`40h+~Vt=JvL2t%NPL{2Qi4!e-4a zEo!8aKAb9SX!s{TmJ3ueW66`k6q=ImyGCRzWf(YuTP^OiT738US1s+FK>6S$L7Yab zAq2uUfZyLbNpaYN!MkrQw8T|~O4}gDOR8IeEA`PdYpUS2E0u+mX30O$pnCiAg$j?3kBbiZ)9b`TIlY;be} z^Z0Q&+^X?S)?tp_C$u7tt<I~AJ9I~`0JC;RayNa=YZSFchE>L^u zTITMuz7jR2R4+cNnKNkLj0CR}KxUUyrnClGl*rJ|e4?{t+ah=*%5%I?-_0Sv2Zr-~ z0nUhwiVD^p23rr(!`B5b(3$az4Y7W_XH=kd?BTB1QOT%b9VYc_2`8U<>=&X<)emaM z-}z6J-c9f?yhn{v98me=^b#(6bky=g;k`@PV#hU1h>9kOQube_V>q zt4-cT9-`!rROIEG@79j5)bFy%S+xO@(Oz~T$8-irhVy84_5_`!=rzHc#SG#RK4e6b zIM(6bQK6!d*^{_mzS+Im&wLK1vW#yrQrOBEmarQNuev}dwcVPJi~KpOC;`lw>w;(M z#}?folo_@$+NL20MSN$^v|)_l+e7%~c<|4y0TO+ekd!Z#*Dnik zLHa}KxNF&|0K~F+bxY57Y27vi8R)4}>$`Zuo-Z7!wC9_#jO5M%hYKCZxc3msJuY-l z+XCTRmigEwus4!|EP2J@{Bsg!wXi4@rEmD8GQLMlIFgr__e=yJqPrK<)+HIV8i4n` z-sWBD`*KDpbL&%3krSDI)(c;QjfO`y3S_^pub%r@)HdO&ctQ@OKJ5krvPl;P%dFcm z1cyiK+@ftARUGnLeLXn16r1|G=XDX4S)8y~%Vw#_d2hq36$9r6&o9rd8*lng;-{7oM+Pqd~|cI zm!tv5;MwT+ve_gg-O7~!XrYS5G_JLy~NbpgRCG=ZU%n9hI=CFX`ZmNaD$g>5!Y+uojh)s=Z8X7M3 zO!V;`eyTaKCuxyck)&MUG>MJE`keKDiEv$*p7C`zMA70Y7s;_UzUQAVEL;gyIPgLw zWt-0-A9v|Qe0GWMNKA-X@`R)>uykt(IE_)TqPXV>6twW8D(Q+?_|*O(2_t!4k1kPv|a{-*6}YUG1WJmMo%U?+beb(`a7cuiHYst zs47Nqj)58Qfm@eal#Z1=(l9Af{X-3R>`CX>uA1IkAA_!8h1xEDxzahxJ~l99rp1G+ zZoM-aY%q7SBIBS}to8dR(oQTdbq0y$v5C#IPD%``{8WH23tZ(<%WvOkq$%++NDU9( zk!@=mtCLoJiE;ybH(8n-RerrkYvcVe$Ept|^T3XyCuK_#)PX(0=}aKCk1+!c9cyAf zDI`>KI0k=N&GaSI=yl*3>89A<$oL4$g8yu#IglW z6p2swU$7BJ19jU`YgfKA0m`c`VWaCY=vBb(`w!9dhPwFj<;yGBN{%#@=+FjpIErRp zc1{k$9<=1ZkLWrjUL(l-VR-0(736UrDSG?&1`~i6xW52iKuJMJR}guG%w~oBeO(oU z_D|(A_S{31rpBnJQ3psa4Y6eaag@NXTNBdxPS_ZUzMc|>pKt&2Wp7+_1IV(d529L> za$lW~^ERD;I1eni#Zl2j4via^vnuHdcpO?=|y<8qGAYQPH9Z^H^E)wm7%%GiSs_&d<{>S z#|pK)lJTO7&AlA^C#(C;p3mwFs{k3iK8sRUb^dZu3V*;G6BEZCCv_r~xI}&zZ*d?u zvGgfM%`ehm@902yy8ral0BS*~$S~b_!;t~}=P765V7@f7hfUU}4YV*Q3Nczuvefb{ z=7NHPE3`rr>#Ntc^BvF6@(P}>t*yOcU?6vnQ}UlS8;tZ!K{p57%%0IaY!}@Q z%}TZ1{zzGN-6C((mTx1517zB}f?0KEJ&H({OIZ37s2#?L_w8^h^UBJ~x+J4kZ(09zrQEaAIoUT!hZo9o!L83GN&f}U3A*FdF0$07jH@QyU*%}0lHLHCakEo z{i4(c;eJ8wF1|_e9OrvD(FfjXHamP7!;G9Zo2H3}>tQ~5kfs!dK$Ci!YR;4Ha+ca! zu2W`@4NG}&vv(3<@1byB&!x6?skJkih#O7+59|oe()L*TY`i)gZx4E77 z9*+FsZ9NEU0N|yhwDffqSk3`1S|LAvTnSUbjAi4l?FMqB9m?22#Trnno4Z!NltTj2 zt)-HpdRehI@CobOWpp19aBpbw+v28!jA zeSVPl7@KP$(Dqe~PKwOTE)*zD`EO!E2Y%1?i=tfoZnoC;Y)SQShGc0y+s)hJ1t55 zMnX=I9WeLwj7OxJV*qCnDH^Gvtc_UpX*j-+$zk$QG5=#oWHsI;Yzy8NEabJcn#`gC zA76Xq8Pyj0Nl`VwQ8xKF9>te*Js?3JfIL%4*7blqpE*PamIdni?AbGJI#$pFTd6ds z-r1v#EmJRIkHgSIfFu?M9#Xu)ETIiZ9_-4=cgXEgZR*IK*@~NUu$?J-l%>N@pPv2V zjS>j|e|t#u%fDrtK$f?HNI>a?=D!p){?&QT=v2(11<@S47iIsNQm?v>3HH_PAs_v)}kFlT{?3u;QS z-)kN_vw9E+1a>#PycCsMTRZqQnvR}14&=#`I#sHbpyLC`rTXgDvwWWmA!9ur!Zb&u zopm~0@MZC*bTzUIF|Dlsmmu$YmTNa*<@lUN%8yEjJ4ol7dv3GL-Ll2*Bf~hE-ziC9 zx1PlYfM^WFf9*UIy)KGm5`P5hyLyvFr)e*PD_ z18P07S_K7Ys(ib?`4t>Fy^@38L=fl!v+mjg)0&)32V2>7|B~|Zto}nGAAD>j*x={& zHQ`4`c;g4{6@kY>jG{fN82XN&+FwFF!4{{U9M()31){62P#Z3GY*IG{mq#Z~(yVN7 z0mOmukvEYq==Orh3EEmWMa}9rzJHLtj;}tixhzKb{6q>l+WCfl!>mr->i&Hn$cPXb zP+(>yC#PemN(;!-9f5Q8TSgpks1LI&(oz^$)3 zKvGA%xxG|S7mq4_xoJlK*rEhWLhBjQz^%$!E~Y{iI3e1+$%dnL1*Nu1fXbdu|G=)o z`(rur_s3v>Znit|lU$9o*hEHpG7_i*193+opWoft*$HKT3R#lX{qQ6jZ$iC+7WC(P z(C{wVACu}wM$EO^R50TcKmSQJ4j!1AO{0K`Z8A?6nLM!yVyel<#uqa~3 z%(h&yXd(k%5Vt+%a+PaSF`c+sfLG60gNKCY(HMw{BzULDbsY=)m?N94P$S%itw!W{ zywI*)U2{|MJ;7ykV{!{6-AQ&4P+ocI> zuY*0S)~xjG{pYSKG8SJfm0$*5?NL~;^h@$Rp3??~_OiPBk^g~b19D$FfU5crQ~!Lp zTbe;Z@MdyCQse$gH4IdEX=OfyOxWwjvzu726pTb#x}6Df~jP zt3EmQyc8eRhV5{hD#TAvk?d8uFHKQMj=;C}BaeYG;mi1LPn_J~mOLw1I%LhHkw{1{zwtbE&ciHiM8cQxOY<`Rw+ zd@w|YbLKnYsDX?rssWN)*GzNt`8IB(U0_E_gh&(wKk;_wle~*5CFEhakz(QGAr==T!q+1BeX$^mjEtWSO5oC8@uv;s^rWxEXh1 zB-U$Xh_`%c*Ph^9dFp?V*d@OQ!tZij#e7TLf0->a8Qm!5+On4)yitUn#rta@N_f+U zXa)5UK;}k`Wa{R26GB;55;2frgXXZhUjgH43`)FkTr){eynB(Sa_|@E;`Gcv=GtW6 zLv{A`8+2U4JWB*<@-!pvYJ8I`I|7da%XMlm)Ln=`92%MF3&Eowj%gdjcl=Y}er_a; zlk_(Wi983z_PW?!0%xI3;LHsV&@;U!bc9ki!$>Gvrlq6cekQaIdN4ato>ka$oD+XnB$ft3&9+klyk2)C;SsG0B{Mv~3vqF476d+j z*=!UMW$Px%TBJ)r1UKUP?HwIFH0NV8Y!!%`)0j(Orl5e};ZDkayF@Lv`6r;Ubd~Vh z7?kb_BO{|*;1d2`{&T&RGa9d={}0YIm6Vi_!KMb#Xgg@)F4NPG>6f3{<-~)^ZJ?UG zJ0Na#FH0xkFNDtP0q5)Sj>zT)p86F|berOoLGjEKKKVLpetpw&&NsvuD+SUo z2=@r1P=|jgW8|<04I3$bk>aa2$FE+=ey6q8AdryqJ=tUE8VnZ{YDaZjUXJ;N!CrvW zA8b=c?X-Jxr$#1vEx!@3D}zDNB%v}@x;CcFRnU7vyCfDQ`^jYtuHT-2-5xZj)C2sx@!HXgQi8yLLqGIr_aM;Y>c|d2h z5<<8FVjJvlyb76lyvn_?&E+TD3tSxfT|uKesOWV(K5q%4c%M%yo!36=|Nlo;yFDp( zjIwQwNri!Z#i77zJL0Vl&G$yn)L1T;<#(9XKp0nVvu>kAT$TH2aWSz}Kn(f$`SSk4 zyk}(pq4Y=BU0fJVOiYlZWNS%53jW7$=)=1{0CrBbP~XO`fRN9wx^N+o-BE|513+kA zDgB9m5or``)qp^Egxjl&z@IlBQrNVoZ zp#`TGzjlv3?NQ~ue<0-?U|`wOqLy> ztd0qUctDN7aZ5l7#3!e^do712har)c4Ke!s(sovO{H1Js&t4s zmHg{TEDUbocdn6RV>c0p`=%`fVo;S<_whgW!efC*#C0gYpB(456Q&;5eq4jPxe@{r z)b;m?>uBsVU~eW4#w&&WV%K#j7%A%=rm`Oxlj`BM+<0-j5Wu7>FYZ)&yKl4 z`#-$WcL!7jtZfA6d2=IK`u5X5Nqfy&4P?42qrX%jJI)|4H99ys|Bh~<7+IA@gw5!g z;<~yclNvegh0UTdg?j@6xVg9MRm1liIePkw8+PlDM|ILP_x}J2IZBG8u%!DQ7uxWv zlZ6d97)6jA?!qd3zQ9P&(XIvE&0SGWHD_`E|2@9XjacNraa3aP;-?Bvm({TjMg0!p zeZCVxXJrFFVd1;&ISRBXw>SuE%{e=2%Iai5yXi}x5RW0xVCZmrQJ>n|$>iuD*oLU| z@tWKF2@pJU|0oRis;Wad8Yv2=4vMWxVKDqt|4;^jBz*DO=f=&nmbv0I5Xi01y@*KY zV`zwr?QCp7p`e)%?T1^8e&tb; zPOKX0Kzv7L70Jltcn7djJz3@^(p~Wc3<+`2({pq}3okUS#gUrslWn}Q2s=ZrPGgJO zirO+PeT656Rl^?uBh_{5@SJ7cR--PKHiyls1oTx#qap!b?!fNxx{?jYK zfVbmaBHW59LERl?61ji%KcF$Yrc#NJJ*3m}!t9CHIIZ-N+?1xkf4)mzDj+ zR4(y*-otMD*#ROE@D8j!b4{V)awfw{80v+FoB|vl4YEpknfBo9 z(7kcfXj@iJO4Q6-C7@rBmW`_Lu{W{iiF#ni6-Cn`%JN{-5ZtIaj*4L$)kaC!itMyp zB^s|9)ga0VgRT_*#iJSuMdBItf7{!-K%ZM@1@FD>E=u{i>xXeeoRbOF#KHfv!fDQ7) zhhMLnhNO(zMl%db;J28Q9T!5|!TUTtIyB0i&{e9e!s!3vy*y14Pag$x1=Xq)+ho4= zU6Z!y0bQ8Bsx5+hG1m?SlLPj2)J6lSj&FaBS8AV`!)QbSV2E;+F8RLyK&S=C!BL)i zdes)tZ&}<145FVjew;4K7LqH^!PEXBkXUMz#(V0~k)P#)P9>qUSD z?0c$89L-S=D6y^KlADRZF)~nz*n3@tZ7c_zf}o~MRTKj@1LhQ11*#y_GOncOM@tbZzt&K~~TbvKqa+yBis#EYNtt;^?zLIE;A$DPo)VmqKQ0TOXD# z1{$|4sj3nX9$_owc_nZN$$@lhO3`xYtT_=-6(T5o3pKUBV9-G<8)D3H>>&_!|A?f| zBHVV#j5YS}y$b=Hq4+()Pd$#4G!(<7Vi>xZFapNd$0$xGG<_L$Sh3!$_4t$!50;pz z!WKHRi6moN0!NXC0;ItT`|AS&R$w zCNNw%+$M;bPbDBEu0(sc#C_z(6Gr#^DDxy^Rx3Wd?_0Gu&>H1yQ4|5f0RTX`^$Hxn zuO7te>|MVEsXata4f6C~j+D(PC}uINPNkgTg1Mt=)jD#+N}&*89{7tkkdd!DXfW#N zCJAgOm;<2600TdSgu)Vb0X%9!WQ`}N6!@bRUqfPj#dsb*R-31`nboNp(Xr2e+!3Pm8Uf+;K$n=ZD1G!zJW4+7@3t7id@NuaOV#3oluUl$NfyAA7 z>0=nONM2?-3bQID|B_5zyNC)h8pP6Wt zvWsTKy``?m!3}JH$qe!gIuHSg%|M$kQ$~!Q2R#Ub*l+gJ*49RCsp`GDWCnwmNWj|7lfHC^2i4gOzzz6Juqg5;F#1))8RuOpYLDT1MBu$K^v z0224>*Z1+x04V`hqLJKXVq8%m5xze38XnZziPH!)grXqcgVj|g;TRs-3KEe>?76g4T0^ETYO3ev$e0)Y)*B#y0ulPfODtAX*h(3PA}Fzniihgm-j-!Dq$7|SL|*gR^_}n*lHS}~ z;R||sRJXPF7>NP5rOaMd1C?p_NxmwA z)YUa8$kB@~?QB4C9)y-$;({Cp=6q^k!DGm90*0Gfpd5HGu{>cOGeQ_;E-X~psp+XQ zWMI31e25CZCr`HbuLOPXGz6e+s4rtMVbxe+2q{k-V`&a5v*U6IzF;)vCeeprwqQ=}CL$W#iKfQH-Yn6gpIw8??p$h(5G*<&A6*-e45_ z)le`FqTtAA?K{Bq2neJ!tCdy3TRn4e+hT4IfG(%1e08O3}1LWwEkfGlEDAGR&>)?$2J{IIM|zG{1-m3vj8$x&~*&+|59zjZsG6()_ra&h0S zqjXt{RA*=o%CfI_rBxCJt^JUBBdhz+WfjY=wsRcT+1@_81AGlm7tExhOI*WAP(Kv# zwJ8W{gJItgW1VI^HI%YF9u3vs#MB$&JZ`!#y#vO{uPIbb2=3tihr2Q9f#> zz}@kSo7;y2uxviC8P8>Cb9cAjm_LIN@MO`3XSr(qitOu1*458(g99Z5)g6}$$uR^# z ztXd63)-8|DaAkmXqD0~OV(Ayq9pcvfb$^ z$4)_Iq+LcB1cEZCN|tRmaAJDO2uNNZXwsjaMv)R1gKR`Uv~}B1`q*pCdH;=RP_{nf z84B}c(R4${LX>B=kw|R7^UT8I6iJ3zULc814>Gl7y>SGRIT6}+0how@>xLkQs?bHv zfrAPVz`~B?7XV=a^7vgpK)37wpxCFtX&gk>2Tvf5<%MZPPF?Y=^Cw_cXw~vr)3nS$ z40=mi5YqpHmrTHNbc|K2^gbJQ=;=d3Ow5!XpD{i7+H>g>(mXRY-tJWr1%VIwD~cQv z)ZExH6RuZ8Z0N&N zJw44}H?*}RJdX%|<7AxL(%9J88775gwUyiifuW~O9&?$O#`g&hcDcNLHJ89nR`xR3 zxKX1u&_RoN>+vezOAB}reUp1txLFIWm{F@&1xi~jP;xZ5Gii`?pkF6$8{veU;{?G) zUi%vc?j%9zPq|-&`xi&O%&OgEw}1cs`>f3&r08-#=OCFEgltmP)M`UDg)o7gd)0~D zh0~$x1KjY5$sTUT&%%Kjhi!z5eOtjylufg~=b6d?DeqBFkh%GX18tpZVJ5uIC6(-BauB+Rluf?3{-ZxxbRw99C@~wnrs@sHqg~5ZsimIeHlXHu0LLJSfgm4zmt|tGajwf zZ5{ujZlaMx5iE)JC^ zW(1oy#gOP!IH0a?^yJC3uL>9N-ae36K*Q)S2F5zWM6kU323pwF-tt?Uo9uOxy|fgnGxZ-=yc`?w z4_O~Q@w#AaoA}UVV!-WS_nF|&7SuQ20?kXOtf{2fuI9poD`qAxJDYnxzN8kc*mcu! zTVY{g#aW4-VhA;2LXRsAQ+kZ9{*b0cf0nd;b#YPA*yB>0rlaX+%XD_ME#QS^k(fLq zwGHl_j#Kf;i5Z`spAJ>|M(MjY|ECw#ADdKucrB@}6f|#yBV=e(yvu=@K;68|sd(2p zV`;i6ymbQ;leL{C5w$doyjSa$a=MES#BD^WJ)y^SvDcp1X0WnH#P09cO literal 0 HcmV?d00001 diff --git a/planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg b/planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg new file mode 100644 index 0000000000000..13ba18bbb7588 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/explicit_stop_line.svg @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stop line defined in the lanelet map +
+
+
+
+ stop line defined in the lanele... +
+
+ +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg b/planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg new file mode 100644 index 0000000000000..6e4c152cd79f0 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/far_object_threshold.drawio.svg @@ -0,0 +1,114 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stop line defined in the lanelet map +
+
+
+
+ stop line defined in the lanele... +
+
+ + + + + + + + + + + +
+
+
+ stop_distance_from_object +
+
+
+
+ stop_distance_from_... +
+
+ + + + + + + + + + + +
+
+
far_object_threshold <
+
+
+
+ far_object_threshold < +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/limitation.svg b/planning/behavior_velocity_crosswalk_module/docs/limitation.svg deleted file mode 100644 index 3e507c0669a2b..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/limitation.svg +++ /dev/null @@ -1,164 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - -
-
-
- stop objects -
-
-
-
- stop objects -
-
- - - - - - - - - -
-
-
- waiting for the traffic light to turn green. -
-
-
-
- waiting for the traffic l... -
-
- - - -
-
-
- The pedestrian has no intention to cross via this route. -
-
-
-
- The pedestrian has no intent... -
-
- - - - -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/no-intension.svg b/planning/behavior_velocity_crosswalk_module/docs/no-intension.svg deleted file mode 100644 index 803ce223d591a..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/no-intension.svg +++ /dev/null @@ -1,193 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - - - - - - - -
-
-
- min_object_velocity * ego_pass_later_margin - [m] -
-
-
-
- min_object_velocity * ego_pass_later_margin [... -
-
- - - - -
-
-
- yield... -
-
-
-
- yield... -
-
- - - -
-
-
- stop objects -
-
-
-
- stop objects -
-
- - - - - -
-
-
- don't have intention -
- to cross -
-
-
-
- don't have intentio... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_line.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_line.svg deleted file mode 100644 index c2d486a7d3541..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_line.svg +++ /dev/null @@ -1,149 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - - - - - -
-
-
- stop line -
- (defined by HDMap) -
-
-
-
- stop line... -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg deleted file mode 100644 index 3842601ae246c..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_line_distance.svg +++ /dev/null @@ -1,170 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - - - - - - -
-
-
- stop_distance_from_crosswalk - [m] -
-
-
-
- stop_distance_from_crosswalk [m] -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- - - - -
-
-
- stop point -
- (planned in module) -
-
-
-
- stop point... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg deleted file mode 100644 index ea7fd9be3ff41..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_line_margin.svg +++ /dev/null @@ -1,204 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - -
-
-
- far_object_threshold - [m] -
-
-
-
- far_object_threshold [m] -
-
- - - - - - - - -
-
-
- stop line -
- (defined by HDMap) -
-
-
-
- stop line... -
-
- - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg b/planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg deleted file mode 100644 index 924f642ad08bb..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stop_margin.svg +++ /dev/null @@ -1,144 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - -
-
-
- stop_distance_from_object - [m] -
-
-
-
- stop_distance_from_object [m] -
-
- - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - -
-
-
- The module determines a stop position at least - stop_distance_from_object - away from the object's predicted path. -
-
-
-
- The module determines a stop positio... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg b/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg deleted file mode 100644 index 3ac1a94fcec78..0000000000000 --- a/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_attention_range.svg +++ /dev/null @@ -1,174 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - - - - -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22%22%20style%3D%22endArrow%3Dclassic%3Bhtml%3D1%3Brounded%3D0%3BexitX%3D0.25%3BexitY%3D0%3BexitDx%3D0%3BexitDy%3D0%3BentryX%3D0.5%3BentryY%3D0.442%3BentryDx%3D0%3BentryDy%3D0%3BentryPerimeter%3D0%3B%22%20edge%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20width%3D%2250%22%20height%3D%2250%22%20relative%3D%221%22%20as%3D%22geometry%22%3E%3CmxPoint%20x%3D%22851%22%20y%3D%221780%22%20as%3D%22sourcePoint%22%2F%3E%3CmxPoint%20x%3D%22890.04%22%20y%3D%221780%22%20as%3D%22targetPoint%22%2F%3E%3C%2FmxGeometry%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20i... -
-
- - - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - - - -
-
-
- stuck_vehicle_attention_range - [m] -
-
-
-
- stuck_vehicle_attention_range [... -
-
- - - - -
-
-
- Vehicle -
-
-
-
- Vehicle -
-
- - - - - - - -
-
-
- max_stuck_vehicle_lateral_offset - [m] -
-
-
-
- max_stuck_vehicle_lateral_offset [m] -
-
- -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg b/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg new file mode 100644 index 0000000000000..c517be5bb9967 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/stuck_vehicle_detection.svg @@ -0,0 +1,93 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stuck_vehicle_attention_range +
+
+
+
+ stuck_vehicle_atten... +
+
+ + + + + + + + + + + + +
+
+
+ max_stuck_vehicle_lateral_offset +
+
+
+
+ max_stuck_vehicle_l... +
+
+ + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg b/planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg new file mode 100644 index 0000000000000..6eb1b25cf5642 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg @@ -0,0 +1,210 @@ + + + + + + + + + + + + +
+
+
+ (5, 1) +
+
+
+
+ (5, 1) +
+
+ + + + +
+
+
+ (1, 4) +
+
+
+
+ (1, 4) +
+
+ + + + +
+
+
+ (2, 6) +
+
+
+
+ (2, 6) +
+
+ + + + + + + + +
+
+
+ (0, 1) +
+
+
+
+ (0, 1) +
+
+ + + + +
+
+
+ (3, 0) +
+
+
+
+ (3, 0) +
+
+ + + + +
+
+
+ Time-To-Vehicle [s] +
+
+
+
+ Time-To-Vehicle [s] +
+
+ + + + + + + + + + + + + + + + + +
+
+
+ Time-To-Collision [s] +
+
+
+
+ Time-To-Collision [s] +
+
+ + + + +
+
+
+ B +
+
+
+
+ B +
+
+ + + + +
+
+
+ A +
+
+
+
+ A +
+
+ + + + +
+
+
+ C +
+
+
+
+ C +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg b/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg index 8084dc2fbd8b0..c409493483845 100644 --- a/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg +++ b/planning/behavior_velocity_crosswalk_module/docs/virtual_collision_point.svg @@ -1,134 +1,65 @@ + - + - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + -
-
-
- - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - - - %3CmxGraphModel%3E%3Croot%3E%3CmxCell%20id%3D%220%22%2F%3E%3CmxCell%20id%3D%221%22%20parent%3D%220%22%2F%3E%3CmxCell%20id%3D%222%22%20value%3D%22attention_range%22%20style%3D%22text%3Bhtml%3D1%3BstrokeColor%3Dnone%3BfillColor%3Dnone%3Balign%3Dcenter%3BverticalAlign%3Dmiddle%3BwhiteSpace%3Dwrap%3Brounded%3D0%3BfontSize%3D20%3BfontStyle%3D2%22%20vertex%3D%221%22%20parent%3D%221%22%3E%3CmxGeometry%20x%3D%22531%22%20y%3D%221610%22%20width%3D%22210%22%20height%3D%2230%22%20as%3D%22geometry%22%2F%3E%3C%2FmxCell%3E%3C%2Froot%3E%3C%2FmxGraphModel%3E - -
-
-
-
- %3Cmx... -
-
- - - - - - - - - -
-
-
- virtual collision point -
-
-
-
- virtual collision poi... -
-
- - - -
-
-
- path -
-
-
-
- path -
-
- - - -
+
-
- object's prediction path +
+ virtual collision point
- object's prediction p... + virtual collision point - + diff --git a/planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg b/planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg new file mode 100644 index 0000000000000..7d4b4017c2f1a --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/virtual_stop_line.svg @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ stop_distance_from_crosswalk +
+
+
+
+ stop_distance_from_... +
+
+ + + + + + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg b/planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg new file mode 100644 index 0000000000000..a09f430e990b3 --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/with_traffic_light.svg @@ -0,0 +1,97 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ NOT + yield +
+
+
+
+ NOT yield +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg b/planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg new file mode 100644 index 0000000000000..d4dea5fb78d2e --- /dev/null +++ b/planning/behavior_velocity_crosswalk_module/docs/without_traffic_light.svg @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ yield +
+
+
+
+ yield +
+
+ +
+ + + + Text is not SVG - cannot display + + +
From ec9144c8b7362163a9d0781f5858805dcd07b8f3 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 18 Jan 2024 17:58:25 +0900 Subject: [PATCH 5/8] feat(intersection): more precise pass judge handling considering occlusion detection and 1st/2nd attention lane (#6047) Signed-off-by: Mamoru Sobue --- .../README.md | 86 +++- .../config/intersection.param.yaml | 2 +- .../docs/pass-judge-line.drawio.svg | 473 ++++++++++++++++++ .../src/debug.cpp | 20 +- .../src/manager.cpp | 4 +- .../src/scene_intersection.cpp | 106 ++-- .../src/scene_intersection.hpp | 16 +- 7 files changed, 634 insertions(+), 73 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 58c2ce59edd48..afb2381e628a4 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -88,7 +88,7 @@ To precisely calculate stop positions, the path is interpolated at the certain i - closest_idx denotes the path point index which is closest to ego position. - first_attention_stopline denotes the first path point where ego footprint intersects with the attention_area. -- If a stopline is associated with the intersection lane on the map, that line is used as the default_stopline for collision detection. Otherwise the point which is `common.default_stopline_margin` meters behind first_attention_stopline is defined as the default_stopline instead. +- If a stopline is associated with the intersection lane on the map, that line is used as default_stopline for collision detection. Otherwise the point which is `common.default_stopline_margin` meters behind first_attention_stopline is defined as default_stopline instead. - occlusion_peeking_stopline is a bit ahead of first_attention_stopline as described later. - occlusion_wo_tl_pass_judge_line is the first position where ego footprint intersects with the centerline of the first attention_area lane. @@ -113,8 +113,8 @@ There are several behaviors depending on the scene. | Safe | Ego detected no occlusion and collision | Ego passes the intersection | | StuckStop | The exit of the intersection is blocked by traffic jam | Ego stops before the intersection or the boundary of attention area | | YieldStuck | Another vehicle stops to yield ego | Ego stops before the intersection or the boundary of attention area | -| NonOccludedCollisionStop | Ego detects no occlusion but detects collision | Ego stops at the default_stop_line | -| FirstWaitBeforeOcclusion | Ego detected occlusion when entering the intersection | Ego stops at the default_stop_line at first | +| NonOccludedCollisionStop | Ego detects no occlusion but detects collision | Ego stops at default_stopline | +| FirstWaitBeforeOcclusion | Ego detected occlusion when entering the intersection | Ego stops at default_stopline at first | | PeekingTowardOcclusion | Ego detected occlusion and but no collision within the FOV (after FirstWaitBeforeOcclusion) | Ego approaches the boundary of the attention area slowly | | OccludedCollisionStop | Ego detected both occlusion and collision (after FirstWaitBeforeOcclusion) | Ego stops immediately | | FullyPrioritized | Ego is fully prioritized by the RED/Arrow signal | Ego only cares vehicles still running inside the intersection. Occlusion is ignored | @@ -219,7 +219,7 @@ ros2 run behavior_velocity_intersection_module ttc.py --lane_id ## Occlusion detection -If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough ego first makes a brief stop at the default stop line for `occlusion.temporal_stop_time_before_peeking`, and then slowly creeps toward occlusion_peeking_stop_line. If `occlusion.creep_during_peeking.enable` is true `occlusion.creep_during_peeking.creep_velocity` is inserted up to occlusion_peeking_stop_line. Otherwise only stop line is inserted. +If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough ego first makes a brief stop at default_stopline for `occlusion.temporal_stop_time_before_peeking`, and then slowly creeps toward occlusion_peeking_stopline. If `occlusion.creep_during_peeking.enable` is true `occlusion.creep_during_peeking.creep_velocity` is inserted up to occlusion_peeking_stopline. Otherwise only stop line is inserted. During the creeping if collision is detected this module inserts a stop line in front of ego immediately, and if the FOV gets sufficiently clear the intersection_occlusion wall will disappear. If occlusion is cleared and no collision is detected ego will pass the intersection. @@ -241,7 +241,7 @@ The remaining time is visualized on the intersection_occlusion virtual wall. ### Occlusion handling at intersection without traffic light -At intersection without traffic light, if occlusion is detected, ego makes a brief stop at the default_stopline and first_attention_stopline respectively. After stopping at the first_attention_area_stopline this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and occlusion_wo_tl_pass_judge_line while occlusion is not cleared. If collision is detected, ego immediately stops. Once the occlusion is cleared or ego has passed occlusion_wo_tl_pass_judge_line this module does not detect collision and occlusion because ego footprint is already inside the intersection. +At intersection without traffic light, if occlusion is detected, ego makes a brief stop at default_stopline and first_attention_stopline respectively. After stopping at the first_attention_area_stopline this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and occlusion_wo_tl_pass_judge_line while occlusion is not cleared. If collision is detected, ego immediately stops. Once the occlusion is cleared or ego has passed occlusion_wo_tl_pass_judge_line this module does not detect collision and occlusion because ego footprint is already inside the intersection. ![occlusion_detection](./docs/occlusion-without-tl.drawio.svg) @@ -263,7 +263,7 @@ TTC parameter varies depending on the traffic light color/shape as follows. ### yield on GREEN -If the traffic light color changed to GREEN and ego approached the entry of the intersection lane within the distance `collision_detection.yield_on_green_traffic_light.distance_to_assigned_lanelet_start` and there is any object whose distance to its stopline is less than `collision_detection.yield_on_green_traffic_light.object_dist_to_stopline`, this module commands to stop for the duration of `collision_detection.yield_on_green_traffic_light.duration` at the default_stopline. +If the traffic light color changed to GREEN and ego approached the entry of the intersection lane within the distance `collision_detection.yield_on_green_traffic_light.distance_to_assigned_lanelet_start` and there is any object whose distance to its stopline is less than `collision_detection.yield_on_green_traffic_light.object_dist_to_stopline`, this module commands to stop for the duration of `collision_detection.yield_on_green_traffic_light.duration` at default_stopline. ### skip on AMBER @@ -281,18 +281,49 @@ When the traffic light color/shape is RED/Arrow, occlusion detection is skipped. ## Pass Judge Line -To avoid sudden braking, if deceleration and jerk more than the threshold (`common.max_accel` and `common.max_jerk`) is required to stop at first_attention_stopline, this module does not command to stop once it passed the default_stopline position. +Generally it is not tolerable for vehicles that have lower traffic priority to stop in the middle of the unprotected area in intersections, and they need to stop at the stop line beforehand if there will be any risk of collision, which introduces two requirements: -If ego passed pass_judge_line, then ego does not stop anymore. If ego passed pass_judge_line while ego is stopping for dangerous decision, then ego stops while the situation is judged as dangerous. Once the judgement turned safe, ego restarts and does not stop anymore. +1. The vehicle must start braking before the boundary of the unprotected area at least by the braking distance if it is supposed to stop +2. The vehicle must recognize upcoming vehicles and check safety beforehand with enough braking distance margin if it is supposed to go + 1. And the SAFE decision must be absolutely certain and remain to be valid for the future horizon so that the safety condition will be always satisfied while ego is driving inside the unprotected area. +3. (TODO): Since it is almost impossible to make perfectly safe decision beforehand given the limited detection range/velocity tracking performance, intersection module should plan risk-evasive acceleration velocity profile AND/OR relax lateral acceleration limit while ego is driving inside the unprotected area, if the safety decision is "betrayed" later due to the following reasons: + 1. The situation _turned out to be dangerous_ later, mainly because velocity tracking was underestimated or the object accelerated beyond TTC margin + 2. The situation _turned dangerous_ later, mainly because the object is suddenly detected out of nowhere -The position of the pass judge line depends on the occlusion detection configuration and the existence of the associated traffic light of the intersection lane. +The position which is before the boundary of unprotected area by the braking distance which is obtained by -- If `occlusion.enable` is false, the pass judge line before the `first_attention_stopline` by the braking distance $v_{ego}^{2} / 2a_{max}$. -- If `occlusion.enable` is true and: - - if there are associated traffic lights, the pass judge line is at the `occlusion_peeking_stopline` in order to continue peeking/collision detection while occlusion is detected. - - if there are no associated traffic lights and: - - if occlusion is detected, pass judge line is at the `occlusion_wo_tl_pass_judge_line` to continue peeking. - - if occlusion is not detected, pass judge line is at the same place at the case where `occlusion.enable` is false. +$$ +\dfrac{v_{\mathrm{ego}}^{2}}{2a_{\mathrm{max}}} + v_{\mathrm{ego}} * t_{\mathrm{delay}} +$$ + +is called pass_judge_line, and safety decision must be made before ego passes this position because ego does not stop anymore. + +1st_pass_judge_line is before the first upcoming lane, and at intersections with multiple upcoming lanes, 2nd_pass_judge_line is defined as the position which is before the centerline of the first attention lane by the braking distance. 1st/2nd_pass_judge_line are illustrated in the following figure. + +![pass-judge-line](./docs/pass-judge-line.drawio.svg) + +Intersection module will command to GO if + +- ego is over default_stopline(or `common.enable_pass_judge_before_default_stopline` is true) AND +- ego is over 1st_pass judge line AND +- ego judged SAFE previously AND +- (ego is over 2nd_pass_judge_line OR ego is between 1st and 2nd pass_judge_line but most probable collision is expected to happen in the 1st attention lane) + +because it is expected to stop or continue stop decision if + +1. ego is before default_stopline && `common.enable_pass_judge_before_default_stopline` is false OR + 1. reason: default_stopline is defined on the map and should be respected +2. ego is before 1st_pass_judge_line OR + 1. reason: it has enough braking distance margin +3. ego judged UNSAFE previously + 1. reason: ego is now trying to stop and should continue stop decision if collision is detected in later calculation +4. (ego is between 1st and 2nd pass_judge_line and the most probable collision is expected to happen in the 2nd attention lane) + +For the 3rd condition, it is possible that ego stops with some overshoot to the unprotected area while it is trying to stop for collision detection, because ego should keep stop decision while UNSAFE decision is made even if it passed 1st_pass_judge_line during deceleration. + +For the 4th condition, at intersections with 2nd attention lane, even if ego is over the 1st pass_judge_line, still intersection module commands to stop if the most probable collision is expected to happen in the 2nd attention lane. + +Also if `occlusion.enable` is true, the position of 1st_pass_judge line changes to occlusion_peeking_stopline if ego passed the original 1st_pass_judge_line position while ego is peeking. Otherwise ego could inadvertently judge that it passed 1st_pass_judge during peeking and then abort peeking. ## Data Structure @@ -375,17 +406,18 @@ entity TargetObject { ### common -| Parameter | Type | Description | -| --------------------------------- | ------ | ------------------------------------------------------------------------ | -| `.attention_area_length` | double | [m] range for object detection | -| `.attention_area_margin` | double | [m] margin for expanding attention area width | -| `.attention_area_angle_threshold` | double | [rad] threshold of angle difference between the detected object and lane | -| `.use_intersection_area` | bool | [-] flag to use intersection_area for collision detection | -| `.default_stopline_margin` | double | [m] margin before_stop_line | -| `.stopline_overshoot_margin` | double | [m] margin for the overshoot from stopline | -| `.max_accel` | double | [m/ss] max acceleration for stop | -| `.max_jerk` | double | [m/sss] max jerk for stop | -| `.delay_response_time` | double | [s] action delay before stop | +| Parameter | Type | Description | +| -------------------------------------------- | ------ | -------------------------------------------------------------------------------- | +| `.attention_area_length` | double | [m] range for object detection | +| `.attention_area_margin` | double | [m] margin for expanding attention area width | +| `.attention_area_angle_threshold` | double | [rad] threshold of angle difference between the detected object and lane | +| `.use_intersection_area` | bool | [-] flag to use intersection_area for collision detection | +| `.default_stopline_margin` | double | [m] margin before_stop_line | +| `.stopline_overshoot_margin` | double | [m] margin for the overshoot from stopline | +| `.max_accel` | double | [m/ss] max acceleration for stop | +| `.max_jerk` | double | [m/sss] max jerk for stop | +| `.delay_response_time` | double | [s] action delay before stop | +| `.enable_pass_judge_before_default_stopline` | bool | [-] flag not to stop before default_stopline even if ego is over pass_judge_line | ### stuck_vehicle/yield_stuck @@ -430,7 +462,7 @@ entity TargetObject { | `.possible_object_bbox` | [double] | [m] minimum bounding box size for checking if occlusion polygon is small enough | | `.ignore_parked_vehicle_speed_threshold` | double | [m/s] velocity threshold for checking parked vehicle | | `.occlusion_detection_hold_time` | double | [s] hold time of occlusion detection | -| `.temporal_stop_time_before_peeking` | double | [s] temporal stop duration at the default_stop_line before starting peeking | +| `.temporal_stop_time_before_peeking` | double | [s] temporal stop duration at default_stopline before starting peeking | | `.temporal_stop_before_attention_area` | bool | [-] flag to temporarily stop at first_attention_stopline before peeking into attention_area | | `.creep_velocity_without_traffic_light` | double | [m/s] creep velocity to occlusion_wo_tl_pass_judge_line | | `.static_occlusion_with_traffic_light_timeout` | double | [s] the timeout duration for ignoring static occlusion at intersection with traffic light | diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 4e9eb50f2a462..108e021240851 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -12,6 +12,7 @@ max_accel: -2.8 max_jerk: -5.0 delay_response_time: 0.5 + enable_pass_judge_before_default_stopline: false stuck_vehicle: turn_direction: @@ -36,7 +37,6 @@ consider_wrong_direction_vehicle: false collision_detection_hold_time: 0.5 min_predicted_path_confidence: 0.05 - keep_detection_velocity_threshold: 0.833 velocity_profile: use_upstream: true minimum_upstream_velocity: 0.01 diff --git a/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg b/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg new file mode 100644 index 0000000000000..d1f488af7c2ac --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg @@ -0,0 +1,473 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + 1st_pass_judge_line + +
+
+
+
+ 1st_pass_judge_line +
+
+ + + + + + + + +
+
+
+ + 2nd_pass_judge_line_magin + +
+
+
+
+ 2nd_pass_judge_line_magin +
+
+ + + + + + + + +
+
+
+ + 2nd_pass_judge_line + +
+
+
+
+ 2nd_pass_judge_line +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + 1st_pass_judge_line + +
+
+
+
+ 1st_pass_judge_line +
+
+ + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index 5f103e0ecd3b0..350f6d774f7cf 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -90,7 +90,7 @@ visualization_msgs::msg::MarkerArray createPoseMarkerArray( marker_line.type = visualization_msgs::msg::Marker::LINE_STRIP; marker_line.action = visualization_msgs::msg::Marker::ADD; marker_line.pose.orientation = createMarkerOrientation(0, 0, 0, 1.0); - marker_line.scale = createMarkerScale(0.1, 0.0, 0.0); + marker_line.scale = createMarkerScale(0.2, 0.0, 0.0); marker_line.color = createMarkerColor(r, g, b, 0.999); const double yaw = tf2::getYaw(pose.orientation); @@ -283,11 +283,23 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array, now); */ - if (debug_data_.pass_judge_wall_pose) { + if (debug_data_.first_pass_judge_wall_pose) { + const double r = debug_data_.passed_first_pass_judge ? 1.0 : 0.0; + const double g = debug_data_.passed_first_pass_judge ? 0.0 : 1.0; appendMarkerArray( createPoseMarkerArray( - debug_data_.pass_judge_wall_pose.value(), "pass_judge_wall_pose", module_id_, 0.7, 0.85, - 0.9), + debug_data_.first_pass_judge_wall_pose.value(), "first_pass_judge_wall_pose", module_id_, r, + g, 0.0), + &debug_marker_array, now); + } + + if (debug_data_.second_pass_judge_wall_pose) { + const double r = debug_data_.passed_second_pass_judge ? 1.0 : 0.0; + const double g = debug_data_.passed_second_pass_judge ? 0.0 : 1.0; + appendMarkerArray( + createPoseMarkerArray( + debug_data_.second_pass_judge_wall_pose.value(), "second_pass_judge_wall_pose", module_id_, + r, g, 0.0), &debug_marker_array, now); } diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index c92f16dd7b474..0f9faaaa901c1 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -61,6 +61,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) ip.common.max_jerk = getOrDeclareParameter(node, ns + ".common.max_jerk"); ip.common.delay_response_time = getOrDeclareParameter(node, ns + ".common.delay_response_time"); + ip.common.enable_pass_judge_before_default_stopline = + getOrDeclareParameter(node, ns + ".common.enable_pass_judge_before_default_stopline"); ip.stuck_vehicle.turn_direction.left = getOrDeclareParameter(node, ns + ".stuck_vehicle.turn_direction.left"); @@ -92,8 +94,6 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".collision_detection.collision_detection_hold_time"); ip.collision_detection.min_predicted_path_confidence = getOrDeclareParameter(node, ns + ".collision_detection.min_predicted_path_confidence"); - ip.collision_detection.keep_detection_velocity_threshold = getOrDeclareParameter( - node, ns + ".collision_detection.keep_detection_velocity_threshold"); ip.collision_detection.velocity_profile.use_upstream = getOrDeclareParameter(node, ns + ".collision_detection.velocity_profile.use_upstream"); ip.collision_detection.velocity_profile.minimum_upstream_velocity = getOrDeclareParameter( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index dad0c194b5c9f..358dca2414bb0 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1041,7 +1041,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto default_stopline_idx_opt = intersection_stoplines.default_stopline; const auto first_attention_stopline_idx_opt = intersection_stoplines.first_attention_stopline; const auto occlusion_peeking_stopline_idx_opt = intersection_stoplines.occlusion_peeking_stopline; - const auto default_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line; + const auto first_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line; + const auto second_pass_judge_line_idx = intersection_stoplines.second_pass_judge_line; const auto occlusion_wo_tl_pass_judge_line_idx = intersection_stoplines.occlusion_wo_tl_pass_judge_line; @@ -1221,13 +1222,22 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( prev_occlusion_status_ = occlusion_status; } - // TODO(Mamoru Sobue): this part needs more formal handling - const size_t pass_judge_line_idx = [=]() { + const size_t pass_judge_line_idx = [&]() { if (enable_occlusion_detection_) { - // if occlusion detection is enabled, pass_judge position is beyond the boundary of first - // attention area if (has_traffic_light_) { - return occlusion_stopline_idx; + // if ego passed the first_pass_judge_line while it is peeking to occlusion, then its + // position is occlusion_stopline_idx. Otherwise it is first_pass_judge_line + if (passed_1st_judge_line_while_peeking_) { + return occlusion_stopline_idx; + } + const bool is_over_first_pass_judge_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, first_pass_judge_line_idx); + if (is_occlusion_state && is_over_first_pass_judge_line) { + passed_1st_judge_line_while_peeking_ = true; + return occlusion_stopline_idx; + } else { + return first_pass_judge_line_idx; + } } else if (is_occlusion_state) { // if there is no traffic light and occlusion is detected, pass_judge position is beyond // the boundary of first attention area @@ -1235,30 +1245,53 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } else { // if there is no traffic light and occlusion is not detected, pass_judge position is // default - return default_pass_judge_line_idx; + return first_pass_judge_line_idx; } } - return default_pass_judge_line_idx; + return first_pass_judge_line_idx; }(); - debug_data_.pass_judge_wall_pose = - planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); - const bool is_over_pass_judge_line = - util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); - const double vel_norm = std::hypot( - planner_data_->current_velocity->twist.linear.x, - planner_data_->current_velocity->twist.linear.y); - const bool keep_detection = - (vel_norm < planner_param_.collision_detection.keep_detection_velocity_threshold); + const bool was_safe = std::holds_alternative(prev_decision_result_); - // if ego is over the pass judge line and not stopped - if (is_over_default_stopline && !is_over_pass_judge_line && keep_detection) { - RCLCPP_DEBUG(logger_, "is_over_default_stopline && !is_over_pass_judge_line && keep_detection"); - // do nothing - } else if ( - (was_safe && is_over_default_stopline && is_over_pass_judge_line && is_go_out_) || + + const bool is_over_1st_pass_judge_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx); + if (is_over_1st_pass_judge_line && was_safe && !safely_passed_1st_judge_line_time_) { + safely_passed_1st_judge_line_time_ = clock_->now(); + } + debug_data_.first_pass_judge_wall_pose = + planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path); + debug_data_.passed_first_pass_judge = safely_passed_1st_judge_line_time_.has_value(); + const bool is_over_2nd_pass_judge_line = + util::isOverTargetIndex(*path, closest_idx, current_pose, second_pass_judge_line_idx); + if (is_over_2nd_pass_judge_line && was_safe && !safely_passed_2nd_judge_line_time_) { + safely_passed_2nd_judge_line_time_ = clock_->now(); + } + debug_data_.second_pass_judge_wall_pose = + planning_utils::getAheadPose(second_pass_judge_line_idx, baselink2front, *path); + debug_data_.passed_second_pass_judge = safely_passed_2nd_judge_line_time_.has_value(); + + if ( + ((is_over_default_stopline || + planner_param_.common.enable_pass_judge_before_default_stopline) && + is_over_2nd_pass_judge_line && was_safe) || is_permanent_go_) { - // is_go_out_: previous RTC approval - // activated_: current RTC approval + /* + * This body is active if ego is + * - over the default stopline AND + * - over the 1st && 2nd pass judge line AND + * - previously safe + * , + * which means ego can stop even if it is over the 1st pass judge line but + * - before default stopline OR + * - before the 2nd pass judge line OR + * - or previously unsafe + * . + * In order for ego to continue peeking or collision detection when occlusion is detected after + * ego passed the 1st pass judge line, it needs to be + * - before the default stopline OR + * - before the 2nd pass judge line OR + * - previously unsafe + */ is_permanent_go_ = true; return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"}; } @@ -1309,10 +1342,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( : (planner_param_.collision_detection.collision_detection_hold_time - collision_state_machine_.getDuration()); + // TODO(Mamoru Sobue): if ego is over 1st/2nd pass judge line and collision is expected at 1st/2nd + // pass judge line respectively, ego should go + const auto second_attention_stopline_idx = intersection_stoplines.second_attention_stopline; + const auto last_intersection_stopline_candidate_idx = + second_attention_stopline_idx ? second_attention_stopline_idx.value() : occlusion_stopline_idx; const bool has_collision = checkCollision( - *path, &target_objects, path_lanelets, closest_idx, - std::min(occlusion_stopline_idx, path->points.size() - 1), time_to_restart, - traffic_prioritized_level); + *path, &target_objects, path_lanelets, closest_idx, last_intersection_stopline_candidate_idx, + time_to_restart, traffic_prioritized_level); collision_state_machine_.setStateWithMarginTime( has_collision ? StateMachine::State::STOP : StateMachine::State::GO, logger_.get_child("collision state_machine"), *clock_); @@ -1808,16 +1845,19 @@ std::optional IntersectionModule::generateIntersectionSto second_attention_area, interpolated_path_info, local_footprint, baselink2front); if (first_footprint_inside_2nd_attention_ip_opt) { second_attention_stopline_ip_int = first_footprint_inside_2nd_attention_ip_opt.value(); + second_attention_stopline_valid = true; } } const auto second_attention_stopline_ip = second_attention_stopline_ip_int >= 0 ? static_cast(second_attention_stopline_ip_int) : 0; - // (8) second pass judge lie position on interpolated path - int second_pass_judge_ip_int = second_attention_stopline_ip_int - std::ceil(braking_dist / ds); + // (8) second pass judge line position on interpolated path. It is the same as first pass judge + // line if second_attention_lane is null + int second_pass_judge_ip_int = occlusion_wo_tl_pass_judge_line_ip; const auto second_pass_judge_line_ip = - static_cast(std::max(second_pass_judge_ip_int, 0)); + second_attention_area_opt ? static_cast(std::max(second_pass_judge_ip_int, 0)) + : first_pass_judge_line_ip; struct IntersectionStopLinesTemp { @@ -2803,8 +2843,6 @@ TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( return std::nullopt; } }(); - const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value(); - const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0); for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { const auto & p1 = smoothed_reference_path.points.at(i); @@ -2818,7 +2856,7 @@ TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( (p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0; const double passing_velocity = [=]() { if (use_upstream_velocity) { - if (has_upstream_stopline && i > upstream_stopline_ind) { + if (upstream_stopline_idx_opt && i > upstream_stopline_idx_opt.value()) { return minimum_upstream_velocity; } return std::max(average_velocity, minimum_ego_velocity); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 38feada725872..1a9cf74624fc0 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -48,7 +48,10 @@ struct DebugData std::optional collision_stop_wall_pose{std::nullopt}; std::optional occlusion_stop_wall_pose{std::nullopt}; std::optional occlusion_first_stop_wall_pose{std::nullopt}; - std::optional pass_judge_wall_pose{std::nullopt}; + std::optional first_pass_judge_wall_pose{std::nullopt}; + bool passed_first_pass_judge{false}; + bool passed_second_pass_judge{false}; + std::optional second_pass_judge_wall_pose{std::nullopt}; std::optional> attention_area{std::nullopt}; std::optional> occlusion_attention_area{std::nullopt}; std::optional ego_lane{std::nullopt}; @@ -256,8 +259,8 @@ struct IntersectionStopLines size_t first_pass_judge_line{0}; /** - * second_pass_judge_line is before second_attention_stopline by the braking distance. if its - * value is calculated negative, it is 0 + * second_pass_judge_line is before second_attention_stopline by the braking distance. if + * second_attention_lane is null, it is same as first_pass_judge_line */ size_t second_pass_judge_line{0}; @@ -344,6 +347,7 @@ class IntersectionModule : public SceneModuleInterface double max_accel; double max_jerk; double delay_response_time; + bool enable_pass_judge_before_default_stopline; } common; struct TurnDirection @@ -373,7 +377,6 @@ class IntersectionModule : public SceneModuleInterface bool consider_wrong_direction_vehicle; double collision_detection_hold_time; double min_predicted_path_confidence; - double keep_detection_velocity_threshold; struct VelocityProfile { bool use_upstream; @@ -606,7 +609,7 @@ class IntersectionModule : public SceneModuleInterface private: rclcpp::Node & node_; - const int64_t lane_id_; + const lanelet::Id lane_id_; const std::set associative_ids_; const std::string turn_direction_; const bool has_traffic_light_; @@ -621,6 +624,9 @@ class IntersectionModule : public SceneModuleInterface bool is_permanent_go_{false}; DecisionResult prev_decision_result_{Indecisive{""}}; OcclusionType prev_occlusion_status_; + bool passed_1st_judge_line_while_peeking_{false}; + std::optional safely_passed_1st_judge_line_time_{std::nullopt}; + std::optional safely_passed_2nd_judge_line_time_{std::nullopt}; // for occlusion detection const bool enable_occlusion_detection_; From 128ecc76c938c8ab45ae3168e56e31fcb6c925e0 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 18 Jan 2024 18:22:55 +0900 Subject: [PATCH 6/8] feat(blind_spot): consider opposite adjacent lane for wrong vehicles (#5635) Signed-off-by: Mamoru Sobue --- .../config/blind_spot.param.yaml | 1 + .../src/debug.cpp | 6 +- .../src/manager.cpp | 2 + .../src/scene.cpp | 220 ++++++++++++------ .../src/scene.hpp | 16 +- 5 files changed, 162 insertions(+), 83 deletions(-) diff --git a/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml b/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml index f9ddd3ce61099..3c22d1fe65db5 100644 --- a/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml +++ b/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml @@ -8,4 +8,5 @@ max_future_movement_time: 10.0 # [second] threshold_yaw_diff: 0.523 # [rad] adjacent_extend_width: 1.5 # [m] + opposite_adjacent_extend_width: 1.5 # [m] enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_blind_spot_module/src/debug.cpp index 7da494bfd5231..5cc90afb0043d 100644 --- a/planning/behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/debug.cpp @@ -145,14 +145,12 @@ visualization_msgs::msg::MarkerArray BlindSpotModule::createDebugMarkerArray() appendMarkerArray( createLaneletPolygonsMarkerArray( - debug_data_.conflict_areas_for_blind_spot, "conflict_area_for_blind_spot", module_id_, 0.0, - 0.5, 0.5), + debug_data_.conflict_areas, "conflict_area", module_id_, 0.0, 0.5, 0.5), &debug_marker_array, now); appendMarkerArray( createLaneletPolygonsMarkerArray( - debug_data_.detection_areas_for_blind_spot, "detection_area_for_blind_spot", module_id_, 0.5, - 0.0, 0.0), + debug_data_.detection_areas, "detection_area", module_id_, 0.5, 0.0, 0.0), &debug_marker_array, now); appendMarkerArray( diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_blind_spot_module/src/manager.cpp index d64f1ebc39a51..09d1c5a7c3270 100644 --- a/planning/behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/manager.cpp @@ -48,6 +48,8 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".threshold_yaw_diff"); planner_param_.adjacent_extend_width = getOrDeclareParameter(node, ns + ".adjacent_extend_width"); + planner_param_.opposite_adjacent_extend_width = + getOrDeclareParameter(node, ns + ".opposite_adjacent_extend_width"); } void BlindSpotModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_blind_spot_module/src/scene.cpp index 62a5e06674d4e..efbff7e2af51d 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.cpp @@ -105,16 +105,18 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); /* set stop-line and stop-judgement-line for base_link */ - int stop_line_idx = -1; const auto straight_lanelets = getStraightLanelets(lanelet_map_ptr, routing_graph_ptr, lane_id_); - if (!generateStopLine(straight_lanelets, path, &stop_line_idx)) { + const auto stoplines_idx_opt = generateStopLine(straight_lanelets, path); + if (!stoplines_idx_opt) { RCLCPP_WARN_SKIPFIRST_THROTTLE( logger_, *clock_, 1000 /* ms */, "[BlindSpotModule::run] setStopLineIdx fail"); *path = input_path; // reset path return false; } - if (stop_line_idx <= 0) { + const auto [default_stopline_idx, critical_stopline_idx] = stoplines_idx_opt.value(); + + if (default_stopline_idx <= 0) { RCLCPP_DEBUG( logger_, "[Blind Spot] stop line or pass judge line is at path[0], ignore planning."); *path = input_path; // reset path @@ -133,6 +135,8 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto return false; } const size_t closest_idx = closest_idx_opt.value(); + const auto stop_line_idx = + closest_idx > default_stopline_idx ? critical_stopline_idx : default_stopline_idx; /* set judge line dist */ const double current_vel = planner_data_->current_velocity->twist.linear.x; @@ -156,9 +160,6 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto debug_data_.virtual_wall_pose = stop_line_pose; const auto stop_pose = path->points.at(stop_line_idx).point.pose; debug_data_.stop_point_pose = stop_pose; - auto offset_pose = motion_utils::calcLongitudinalOffsetPose( - path->points, stop_pose.position, -pass_judge_line_dist); - if (offset_pose) debug_data_.judge_point_pose = *offset_pose; /* if current_state = GO, and current_pose is over judge_line, ignore planning. */ if (planner_param_.use_pass_judge_line) { @@ -235,69 +236,41 @@ std::optional BlindSpotModule::getFirstPointConflictingLanelets( } } -bool BlindSpotModule::generateStopLine( +std::optional> BlindSpotModule::generateStopLine( const lanelet::ConstLanelets straight_lanelets, - autoware_auto_planning_msgs::msg::PathWithLaneId * path, int * stop_line_idx) const + autoware_auto_planning_msgs::msg::PathWithLaneId * path) const { /* set parameters */ constexpr double interval = 0.2; const int margin_idx_dist = std::ceil(planner_param_.stop_line_margin / interval); - const int base2front_idx_dist = - std::ceil(planner_data_->vehicle_info_.max_longitudinal_offset_m / interval); + // const int base2front_idx_dist = + // std::ceil(planner_data_->vehicle_info_.max_longitudinal_offset_m / interval); /* spline interpolation */ autoware_auto_planning_msgs::msg::PathWithLaneId path_ip; if (!splineInterpolate(*path, interval, path_ip, logger_)) { - return false; + return std::nullopt; } /* generate stop point */ - int stop_idx_ip = 0; // stop point index for interpolated path. + size_t stop_idx_default_ip = 0; // stop point index for interpolated path. + size_t stop_idx_critical_ip = 0; if (straight_lanelets.size() > 0) { std::optional first_idx_conflicting_lane_opt = getFirstPointConflictingLanelets(path_ip, straight_lanelets); if (!first_idx_conflicting_lane_opt) { RCLCPP_DEBUG(logger_, "No conflicting line found."); - return false; - } - stop_idx_ip = std::max( - first_idx_conflicting_lane_opt.value() - 1 - margin_idx_dist - base2front_idx_dist, 0); - } else { - std::optional intersection_enter_point_opt = - getStartPointFromLaneLet(lane_id_); - if (!intersection_enter_point_opt) { - RCLCPP_DEBUG(logger_, "No intersection enter point found."); - return false; - } - - geometry_msgs::msg::Pose intersection_enter_pose; - intersection_enter_pose = intersection_enter_point_opt.value(); - const auto stop_idx_ip_opt = - motion_utils::findNearestIndex(path_ip.points, intersection_enter_pose, 10.0, M_PI_4); - if (stop_idx_ip_opt) { - stop_idx_ip = stop_idx_ip_opt.value(); + return std::nullopt; } - - stop_idx_ip = std::max(stop_idx_ip - base2front_idx_dist, 0); + stop_idx_default_ip = std::max(first_idx_conflicting_lane_opt.value() - 1 - margin_idx_dist, 0); + stop_idx_critical_ip = std::max(first_idx_conflicting_lane_opt.value() - 1, 0); } /* insert stop_point to use interpolated path*/ - *stop_line_idx = insertPoint(stop_idx_ip, path_ip, path); + const size_t stopline_idx_default = insertPoint(stop_idx_default_ip, path_ip, path); + const size_t stopline_idx_critical = insertPoint(stop_idx_critical_ip, path_ip, path); - /* if another stop point exist before intersection stop_line, disable judge_line. */ - bool has_prior_stopline = false; - for (int i = 0; i < *stop_line_idx; ++i) { - if (std::fabs(path->points.at(i).point.longitudinal_velocity_mps) < 0.1) { - has_prior_stopline = true; - break; - } - } - - RCLCPP_DEBUG( - logger_, "generateStopLine() : stop_idx = %d, stop_idx_ip = %d, has_prior_stopline = %d", - *stop_line_idx, stop_idx_ip, has_prior_stopline); - - return true; + return std::make_pair(stopline_idx_default, stopline_idx_critical); } void BlindSpotModule::cutPredictPathWithDuration( @@ -385,36 +358,61 @@ bool BlindSpotModule::checkObstacleInBlindSpot( const auto areas_opt = generateBlindSpotPolygons( lanelet_map_ptr, routing_graph_ptr, path, closest_idx, stop_line_pose); - if (!!areas_opt) { - debug_data_.detection_areas_for_blind_spot = areas_opt.value().detection_areas; - debug_data_.conflict_areas_for_blind_spot = areas_opt.value().conflict_areas; + if (areas_opt) { + const auto & detection_areas = areas_opt.value().detection_areas; + const auto & conflict_areas = areas_opt.value().conflict_areas; + const auto & opposite_detection_areas = areas_opt.value().opposite_detection_areas; + const auto & opposite_conflict_areas = areas_opt.value().opposite_conflict_areas; + debug_data_.detection_areas = detection_areas; + debug_data_.conflict_areas = conflict_areas; + debug_data_.detection_areas.insert( + debug_data_.detection_areas.end(), opposite_detection_areas.begin(), + opposite_detection_areas.end()); + debug_data_.conflict_areas.insert( + debug_data_.conflict_areas.end(), opposite_conflict_areas.begin(), + opposite_conflict_areas.end()); autoware_auto_perception_msgs::msg::PredictedObjects objects = *objects_ptr; cutPredictPathWithDuration(&objects, planner_param_.max_future_movement_time); // check objects in blind spot areas - bool obstacle_detected = false; for (const auto & object : objects.objects) { if (!isTargetObjectType(object)) { continue; } - const auto & detection_areas = areas_opt.value().detection_areas; - const auto & conflict_areas = areas_opt.value().conflict_areas; - const bool exist_in_detection_area = + // right direction + const bool exist_in_right_detection_area = std::any_of(detection_areas.begin(), detection_areas.end(), [&object](const auto & area) { return bg::within( to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), lanelet::utils::to2D(area)); }); - const bool exist_in_conflict_area = + // opposite direction + const bool exist_in_opposite_detection_area = std::any_of( + opposite_detection_areas.begin(), opposite_detection_areas.end(), + [&object](const auto & area) { + return bg::within( + to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), + lanelet::utils::to2D(area)); + }); + const bool exist_in_detection_area = + exist_in_right_detection_area || exist_in_opposite_detection_area; + if (!exist_in_detection_area) { + continue; + } + const bool exist_in_right_conflict_area = isPredictedPathInArea(object, conflict_areas, planner_data_->current_odometry->pose); + const bool exist_in_opposite_conflict_area = isPredictedPathInArea( + object, opposite_conflict_areas, planner_data_->current_odometry->pose); + const bool exist_in_conflict_area = + exist_in_right_conflict_area || exist_in_opposite_conflict_area; if (exist_in_detection_area && exist_in_conflict_area) { - obstacle_detected = true; debug_data_.conflicting_targets.objects.push_back(object); + return true; } } - return obstacle_detected; + return false; } else { return false; } @@ -504,6 +502,37 @@ lanelet::ConstLanelet BlindSpotModule::generateExtendedAdjacentLanelet( return new_lanelet; } +lanelet::ConstLanelet BlindSpotModule::generateExtendedOppositeAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction) const +{ + const auto centerline = lanelet.centerline2d(); + const auto width = + boost::geometry::area(lanelet.polygon2d().basicPolygon()) / boost::geometry::length(centerline); + const double extend_width = + std::min(planner_param_.opposite_adjacent_extend_width, width); + const auto left_bound_ = + direction == TurnDirection::RIGHT + ? lanelet.rightBound().invert() + : lanelet::utils::getCenterlineWithOffset(lanelet.invert(), -width / 2 + extend_width); + const auto right_bound_ = + direction == TurnDirection::RIGHT + ? lanelet::utils::getCenterlineWithOffset(lanelet.invert(), width / 2 - extend_width) + : lanelet.leftBound().invert(); + lanelet::Points3d lefts, rights; + for (const auto & pt : left_bound_) { + lefts.push_back(lanelet::Point3d(pt)); + } + for (const auto & pt : right_bound_) { + rights.push_back(lanelet::Point3d(pt)); + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); + auto new_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + const auto new_centerline = lanelet::utils::generateFineCenterline(new_lanelet, 5.0); + new_lanelet.setCenterline(new_centerline); + return new_lanelet; +} + std::optional BlindSpotModule::generateBlindSpotPolygons( lanelet::LaneletMapConstPtr lanelet_map_ptr, [[maybe_unused]] lanelet::routing::RoutingGraphPtr routing_graph_ptr, @@ -512,19 +541,20 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( { std::vector lane_ids; lanelet::ConstLanelets blind_spot_lanelets; + lanelet::ConstLanelets blind_spot_opposite_lanelets; /* get lane ids until intersection */ for (const auto & point : path.points) { bool found_intersection_lane = false; for (const auto lane_id : point.lane_ids) { - // make lane_ids unique - if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { - lane_ids.push_back(lane_id); - } - if (lane_id == lane_id_) { found_intersection_lane = true; + lane_ids.push_back(lane_id); break; } + // make lane_ids unique + if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { + lane_ids.push_back(lane_id); + } } if (found_intersection_lane) break; } @@ -537,27 +567,49 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( // additional detection area on left/right side lanelet::ConstLanelets adjacent_lanelets; + lanelet::ConstLanelets opposite_adjacent_lanelets; for (const auto i : lane_ids) { const auto lane = lanelet_map_ptr->laneletLayer.get(i); - const auto adj = std::invoke([&]() -> std::optional { - if (turn_direction_ == TurnDirection::INVALID) { + const auto adj = + turn_direction_ == TurnDirection::LEFT + ? (routing_graph_ptr->adjacentLeft(lane)) + : (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane)) + : boost::none); + const std::optional opposite_adj = + [&]() -> std::optional { + if (!!adj) { return std::nullopt; } - const auto adj_lane = (turn_direction_ == TurnDirection::LEFT) - ? routing_graph_ptr->adjacentLeft(lane) - : routing_graph_ptr->adjacentRight(lane); - - if (adj_lane) { - return *adj_lane; + if (turn_direction_ == TurnDirection::LEFT) { + // this should exist in right-hand traffic + const auto adjacent_lanes = + lanelet_map_ptr->laneletLayer.findUsages(lane.leftBound().invert()); + if (adjacent_lanes.empty()) { + return std::nullopt; + } + return adjacent_lanes.front(); } - - return std::nullopt; - }); - + if (turn_direction_ == TurnDirection::RIGHT) { + // this should exist in left-hand traffic + const auto adjacent_lanes = + lanelet_map_ptr->laneletLayer.findUsages(lane.rightBound().invert()); + if (adjacent_lanes.empty()) { + return std::nullopt; + } + return adjacent_lanes.front(); + } else { + return std::nullopt; + } + }(); if (adj) { const auto half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_); adjacent_lanelets.push_back(half_lanelet); } + if (opposite_adj) { + const auto half_lanelet = + generateExtendedOppositeAdjacentLanelet(opposite_adj.value(), turn_direction_); + opposite_adjacent_lanelets.push_back(half_lanelet); + } } const auto current_arc_ego = @@ -587,6 +639,24 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( blind_spot_polygons.conflict_areas.emplace_back(std::move(conflicting_area_adj)); blind_spot_polygons.detection_areas.emplace_back(std::move(detection_area_adj)); } + // additional detection area on left/right opposite lane side + if (!opposite_adjacent_lanelets.empty()) { + const auto stop_line_arc_opposite_adj = + lanelet::utils::getLaneletLength3d(opposite_adjacent_lanelets); + const auto current_arc_opposite_adj = + stop_line_arc_opposite_adj - (stop_line_arc_ego - current_arc_ego); + const auto detection_area_start_length_opposite_adj = + stop_line_arc_opposite_adj - planner_param_.backward_length; + auto conflicting_area_opposite_adj = lanelet::utils::getPolygonFromArcLength( + opposite_adjacent_lanelets, current_arc_opposite_adj, stop_line_arc_opposite_adj); + auto detection_area_opposite_adj = lanelet::utils::getPolygonFromArcLength( + opposite_adjacent_lanelets, detection_area_start_length_opposite_adj, + stop_line_arc_opposite_adj); + blind_spot_polygons.opposite_conflict_areas.emplace_back( + std::move(conflicting_area_opposite_adj)); + blind_spot_polygons.opposite_detection_areas.emplace_back( + std::move(detection_area_opposite_adj)); + } return blind_spot_polygons; } else { return std::nullopt; @@ -677,7 +747,7 @@ lanelet::ConstLanelets BlindSpotModule::getStraightLanelets( const auto next_lanelets = routing_graph_ptr->following(prev_intersection_lanelets.front()); for (const auto & ll : next_lanelets) { const std::string turn_direction = ll.attributeOr("turn_direction", "else"); - if (!turn_direction.compare("straight")) { + if (turn_direction.compare("straight") == 0) { straight_lanelets.push_back(ll); } } diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_blind_spot_module/src/scene.hpp index 3915acd3532b5..6f8450568939c 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.hpp @@ -30,6 +30,7 @@ #include #include +#include #include namespace behavior_velocity_planner @@ -38,6 +39,8 @@ struct BlindSpotPolygons { std::vector conflict_areas; std::vector detection_areas; + std::vector opposite_conflict_areas; + std::vector opposite_detection_areas; }; class BlindSpotModule : public SceneModuleInterface @@ -50,8 +53,10 @@ class BlindSpotModule : public SceneModuleInterface geometry_msgs::msg::Pose virtual_wall_pose; geometry_msgs::msg::Pose stop_point_pose; geometry_msgs::msg::Pose judge_point_pose; - std::vector conflict_areas_for_blind_spot; - std::vector detection_areas_for_blind_spot; + std::vector conflict_areas; + std::vector detection_areas; + std::vector opposite_conflict_areas; + std::vector opposite_detection_areas; autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; }; @@ -67,6 +72,7 @@ class BlindSpotModule : public SceneModuleInterface double threshold_yaw_diff; //! threshold of yaw difference between ego and target object double adjacent_extend_width; //! the width of extended detection/conflict area on adjacent lane + double opposite_adjacent_extend_width; }; BlindSpotModule( @@ -118,6 +124,8 @@ class BlindSpotModule : public SceneModuleInterface lanelet::ConstLanelet generateExtendedAdjacentLanelet( const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; + lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; /** * @brief Make blind spot areas. Narrow area is made from closest path point to stop line index. @@ -169,9 +177,9 @@ class BlindSpotModule : public SceneModuleInterface * @param pass_judge_line_idx generated pass judge line index * @return false when generation failed */ - bool generateStopLine( + std::optional> generateStopLine( const lanelet::ConstLanelets straight_lanelets, - autoware_auto_planning_msgs::msg::PathWithLaneId * path, int * stop_line_idx) const; + autoware_auto_planning_msgs::msg::PathWithLaneId * path) const; /** * @brief Insert a point to target path From c833bea85a2ff4fa9c99ca31ce3001556f8a8a9a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 18 Jan 2024 18:51:11 +0900 Subject: [PATCH 7/8] docs(vehicle_info): add docs for versioning (#6069) Signed-off-by: kosuke55 remove non-support Signed-off-by: kosuke55 fix link Signed-off-by: kosuke55 add yaml Signed-off-by: kosuke55 please check readme --- vehicle/vehicle_info_util/Readme.md | 29 +++++++++++++++++++ .../config/vehicle_info.param.yaml | 1 + 2 files changed, 30 insertions(+) diff --git a/vehicle/vehicle_info_util/Readme.md b/vehicle/vehicle_info_util/Readme.md index c3d06a3b43260..600fd62270d81 100644 --- a/vehicle/vehicle_info_util/Readme.md +++ b/vehicle/vehicle_info_util/Readme.md @@ -7,6 +7,35 @@ This package is to get vehicle info parameters. ### Description In [here](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/components/vehicle-dimensions/), you can check the vehicle dimensions with more detail. +The current format supports only the Ackermann model. This file defines the model assumed in autoware path planning, control, etc. and does not represent the exact physical model. If a model other than the Ackermann model is used, it is assumed that a vehicle interface will be designed to change the control output for the model. + +### Versioning Policy + +We have implemented a versioning system for the `vehicle_info.param.yaml` file to ensure clarity and consistency in file format across different versions of Autoware and its external applications. Please see [discussion](https://github.com/orgs/autowarefoundation/discussions/4050) for the details. + +#### How to Operate + +- The current file format is set as an unversioned base version (`version:` field is commented out). +- For the next update involving changes (such as additions, deletions, or modifications): + - Uncomment and update the version line at the beginning of the file. + - Initiate versioning by assigning a version number, starting from `0.1.0`. Follow the semantic versioning format (MAJOR.MINOR.PATCH). + - Update this Readme.md too. +- For subsequent updates, continue incrementing the version number in accordance with the changes made. + - Discuss how to increment version depending on the amount of changes made to the file. + +```yaml +/**: + ros__parameters: + # version: 0.1.0 # Uncomment and update this line for future format changes. + wheel_radius: 0.383 + ... +``` + +#### Why Versioning? + +- Consistency Across Updates: Implementing version control will allow accurate tracking of changes over time and changes in vehicle information parameters. +- Clarity for External Applications: External applications that depend on `vehicle_info.param.yaml` need to reference the correct file version for optimal compatibility and functionality. +- Simplified Management for Customized Branches: Assigning versions directly to the `vehicle_info.param.yaml` file simplifies management compared to maintaining separate versions for multiple customized Autoware branches. This approach streamlines version tracking and reduces complexity. ### Scripts diff --git a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml index 8941b92b4e78e..72c070c17b52c 100644 --- a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml +++ b/vehicle/vehicle_info_util/config/vehicle_info.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + # version: 0.1.0 # uncomment this line in the next update of this file format. please check Readme.md wheel_radius: 0.39 wheel_width: 0.42 wheel_base: 2.74 # between front wheel center and rear wheel center From 90075cec6fa1713d90d267b83d2365c476c9aa8c Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 18 Jan 2024 12:49:52 +0000 Subject: [PATCH 8/8] chore: update CODEOWNERS (#6038) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 80 ++++++++++++++++++++++++---------------------- 1 file changed, 41 insertions(+), 39 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 12ad752b3ef29..89bcbce9e5656 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,7 +1,7 @@ ### Copied from .github/CODEOWNERS-manual ### ### Automatically generated from package.xml ### -common/autoware_ad_api_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +common/autoware_ad_api_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_auto_geometry/** satoshi.ota@tier4.jp common/autoware_auto_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp @@ -9,9 +9,9 @@ common/autoware_auto_tf2/** jit.ray.c@gmail.com satoshi.ota@tier4.jp shumpei.wak common/autoware_point_types/** taichi.higashide@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp -common/component_interface_specs/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp -common/component_interface_tools/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp -common/component_interface_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp yukihiro.saito@tier4.jp +common/component_interface_specs/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp +common/component_interface_tools/** isamu.takagi@tier4.jp +common/component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/cuda_utils/** daisuke.nishimatsu@tier4.jp manato.hirabayashi@tier4.jp common/fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/geography_utils/** koji.minoda@tier4.jp @@ -24,7 +24,7 @@ common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.sa common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp common/object_recognition_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp -common/path_distance_calculator/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/path_distance_calculator/** isamu.takagi@tier4.jp common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yusuke.muramatsu@tier4.jp common/polar_grid/** yukihiro.saito@tier4.jp common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp @@ -32,16 +32,16 @@ common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/tensorrt_common/** daisuke.nishimatsu@tier4.jp dan.umeda@tier4.jp manato.hirabayashi@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp -common/tier4_api_utils/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/tier4_api_utils/** isamu.takagi@tier4.jp common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai shumpei.wakabayashi@tier4.jp common/tier4_autoware_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp -common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp +common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp common/tier4_debug_tools/** ryohsuke.mitsudome@tier4.jp -common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp takamasa.horibe@tier4.jp +common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp common/tier4_logging_level_configure_rviz_plugin/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp @@ -54,7 +54,7 @@ common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp common/time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp -common/traffic_light_utils/** mingyu.li@tier4.jp shunsuke.miura@tier4.jp +common/traffic_light_utils/** mingyu.li@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp control/autonomous_emergency_braking/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -76,9 +76,9 @@ evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4 evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp evaluator/localization_evaluator/** dominik.jargot@robotec.ai koji.minoda@tier4.jp evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp -launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp +launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -launch/tier4_localization_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp yamato.ando@tier4.jp +launch/tier4_localization_launch/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp launch/tier4_map_launch/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp launch/tier4_perception_launch/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp zulfaqar.azmi@tier4.jp @@ -86,29 +86,29 @@ launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp launch/tier4_system_launch/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp -localization/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp -localization/geo_pose_projector/** koji.minoda@tier4.jp yamato.ando@tier4.jp -localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/landmark_based_localizer/ar_tag_based_localizer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/landmark_based_localizer/landmark_manager/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/localization_error_monitor/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/localization_util/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/ndt_scan_matcher/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/pose2twist/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/pose_initializer/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/pose_instability_detector/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -localization/stop_filter/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/tree_structured_parzen_estimator/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp yamato.ando@tier4.jp -localization/twist2accel/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -localization/yabloc/yabloc_common/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_image_processing/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_monitor/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp -map/map_height_fitter/** isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -map/map_loader/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp -map/map_projection_loader/** kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp -map/map_tf_generator/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp +localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp +localization/geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/gyro_odometer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/landmark_based_localizer/ar_tag_based_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/landmark_based_localizer/landmark_manager/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/ndt_scan_matcher/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/pose2twist/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/pose_instability_detector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/stop_filter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/tree_structured_parzen_estimator/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_common/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_image_processing/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_particle_filter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +localization/yabloc/yabloc_pose_initializer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +map/map_height_fitter/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +map/map_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp +map/map_projection_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +map/map_tf_generator/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp perception/bytetrack/** manato.hirabayashi@tier4.jp perception/cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp @@ -156,6 +156,7 @@ perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_dynamic_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/behavior_path_external_request_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_goal_planner_module/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp @@ -166,6 +167,7 @@ planning/behavior_path_start_planner_module/** kosuke.takeuchi@tier4.jp kyoichi. planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yuki.takagi@tier4.jp planning/behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_dynamic_obstacle_stop_module/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp planning/behavior_velocity_intersection_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @@ -223,11 +225,11 @@ simulator/fault_injection/** keisuke.shima@tier4.jp simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai system/bluetooth_monitor/** fumihito.ito@tier4.jp -system/component_state_monitor/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp -system/default_ad_api/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp kahhooi.tan@tier4.jp makoto.yabuta@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/component_state_monitor/** isamu.takagi@tier4.jp +system/default_ad_api/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp system/dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp