From 06afbd556aa88479deb6aecc060702baa5fdd9e0 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 4 Jul 2024 18:31:57 +0900 Subject: [PATCH 001/151] fix(motion_velocity_planner): use the slowdown velocity (instead of 0) (#1384) fix(motion_velocity_planner): use the slowdown velocity (instead of 0) (#7840) Signed-off-by: Maxime CLEMENT --- .../autoware_motion_velocity_planner_node/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 2bc820d74693b..a8b84fa3dafda 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -325,7 +325,7 @@ void MotionVelocityPlannerNode::insert_slowdown( autoware::motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); if (from_insert_idx && to_insert_idx) { for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) - trajectory.points[idx].longitudinal_velocity_mps = 0.0; + trajectory.points[idx].longitudinal_velocity_mps = slowdown_interval.velocity; } else { RCLCPP_WARN(get_logger(), "Failed to insert slowdown point"); } From 421c1e5f3b083f5fc739d86930cf78944c8ca124 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 19 Jun 2024 14:04:03 +0900 Subject: [PATCH 002/151] docs(bpp_static_obstacle_avoidance): add documentation (#7554) * fix: package path Signed-off-by: satoshi-ota * docs: add explanation of lateral margin Signed-off-by: satoshi-ota * fix: typo Signed-off-by: satoshi-ota * fix: wrong description Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/.pages | 28 +- .../README.md | 98 ++- .../images/avoidance_design.fig.drawio.svg | 668 ------------------ .../images/intersection_problem.drawio.svg | 179 ----- .../images/path_generation/adjust_margin.png | Bin 0 -> 79777 bytes .../images/path_generation/do_nothing.png | Bin 0 -> 67002 bytes .../images/path_generation/hard_margin.png | Bin 0 -> 148426 bytes .../insufficient_drivable_space.png | Bin 0 -> 131540 bytes .../images/path_generation/lateral.png | Bin 81586 -> 100402 bytes .../images/path_generation/margin.png | Bin 102350 -> 102313 bytes .../images/path_generation/must_avoid.png | Bin 0 -> 70762 bytes .../images/path_generation/pass_through.png | Bin 0 -> 68871 bytes .../images/path_generation/soft_hard.png | Bin 0 -> 69601 bytes .../images/target_vehicle_selection.svg | 296 -------- .../traffic_light/limit_shift_length.png | Bin 0 -> 121671 bytes .../traffic_light/return_after_stop_line.png | Bin 0 -> 118102 bytes .../traffic_light/return_before_stop_line.png | Bin 0 -> 118035 bytes .../traffic_light/shift_from_current_pos.png | Bin 0 -> 119341 bytes .../traffic_light/shift_from_stop_line.png | Bin 0 -> 111667 bytes .../images/traffic_light/traffic_light.png | Bin 0 -> 114927 bytes 20 files changed, 99 insertions(+), 1170 deletions(-) delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/adjust_margin.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/do_nothing.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/hard_margin.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/insufficient_drivable_space.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/must_avoid.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/pass_through.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/soft_hard.png delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/limit_shift_length.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_after_stop_line.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_before_stop_line.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_current_pos.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_stop_line.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/traffic_light.png diff --git a/planning/.pages b/planning/.pages index 67c70b928bdf8..bda94919fc352 100644 --- a/planning/.pages +++ b/planning/.pages @@ -1,22 +1,22 @@ nav: - 'Introduction': planning - 'Behavior Path Planner': - - 'About Behavior Path': planning/autoware_behavior_path_planner + - 'About Behavior Path': planning/behavior_path_planner/autoware_behavior_path_planner - 'Concept': - - 'Planner Manager': planning/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design - - 'Scene Module Interface': planning/autoware_behavior_path_planner/docs/behavior_path_planner_interface_design - - 'Path Generation': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design - - 'Collision Assessment/Safety Check': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check - - 'Dynamic Drivable Area': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design - - 'Turn Signal': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design + - 'Planner Manager': planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design + - 'Scene Module Interface': planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_interface_design + - 'Path Generation': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design + - 'Collision Assessment/Safety Check': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check + - 'Dynamic Drivable Area': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design + - 'Turn Signal': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design - 'Scene Module': - - 'Avoidance by Lane Change': planning/autoware_behavior_path_avoidance_by_lane_change_module - - 'Dynamic Obstacle Avoidance': planning/autoware_behavior_path_dynamic_obstacle_avoidance_module - - 'Goal Planner': planning/autoware_behavior_path_goal_planner_module - - 'Lane Change': planning/autoware_behavior_path_lane_change_module - - 'Side Shift': planning/autoware_behavior_path_side_shift_module - - 'Start Planner': planning/autoware_behavior_path_start_planner_module - - 'Static Obstacle Avoidance': planning/autoware_behavior_path_static_obstacle_avoidance_module + - 'Avoidance by Lane Change': planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module + - 'Dynamic Obstacle Avoidance': planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module + - 'Goal Planner': planning/behavior_path_planner/autoware_behavior_path_goal_planner_module + - 'Lane Change': planning/behavior_path_planner/autoware_behavior_path_lane_change_module + - 'Side Shift': planning/behavior_path_planner/autoware_behavior_path_side_shift_module + - 'Start Planner': planning/behavior_path_planner/autoware_behavior_path_start_planner_module + - 'Static Obstacle Avoidance': planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module - 'Behavior Velocity Planner': - 'About Behavior Velocity': planning/behavior_velocity_planner/autoware_behavior_velocity_planner - 'Template for Custom Module': planning/behavior_velocity_planner/autoware_behavior_velocity_template_module diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index bc70c1fdd5c6a..33abc8eaf40ed 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -8,7 +8,7 @@ This is a rule-based avoidance module, which is running based on perception outp ![fig](./images/purpose/avoidance.png) -This module has [RTC interface](../autoware_rtc_interface/README.md), and user can select operation mode from MANUAL/AUTO depending on the vehicle sensor performance. If user selects MANUAL mode, this module outputs avoidance path as candidate and waits operator approval. In the case where the sensor/perception performance is not enough and false positive maybe occurs, we recommend to use this module with MANUAL mode in order to prevent unnecessary avoidance maneuver. +This module has [RTC interface](../../autoware_rtc_interface/README.md), and user can select operation mode from MANUAL/AUTO depending on the vehicle sensor performance. If user selects MANUAL mode, this module outputs avoidance path as candidate and waits operator approval. In the case where the sensor/perception performance is not enough and false positive maybe occurs, we recommend to use this module with MANUAL mode in order to prevent unnecessary avoidance maneuver. On the other hand, if user selects AUTO mode, this module modifies current following path without operator approval. If the sensor/perception performance is good enough, user can use this module with AUTO mode. @@ -83,7 +83,7 @@ partition fillEgoStatus() { note right This module has following status: - RUNNING: target object is still remaining. Or, the ego hasn't returned original lane. - - CANCEL: taget obejct has gone. And, the ego hasn't initiated avoidance maneuver. + - CANCEL: target object has gone. And, the ego hasn't initiated avoidance maneuver. - SUCCEEDED: the ego finishes avoiding all objects and returns original lane. end note @@ -122,7 +122,7 @@ if (Is there object that is potentially avoidable?) then (yes) :return true; note right Sometimes, we meet the situation where there is enough space to avoid - but ego speed is to high to avoid target obejct under lateral jerk constraints. + but ego speed is to high to avoid target object under lateral jerk constraints. This module keeps running in this case in order to decelerate ego speed. end note stop @@ -747,6 +747,59 @@ The longitudinal positions depends on envelope polygon, ego vehicle specificatio ![fig](./images/path_generation/margin.png) +### Lateral margin + +As mentioned above, user can adjust lateral margin by changing following two types parameter. The `soft_margin` is a soft constraint parameter for lateral margin. The `hard_margin` and `hard_margin_for_parked_vehicle` are hard constraint parameter. + +```yaml + car: + ... + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] +``` + +Basically, this module tries to generate avoidance path in order to keep lateral distance, which is sum of `soft_margin` and `hard_margin`/`hard_margin_for_parked_vehicle`, from avoidance target object. + +![fig](./images/path_generation/soft_hard.png) + +But if there isn't enough space to keep `soft_margin` distance, this module shortens soft constraint lateral margin. The parameter `soft_margin` is a maximum value of soft constraint, and actual soft margin can be a value between 0.0 and `soft_margin`. On the other hand, this module definitely keeps `hard_margin` or `hard_margin_for_parked_vehicle` depending on the situation. Thus, the minimum value of total lateral margin is `hard_margin`/`hard_margin_for_parked_vehicle`, and the maximum value is the sum of `hard_margin`/`hard_margin_for_parked_vehicle` and `soft_margin`. + +Following figure shows the situation where this module shortens lateral soft constraint in order not to drive opposite direction lane when user set a parameter `use_opposite_lane` to `false`. + +![fig](./images/path_generation/adjust_margin.png) + +This module avoids not only parked vehicle but also non-parked vehicle which stops temporarily for some reason (e.g. waiting for traffic light to change red to green.). Additionally, this module has two types hard margin parameters, `hard_margin` and `hard_margin_for_parked_vehicle` and judges if it's a parked vehicle or not for each vehicles because it takes the risk of vehicle doors opening suddenly and people getting out from parked vehicle into consideration. + +Basically, user had better make `hard_margin_for_parked_vehicle` larger than `hard_margin` to prevent collision with doors or people who suddenly get out from vehicle. + +On the other hand, this module has only one parameter `soft_margin` for soft lateral margin constraint. + +![fig](./images/path_generation/hard_margin.png) + +As the hard margin parameters the distance which the user definitely want to keep, they are used in the logic to check whether the ego can pass side of the target object without avoidance maneuver as well. + +If the lateral distance is less than `hard_margin`/`hard_margin_for_parked_vehicle` when assuming that the ego follows current lane without avoidance maneuver, this module thinks the ego can not pass the side of the object safely and the ego must avoid it. In this case, this module inserts stop point until the avoidance maneuver is allowed to execute so that the ego can avoid the object after approval. (e.g. The ego keeps stopping in front of such a object until operator approves avoidance maneuver if user uses this module in MANUAL mode.) + +![fig](./images/path_generation/must_avoid.png) + +On the other hand, if the lateral distance is larger than `hard_margin`/`hard_margin_for_parked_vehicle`, this module doesn't insert stop point even when it's waiting approval because it thinks it's possible to pass the side of the object safely. + +![fig](./images/path_generation/pass_through.png) + +### When there is not enough space + +This module inserts stop point only when the ego can potentially avoid the object. So, if it is not able to keep distance more than `hard_margin`/`hard_margin_for_parked_vehicle`, this module does nothing. Following figure shows the situation where this module is not able to keep enough lateral distance when user set a parameter `use_opposite_lane` to `false`. + +![fig](./images/path_generation/do_nothing.png) + +!!! info + + In this situation, obstacle stop feature in [obstacle_cruise_planner](../../autoware_obstacle_cruise_planner/README.md) is responsible for ego vehicle safety. + +![fig](./images/path_generation/insufficient_drivable_space.png) + ### Shift length calculation The lateral shift length is sum of `overhang_distance`, lateral margin, whose value is set in config file, and the half of ego vehicle width defined in `vehicle_info.param.yaml`. On the other hand, the module limits the shift length depending on the space which the module can use for avoidance maneuver and the parameters `soft_drivable_bound_margin` `hard_drivable_bound_margin`. Basically, the shift length is limited so that the ego doesn't get closer than `soft_drivable_bound_margin` to drivable boundary. But it allows to relax the threshold `soft_drivable_bound_margin` to `hard_drivable_bound_margin` when the road is narrow. @@ -804,6 +857,34 @@ The `prepare_length` is calculated as the product of ego speed and `max_prepare_ ![fig](./images/path_generation/shift_line.png) +## Planning at RED traffic light + +This module takes traffic light information into account so that the ego can behave properly. Sometimes, the ego straddles lane boundary but we want to prevent the ego from stopping in front of red traffic signal in such a situation. This is because the ego will block adjacent lane and it's inconvenient for other vehicles. + +![fig](./images/traffic_light/traffic_light.png) + +So, this module controls shift length and shift start/end point in order to prevent above situation. + +### Control shift length + +At first, if the ego hasn't initiated avoidance maneuver yet, this module limits maximum shift length and uses **ONLY** current lane during red traffic signal. This prevents the ego from blocking other vehicles even if this module executes avoidance maneuver and the ego is caught by red traffic signal. + +![fig](./images/traffic_light/limit_shift_length.png) + +### Control avoidance shift start point + +Additionally, if the target object is farther than stop line for traffic light, this module set avoidance shift start point on the stop line in order to prevent the ego from stopping by red traffic signal in middle of avoidance maneuver. + +![fig](./images/traffic_light/shift_from_current_pos.png) +![fig](./images/traffic_light/shift_from_stop_line.png) + +### Control return shift end point + +If the ego has already initiated avoidance maneuver, this module tries to set return shift end point on the stop line. + +![fig](./images/traffic_light/return_after_stop_line.png) +![fig](./images/traffic_light/return_before_stop_line.png) + ## Safety check This feature can be enable by setting following parameter to `true`. @@ -915,15 +996,6 @@ use_freespace_areas: true ## Future extensions / Unimplemented parts -- **Planning on the intersection** - - If it is known that the ego vehicle is going to stop in the middle of avoidance execution (for example, at a red traffic light), sometimes the avoidance should not be executed until the vehicle is ready to move. This is because it is impossible to predict how the environment will change during the stop. This is especially important at intersections. - -![fig](./images/intersection_problem.drawio.svg) - -- **Safety Check** - - - In the current implementation, it is only the jerk limit that permits the avoidance execution. It is needed to consider the collision with other vehicles when change the path shape. - - **Consideration of the speed of the avoidance target** - In the current implementation, only stopped vehicle is targeted as an avoidance target. It is needed to support the overtaking function for low-speed vehicles, such as a bicycle. (It is actually possible to overtake the low-speed objects by changing the parameter, but the logic is not supported and thus the safety cannot be guaranteed.) @@ -1146,4 +1218,4 @@ The shift points are modified by a filtering process in order to get the expecte The avoidance specific parameter configuration file can be located at `src/autoware/launcher/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml`. -{{ json_to_markdown("planning/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json") }} +{{ json_to_markdown("planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json") }} diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg deleted file mode 100644 index d0563e9f2f542..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg +++ /dev/null @@ -1,668 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Calculate avoidance shift -
- from target obstacles -
-
-
-
- Calculate avoidance shift... -
-
- - - - - - - - - - - - - - - - - -
-
-
- shift length = avoid margin -
- + ego vehicle width / 2 -
-
-
-
- shift length = avoid marg... -
-
- - - - - - -
-
-
- The shift gets sharp -
- if it is close to ego -
- up to the maximum jerk. -
-
-
-
- The shift gets sharp... -
-
- - - - - - -
-
-
- The avoidance shift is basically calculated from nominal jerk ego vehicle speed. -
-
-
-
- The avoidance shift is ba... -
-
- - - - - - - -
-
-
- This is not a target vehicle -
- since it is on the center line. -
-
-
-
- This is not a target vehi... -
-
- - - - -
-
-
- The direction of avoidance is determined by the position of obstacles, whether it is on the left or right of the center line. -
-
-
-
- The direction of avoidanc... -
-
- - - - - - -
-
-
- Merge all shifts -
-
-
-
- Merge all shifts -
-
- - - - - - - - - - - - - - -
-
-
- For multiple avoidance shifts in the same direction, take the largest one. -
-
-
-
- For multiple avoidance sh... -
-
- - - - - -
-
-
- For multiple avoidance shifts in the different direction, take the sum of both. -
-
-
-
- For multiple avoidance... -
-
- - - - - - - - - - - - -
-
-
- Pick up the shift points where the gradient of the shift changes. -
-
-
-
- Pick up the shift points... -
-
- - - - - - - - - - - - - -
-
-
- Trim shift points -
-
-
-
- Trim shift points -
-
- - - - - - -
-
-
- Start avoiding as soon as getting back to the center line. Remove these points to avoid obstacles at the same shift. -
-
-
-
- Start avoiding as soon a... -
-
- - - - - - -
-
-
- Points that do not have a large effect on the overall shift will be deleted. -
-
-
-
- Points that do not have... -
-
- - - - - - - - - - - - - - - - - - - - - -
-
-
- Generate path -
-
-
-
- Generate path -
-
- - - - -
-
-
- Each shift points are connected by a Clothoid-like curve. -
-
-
-
- Each shift points... -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg deleted file mode 100644 index 67d21dfd78a09..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg +++ /dev/null @@ -1,179 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
Parked vehicle
-
-
-
- Parked vehicle -
-
- - - -
-
-
- Normal avoidance will block the opposite lane -
-
-
-
- Normal avoidance will block the opposite lane -
-
- - - -
-
-
- So, it should avoid inside the ego lane -
-
-
-
- So, it should avoid inside the ego lan... -
-
- - - -
-
-
- Or, wait behind the object -
- until the traffic light turns green. -
-
-
-
- Or, wait behind the object... -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/adjust_margin.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/adjust_margin.png new file mode 100644 index 0000000000000000000000000000000000000000..ccb1f8c671234e87703762db04c45ddfe3685446 GIT binary patch literal 79777 zcmeFZ2|U!>|3BWUg;KXgQdF)~!kEF3Erev>*DwZSAI3V?T$dK1lvLJoqX@~?l%-O3 zCJ9-hY-1N=$=LqqJ!49x`?;Ub|NGf~pSt%^Gv|HY=e*AA^*XQZJkOk0S5?@wared* zD^_e$Jb6NM#fr6cD^{#xTh9PmR=BRS1Anh{(NvIGkzTW>Z^a6QkFIk1t`447Hujb) zxDc|mPh4=AHP*$I3vq%A4o5jT@mbiQFgTQh3!kHGw=aV|Dk$HgTG@(J<@AZXNDx}q?& zW-mn*w5x}kgQ*-$Usl15*WOtfj0e5#ig&W4^}%4V7<(`y)arspfsa(i3D8>1u{aA$ z9Ic7^DngD6CJnkm|084{H@V~xTp|cAQR&4GGP2YUa4s2<#X)Tr8L#GS z;jXW*CWA0_a&pJHtDdk>fMmwCbPoDV4xS1)l#{gz*22;rOlRRqn+yRLSzM6?evxn( z3?V`z9)qLLv^X);pk?DlU*h7M7&jXWOP9sBX>Yn>vG%SuPG2{ov5tIl0!vTGzZUdCP8(r~eI_!$4>o8ykRm*K0s1lF?TgKG}@Ld^YZfUQMb+K`!Z6I^3 zt1H$4>|%T9feZ?5hrwap94%zA_E<>wEiA22ZuWp(pGT0kx4}SL&lT$gT2U@eG`+C0 z@q~{iG_~5HBNWuIK57_Hq(5 zSFm?OdBJQ@CpBT{6Igd;gayI^FN9FR3%R2m(C#YQc0y`eqO^W^MU16_fQz}Kim0N4 zHO%6qw6HQ>6ug0Uv+z=JGe?|qRQ6KzP&py(jz$T{oWm^rn;t358@Z8Dp1k6TTL0-sE|CE)AjUu2^T|v{{&`|~YbW#;&spo00ZX;xC zep1C%Mc>sH(CeYBFJo1hC-sJfu^WjqY@HL;4ef+A=K zU0VxT8LXk6y(8)*cy3EwGXkZj2}6N(16~Ly+sb(YK0y3&Q`J($fHAGn2#CK_8t{rX zz|6>iS*fekfmV4!P(&I2nMVp}+T8Z1+zs?Jy_TO>&PMShZH-_aFJ)UD@ZAp31IYsV zj1g6|5flJ)fLY|d&_Ew(JW{by_5$mm@>a%9UF(#qincUN+1AcQ#a7x)RS)B;iWkJI z=o`4I=wT4bwu+t>w(=-*EtsdOtRPH9%fkaD3!}B$z&ueW&~7TW@^BShCs$={IWUff zr}7CItg<$(U0GWmyEvYwo&yZbrQxP}Le51+;om#Y5Bc()eE$NUfxK001U*&0m$lcT ztbs(o(E?AZR24*BEcGnh&23~n%;ENK7AJw0*n%AeB&Vh&4R)7`o2s@VMny}|L&ZiK zk}_WLgq)ko3DAb8_VHBF#sH2QeE;3c0OB-wSK3R}29lh#Cm0V7B!p3srL|FauNRuu z@AEEJ0n*g~edRpWv;<+QHqv-7uMo8_m9FnJn!ZX|QAc%K4|hYLU&;tzle`2WkAjc^ z{?8R<<46q$Ae**mfPqo9T=d4vn0RW_pZgiQO9C$55(Gc4I6Uw;iz6ZhK{Q6S>x=H4 zS432lPjty2A=+b)FP>9CPz1@h*lfMTaSFi}he9nnY|Q8BAW!mFoEqq}=o9~ZNz1s- z#o)~SPy7|t=}@Cmh`k=xHm;UhPAD|w-aJ6?1KO-zfvZ5AfFe#1^xD%M6c-#JFE1?( z)`yUBam8WnEPwoj9%2BY%3#6hHm(q7h5ls%6@>}#Ar_rCU8aJ`F=YfC*{ zygo1|>b9PChI)ox;9t6HUUc#DNJ9sE7xNQNZsu?ydo_eA4DBF_Gt|b~s@S6Oz*q`= zZqpKQMd@qWqa8e*%=PSHYPND7Y6uu)nrI;iWU3T&9nipBf$)hMw&*N|5BhL>TQL4o z*NeB*hS>l^idU0W#GoCaH5dTbhp|yqu(n6(Szs+7_irn`)GfnQq3{a4_vbEIj^>hS zuII1KqiwKs9xs)}c_7EJ7<$mc00mVS1ASF5;O1%JmX@MB;3+MfQGmi5m?v-~z_ojL z0yizBqUQlzxFSqhOHfEvLB*5m&b0)+fZGR703!g}!J4Rjgs7k47~oK>ZGnRl1nnNm zki!CDql&G8i>j8O0H6nT^5b#4NBtK7s~ba&BrT&@L*n(7b3bKqp?+#sh?9I(YE;3q9J9BmE&gE+{=A zdk|9LL3rf}#-;LA#TJq=HPrHi+SOzQy;OldSe}pr`k=T>xJ8pK6p|Zi$p}I3gD`5j zu>gPN;E?Q8fWA=YSe{Qy=>oE%hI$Z2(7suviQxG64aoya+5B@1@>^?qU8d@xUUPe-;l|I$B6W^#$Oc9kGre z3|Q*_zYZ3@^ZGEDyu1t)C(xeIy*>zY5HcYD#^LqBsGq+WKwm)2wD{}<6n%YucmiVe z7a3bxd{@r+lF|R8;ocI*4?+=Yz_(OV^fsKOJ$>R204-}@YN ziU`3Ge8S(vC_;jwd~m@pf#;(9=##r(-Ee5j#ex1>IQh4zKq6p#BEny0{5lT)8}zuM za2QM1e}EnYC`*DM_j4%z=bT*ZO)V4st)AailRz;P;?$pQ0kj*=of;8Cs{D8Fhp)8$ z$6Ex9D-WXSMJ;y$taJTl-_Z#DAJBaGx9OJfw-NV0LDBz#?e-6=H*M1)WPyNDP@YNO zzfO<|aDn9f=W4uk)6&Os@ch<*An2}z?xjAn@o#6De{BXq*k3kLf8UhU9ZloTU*W{R z&|ECm!+)BK#S;R$Q~dWiN+eQvvE)P7b0N{ivkCgX`oA|9pd=)`jCV%55_;_nV9mXy{0EWrL>2^YZrhkd^lMMb_& z$Y|X7=NSYM5VR~q#j<5$Iu-x0LHHN?yG2X-_bIRi%EkI~z`Uef47IDHTwN`3(77cr zH!#Ha$suU@I<2(yv~i^-ihMAb2o!;X@3dS|L{NC~`=>pv?5kfYfi0Yx$guemms<%uW*&0%Z=`YU#dKQ23vpgNh(we4@z3 zd44$Yf5UD9RjR+4ZGP_$er_iyLw7>`KUU#ELfh%vQz#*rFdqW;rQRa?ui0LIFB$(8 zn{6?k{pq`Y`Yt%wYyh74O*vIqP>4@hV993tr$>n*NW|Yu#ecj%{9_S3DFB@me0{J0MU($C!I-GX_ufNLc(I&KPci-pm5=4- z6@q=^rv59G_Aj7emIPy8wDbR7X_q7=pU=Obl!SKR@Z)ske?{3vV073vJ^UAf3DV(J z|2$m>(}K)H03nPN5CHWtg0M71g9BB&X z@&(QeV0I7&d5M8WEy9q|K#8F&`#XHHgN=m+goa)gO!l>T{}$c1#N30jBHg${5bA#( z+D`-~3>j7!{m(Z-7ZMf(Hz>Zu42zGKoE^jAB7B02Y4XytxS$9hJ&C2O?7tNJ2OQ?N z$>$fTTcdCm|I1QGii-ZJ)CFLC$R!8w|3y;&3kTf)&36?3aloJoUK#>jK>(`1_nrX& z5}tBL!F61zU@Sc+ca)x>FaQq6O=;FZ~ z0DPz+46yY`D{T*OcS2LhTtSD1`=>)29TgSqAq2iQjWS&;l%A?PxQPM5AMu8IsxZZq zr-UG&6@cCef)(Q}A&4PfP!NJ3q7-zU4B^%=@En5fK^*yf3xNjG0=EIazyX)Li2!aX zP;Vlfq}_Lb?roTB%YoSd0{jHHyP$1|Rk4M@e7d#}z8!!BsQ^E<6Bri&!b5=XRLUUG zpV|p)H~{>?RUA}6A4NBS^LPEKk2cf?ya!P)hk-zcUaD|#|HDQQt_JQDD1&mr5Ky9;tD}#4cZ2|aC76w3a212y)!TkYQD(G-&UlicNH}@UB2UpTLNCRG~SP2>}BE2zAN*ibV(IzXiz^;QTCLJ01~oU~hn z5PpUaf;pF`ekpwLE65)e_6Y&=pnC##bYLDHf&u;jl&7HTga-Fe02q-9Y^08+pbBZ3 z5Hve=T~tu(H^5OF2srv5g6#(hIk?{lE?>fFA>KC?0wIuO(Qmpfaq$9zP#RAU{gyg; zVFVxI-|OYSM<`&OoS=JV&>c?;8yvVL2HiLV*FI4I&PR<1{uAOm=)$WEHQrkcHWyv& zKR4Jzio(GaTEv%dj>ZsrmVrcy0&&vXmWUr5dhjihw^a83_5klMoHqY-^?&D;!k@1G zN9O;htN-ch|C?MrQWPc%u*^Sl^}-+!SjN`>C%gK;51jFzSit-a4=pbbg9*!iF7FsQMA9f%0gkpuL~(f@s6Uqk?GfIlgABEVT0J>sQP@!wG9 zhwz9HeqhPj6bkL?MyqvNV?ikq3Won9%bid-yaes{&EEJYN5)8mFi4C(|M^xSp)x2a zn$iC(K3)#iH?OiO)?`rYIgugmGLHB#1W`D5*%=9-mqTMlph?Kl6eTkZFq%v|}L zdB@d*xA&d9aN*3k^_tsHNT;0IAQ$jTOmUtlR(Uil3t{xoWu&IcuZBE$rMjl-aJ&o2 zid=xHiM1@b$cm8JfBejfm8;gQ-?HzU4>vbf9Z>dg{jQzXGaz8??|orgmU|I&fSo%7 zd$(Wa2P1=q_o2-qHeFtxX8D8rlsRt1>uvjXF;t?T z?%J{?DLg z125#+u&w>JN@>`WD9SpIR)O@QVTz_$lECsCrFV0H#8jJ@E&gHSmwvEc4ZxPF*p`4_ejaQ8l_;+n;$`+hfDuv*@3ZPw*qcTEJVVZ+p4r&+6SJ0;u!w(lA)<>K;U zeynl)dRu6gt@85pztRMxDT(UHFVE-My@F__@26 z+e1H%`Le#?r!ik{5B>Dr%enr5{~+J3p8wRljU4yrQ%A^*prFm`KORjs+l65BtBpQ= zDwSeypBwg=8ON1#MO{3sl{7vu-B>g~A<~-=NST|RCdG$~l47!|6`JGTMSHa2JDV`^ zLv@5eW=WASNlNeJpwsyRbFBlpN%Z(=El6@1f79VzRF#B7AnynEHZV;9oH z9FdJK%c6H50wFe*)KrUHv_r>NuS7kD6`XG0wF-^$dcqz}ky~W1br1*wcUVnZ36|N*MX`)$e^mbIj<+ z;3^KQux(9ZtTXanlM=eP&0m>-IBfDJa{;|l!gSmocAz6k{FE+6E#22bW1YtX%gzF_=o#hH5X2Myvy;p8yM6# z_0GdoIbO1Wx%$QVZRmitJ9jY}uMVpX3KsBRzhZGEk3rF)ZS587^^1NxAYhG&-*mUW zedf!K(NYeUBr)w^u8+eWMPhz)1E$QP${f1g=)v;m;{w7Tf|Y38alHeW!;@T}K<8`5 zhS{;GqKi`nBfh>T?a3YMS(W$c4e=L#>bT5;PO*Ft*%w$ZdJPO7-ra9dtyTR-<(LZcqeyS+4;5I47rAFWSR#3-8hQF`Fes=(Bs>d&&8&XbRA^P(shm)G=~u`r{+;i!%eJ3%j+Fl+WALCB4*C z;@x57NU$6%m}<+U^rtevRh9G`NXwhV*F0Otu}6W!*R>lHE-|U!P=yV|p$zT+)y*YTodq z>_Es1qqebYZ|$?HJHRvl5s|aaPusy#L`L$-9ghdnLt3y!1rNI`$V4d)auq_Yn;~4Z zEnnLDF*Mw2U9qcdmmITe<((($^_X+K1zw$+&@;i`>40|J3&2dHOuvrv+(%~2iiX`X zQm^~GU(IoDqS4g9Y-rQedGN3A?8mcG7kSbj9botQ_^cwXM~T0{)&9|k;K*q6^sJg= zkw>Ngqx_I%#$ZIAQZwIaN@EfGy1lOIMe(HkF7L$LuGa2dc1ksMoZ;e{)3tj&TDP9v zgF87p8t#98Pc-4I??h5;Xvxh|y$1YrcT_3Z{TUUR*SPXJ4J;#dI)DaY2lL4_0;uP| zqckj|r{}8(luFZi&A#?4YLW)`FhKLqZxVi+pgB?kN(>L$iZ_cL4HF+L+n;B^kskgl z%y9y5+wMCRx-e6;Fo3u=l-FL^VZvK9U5)L?u2UV5NGH!dnjNbwebP3O{;7*w$^ehe zO{u!C!XD0Y+Ert=U$5vw(cBO=vQrAn6isRtXJ|C>9`Y;|Yum~}d3BaSf=L8tAOQ`H42dSCY z(EdvSWR{{&FCUTOyo2A|YUP}cZlATf|ES}FO8ml;_Bp<``N_N~Z*i>T^$$J_O{~2_ zJghhl=NDTqfAGwT*l)wIkkg&WF=x&7sbbQj)w%RkLd*U8Ky@P%B>1;8>B8Ta7g{73 z`;%YDXH;)F6j;a9!tg|+dv2O1u=&|RvyXT*mj7Rkt*c7(MnnS3}o<`;xjm9^o}!i@g{e;6=JZ~YhMI=il@4U_YA zfA3>e#h4iwS;e|FRO~#2cm7qjzqvEh;CkFMcdt0-64ppY<<*g`=G`sr^X}dH9H+{U zF-wfUI%OuRUmn7X&$PP}soPI}Q@gP)L`1E7ruRBJtPfGhoBQ@QPD23ue&z$SzX;!> z_rE1+<5wOCoXRh&zW@iOSj}(jipa;Ot2=L#~HC!`xjtiiOwNKYb2bTGq zX6R!rW6pjos3%UUD7*E$&cs~Rj($uW-pVr4GBJWD%;n{R`txc^BWYuEOrUw}WT zb*zP(wwpIjdFRyYrrsaKzP!+8kIcIZyr4_4tGI8!R(#4H7S`UzYk<#$4sp`M!mgAL zOieEJ4h}ZklSnU<#N81VdsNFuyVl;Y;))&f9Z$ph+KJTb>ZX!xNzFR_mS_9q;*!UH zJ8g3EKJP&K6UQ!ZNvWVKXpZ|;k~4#mJLa)obDT9Of;Tkg9M0~exdFNnAlA{ixNBfUO(5Y}>Y}iD#mC z32-0a#Llsp`eZ)rR!WR8THkf;*HD>1X7P!<5|gbi#ESmsw&g<_armAao_%+scIRH^ z@x~Imulc2-$>pratR83@!Oe&}Uf1hPvg-HbG7&6QvLaH|5FZ`2=Yd_+%Ux%a`&?os zekHM(S*q2wGK|UFMaLmAV!x${=Usk-k%yIhY}>e1F9IiWWbD9+;D-}j#e?!KmzcPe ziG(uV{qXzw(>>8M^|36wanaXoMf>k2QjEoIveOhLkuxzaS4!1tWF4<)6vZk!&O`)I zPAb(H`BmJ~C`WUbUW)&<3|}QhelF|y@=7Vj!A9n3Ty{+w0-2Pal<$wK=0&Wk_dMZ@z24N$|~BZeBrJ z`^$)1g}IaX;>_|XwYZUfev42JDakfUL!LZ)-Sm9w!nkT~6zN6&r6`{I0VURhP44M1 zVw$zBQX$4AI%8JwL|hiRRpZ^kdzAdv+=Jl@v%g>YEMEm6U$L4ClAq-}pG{cj;9G9S zySka_48o~A;+cY@bA-|DH&IM+@WFJ`y|Fw(h!ys_lJleCdb+<`y}!85Jw820#+jy5xxyhG%qLcoca{0R_ju>l*cOj@A4{C6&?|gRBJgD7<3O~yaE|F$ zJ0OG{*ZJ>1BYppNpk`TT6mQIirc_I?ltznKs$gIwtR{X7;^t42p<1DOVeO z69ra8-ZWLnU;L}ov&->acX{!fE7BrtXW~%alXD>8c8e$V1U((`Uzp*%HEBo>hEX6c zeQvFzOpV9n)%L9pF?KLC!pWf>f2-SvT-}&#RQ-HBf8V8*pV-gn&Iyobw{?lE;Je;^h3xH;mM&9L3O`}gzOyqt?SA+_0S-XFyd z-{@4#Yu0qV9>?-a|5O$cUlDE9qhc|jlpa?7F(cO^J{5iAhKCG;eW1T?PSI(A9g%qI!f2g-s2+SuIFw6DW)V_>~EMN;hpu?3v~WmOK3_ zl4F;{1;vwI->uCRoHi*_+y5rYILO5R*}Yy^0T42kpHk%+-7rf{&Y=n%g`(L+2hFWh-WdsD{q(EwAYohVk5gAQQi% zpOB;KxBKqo6$GdA)MqL10N<4MMw^A|tE^WCSb2+$6wVB9(sR^%5`(O$N@MTO`>iaz zyYZ}7^=~hkUbx6Prr&kc#ubr`&l{PJ9X!+G_{1Te1Ibud^f8Ek+~|XmFUryT(tho^ zhV@uKa`cRY+e2Xark)6xr0Z8lHdOK#`PAKL^&Tl;OTSsQBQYmntX6^J9cCuvK5WXy zG1u!D2Qe4%s`4W;?>8IW3!Cc@+SQSda=7xyyLyuz5>Bi7dLkq0^Q&XX`c>$M8s#fQ z^RD0Hmpj`>Smgr(V(Vk3gtKmm(dT;BUT3<`7CF1-I6HsNoq4T2gojAI*&c3gTcwGE z(V_j-jCy!<9c8Mlv2ZfSZ^ng%H7UwD&UWV>61UaZbM=Wj(Hzy#R`O^*%>A_@cW5t@ z)Ek&Yo~Vth28{m?LCOhrlTQ_lW;t9VogW9Yh?4`@+Jk*pS=eor+NAbNZFn^pTtR5} z_p`m7o88gz^4!775PBY=0`ic}o2Z-MmF23?+$&}Kd)V_se=BMJfNbs*Tb0I+cj8g2D3=?zQ*-Vdy_88u*$rvtm1I5=mE(5UZ4x0Gnwj zJ6IYq(@hdS5qhddcCN5iG`HCS%U3Y|IvBa3hS#aOIm(KT1((~;Uwo_*-dq4TjaBxdx8iQ-rE<1%Ne64 z;$N4CtXTbSP>4UN=jG#O_}e0`Vxch~x**MF3cYT zDnJxoPda$Fp44MYY$YC3NrAK76 z$3LccPIAp$YANZGyBNT?<;_%b8B8KPR-UH_(OThPeKRt@Or7JpP|FzR5H`}-z{p># zp*2e!yXKgB`TKM~=AHw^*5%AYA2`QngEN1YJ83k`6 zXF`z2u8qaSJ2YH7pz_dkx-f0QRVzJd;r%+Pw^xUu>=Elf)8flcoN=2a$1m*Jkk?2* zwA{FLOA^cT6iq6-VP30J({c@qw%qoUv&(AhRv034PEFkLvkL`!3GMf?Xb)i?))n3T zA1P-7n9_f$p9O!cT79jH{-(}Ywh5Y z1(w)*kN=2wJKO7LmsnWGf>W9@T7R=jh^#5jWF6jg(q&@k__M}K4CMYRxV8T2aqN!e zYMZ+xyC%4%ekBsv?m{2EC&5-`wiLS{|6$NcC55;E1=il}f%52TQnyMF+YmvbRXBvM zf-b4i^2qKqN*5kVb_a@u-uCz3db=6Kreq6-PlRrzVY#>#{d#|Miv;(x+miC0|C)y@ zpApZ#-Ic7?FSYm81+RK~L17m-$n*WmTZv}O>gOavSfMWwklp* z+}cSquHvTVA>pxUf}H%EWG5?wrEjR?;4yVJR&#d$+0jV#0*%9PWvpxGn`h!TCE|EA z5o`81;=3*@c9p0w$UhvK5vw$v1=gh!RuA#UVmE8S?SJ9uiX~Mvg)m>H%U7 z!YG)^7^43KGBdWRkTig^OE>OIr=v`o6+sC|HR~2XwFH!~b`|G_dpCos@T*_$b$@#+ z&jUE`=KA*P;MdkVQ(*NCWjpe6?r4~`TCer?6|2?-`Ac8F35j!49UCj=oGU1T2=AGs zrekAeoHIjQ;;&r8Iiw14iFNtT_P!7ktPqH^R_SFmLvF!Fa8JkW49p-1_kCA18j2ma zc~}PXeV~T6P}sefzgXy=q*O7vb?0FvllK)YNtSgfZct(GvQZY3?rw+1ODkJJfk)`Q62iV>$bKHwI7^^-V`ST! z3H~@x%JJBqo_QIQdMO4kZ<6Ke(ms$4P zR$2qkx!^J<7j(|sIxJCYuo>0bv=Nn~jv40e$N&lFTGIsKOV1B}lDYvo^ZTvz= zzpgr={Zqg?_P1ER%FT5yQVa4QJPNtVtIpA5`CbMP%Ok693sBV{V0S=TZgWbzWW8*` zN}Dzqe04V^0{L6z@dt)LwE~Ak{Nsx1h5RNf1Fk7$VnLl~)p{cD@kU+%r5x6pcr+EE&6a_&P--b`@ zjxzDOM|{&A^kQ~gHLh|%DU0zONQDV$IwosUi)w~kxNvz-w8>&kbIUGXfZnh! zw~L~dX}ACSF*3u4t8liPe=4=W&kdj0(`f8cU2&?nIpUe>FzPg0hah7eqD*oqyY6P# z;O!8;3l6zWN$s7cGtG?$rXHvB0%rM$ubu`a1vmVva!+}&W zL;%zurx@+dK72e&l3KvqKN-rMYnJ-(`!@51xvBU*gX(<}QMy(5jmFG#pC(+u#QsNrVLN|I?b%A+tl#VhxnO^K?!&jA7iX@I0_vRf@JNA1`Gd!`+`<)`>$0!|_p?-6L5S=7_y#h% z0OYU?Vlfh`izVIO^+4wol&`2#U01*@MnOh2HMlm;Je@WT@(*vw_s{LN&F*+?aJ}&3 zbH-9oUu_vrawd=_ZeZe?GD2G^zfQ?!@B*6@@Y{2cu(XesAPX~1x8%=L1{8)#CPrgc zN%(+UxfXBz8c%z?1T|Yq(tCVXIjF)vXz!dzog!}lNu_LMt2<}$OkTl|!)nzot|;SQ zMnFxEVbg8HO!(XzEwxZk)JjD8w~Z$uCm4&aflBYmc6lCjR>U5(W9Jo~bi_sMWd1Go z@@h$xy7%fD%46Jw-B2hlH9Xw?dK~ibJHMHsnN1Q>(w9dn<+-ryZx|IHecXF{M_ub! za$#3cM5`{kIormUz1b{q6Xo>Pdy@P4f9;;_(mj^LHFcACsUTNyV;!6Cg+C^RLUWHF z`}97rvo|q(Sj&TzbWfG3&VMw-^hJXa_8m6eg(pf46ouye;*im&LD_!h^sXxIp3pc_ zG`3JO<8bq@{D*`e_g*7~4PrpeAxs)?)bi7!hgAV?ji-_G zpoTknZ~y8Gt#x97xs(VVFLF;z=;UlosQT z)Yx@x2kY;8N(=)AQxa3Hb!@IZwv<-eq^6X9ABRNA?p&@YQ$KvXF!1iAQ^Uq-r%iD? zaC4!@QiyDBTjuiq6ELWwXc zu-GEjVxKjEKNMJOyd%0~0#bXX2T_K$_fDDV8{vdJ(+jcLQa*l$ob5{W5y;_cwbNZY zg>y=+vO>hF`Ht;zd!ympd+Y2ZqQc8X>}K;=53-2RuHur#Ji!xgXNmyXhpE;$KBf1) z=b_S3Cx@|BrY60q{GhOJ7XzxEAnqf*p8Z2@Zth@;S_NY?K+Y=1H*R-`SQzfgZ-@%u zd)^iFCcj<&ns_dYvD34+E<}l$(`Q)I^GI~8=>-5TWx182N)uGYD%L+N-y53ZY z4i8@-NfKGt1m9iZ4kv^=U26^Qc~HDLWW;yGd#=CSxu^dl6T(hul8677uDI?At~}>* zoyYYO4K4#$jOAkXTcqy-R*g>+I$?Tpb~(O2P3^ zy+1yF6Sp$)X`05FcoqTp?@EE$Wyi%=w;TA?sZpsnP$H4h7u&q2+KG%p-a|Qh#{P2?o1!ZU1&>Vz zZ#yb1)jA7TCz;^KJRo}~nMMLWI;se#ur+U04 z+S!_Pb3m}cPZ1Z2nNG{8bO4oQ6^HVv;S9ft)ElB#&sts~U6gOp@7^;HLilsB9&Ln< zIC2E3$yUl`tyke$J0(efa6UIe&VnoNe#f~_>~d;@OZY-R{$O~lIJPmvf~dB>dxn?4 z^$`7F&V3s|bG2OTT}-1cA7|*AK&IcF5tnL&`;|Z?!Fv9a-JbLz!l-p9n-mqnDyr1w`Bys%R`rW>y{L;kQP1jLqgo&^&P z10HI>4XTA%f+K>I@dc@cX|>``fxIIXZ0f?zt2jrHmr7Bf;%ir<7o0sozDgwS6JOob z+W5GzYwd+uL7BvenMNY0q(?H!E`YGiE1pWTb{F1Oglr^MQp;4A#SyAIs5cW8UslG* zor9dNN(&t$Vd8z=|j?tdb}m zps<}0PT|z!fDU~lBeOzJB|a6I+CyYR2{*Gm(b&s+yl3a((A?U)l2WA+-rJEIv)17% zSBx{7ev&D!FR5=F0!7bAoqU8AysJvoI-5vwDjql1i05ftcO=vicC%%otD^S9RoC(m zkzM=m1YpGG6PIhyw+Cc}J9>`n@7T7nu0~QLFey zd$T|oaE8P97{SM%G^AL-A*!uqq?coecG1RyNkY9E-&ML)!P0LER8lY&razw=_SmmBn}0qICR+#F}+4SC8jBF7XSEEvYM3g&Y0E2 z6d0!51IolnmzJA@7>3}$y>|F#ho>rPc2Mfm1Q>ADX;^A*;hlx_Qel50s#oo}(ZE-Q zA)7FyoCPWc1%}wIqE2Dr zDT6QxvCC7rWdefDNA4D0nci?A-zlmkFm$}=P)USBp>NDjVCzzOHclsg!}Eh={;ik5s>BS|=h(7QppP-lcK$oWMX^E4Kj zR3%zQ(E|s=6~g;O*Fh&$!46kCYv!_|Bke~(o{@HuU+*NQ+}$NQ%(eRIpCb7NW9 z$5yGk`Omc0+^&_onVmk;;`F>hH>j^(phv})C^nK`!Oe}6gj*2PF5ryuN2xFZ(Q>u( zOvzp1$1v)zoHkL9BN+>1BFM)~%~dD3_6;es9seWOIFnM+ORhxP3DQ zyv3()n6#YLjZY3n6y?lWpM^=xT!}X;WBe6=vDKs9H_}XkB+x!U;MJPjbd|%a_f{FN zKTgLp?#WndM5$(thRLf+`0j&E3*rmio6^b8Elu>R7>)5v-71b`pPNRfgdS^*sfTG0 z>F|=PhxaM-YZ)2QvVEmBhI@|+o3jr05AfX*Vxk5YbUd)N76{j)RWCZyj(gm90tZAM z>}C53h_!t`7*0kfmNr}^s8*krd={**81d7TYYr-@ZlsNE_7)r~pswIoel?2gBVa0v zxz(qrRoJK2>jCgy_H^{3@1u2v-2`vezG)Pue(hBU#GO@*aiqsb)QI+}GJx!3Zq_i; z#(4`6(Bbb0NZitOUDN@YoqjC7lXm>h30>M*K~$pGe`yQh1Pj?K>Tv7_cXccQIJ)vp z!_Kc3K`*GRcZCc;XR=E2S7Ux=NrEyU{YG>14}jNU5Td**yH9ZW!M~E<=P~IYUR?%E z3X2hrr7i9&1_HSTz`?pKZS6vq#Tc$RrU^aUg{NRVQj$b!P%FU&B|9W`|KZX4bJ0br36!tRO@^fb|x50ky?C(u=z)v$y_eu14 z0vMT}W_%e-`ycJI!8K36cR7vMnv%EX3E9j|C>WpJ$gs0F8-4oxJu_qZ~4)hujicR(jB>uJ&+On}O0O-=Pn zHVotQaa>I7;ur>ITKUeo`yL!FHMnk)pS7@hCpLyx1R2#i*lL`g1uO9Er0o2?uRGd9 zE@V|SE~%DZvs;AGzQTFu+wCJzmrPi}o=*Fh1i~IWQcp+hTH%*$jCGX)H2}8q(r8A? zY_tT-b`hFwXHrzBamxi*fe$&|TEk4MMvx+x0+A(JvnskHHa0p03A&(A;7~xN)$Gyq*66sjU!1do_(s_ z-~S>&@LdCyYQH)1r;onSQrc(zy zQ@!9v2j;wqb5mjq4I8p4?eX#`F9UMRP$?)P(09p}w74P)vP?f?Ay901d!w>b0sMc0WU5VmMu8QSk+oEN^zRo*Dr2X}WE1a^ zz3cqvFO6;cxHDIz68uzz6_ajz4aZvn$4B#&B(-Q^U$0h|1z!Qb)<^n|eU=o7jH=Rh zNqnUriUQ#AyF-pXJb4sA+(*ke!^a2WOV5sIvAxX~F6u-R?nJSh%`41|J_{p0qv*{K zAe5!%#ki08DS0l0aUkE$GEaI=mnsxC8G88bwf6~>kbL{8^d(PSlIS9%C@|k%66qNU zYq3zs>^{ph`N?dKZE%9qHy=Aw4=boA>n$*_4oqN+hTKQ9;!Q=KjzrZR;D0S7< z1J(f&@jz)jiegua#gmO@uoiiFMLmXgI`eZbeteU&;zV)siw;Kq*ZYcg^%sqVEtE{F znHDW!sxZV&-72cKKru{wU3R>zV}^_vW4!dMKwcZ0%0{ zeU6X&l4$y5yE@wa=0dIHyx}{);6Cm+pNP)9_fsSA%A?yd@@L2H#upj-&W@Yh;P0Ci z(_b+49F-%r9}Cc3n9<@$5|d&f&nSZP=ZV?+BI%0z{-Ht*=KzwSK#irszNmHtBW6D} z|7n`vzjkMl>1KDofv!?LQ(w0t4wl)4z;_-kX{OhQXIm*`7Y8#$GbzK-QL5Or6gv>! z-t2#-(GZ+lekdub;NMt-O)3~WRV6TBpLo;MZES>DwtAtzc-&D^s^^*D?#|RrbuDwV z;z`fPXNh?3NTz*}=4+1)T|cCo__ld3@g>D-D2&t*nzgnRNAp0bysmYlG5aatyqaCl z*jdgV@S=PF=GPIOgqVB1Noc~J%nx}T`s{^GRfW$-#j|j-{;{3-UR_Rn5*q)jm#lXh z8gH$d=6S7?u;W7YKpAXq1lewE&&iu!P#1oFzXSQTIimh^mYjY5DXx;2Wva~^%XN}? z{4~81LpymdS@qmifnhO#G`qM_TknqE*>=a&y3*e4U9?&UEoN|lj_T^p*U}T{bWAduEp<&+mhdN2#5f4a|POk zExruOK!IteGA670$7^G_9F~*|UWI`gfqTpjUwUC>`##tkz@elxRerNyv=zU^qsL33 zQiXfJYYcr*@c@cWpV&~gRt!{uKXp(wW|v($!3w(7Q4nbuD=BVDTvAa<8w^(v(||>-#qETbe_S zgHqSt4OD(5sH{m+joq!q;eC|dzvKLM0bj4^@l!}EU9)QjR_8Zt<1Ue5%wL*#x+ka5`jKYLm`)O7IB_v10Z7FC;uO?R2C98#J5s&exip+oV z?74w??3d5*R?jRj`Y>(_192bbSETDW7jfCGm9yNVm?6hcjkmu`jxpyI2!RiYpj zPe80qr*v|3)~#dTr6x7!8ox5XGj`-+UVb+(bc?IhJcOS;gul=ev)SpOcWl70Je%X& znf@%ID0c(6Rd?flT7k)AFK74*S!Ss{dF_7Qv)#dL9T7@==UL+X3)Q&8#ryAiE=;zB zpDGRNOMITLu|&|vpdW&`wJo`Y$`^xG(5)17_&bmA){Z-dy2j2gKQ(|8Nw&6+!8N;; zL%dt6QC<@Dvdj|O*ZEIoInTK@PT+e#a)zB_9(;rjv0RrioLR~q62xNiXzT@r?b7CX zTjJ8p;_2I8KvgqsT9}F>-nBMhW~4|ex5X-2lIJz~;MLMS9>!JRFeUL-;-oF^Xi%Td zbSwWt*A>8@X*M+@#kyaJ zcFfPrOY|Pj(evp^2yDLH2|>}sr(bLv?b1?vS*Iqk1KbxnRA36>QwEFL{R)QIz22fS zL4Y6G7JkFQDV;zH3)*Q6gH)|Jr31iVZG1)_6nmLwjlWhZy%S|BdHEzg<%&_~8+alygfg zm%u)7Dz*BG{W(aI0B?B(*)E<0AZUG0%|m#1Mj3nARDn~*J06GhVipEx$(;~lP<*mC z@lKx9PPSI-&d|LY1Ca812C0{`q<6vj9dv8o=z6FdhcogbC*d_>fV6_|F>871}lW zlHd2R*$cusCWH82@NvvL9d-rcy)LwboyVhqHF{!kU{fGfylU@L z74~e!#JlOe^GTb*PrTcJCw@g#?=pDmZ(X|Y^ufM+b|ra$y6@UnVcTs}A5F!1ABpuD znQ3Dw^_?5I6W2zt5dPa1UT?_?kt(`?#nBjuKqNf zx{?C0Vmtf^qb0kf{CqwX??_@%y}#6GJ_aXoZE{y^sE7TpB&kMIN6&^ZtU z++Q5m?Uge~XfzqU5xBWu!4;g-mdwY0Ix#}@_vpKmS@p1Tr|My4{uuq$OI7VMP_>YQ zbySE@g72C*&yMr@{sj|WVy@56bC>91{k;$G6(6WVbe3iK<)|4Y`;2&J0(9BV*M1DW zGrk?$E*m|06V=E|usBNSiU`U!(!G<{?rtOw?nBSrtaSDzbzNC!e8+DJptH_;G;u-b z*tW)nu4E|?IT~lF`Qlf<&fjX2GduVjqj^rf9>34I928|0+l~(k6+KeV7=xhBKY{eI;yYVBz|Qs&Cq*?I6u} zar=5jAy@ehFtCl!4_1N8))NO+Y(K2ut;hAZ*f{)Ts_m_9C9k)b>$4!1ow;iGp}WWy ziz}W0Q{?6E+M&q(@|w_`^&NGFsusrrxA-H7<3x$3b}JbDv};QPO#4 zC~rzQ7G3c1b_j!Uz(T=@AF^;70A~x6=C5odjLq>5+^?JYbT2t}C!0gQ^M~SXe@oXA zw(Tyb7DVg#tlG+qN4M>!PI53kn1BBKcxoM{>iX8y^n6@byn&?4E9p#< ziMLK6OA_zBLcqy!(s5?02Vh(a(3Z&Sf`@UHVMkl+pE&ICtr7^jm!98o zp}>tfH%Ac_Ypw3Ac4Dspr&po(&`8Ey{sNJ~zuL@gD63MTBWVD8S3CRp5uVaMme}@$ zxj2)d2YtGu?d!Z9x6FL-oeT?Se`MM{gNgGy*!H9*xFGQuC0on>vPCePy6EBtSH(MyZX&t%O&Nvp7AgpJ}JuZ#@tr-)E*wdV&);>N= z;=%Hz2I$0wns-&>In5c*LT`FAkI&n>+mBIrB! z3pmkkcH7_;!s)Jv`lH&Sxm#<^IXBd%6zuha=_s2Wix7Adtc)0*GZioDzEv<1*~Bk? z)XE@@JKKJ{#iq1(B`(K0Ym?1$H!%-840K zn2we=s{%B3mc1`F(~K>pR@vz5j15mb%u+yyrb<$FrXu z=ePUkr5nFfZTnke`YEcE=LY>`O5Lnk@LKf-MZ;4s>d4g^k$N}XGktf%#!_vijhU_I z>+CAVle^8cI=d~!moFR3Cpy&mRr2f>3H(T~Q_dTD&p0{jB(AT*#yLm{M-0(bh4%8+ zO@drnhNj`@inp&sxIIojiyBy-?RSc3%xih<{Gnv%Y?s|rzR*vYLnbH+M?u2}CCYrd zupytt1X1EpLE|q8O=nlBX-%hY+bfjX|9ZKAK_EA7gSwl{0c|Lboo-4ra|EBx?!*F* zriL2VuXG1y-$*CSy{QnqG-2jeNIN^yG5O=;JHfpHqA+1w@#-Tp{11nLu*gu7+h6Za zoVJ^u?umP)(I!4|O>vsJnNPTh3O1g>=Imq*AE1Uct)4(lqO^kbVExTB8nI?HsjFo- zHDR)6^Z7<YdGk*iCNX8+};3ZNbvY$r_#qUwpA4w(${gQ(ftmL+?B}PDA_jHig@=c237HX4_j|O-RqUR zsIxnFOUp5f5j)9B>dHcIHeni#I2WwqXhYyT<%1BC0WzvA`rtG*z3H@o(HYi>{C|2W z0R>^WvF@l`x_!V5&M!uqeazmRzupEn9=Cd_>atO}g(+;&FwOcRI z>LSKiB_BohB^-u|H*pY)?=&JOdD`CacRk4Q=E;VMdS&R5<%h>^1}O&iV&e7e)*7E` z3a&-Qnlx+N_3y7o@^^@M|6_{pWmpDG^rL>79#6pZj>fLsLqmkzt&6+l_QHCG2-cBu zX#F9mZbTc1xRq$Prwv$Zw7)K88uF=fFMMC0o9cRuL(*eQL0mRL4DPJ|%3tC&q@uG{ zY|+zZLCh_JGmj+kKLW?O8bGCrb*23VsfAScVh)~tOxS*uS;PBJDbR;To@V_jIRIem z?a0tmjXgEZW`ht<~QAp6kx>_KS9R{icSst*Y^9 zlK`mjQgT~_ssb2tiB(8=+*J?tODk#2$p1gMKBNK4w?b%?Gh1yAoo5J@x&{ta(+;kG zCFmP-@{B4N8Uux#5}!jJp#`rRPD8HBeKmU*xjOHnyH6LrD=bJQn!Z1`u}tm75a$OQ zr@QMv`a8DWA=$mFtC{m@GiW$J0T2a`HANXZ>Y-&ytzu$fb#*69kKR`Nr$$BqfCax< zLq++_5R-8cdH9}Qq{KH(IDvJSl?!Sb&bYjKx|^Qr@*Qka?PlUZIJrqEtg-&1XPnm3 zU{ZA06Q{wklHbx%7a!Q%r($E%S{nOb9`5(yFc+%)+juNNj#+qOS=;=YjnFPyn)RxJ z^}k1#fkqx``3jrDAdL4C`qYVL?#0fj;5o-@g(+Tu(6@D66TjNh+&REzebiWf-f=!o z-7-{Kb^)tnAig?6jqT2Ulfb%n+lL?Il5f(EU`&flxC<2JAXtxbU+NBek_TRWk05~% zyF=JyctV6YD$*olk31d!KT2=wzMu&c(oT4;Bl5&Aq{IwyO}tLyczf!N#Mxth4N zi3n(hoP#NmxXWPypL2%hMRh>;uc;a=MEb6F+@PIa%mCdEjP;>M<$ zFO06b;;9oJfeF<;-q5pAx6U@kTMpBPyRy0Neeq?J!x=PI!ZGH5C!?feqdeD~7b1?f zF+OxxQP}v1{{-^ChjXa|^3B9$EwVvlA>!hSnjUQ(w*H}JZsZ0c9Lft4-tm|#`+A}Uqw%@ddH+>A3B3S9f?4r1njOEEE;aAd zdP~?{7tx`){Fdr#H^7TFSc%Dc@qpx&so|hbcE?Lb1F~a%SF1EM11;y5EBae1XA_m* zqnxc1ZvQ&r6Bx{L&-NnTMG-{;!p(rDCSX!HuE?ADKUMj!Y;QUQbuWC~>jA=`+fP8Oc}x0}<@9CC4~Qm?}(5 z-(65&%iFl|Ap4j6Zkw`R+|-R16gKLnetEir4qUOpY{q}c#KUGTJGojzq~TDmGx`O{ zfR+(s;E|U5EBo}Qrv5weHsULQwBHwab&^}@4&Uig;A*I+ugf7wj6EG9^Xl%qhV^(; zvcwXewxM18xYDoLq^R<$A&!_d&KHGG z`y>iw`+fMld93T9!&WtJ(ZuIA>-=6JEhizVp51drx~%nyhT4>;Z4-aTjoCgN>h$it ztcLa>chjhN^_}|R#;p#obup~h*~s&YN~SFY1&L7>h@{`1Cq zXP}A0dDqNKV4<<0YDD0{PIHcaYz?!AOb%4aCOa}B-?v5>YN9#=+b^|o+w@thnu2;0Ky8FJV=UNry z>|VHvGn+PDp7uH!Oc}MiFZST7H&dS>j-mTP=qF=`Z5CIZm5~}26Y~LG{1c>?QGRg= zhku{vNVcDE{cIDvXJ9j5|5*-~5dg1g$ z^e>dAl-uGm&>xEqzsy4V6&o<23`w`_fqp+c!Ijb`35ks5+FbP7kA6@yQ+$Rbe%V$5 zTE~iXFRrWtR)!!w<7-(C2^UMpuZ#Ocd}9%T}_Kqtn;BZl^n;bGbW} z%Tb3lNw)bSh%bN}hEY1cTD{6i^A(ya9~5fh6g;Vf8)rrGb9lc}5|gjiN%lU0z=@T=#gz{QA`| zDo(GiC%vIoEy~_|8cTXsGZ0rqSxzVDQDzX4UD>4RVQT@EjzTI0V~V#Ue2USo z*+b#S^Iu2jW;jAjr!!V1y=QF*V#SbrjLHCDIE=43^~0{Y_t)XaYF8DhX?Odh-P7rP zl<*)M<50QWX3zd{sL$BHRD8M@P{3L4cs_{ST6O`mOoc7+=!p-=1`PYmupVUkE67t<;4IlG*?Vp7M#C>(_-TcyDVjBgJ1^e~K zgYNrYo~O-&S(uZ8RFO?2}fR6v@)$YFv6`C&`O??lj_x@gDzk|olV(v zu=q>^Z|`=T?sH$iPNFvr-WMO@I~h-BYt9Z0z<9K>r7%|YTMjTr@y8fH1dKA%8Bz^A zxoo{LIJCazPK`>HcQMJ?A(rnxGmh*f_Wv(PNPh?{-jm*`1m*yPj`mo*o9M#{g{J0d zgYOyV)NysNwO+A!* zP{^tuWy|A*(R5MG-s~Lx0J=`b-JhGY=y^TI*B^X|^_+*#m+yxR_+!Ck_nY!RKxUuW zdx@xEjvjAU_ol&AZ~JMQb^5Z)l#{9LLW7J?Z7DMy{)Kur_Z{O|e}=#*_;sj&g+|o+ z^?zf-cN#-ob2_{AG4AJE^FhKhHwzfXfZq>hao=y4pKXZjxhD+8h1Qer8Q-U>Rf|4+ zTFPBw)QK zsfMC~r`JALUGC*p>FN<4%Wh@9Y~)UE0|^iR&8C_wfvxl!>`T}g+GV&-ENMj7cZ0-75RQ8yZ{eG=Zh5yl2P3?1F(A)BYBo6bZry6Ga z^?e-wu#97AS9WH(jRV!w#3O6w>WRyu#}V8t1{Xe6jUSp$mI^CiRHasFVhjG~V3OkO zRq_faAf8gYtM;ExwH(WU2sl~e%{7)UTo>$XjGHX*NoM2j80vPO*6oJQU4 zI1Pq^M%5bo=!YNN-0!ZILEqG-&Gr!JUc}w6w|Z)`9=5HtQ=yb5Axhrs^Ow=C?t?hdI@fqRmo)a{lg%_GDwhohH5O1yuaW$ez~ z-3n}38EhZ_y>A{V`_n~!cDvKPo(ej+n_L&)SMk$;&OQ&Xv)`PJMvnmeii1RV$vf!L zYx=Pprjc>hd@x9I*@Bfh6jEb5tERccf#@`aBj(Jmel5{z>Go2C;P7v5d>CIEuUWwxjLe()=Om+y3qO?%crlCXhJy|*A1G26y* zAuL7MOfhEiS@so04H_P@&g1h3>xXnvCQqV_nWH{_^eU|(sztAgp_^z|^#<#rHS~fk zi(fq?U{Gj1H0icZ3x9l&EYU6#+3(iZ=yB}Xtb$>~3>E#v09VYr4h)x(q7H1?A#`ml zQJ4xeZGk<(@NN;ASTRZ}OUW5tBgWszP=CX}+C`?k9EYuU7PL ztr#P8sQEOk`7}xRFy>4%sa}-R>{;+NFJmQgq9_mHiM$L=SVSxf$DAz)t9;#<%54>; z*=M%mnk7_;yjGtrM+@kDE`RD3MyhR9N|sr_y-qB}MK?L&W7o@9FA6i|AX?e`oP2jO zPAY0iXdbXU)#Zc0w-i6{pJp=HnI^$rgYoYZF~36zZ@C%_o|JN9ht6^)@P=S~VhdQV zjZhPyIuZEH{=#%p;1SUf8S2Zpmd6Ch_;>*lc;~0ncEjrz>&q00#L*s(>oQ^A7k_=Z z21&zOst-0Qm736%9(*#lS7ib_2N{ykuu5IV7WE=+QeM-CBiWDAKE4ax3^-rGghSVt zV(^E@7e4J`tjLhjC96o3gjvgoC}_(ViNMoFvu{flwi*?zsG4}EcOKEBy*Sme6AVn`a-iLF&;kwZ!*U8|^m-@kkVSc#$K#RdVkE%> z+3M)C`sx*?Cpa06nu z11#}h1?e-{=KtmHONA=K(;cKGP^{(rPrtAy@}svXX%5U=y+jqRw|@*5BoTJq;j(fr zGoH1i6msq8jwuf*GCcLS=)?S+})k8)-gQ2LN#z z-uZgXzF4stY@SMu6`+@kLm^>cH)s~wYq;}`wze$RYxs<_J8g1P?=m$Jm`LfT1?t5e;LGigIxv%ke8|jT$-k>|_w{b01_o0%*)B788C%8) zS@kJgw*DS&*ak|X<7RqPn5LK1k2aql$%~C8XQU?{lEa$MTjEie&-WG$=&rtzRGg+;CHQqOrvVxp<2s+s#h{ow$H5~ zi&{S6k-07j<%e>F+Rv6u@uUuCzmYLbAmGFSXNNWTqj#T7ib5nR(PP>}w%&YU#A~-w zxL3T=M*()kY!dTgKFNn@OUa`|V>5zITzA_g_f_lDpED>Q{L)(m|FpvjTC&oq0b@U- z#iI%|N)iWHG>Rkg;5pOK578!Z342f$n~kW}8UbSz1gCu~vA=uywZPFbCQ6s_Z{irj zpBN$jN*D<5Q!O^V`oEL>tUtsl_;FCNi4lL?UAK5E7p|2Wo&mEG8?L-r<_zT^bgE<|7SqVA&uY4Zv%0K z_6-NVa5JhG>V~T3y}O`<$Fb`ibfv$TXtqh3@5Wh2-X0>ki{y_Hm7P(<*^i;e02yKVCEtig>OM=vDU)V!E)%fo{ z@&aXmJPBu}PlM~i>vXH-%%6Jo&X@_&^=?|{rrY-T@Mvn`&tPD#N$<)Z=rsd22{U94 z=SfIV5^(uz3F;-_D^dw2K39-N=q2EzY_mD+{*;aB4%rrrnL2(}`3r0r#wVr#-U5v* zryRw>9W)%WPu*$mZTpirPee#nauh-6UA!E@YOQdQ%6ai-u_(gJ%C zISKKPy8>3>5lqQCv_hyZ|7##H5^318sHf4uhx$bJO&MFOV0mt6x%H~O)2+jZ-u?+=$q z^WYp64&NB==SN38di`$NELG46ZJyI0s>*8Icy_8vz`m8r_MrnM^~LeJ?B>X?w`af6 z4<%BBdXgt^QZ(6+mZbysTkfdfId8&;DaW-g5f!i{gyh}4RmoyON%QlogN6a^_y+qM zpP5TfpqtGM*2}kkZJ1`Lm!`?pZx{%NELLgnB&QXAK!^fL>9~x~?G=)_p6(o}w?Q#0 zEl06Rns0?_7nITyI}j3I#%sY5?_r397oFpI1!5_>{_MI5Y4z#Bxh$NIY}LJf$ijpr zgCa#^jp6LI#ayUe)w?1;jWgwTUZB_Lj<46?9BLHVQ?|`-?mw>YM=9vUaC7NKIP5{P zd1cal$vWU40Wb7$vd5pSm2yFo7EX!R_r?eA+@Y&y*9?}jJ(ll$QU1Zb+RJUdn$_B#@B%J-g3x+`3J+TB?2VmJ`_64bJv^l!cz>#$G5w&7&?hmE_VzVvh|oX9o-R2Qsm2VP%|g%sps zw~0CROqAwCL4r+qPITGyVter0zD`D;E)9bW-HW5Aq3?`6Unv%ty{2rXFYJ7MobKO@ z#^``LE;=n3Qk@@CC?hqVnfZc;8A}@YXI6+V@=bi2Ul$OOC~?>QD2J2zf~ZP|A$%s) zT)f%|HoF3FNGvQGd5=}0BgWnJ>~V}8B1Y=}19$}III?f4#nFWxMt7Bbww6&Xi6~tA zqH_9`$^k9|-uRS8xytcFaumz;VUEEi`hH7vnMs$xQvh)uEi)=e{1Dzdz!Xr=!lit^ zlHGi~3X29tJzXLIlCFkD?P_T@nA$l=Dcp|=(PtCb=qk?k3C598jV?Lan48_PtBOhy z%9!ut?4DTdiX>-J$tOJT=kx3*bs~Ae#0OBgK!L*wf^l%!j4m;aE83>?Y?N=#@il%* z^k0mA2!WCFIg{GG6@BFi@lryPcIJOO5_r-m8@icVF%k!seoNo#lDOA_b%&FPl122w zGpBS9Z=&L9pvd?)|H69kix?;Y@95=)f=}WF$fh|y1yMV#4N5Q4N_&6wrxogS9`AxA z0C1lvH<~Z@gj+df=2LkPxtAi%&I>u*vvx7G3H|KPY>w}ag zXK$5?ByJ4nlxkP3kGcO>vjKn#H(MzwvrZ!vEdjKss1gUhzVEL z8+{K{N?}(7W;ggV-DkR5F&Y8rMWcxj{9K)yVx=zZYQ-OZ4SY8Cr#o6^<|^5Wku_xV zqkHtyVT2R49^4~8UoX!X7<-lulrKS1P8Y7?r!HZ3YqxmXi)Ck8UC-gOfu3RFVO#hzNtkiyNplQkrCwLjc@7KvdgWiL)Rpv zqDQDFwPYl;yCZcK$Ga0t4IKz1Mblbb9~_MreoosjkW<7fwyt@KKT}d+Z4izy=N5$e z-@DR@WPi2TK{Gz}Uj;&zN@de4fDk3kE$C4_4fYX;;rxHy^K?d85T|J%bK7gHv^;<`JXbyrY= zhVO9~baXpWw$N^QsHa-%eet}OiCy&XWKYCSAp>;Q@0d7_E~SmA=A)qWal4VS#onKv z@R3#N88oqfm-z_;c|6~lm0m3e-P+NEHd)NalUpnemL^VJs>yS|TnzV@hJ?3mG&_(M zrM%8(cslm5=*k5v!7pfanW-0E>OUU~{UgdD{^Fg8-*(NR7H`#tE#SY}OUU^@s?#=` z!(8`qIGlTByy90`)oGm8`kP66iG9SB8~AXj1PqPY_3C-nd~aNm9cnCxApr96?z?Tx zJmEaqUY}7nu4m5{76=si+$RwB>Y8MGvT7=MI=7CIMxKQ7$-UCyWuh2s{L-<=2YXDw z@!uXx&|+A3ShoC2nTDC~y_0HpE-kSzg(@Q~W6NOzk>#hr} z$ba+nrbB7OZXcjOY>hYYHmWYtZxUiqOl5*YO*1-liZDeqctu@It&&db#tQ7g z+d;QgCM8xnC5V^-hx3oFy^N92Rohh0&sW6l`6;h}i{bi+1(>@}D5}3wKXC)wn-+um?Rjz_H(*qa?x`47iS-C7_F*X`gv zt~E@}@^d>&G$G$!oZwpnAS`6jtj&H{QC!jBV=zm2zaqXU$;h)>>RkZhfqWP~fE=p* z(pfAJn%yU0hR*Ky@TLQyj>hl~q&r9PDnpX>=J{A(B^=Q9D%dAP8)S!LT&x>?2wYy5jLNPnQWm0*3{o6*S+x|%R zL93iyHw;Q0HICoC&EH~nviue)ROnfy6BmAN5QU7CUG&GJ8SL!Pw`}+Cv%m_e$(O6? zQgf*itV1INt^|r4x+R8Yy}U=CJ?(x(=-G;KF0Wuv=SZKrH#PcWeXU66 z3!ja4+KQ-i51vA3IRhpdG^OkzHQ&SW5`z}z`D;|Hg;5QI&Ic}A=bwVCayZYngFT$q z6XTbbk3ckY?tST8p$DQtE{k45GyZ&qXx=w}xaQXha*$spNno#Vt8=`G5w0XqbG=_B z4FrmbNPQHczxgCK)W#o2O>|mahd$B210hAHiVi-0At#aP8KbCx)c!SrO5&Vssv6~* zKAZDqPZ+T?-2TVnDvI*e7uq1D+B$VZbZrG{ZciSu>xDp_wLj8gbrU(9NjXGU`3h&5 z&-IM!IdLb4b{jB8vY?L3uL&hw-eb>7#s0XrTp|8m|KJPs4sXskax_QzSG(a-NPf7F z--zSaI&VI%Jzz>Ara2*Senba$Rs-^Q^d?L=7yVlT)n9nl!pHCa9nSM_`g@6351eak zp=eAX=yhD}4Qjc)#J)P)cWaJkctggfRZr+~v~s8=@fa>DyInRA-r)?(_vG zc3~bNVoK!tZ^+0+KV(G4TbnE`OkhPWOdu_FWBU@aXmGS6$YU7(&_Cn;*&?W z`s{hkmsJg4OG+4fj@YYmE=o%n*W0aKfo6#p!LGZ>DR;G|j~v(fJ>Z7nB}DFDY{IW(yue~EbO9}u99tbhE3tnp1Nb7r_rxUke(oN%MM<1JX{{ZN@)5H}6>+*7 zxJs+v$TikDW=0O(6zeP){KugfQYsqJM;Q@CEu&L(3wD%M2S+--%Y|aTQW(d73YjB_ zN!SzRRyx&e^5m^|-ddS)2E@UjON8#(ozW>02{kg5MtXSfL05O#XOoJHqtN+`aXVq-}>&@_*%-yS`Om0F{pVjY5D1& zLX4zoUiz2v{#Og2{n6BXj{f=SB z>#$|8f3ooGH#U86cq_HvwF9_q`av)b<;zqN50Tk7)1eZ|__bl=ibk`KCu)|hl{<3{ zkwQ0xu%ueOfZ#Nltqo8qxov-rWmTVXj4z(8UknoSv8~fH<^%F8D0&~UmCwdW$ILM& zsz|KU#k1*H^G9P%$e?`YMAiO|Zrk8NwD$}~OW1*EH}j8He^A1U^o~KvQR?aR;;o8A zJS-r156N?^(k#&?2ML~eeVbkVVCuZMtu596nxv{AAr)BIA<5b4I6_*)!D9PxrZn~p z$eqvOq`jYJl%@*BGzFYXu0{z}Zyb9#n7^Fidvm!)+X=KhltR!k9gyBYBhAlNXG(PI z9vgTcqH2Em#Q@28xjV<43xMz1tm4S1+f&a zS?=zT{6KWHiuDq)yFD$j@?($4AaqlI5o<0|o+dDlr$)-@mLenUcp-&Ln%ENsCk6Sa z35(4W&0M+b>>}u6!fj_s>$h+I;rkE^m*9wf+(a6(#Xo;qNysUX-`L@bXfcO;#4b_( z_(H)<`njE%UZpuc8IL($DJDi`!Yyc_&QwYhlM(UTDeF$Aumv4$JXT{52~$Sz10baZ zrDXohOU2|!&o$V(Jw^O(nr@644OFy;@zo+KJ$Q@TA92#yB*t?yb?2b()M0N%Q00{a ztm!QCLxH+jm8-*mV(exrtP1!mEmZHmzprq@*63rPTR+5wr4aqEo*bML0xQoOaM6N{ z>qiT{QAhuMLf$&MEwM$|itXforv9lW!S{kJhD9)jZL+8*XzVIl3B}afc?I!7cA*R_ zBQ`Cv9Dod;+v^MW^TptAstPS2JbCv^F6h1fwGArp>LTu3`e4E=DTQL1m`#3_f#>G0 zbP_m#BlnCiEg-V_F0qw!Y4Jo*qG+Fgu2l^1q2^dX;#edsMo~)Vi;^;~k7QKJK#%Zm z=|HFzsAo*8C7?l#|4XC-0igaqK$I-rsmKKyfr+ z-4c@b4k=O`(mYG$lt%3(oL|J+@(7WS8sW*acC};I^VolSRzu`cRB8FB^7+kzh5sox zcFlupK_AP7sK(agssP!&Fsk^}O~N|71tnT#B2wYp1BHDg=LD=|x4c%lFBG*xQ)Ses zYhU^(`DnbN1V5dXUr@v`L~BIsT~(y{=QJb5oglfJwd(Zwi$_5OxgnAJD4+RJpU*F$ z6b`&MyhK|-Ot}h zvp}m%!rBpnP&~m}>A^^@$7sCf<+3YS7FgDlOhoddbXpN?As<>%?1qw0gQCmjwuaUr z`qu9*t$yqNZIk{v`%V;r`XOOrcgJ>u$O%<{p#2&t{&8+s-me}lr22DqA`E;lQ0JAoK~4VHz;7&6@cA5L3|UEH86rh^Ph%J7%F zBHQoDKCAKK49zm*?4w457T@$L9P$>n=ZfQ9oYe5F=3LE^Z?je3^tH#P1+yQdLw zITO`3xS3P&?aJLwDTJCz(ehn^m{C#_K^%kHn#NO=m#Kd=|w-C<81Bgr%g+*87?vK4h z^nL9GD59I%kH%~;dClD@$ak&(#|a}la9ax^#YW;BWJWhg9L6mkQ5VNg-RUd9K z2>T?v)g+#K3~x7EPgJB`X^+ zWD_M#Q0KnH=@kIr_Rd|)=hj(Nf3g}uDP_A3XS<~%DTN#X-)=kr!dokN{omD5(y|B5 z8{DCqI!6#gnX^@_2V(JiVli{oAOeoWqzzcL&ZrZ&EXvR01F^3P5Y>{-*{yFJZedxi z32IT}aVIEy(e)CB9wu(NSjzrpEd#xRzPIx=t=Ts?P~JCk=@wcGU60ZayQ8p4b_)bJ zc$A%UN}F9dxeD`^KcbU+sKnUn4}wlBRg#_*%ygfJ%eFeG2_t;Bbd|@>hHacUhd0IE zIN_-SR{>&90oPjoazXwxKPZz0(wfYKIlf+BWlOG@9h=T!HRG%dEE)DL|J1}ux1*$y zv`in=T)3K*Xn&4FjF4G(P;22iSS=ZL6RjnH7m4)n$!iCr3$8nDxV0YXwVsbj3f$YfWa4ayNBz=+DrWz$pDV{n+{22)7SFhcW^=Ju_8S8g$-w7wc&<{cpgua{Rao zGZ+q54YluihL-cUkNdN3^B~J*nQ)_-AvJH0RklN?QLGCp0y%AanVcrc`oskOtTC5}LivZ0QnI zTKC6_lImVb{7z^)oUAY_1GNL(V$LUCfBy5_795g)E6L{Dp96Zy9 zyi*PK!*9bMIO$ZFM&i#V@!Q#+a;juMl#65AJk@+EssG9xAYlCU2Dkkvl^n$<_(_>U zX@8=1nYJpXe7d73*IbRCn;bjO)v_=D;Im1rqxl_92%_TWt~?0uoDG=BUhOi@@*Tid zj$rIgm#+PSSpT2$qEPm19S<(Eu+4~Xg`0U|t~;9CdxY^=x&GIS=F0dOFCpU&?abvW znrzFlh|(&*STMIy>Ri zdbt_n1@$)%Q29WH!OJTv4O#YQU(athlZXzSnO>5_Z4>C~_ zo>A${g6PWq)xu*TU9WDYGrBQWU3hDX zT2Wwj`Pr|L0NxbZM*#Ji6-(a|Ze>03&v=u$SbB8zMakb%nqo7csD6bKCD9V@JZgV<^DLgI8D#$ssnD0IcKm7F?<5aau^tC# zrk|*xVb;c>?iSmjh+_vObVxCZ!YBR_JTWs^3_fSG_mi(vqiLLng||-1{!U zwdlx{NC4Gt4c2SPrv&y?PUWF~`TNkk%4#xcSFG-cZ7}=fw}Icyhx}4z)#J<;z29-< z#jv*2)oQE;_pJ464NkU3O+sJ}luU$q%sk(wPj{zNh|UU?b7B-^^NDKr+>Q99*ekxi@Z*bev;vTgGYnkX(#n zAd%lK{QXdCz&WT2AMg@U0#yn>Onl=9r$P!K5i{0^fpuPWu zFIn8`yB8CFtt;i)74j|=jSYp^*-4e9LK^Yl`7h+tCVXxab>@9x%&yW5qbMG0hDr)xON!h+?k;v6hDHRD&dJ;HIkCP^~m3ux6%i7EB)v-kH{?qa9jf zBY>lMEo{HV9*p`%cOcBp0ylkccUY%M0N342kgF;st9RORtP_epOCbl%s;NW_c?}k*fbO1m4g8_laaFE)w z=Erao$)9O_)Pn>i->{n~&D z$6vDGZO49S{hB^oh1ASI-GoSF_brnz{AH(Q;X6))=El0*-{ItY+TO=wzvM~4%(XdH zxH!0KVsO^)a+6UdV6XvG?Dl+_boPk$lM9r#xYt=8L`0V%nl&U9iGGJmo!Lub@^NfN zCpG!+rD=vxXdPxjFPowGI&Ee5^$i)v0!yvWOtckMOZ;~ac?Bi8#4T3cd#lL^Lp#|r z+MjERI<7=}#04^xX-37mWtoEL@2$q0MK5KEh|jHCY4+WphZ}yzagnLBZT~D_bCSA0 zORmcmTcm$;NxJMv18Ov(mCLMQX_AO!1#?9C`ZQa=1 zG~LJ_&Yt4>tQ;Jgnb7-Y348O$c}B&9tmR-3oynD}*GHJ1G{3awRM`+`avVn?mzzzK z=LtmGg3rxZh+Q-lTo&UV4ExUfEl=4rD`BwLOg*#Pwvdz>#JK9kx)#+&*2R(G&&oWf z;Jwb5EdUx!dQTRp=6yZ1_dEEF?f`1i1PWl2;_QZ+n>XO*SJFOm5MPPkk#ag=T@nUQ zew9RBL1r??L`jqlr z0y^vOqBQtZ!4a9Jy-iq@*o21Tdl|VL|I|l$-UsW&9QX91^upz%;1o2U!Oi6XEHe(x zKd4+5dM~kY7^e zbg6i|(&Rj9l(95r9KKm&Y&@B+89NuJ`G!1hnqsbNa7|Hx^FYXcqf*i^vS7F&MSofS z!)1;Vl3u3LQNQh6*k;*sMF(O6yQ7O3-jq^PD^QcVb5I`5zQrBSPa=H1DvA%Eb-*{Q!_#?K;qun=}E3Hg|ug zw<>))U-?)#TdvE?RE@II6^wqQt`M=PhTxMF$uXf-d`!Z2E2oc5xZTW2`}neE6ePk< zmwxSmAYg6aG2Ei_<*oYid7&J5gJYk|zi@(i0;s4f)moOGu_ui<2T%3?$a2!hOsnPU z;U%4js+Q}Ir@K>v%q_x}-?gy2NZ6}K<*7pB=+u)tdI$v6T;S=VMF(c(49y~_%pyM=d?Q@CWgNOQ$0d9=l zEL1QJa`Yb1f!_S`Xr1mumM=VE;OJV+OV}ghCV9JR{C!znICWYLnL*a0(}N{@J}gx2 zhawD-&jIM2u+3lS4-hEgd^3yTR0h~+(AjB^@bHSx-SK#TEL0QISvL-@qpP9E@XZHG z;_lV^si;(Jzio>5A{Z8unL4IxG?==k&SJUd!|lXPe*h>ubCRV>7D$4B$W zV7}{KAF=sAi;-7YUrOJduHhFkcUqomzE~sYu^5pu_VmA<<1PGW!vRp02kBX%{TM6F zmS(NxpvX>APz{a4{O;Uz_II_-lp!d#RD51v6AHzz{^H^a{mu3aXn`UM$eYtA_(ikSp)tcDy!_{c_e4(etzB64a;> z0EzOU5_CklI9la~2>SFE1&Pn9nX5>c{UR!u*en|Szf;M<^+^$OnbF6{NV^)!kfhH> zUn$WG1Y-J6V(kp&nmL=h-mc{W%}1A`s|D)LrCk+vqBnKLGqd-*0eia2V!5z0VqxWxK?z<|>2%YAW zt^isiKAhdpZd`Y=yUQ;?&QAD9k9ZYI4Sd9E(r*36rUrRHH-pUC7q+ct`YE{m+u?cK z2Mzje6L1vC5A`+2#3W`MalO~tYDj=DxNZ2kpnK-i-ByzEEctlbxEGu zH%$(CV1fkrMYZSedkl$d-k*exy0;CYKGU*U*@C~Zv(YXEqz(E&BCnIJ0mzM;WV}rJ z3R(z+406x~MO*9qnMokL)J6^yjhfZ;h)LV2%Dl^?YND?oQpT zOfk|03{&J=mpgC)@sohma34pJHLXT>2f8JvX>gsGkW=Z7oVnLaR*HK+eZvG?t}&Yh z(_r^FTgl<4sYZ8UJBQFs#O#V5CXg9^-;2!=LE-?0G%$P-exA~|MxX9?N~U|C!T~=b z3=4M9l+n#MS#4frVhlWpEv`K<0;#qB$3`lV#-XAb6=8D zZ~lW*IwaOEX0)?>R37&K$JkpyRkd|t!-@d{N{1jV(y4&N0VJhCx<8r>6c#AupQ=SwJo}c|iT1PaU<~Bc{zE7M<^) zjEr0ibDS(Z4sn~o0(!I8NrzyMca2NwhSjTU1n#RU@!^3PyjsmubJBd4P7RGehgmF4 zn@KaBflMvu+Y!dwi`U-I9OP&dOty!FDsdmTEjf~i>($ueAuW7^5h6{5;bLx3#aorFK{+1nLin_~5Ky7kw2~d7uaLxl1UiU9PY+(a5)0CQY)ly96aHasT|D zEc5Nh(|LFg1gNEa`($m{Uj`{O@c#j)(h@tbvdELkq&O^p&*_-=R(e$Ty2;?@m;QNg z#q9@4cy~YhxNU;0x!t`PY00XaP9e{Fu$7J@qG~^=z_EQM9`5PSt}e&+x>aAJUGTTZ zwOQVIvm2rNQj0!u9A+&up^*7e zh;zt;gXtb7khx5GXLo-kMNrmKwYkj^+2KEH$>W%J-aT#7~ey`L^DLK1P<@?=mmu5e2>< zAfft$L>>Re&!$Xw&+jyzHC5d2c3o6G43ZEe?5``L+@N#j%$B{Dl?1crCPH8pHbQRf z8$@^^dRV3TX+B%YFvCj7Nyi2y*^$#1|ExtrXOJYs)#%RSY>YRPPx|*zL~n5jzhpm8 zIT|LFe+1CF3~Bmi%|Bm$4R6y0#+z)L@p^>-WF>zeZHVbK33%WPu5yrj&FD3s5nRjI z5h9V=@?V-AvEnH{L4VJe=OsLaG`Y>DGi&8xkMgEjo-s!45!$Bd-N`QTZ?1@5G3#q} z?d`EAt9)}$8I4HVyrmpj3{>QGelkuD-ugB^y&IWT$JU#Ou2<83wK5_9p zQ>VuEbWeSI%MuoKwiWQydb@D~3M8T#*#g~_@>RYK*UD07z2?ztLweO6*`-iu*q1m) z&nmtW;pc}W?>ScYX{MK~q3=Yc*-W*pUu3RgNJ|j(rp43GU_w7#KNzmtHydaNx329a{abJ-$)vYKP%gulSmKu&H*r1{tjjh7h@ z!C}M|w2GyH{G3QzR<$`Bz_1BIkb4<-T49*M>o$I)_3q73xPauo!T3`|0AyidVe`|s zm=cR&jjy`G=hts&p^}m`bfVlhjYsPZv-RcIaD1cAz)zq+LIUSU18pQlMN-JoxNj(( z#2yP9u%cw|&XLd5`8?U&8?E}B#cf(>vsYOAiG9?_17G_QIoXBBeUL-btPbwmj-r%( zY0(Ut0XGoujbb-Y1r{~**K*)8YAlXci9s_RjzDYAE-03>W{Ah`XjX=8)cg7pJAIa} z<_S^MtLe-xPq}n?ZhC+OcM~GtHNqoK+5^E9MUp$mr9)v|eXbzQCO}4~K0isD3Eg;) z5}xbtQH0d5mIa8t4q&EZ0xqP1K;q=eP$NA|yoPsku7=jM-f6$%@mMWYgFKq^;@+q= zsBM;5o2YdLyX2l%d&wUDTa5H~4bFK%prU|Gi7_vEqCPJEpm1m55q8VDb!G!U;n3lCgT|Vb^4Qv`K zYZmN<9C+KqIxeG@>AE;-I|$0K4HY>r$(*506iEo$7Pp8$p}dy8{nYtRO!*I8uN^Jx zWP7utIc(*&-O;l>?ao?4Ed*Lz)Pzyf4_%Lu9*4Dbo=d74Op7B21wNB-%z4`718Kxod^w$G?e%&ufbRNGkp{g1-KNPcUKdUOeBg%Tmec zlZQjlPoN>;jr-S+fRhxdD$AQgAZ#1Zr6H6kd<}7IIPKw}%IPAN_UUm)Z!vJ$v*oMI zk5lH!Z>o0$-7f(Yk46%@Q=Kjr&@>WQ z-hpw>ctQ6(K+>o|KvhR}slYf`c=#T*DdEr~k&Wo|cgpv5;_Ig48=qgx^Ci3Z4G#^! z2?6b6Zw5>;x6?sap!w+2)sc#xgLyDsvwln4aSkV4I$`9ID)o6g5S)E%fuNCHstMS_ zNE;yp`nVDM_G!;0O4u7Za+fdx#~VfXm}sV`@ibs%s4!MH5SPveRQ3Px&6O^UqK{vg6+PwOrEKpQp_9Ds*AGY1at4IZtTu6pA|6E*hKOX2VVLEkN_q zRa$*M*_(3jh@jH!#FKk_geCC3pDO4VkW34|U>2SKOu}#gUc{y@8>5<7-x_~~`|q_@ zFcI0rRHd@Ll>Cl@WC}YYbg?lZetrQOd1%{=s`^Dw@0Q6ysld`g6 z?vc2lgRHNe-B!nB^XtJ}MS)t$(v#N`rH(rWWzQc8+o?tMTRlYo+RF}F_R59)F*_bD ztZ&af3$>LQNfGqzpYNiwY-*QxTSX+9Y(^y6eP#d4oPuSnQa%fGKVBg0=R4mC?%L$v zE-xZ@-2ZFhrrp_sgW1puf0xF$4Uj@ZRYO93eG}UsY5V3HNg`l^ubsiRqsc z3@;vKiiFNirqpX_4V%OI>k49s^IJ4FL{H?oo*B?4G{2D2>XUMq7V7hapfC`c^Rg44 zcjZg$CtoK}VqAWle+)-@IM~bHd{l6YOWN9R`UatJ;4ZqhCn6DaFBsYq3Y<6MXoF4db@$;ysNcv^lX?gb+i-!|r=zY5GujkgF(Ho_T( zq^qJc9kIgm1)#H*P4XivCH=h{{!6+nU&XIvjv$o$`I=5rD_;bZASS(!OD&p6zW$NjEP%^) zW#ma&n=jF_9&EhcnZ@w8>6b(Zw+I_o7a+dhOOlH50IYmU;`F;tfNtd__QLP-Sm>xD zDB0GSAkakIP%f&K5mQ`pOE8A_3l=nAN(u<8>Gw@s1`WRj=lzh!XfU&dt^`7wRAhG3 zq+;JY!#^KG8n9&&pXwfOgKqN$yE4S(@6ENq#+4gEot}4}#)(N*ojstvaX}KpKr%-t z99*gjP*7Z|B9Bbp0GZnt@yn9`C}YdpCQ#1b8vh)201jO%xi+QaV^82^*f_(C$~XGS zRyRSoSWBbaa=C*^LxlBQ=$LnMu1%8EmmK-5VxX_^uAUBjkaq>`WI`b94P!G=N@~vv zxm3h+9at6B0riI%(DL*nUn>}kDm9;IE!v0t_gntC?x^5|z8M)F45h)vLO(#kvut`T zf4Kqh_%S!rxil4*?z~(1X^uS*K`G&L{l@L5!g~j8HUW!Xx9_%q3`A2BoU!xIKT<}7 zUzKL9Aw=Apo$F%NGaobhZQE|!7Ige_ zm!ORgy&4dJa|a+PG1+F+enW+tzjmMLCZxhZ-DyL^;|XY}sCL@R#ptC;RY!mY;Lw@p zzLrrS9RXCgf3E}HQVZC8QdH8q7X(5-k2Rz=<%Ggqn?^}0VK}FTvvYdm!)tgw^Lw@& zg$Rxlh)xxw)}v#;k^WiD#V>ZGfU|e6EFJ&qfMX-IDV|^IYoUp44V70e?HHE$$c2CP zXBDIxa7Jr%tWx6T<uuKGT7QziY1TS1+L)K(6=3+VOR|atpcnYMI6>H2g6+HjJ`15SW zfj^-5@p=AW{P9{ClTg8m+eAC+jz6-)IwW^wNM zA1&3NKbsruYy>KQ%bU~>us_kJyX0P9Z8rR-N`jW#)8a#Y#|*?bZ)bAB5}mG52@765 zk1KDG4e+_1K_JM|msb>sY#PVn5A#Ep>LoU6KbN!fm!woc1pk*M!Pw-3)4&W1G5*nY zQfee1NpKfg$-s-w$AA6;=>?$tdD-Y;fA~kf2Os%Ymu-O9KUTxeTa*9!dhuh=n}JJU z$TT86OoUTOK&hzO-*X&~gop%o)W6`xOR{(N?2P1P66xYG=|L}A{<4iy2B`RCaWz5@ z3wk&9PDCa)c2AThHeO=%A4+T{G*(N8&5Q0(oX|MzQE>;(Tec_au(*PbCTiuv2kSK} zjDTl9mwCF^aIkpLKjF(uvU`|)h6X#sKf3vB0kPTMO-C`Sj21#pF0f$F)i`)q-!QRw zl+ZA-eB?@xz~z3YVFz!BX5jd>TRPvZqEkSN_HJqq#4E90kWQC~zLy~$RpTH0|F?XV z1w<<8c+l5rYjcVo$e-Msbo<@|Bwhrz2JdGxE5~vRp z1+JHWPnrS<+frvOlYha24+`C0<(gPOe%X8_Z) zGgUaSKlz!LM`y(M>u;n>4Za3|UcpDUL(4LM%eqMvJo+P~{F*=h3;@0XK$Hpcyn(3K z{PtGNW5bZ<$H0X@-tJ+F;c+a*Qf5}na;6pNWE%o}J4&nB&z?25E4O#wY(7B)NE4Sy zmE?j67(7j2u-bCtGq&)5fCLWI{HXw_Ww3eIt{yEpI^Oj>+A+*;H2Gx^!1j@5as9pe z^YwTgXElSjUBGg)Lc)3u5)q!)FN;PZV0u~s3HXLnvcpH;wp|bDh}-{>Jdzb0z+B#9 zCtlunIO zpoyOhB*V0(z?J|99CXKYf=Dim%XazcPI2JZK&np;Y^ozyx_otrUc-@nBu7r?N~1pB zoCXY%AejU%{p0i-W2654qLT&{f{j;Cd9)B+YURn2Bt7+)rIJ>Kwkc z@mtnv)jP3R!2rcRSP{*&5s>xJ#=V;kT@UA?gNNz{;io)b$nlvp@VsX%fZyl_So zBpfAA>n8bEk^s{y6*!VUP(WxjPqdheJq7oh%E?M>0ZD{nvtR5%#1H~RkY+16-f%w? z1RyRI1o)7|rziW`k41|bV6>p^8jAu?WYMes8Y86v2p-QNb}*3 zWMxTt`|^=Yx+4H5@HDjh#IHnn@h%}d{uB>6IRcO(TMGvsRfbBBw<66ocrvR_#IhRH zjXOFr&3;viJY-ZYeF)rlZ`j@nVM>(iY{) zb0($s$D6HBT@H$u;t)=OnQ#Z)YcpE{f@vbb??LOA&Bi!U9lqcNqb+(A zG{PIaI|7}$lSA6>Y?42D5|qsewHfPl1g@WjaIf=&7k|9Jpt0QsB-5gIZM|+h&{KF|JxU{=d9x?UXZqis2fAnRLx6$wS(;*(t_=Sq(y*$eVfz+5 zD_}az{5@Y4dS~m3D77f&85FdrP#VAw}2uh`f9Iz%c?0^;9r|sN=)C!I{F~R3k7bOR}BI`!)MW zrR=DIcSYVwVC@|PeJ(<8BPAOsYkR5MmXai&<@CEP=c*C#ex_Hsc{JHj#&*q@gB;fQ zTsG9VQSm(h5fk4TvyxG>M(6loE13Z`Z@8c%5VKCU$=gs>bA7}?*Aow)2M0EM0 zCBQ9R5Rc4Lg3K=i_c_bNkWxNVG7}*-SdWV?PSu~dc5S?#5FUSZN6~#{5BgdGUM(}A zO0*UXm@D#{c_TlmAm5GrTa0a#rpj1E0*0{bKD}85@v&YIpZ&T9{4E;uY!V(?jcyQ- zQJftO!NZ}pfeI$*)tjVka0%;U*R(>_XUg~1O%5249prrjRpKVH|x=|MsTzKrKo zq1;szWeVSZ6>ZQ)?FO&>Pf3{_@S?#uZ>B$NiHQ6byMlf@2>xqNJ%(K|mISRijV}Wg zTlPxT(A(ZoUv@1QrX$O*!Pyc)_KpJWHuf{^xKJ8i`Q!OpH(<%u(nglyUWy3Omm%q96oj|4ZD1~K}EGmT5+$qg?7Nw2U)3& zt=Pwg9r#HoNu_#YSS(|hnPZBXP}T*&I^O#PuYPn;W?EbJ18{vg`#B7}Fb+?T`EWkY z;tN7vqCzHUW!{tF2U7w5Ifgoha9@?j`A^2~ZOpZkgaToF&DLEZ$xst*_pBA;&=z5q zPt{a;?`W`V+131u5nxJyq@ly4UP%vz6q({q1dY9(X-2llYX@w&@(hQb086E8^g%r92vD){@$fB!fZIyfo!Uz=L{5sBk^>3od>#fatc;|r~#+}TA*OEB(I$% zO;m*^zPKRGQVYe?!Cgq_zYOR-5<*E&j4+Y$7)^1@QGIaL-(|k3*J(zeP?JXj9uYV1 z;Vjn7k(4DToL0f>Qmtwl9vD$79v?MdexjquZ6-%eTDJU=on=-)BwuAgFQ)FGDZqBU z6E`}hLAUib#rFusv(uAcBq=g(0MH_UlbHa!!{2hJg?`}crnf4TRV&p_`h`J|EZ zmAE_)?#Rlfdn3kC=31ACArF|syHP-Q%QK8I<8t&nKDjm>z`h&Wvb28(bKE|*^U*2g zzh2c`l$TE01h`EK2Ux3wqkDwxsG!m2gKA8~TUKv7c2Mej?W?C+_T+Vc6B6_mGWMHN zKS1iay{m0V0>%TeyoKa79Ug%}Il+7!?OL#q$A#&Ik_!iM>}IU=2VaC$Xnf?K_eC?2 z0H%WhzT9WSTW%V9Tt{S3;Kjaen6A4fS7T$;&+eP*w9uOXcU~i8G(ew=5#aYTV3u9W zfy*aALNYWc=m{Q&gQfT2As8+A1f^|T0GWwk6QZ?P9KvuawL1C>`8memUYQ za=oxIZ@oakIT?c}Om>L`WMWOZ()Ln}in$8aR&xQrT)c89mH&dVeQM!vuVS+Yer_@a&!#^@t$9Pj9-8fj;tPtgvr?S_8)b@yng!fFnGlim$%$Q?mwoWma35GX697!dt~A zLyR+deYXsf9H#HoZFkdksB4{9#4imoaH*Rb0Mz`lU&sD*6<+x?6~L2T=5aX+$$y~| z+@Gn0`!j3b=`1gWvB~6l0RQ&-#HaqN3>f&{)xXP@=(Ve-K>q$3f~6u@CFDADMd06o zBs`X%0RH{uw6^n0Oi46p!jqz{`wp`6f3AA9V=6eXKT!`jp8yKBWGYQ+2miJiZwj*Z zU*`sV*y0B?g88Fq##OSRnZKz5p5|?4rufe(gG;9g3tSwMl5X}#RN+BQ!0(W&wKL16 zg>=2oy>jXP^-TCcvSuCeGr^y94e29K5Sx19EW2d?}g6`6kg5_x`iaVJajZK9%Y>WMHaD>JDN8-_kJ)E*Mg?a;&=0 z$L0Rxu&g)9_B4OT(0-v0c9wjGW_NO?gXlRLhmS>>X}|L0Zj#G3oQ(YvK+ImI<-b#H z_*Q2mj6~0>3N<&ozFTZ=al7_cn9anUo$V3j?6-HicZwFOv4lKJa9=u>SkUG=8#s*a zZ4_8PM)5dpTsn)p{PA<=ERI8;J^2|M~6_3H%)|r32ikViMpalp69_qhUE=V zE8+(`$hRA4jb6OJ`1@z@ zaSZ*E!Ya4P|B4MSRUGLiBDj4s3tGU%p=e@+$YXr)1d)G_k@CRhsxO2Ocmr^Y_~wgO>cztWvvz>&V{`h0MNitK2h&FE)!FcT{L~JH zX+C<*N?*d4hjW0!`9t~Va2B?KbZK3@@PNl;;L23*KK`!ZQ_;HO0$f(!|18P#AsGm$ z#h7!k&SmUbOoo1qBmD+U$`UI3JysiMApHPaIFa`g0Wuk*vcm?Ig(3}4VoE%*Ws8`7CORd=S z@gQm2EmA%Ww$C(e5EC-=J~X>kmi)XylKKPRV{^L5TU64bdVQzR;j%N-(_wq$Gh)sK zDfVnxTB`M;_jvjeuQ*%*VHDTsMHg)co!{xG3K%76WJ3QRrNi)pEA>4v4&+>T;I3%x zyPxTXHe0w&ie1J|@iB0i-rv8GRQR^rezrzGJ(^Lwb=@_~+$sJkmSc}=!ClsL32y?N z?NsBRqtx>B2)C>ZpSZ1-25jM{Y_LbhtaDc`{~v`k^YdF`{Bz4tFk&=|X)1?9X>z|& znk%gWRv(Gg{ezMt$ zX3C^9YR1rFax;hUsZ~JV(AU1sUZKt@F+E{xDpCKsE;(jr*4fYTsQ00d1OsLhS98qj zDAA9qxrt(NdroV<{xUDG|NCTsgnL4hpcKIjn0S1`YyRS13^fac=7ya1rMiHk2Pdmm zYs6q5x$E)@wfZJ2qlUE4#Hm!oWIvOJbO_TAQ82tGZJWoDb+UQDP?jfap_2X%F;56l zk*16f7T$}=w!_G$Zj2d+v3(0n&V}!@q#bVvlQU9i|LFM~yG6^IQ6KVzridc!)^D+d z+%=d)66|(2Zctl$Pgn8Y#1rtBw=&P-yX+jP|6AqTr0CBuQLY<3!%?SVWEuMb&6>RM z_>QGWbJ}+uP1C?% z*+U((hHPa}^EQ8}kW6!V#m8Sw5@?dG(0}eW90g8sZEyVaWqkq^x1ZCpoOImPfz=?z ze~N4odQm^@II6iRfRH9WGIlS~N}*d+ODd#iD4b0GqsjdK>ir^eDe*pRE950ACL!gb zIOE^eG?t75)_M3!%XnRG_YX@oSn%$H$8me4^Icg7nAc_$YWq*%dV$lE@Osfnry9jo zWmOg(EW`Czv(3R&XwV}nwIuMC8KEX2J*5vDJmI$yWimQEsmUOW!`M(7Q}t=P5LD$b zrWKsf1)mShor|r+ip}PVW$KAri8gH|DBoxw?clUB3VvL99y|ItY$D>+%MlD9YUbe% z_>Z$o$_tl~%avV?!2oT735rV*?p^m7dApSwC3SEgWV~tE8Yj)d-E2yGxR+|&Wv`xmmP(m>(cu$ zYjY;MLE6kZwvaFa&jv&F_H1^xW;bCU^+Eg`?J;X4Xr6lf3H+w#cLqP2Xs@@}-pBbO0+^Uew^05MwWwW`u4d=*$wMCs(3!Lv<~J&PnAd5x-j;f z4`rX#BmWponw2CWDqg@NFoC8TXJf6Lj#CaudXL(QlRP!fR17kXvvy;$!zs<%9Q!Pr zwW-)dd|!?9u3{ek8TnT27qxcuOu|nQU!MK7PC58G>*zGFF4u`%O_-V2`KqBTHKn1Y z=2V!qRDG}9L5{5Er8?eTe?PCKsCB^}VqALXu$ zTR!2hB-$IA+C3CZSPlW4`Fzo#9=yH%ToFf;7>Pkzk%R_5$Bw++hqdN7@&x74eAqwk zhrr0mQl+1%=EVryxl28ewVP0HVQ8CBFCDWk={JP&FP)pT!pUaSg$4FClKOMoX%y~z zt_Yk|ZHba~Zp8)CIH5Rh<*GhIm44S^ zn%Q!qM9zQ$>f$N`WP0qE^-vhdiR3-UjOeR$u&iSzVG4_RBV+XKv%H#!gZL}g zmu59YgJeER!E3CI`FpwP&_&JtF?;fHMy zm|ldng^Zgs)V^u!^2xN3XYYqG#C_zQmX+(mBcGv<2@bT}+OYAnsO%(T)TJ?jN09Gh zrm^A+Nn8m`fo?pc6UR3EKg=WwY_#4ahuWCoF(ynCiksSGmxmySJ-X|~7;`ofq^%FD zTZ2tdL2N3(B{a?o3;8VFYgYT+Ss!xl*+d;_t_qAiL5nz;*ByAm^Sq`awErk?A~jffu%pbySd;;ln zDkjGAxBg(x#j_R%z{5*=vGo{?H{i9jo4@;54Y#!FXSVl!pQph*4eU7B?3WGIUoEdP zI7zuk#<(0hxy!G7m6V3WQk?C-45!y{LX4bZKkYC~E`5u~(!5-+ab3EbTDeHW5 z6ct)@|FN=kVs`|WCvU0wJoB&7UcRV?S0g&|R3&4dim_rpr8YcKsbo}*-rCvTQ1a9Sn4QU^J8P}B z)rA7~k6-qsNdBy*km5bDtGaj8eA4)M&BD7?-WVFh5QA9OI|VaT3=}KkfuCz?&}x?Zh-Wt_ zo?Rb*!2$YwcLIbGB9+ewNg#uh*-Tm&x0b;K4JV;UU^CXQSs^R_U6Q1{ESyJUjC76S) zt%47d1`E|1Bwd%e#9ou=I>p`U*@$W5iibFp@P3DnE52F2vdK+mym5B-=9M~>%gbd!?liC?va~pO{lR9tGNTB`tO|l zY$v~L4&k$A5u(Hx~F|nm?_s|U*j)y`7 zOoB1yqXDshD{4DXR9vqY_s$j72L&kV#MywAYRQz}ZP*-?`(e|>FWh`S84VhVAH+W@ z78-wO1Eea`PwEbED+e2i@;(d=Z4f_YE)O<4BH{T+iFI19^j%PN5PzgrIHUfnt84wk z{E(#YC|eP?Q?7IIpcUciERHDj?R~@gu!yxY_j0%CsUvK>*XIYfH0(|DJ;%K??Onc{ z$|n{V%?@u+Vr41K!)te zFEGz#cpIe}KXYLoN4#??$s|Tg^J8~ypN0iWIPy2em_m_rWUbk9n^V&4FQ#gYV5pT@ zwCWirOqKEY#TF1Ck$$q4v|LFOyo}flka@U5QFtsT$t*0VtV-edBm(a!W566O3q!#6kNVyJdtp-Wg*Csxy?D6DU|}SZUEveKn%Q#ewFL=0 zT-)O69tyP)-})H8Rrv0jlSL3OoA>Z4;;cC=n09?-3h(D~E1i${Wjdx^p?QD%`BJM= z(aLv~ap%gaf}5r$N^kM~0$yNG*1VeY(E!8>#BmU@F@&awKBWgdPA z@CJ)s{{nBaJpy%MrM4Mpi3%^b(;%;!Y`;}r(_HoqU6Y^}a;P2cd+ zy$02_d{?24KqB*Q;qFvcl;(G+{Ltq*$_&WxUDqyw7%j8?=-_`x1=l=xZXrPrB`-o2 z9g(JXW=-!xT9>`u&G!Y?zAH&~L2_8QJvC-IjJ~z&S`jb#wiZa9zvn)xu!66H#KG|s zy|%khUo6MrBcorbi3LXq+M`=ND9R(t`Q!2A_Ghj+j3(L9yt+;m1cKxs4d;q^Q z&!0PcGuNl53yqAza>g@kZL(eVI=&j%Jz?W;Tcn3HN+*Zr$8mo7u15DLPkw3HriP&G z(Kt15cGTo52M9PutN26G^;d?f+*mZ~>LF%h8^_ZjXfBEn=+Nnco%~TAVs>S1!ETxE zYlv|Sw`Op%5Hbz zT8n;%#P8p9jl-0=ZcDiqH3Tb$_aY|wN$|$~ODJQrb~1itb2?e&8IYAO7F_SZRpVLd z!&2@Jukf`U%#qoPY#1Y#T1#G!t+6*g-u_91Ik}*D=+t5(Un%)FmgmE<{6&P?xu&pb zH+eHdfXjwTvr=#}oE@^=ss3wZy8K|FmDPMeT+{gy#VS|jRlkiMlP`heb7EEIr*k+p zrfxdse)3!4{^1wB`p&OIB0VOdd&Rbm-2r{tH8LGCs%hGG8G}8LK87g8xEH&y3@D;R zgwM06Mzoe)39Hbb*zmLa$I8fp1MPC};y;)vfS4L|4&4q{;_~(wp^tXMSGYM?%F?Dj zg`9MEPC&&vPy;yXegycd+al4ZjM8vY~s+k**nD%wv%Z5&w=au3e`CI#lpI z9Ty&z@qfj8Lne84RBNLD+uphSYw5nv^O@V8l}|Z+mXhj*MKMQ2hf8Jjg%=oq()CH6 zs5Txqt*y;6Q52Tjo-Je*M94HU+)bGvo{)z(Fn`^fv+VXytK+{i&1+YAKHxN41 z^Ton$i7j4|L%8$Rza_(;tOgd67ZvyQTsm$$2#oKRyhsk!>>la+`TBnT{mFhQ$qu!1 zd@Pz=GHJJ2!obQIGo|kjw!Wa1>NoCInvE6ZPNzMh z|6u#;#UAz^`inhgxwM(n=np*scSU!1gOkR|JWqEeIgC4b{$2_fd@1sA^%qMyf-hw* z>%)pKtVf1q+&IqjWpXX>Q;i6;gg49x3tLL|_ggqDJ`88e654U9v+B-1kYiAKi%_TE zn$K-I)}v}E>RhJ%3f1M{>{Va0WPN*xqjZC5%Gba$_2!ko0pAShN9DH{_~(Exf?SQB z*@>2rK{Kr zVvS|Ce1`2rYl?j~gWO|_)!QLI!K?gY^~+%K;M%|i4CHQj#^4o&cvn#xJbi_pdfaohsQ0VbDYJ(8s#ye&UY;>P=H#jRMSpyK zFmLMAzGCrZ^x;PD&&;z^clq1mJ)dh7izp>IOnZd>QpYA^VDs{Xb9~Q3r?Oib;9aw) zM=w^4}D;nps((v?2BfdvIU2$0MpXXPyPk!Xl}D6 zKVu^={UxQLz8@#Kv=`=Xmk^R+Qu`)$>xFjf&~}zTo&M5DtJA5EYU@MlrmW?PcS}BI zv3`F&C=~|a3RF<jV^J7#t{`wnt!#eIFjL|61sSWxzjIAY!iHZ3OeMgJL*+45XW1{e0U>c*E$;$sG z-#Pa4S;yTComa7m(0$LM+07Ct%wBL!7YTaz7c0hJxLT~{!8~Rxw|uVC-%YRMwSYVJ z4P}HozaeQfN%S zaZ&(WBTl;Y;XJo#uQC0_yA1IR--;Gyak~{8&os^w`x!NOS*%hMn8)5TL|g#*6})rb zM1ro#g5k~QNQwiHR2jd1L!DF_DE(hc5sqTl4(|d|FEfB$x&mj7Cgn8YmMM74OFOh+*Y1sQk7;}n}~NeK&;BU zi&1A|q)GH6IV*WO%D3w5LN=6vvvj(ZHm-N+ER|Su$MVc5I~IMh8W2?Oc|ZQuY^+ap zi+7(1eUH+Iz(=hj66g5X7qVUDUNq=_H2H~e_9Go3=P&Vh%wwN09{(+&I3OXjw;A;3 z61s~6yf+z%zA(a0#>mk+fxA1QjT#hH8YC}K269$imaHcby13+%SK^Ey)7`h~AFnoqUGWAabfyLGful9i8vGqKo!9 z>e>T03Zi4RHwJd1>p4^iIG8v2kbnvu{Vx@2wE?fKIbPc?l5rd4o!UcqH9mVfK>B?G zm#K4n$@m60i3n_y?~HDufGc~VGhf*}Qre7QWIM4tkSp=##CH3et*zhXwvD*~@C1bj zU#*bLQUp4UMd*gnfm+A0ng4O!Tufr);m*|b%F9V`NC{@Ti;=EkIwmnzsT4Ogxs(pCS&O4Cl z7&GU*M^g3tH&xPr?aBTeAxHIdkq%%JD z%%zfjV)$&L(h0poWHrdpyLVe`1SKUevW{1d%qlwYt^}h#p0Afp8AQsODXWs*@43%l z3A6KfMrrW4iCadSiJ16DL=Nu5G%EVAwsad!ja$n_Jj0rW4denKkuWQ%m152v5uyB$ z^OJXYgth|Ae$QF!=fqAg__wwA-X9or7mhVA=>50NzffCH`lstn&=PU1k7dU_cpZ0~yn=fKYRA#6Xc zDEPw=@rv$iA_z2?g$3nr6cGd{a!=8i9R3i#Yh34OwYilBb3I#%ih7~(A~nIu&X_!c zWJR~fe|_hMZLNhQbd%I*yu7eY*cX5|x)BZzc|n>$+eF{5@B%)NYvSQEODNpi)KvaF zth>gLvto?V`Qb4LEO7TugM-datrSi-TUa4`hb4Ec7B*0S$1c38!O;4v0CEkX5*{nJ zh|68rAv&FBF@>hQ$Fy= zVuki`T9S<)o5RE%=-2T_^M9Mh55P34i-?ikB*Yqzymk!@MNH_K0yyZNYGgWcF@^aG z)W_RLghG2Slm)$ePYOfAMMbq}&Auv&}FOX)9vtF|dzwXa8oU#PZ9Qwy^ujoFB;MiK#EVwm$iwW40BhbgY_ zY|MYj7MhMVvG!M}hjvBwRVp}%YwjtAS`cTFD2!w}X7kF8S7=t}oS>0#Gx&?$FJ0mH zSshMdZkY|8$)yb7DjDOVE#Eb?$$o;0@+MZryNQHp6rLnvR}kDo zP;Rz!>>p3pU785Kx2GeIQ|#UdOLi$Hm1El3-hQ8&I?%Ay>$Ci6yihpCbT}+CE0+o1 zpb^Gx*kkIfd6>hjc~`&02By>MoTGK9JkFwyj2vhiYCC8$wh0_O$@c%ddt-_O?P*rX zi|l&L-lg2Lugnu)PAfS`AOu;IzqK-Vy%sjs*V*$OqH?^W>)N80K+f??Su-I~*|Qi1 zEpUC;aL=};zI5wnRqfoTQba%AgCn|E{kGq5vWBao6ZDkpKPTK}l0jSgK_=j2V@ls@ zZmK$$*lYZ0yJjY57o?4%Q#i_*H4H8tR;SZ!Ps{Bf|KH34G3LXu{{Mz&5063MtSbe+ zK!amQvH{94er9y*93FO$XPRma$3a!zz3x7Badm(E`-#NF1Nm~r_bO)eTGDMJxxNuU z`bz%RRt6Lzy_aeGrALzrZ`kcEJpZ`kQCnxHSfHmB)1YPGS|%ZrusyUg+p+$Yu{!%KmhLiC~;b351Ff^HM7Wj)CT1Emt8HzZGgm4&svT zbyJ+diW+=4h#Qs6mofB@osgix>MU4)!=4I&Jw4g(3+L&Lr!f+=509P(^O+BH2T&R~XXJTXxYnqio*XJ^&aBYf*z?l9i`HV(svs$JWrNOLi+o&gTGb+* zE>5fZB<8!NC{J9R=;y%7aYlw`kQjV2=wUguoWYQzstpd=bh=(66}0S5Oqik8@oq7B zZ1HJSLXk{y(bz{?U->dh&b{&_C6>AR;T}*9hK?`q=lXD!G%OEcA6gx{$)WK;+@F}^ zKRkO(Ep5K>>&07yAa`Ba!9?2U?oQnVavQ3_miBh{f@Y(&5LTKuK{$x^L`@(`t14Gf z@~~B=wi2aL$KBT0eXQ~&ydreywnx_Wm2dxgp{1t7O z*~Gj3AD15KWSWkKJ)+|v4ojy{^|APfoVj;HCasruQ{e>C)YfH8r`G=DF4~88zo%eN z>bcqr-EvdLCsLyjZHgQ8`~0oPqmc_m@A*a4B6h|(spP-}bfysrg%ZS>NNArcGZ^PO z^&9JF_xzxQXTukxrTAPF7|10#jvfDpv(z}ne4@vZS)C7R)lsFIRVH!;dLc^Xtd@3< z2L+`lTD@%Z@H-<`zez3oIpODq>5AsX)V(EFttJ=4rJr!`r93!t?D0D-v6?Vjd-!m; zYM@7+4EFt}x=_M%`v-zfRqw^nY&o_o8Mzi@fXN-G$Y?$m?VBJSD|-E^5chwJP`0&Y zw|ia1?O93umoHH#qS9TsgR}rbJI1(`)aFaOPlV519@0uN#q&;VSFU1CYpn_rkmMf0<ne*Q+V-b z(N%$M>6aqn9MjoxQDUle29vwH-_4JUY}#^h%wucL&;Ei!{w75bH7U=jT*TVkKqz-7 z_TRP)D6xo%mc3e8k0>?XkyEXp5f<;YQ_m??lJy8J54lIP)=5m1+4}n+Mpo|3+$P2d zCyn?;?py1;tuZmr|Jwzj zhr1xx!Z6Q4t>QUA=e4+mh%B}C+0WyxvD*^Uma3n&{6P6bx7vKh=NTp*@H=0M-}qgf zEo(%qs{H+qeVSlGs*E(GAdBNJS|$BcKKHW%XX*cMr|#CrD*?;rFW%)}`={=|d;RK* z)HsWNgS(~HVc;e&yz`L<%<;Q9PZU9Nyc)2xf0|ccPjlj$H%xc6($a%6foU=R&lAn$ zwMkc+ZKB<#*?zdPP`&!_28QT$*F6GDx$57X)>Z+|&iRKQ{C}tZuFAc*W4{l_Z{Sbd zC0K>Of$K0MZteE4tzDk>Q`OmnH>I4OH+fSPu*Nu9J&>#k zN$J30;{7^#z*RPrr_EEY=ASz$zFcm)e7&X8?e9yacbWO~^JiYu*s(=?cb0H)*`&RZ zi>)3d?g>7_TD|hY|8Dtjr@rjGt@8B9%&zOzrI}j!c9m;Q8SN5xEv!DH0t!5M;yS@ zxB5lqiY=LfYNgFJbJzU`b+petkAC{%<7UNOQD5x0A2}UdUS728-Uk-Kl_PNdjd^)J zcXyYnvUWV5%-Kn~)&8emoz>iw6T9i*_l3XKtqy(z>MzJVP+m2U>+IE+pOshMEP4^~ zve`%09as)MdH=n9qIR^o!Jhtwoxo9{88ceoomEhe>4qXOp|oq6LMDjTF(g*??%ck! z(sk0biORqE=L16)=uh|5)9-}y_U@lHu{8C~hHpk2(tDyywPJl{ z{R=#XkZ1Z~>EQ{6}F3vn~^iauuwjBxqwM^-gT=q1(9@^FM!@XmR zOmuDaX6V{6XgfTh8<>xPn|YtF1vglBC=}Gqc<019P2s^dV5r<~5kbm;z}Pqg3VzXK zJ8;H-D^|dB`SYc$?X2(rUE*RnT440|(mlp9cSM#2_Gf`5U)q5r;ekQL}i*f&a{BZ_Yc`b!Tb_0}yz+`njxgN@xNAjGzd- literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/do_nothing.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/do_nothing.png new file mode 100644 index 0000000000000000000000000000000000000000..9301382dcd093cf663cc18c89fb5fe0e57a3f438 GIT binary patch literal 67002 zcmeEu2UwHYwl<)Mq6iA;SSXGSQCjFAy(^)IDj=N%LXd=#AWcQY-mnZ^q=lwpD50rf zL!?OWA|M@1eAPF)%P!GcYhtu3raA6!O_0fM1MQBP~^i%*x#Z3=A>{aT?}0w4XE5-HBnpxEl4- zewe5$28-J-uD%}zv-9*6c0}5_c-f(`!X8dIPz0W%F^))Qq?04H4onm#AtWj#Bqn1b zD!yM_MH~ixNXiJyNQ+xi>)W|FdC(e!V+crhcf0*CO-W%<(3F6=nAm=CRq#m{>EZ1M ze*4Kt*-A+q0-sboJ>8wmoa~PyLBE=k;?lz6QqU{MwN2o<`(bL}vpdqw3H;J>a&W^y zuc*0tVbGvNQ%p=uSQPpX6dKz(+j${ZH37}R$H@ze#CXuAAR#OvEGAAJtrO19g<9;6 zv(R*r@jI^W$qSrF7BX5s7Wc4RuOYr)Mtr}l3hjfc8s!6Qzp4zaQ6x?97-w%= zO;;avO$Q?vUt3YJW8Sugzwd+I6WUM9%g)mkj&XEy2i-aPQ9Bcd$xwy`O7OISi;9ZN zPzUegMem8$F;rlTB+#cwd(*`m>F9)|y-j@+hrzhxke)vlI$%6JoE&KTfYzd&mlwwO z$7;?PciQ}Dbv(iL`Jr{F!1xcMhDyzljyP9pT^X1(bu3W1wiD9DmENDV`aY#-^=eTiNtdS=1_Rn#wV10P(<`C<)STQQant2U>j!MbfBfAQX?U$1 zrvFNFV82q1ft|ZIedAI0Fb+@O!$2IAU5-RkRzMXT85|PGUDwXu$=v{hMdGLj$R2~k zVbI_dyF(9D?Ht@(yfEG#j%pZp47B$hot*8w-GR7PT2OIExWE;PSRa@DFjYS^kg=M9wjRt9uPR}0=I8A|@RYFE za`(0)h$8K@jYJ*PF+RHDj^d7ZNpUz{(#HYq-~%^tlhiksrPjmixHxHvVeLKOvN~v2 zQAceRDP6oQc*DWlkpTC$7eD5qOVII!tE>1ph+BH-AXQ;@W~SnXXjusZV;x@|brl!5 ziH4*u$`GcbZs-f1ds?cCB2Bb3B`wX5Im3}UV4Mb8M(&m#aOjh^o~V1nU!E2Trw zA;8Tn@Nn?VKuwn5sO^rmG?9=2?RYw9QpVz9XJ!awqKCCJSM{|pH^S(kBxD@WrYJ`> zRg9&XyN8`Nc#fjXS=`RdNYoC@8^}UT7p36`1+?kvAP&iwG6uX35~vwf z&?{w@2xyk-5;D556&YzcQ2Ta2=3`-IMELW5HIO>m)H#BF2)ZZ)`0fVA1FZ%0*+o_d zDIo^N0eaCSIDq{?l@T1NO91nr$X3lQEE9-)Xz@c!5fa!guzWcak?fNpdCX$U3FEA zt_ihV*F+OTYtPRNEeiTF^wv|?z{0iuwf+25E`M0xzeCPoz2Qg+KlmTlnm}7?u%f@) z1%8xO)sn?JnK}B{BUOFvVea0J+F+NUz=;AYr*EtRP8Zx;&qT)sZY<#oN2)-pjMq`u z@P?~{GCZY@AKb(RNYvtw-w76wq`|u?1U)3Qaw>kHJs4Oa7q}X=jB|`|R~+ahf&^qy#8rX)!`UG{ zC~yGMX*2~4l&TZW8vlukrxg8dJM-PzXgLA!gY&`zi$iNsR#cQ`BxvScNJd&pSa#Jv zN$N0szgtc*2^nc&TCwXY!zoE`%8q8RT~@k-EXm(v)Ic4YP5j$ag0SfCOeYO^`TPxg zMKL-QR0@gL*Asy-aZODX6)-<>RV>a6 zVUu}BvP9~yA zph)rhYC0|s9?%>tfa!BV>S(#T+nG6H93k_MQdw=5MfD(f1>XDHCRu}OlBuTW@9W3J zVs$?RIISPZaL}L!6$WVOVJ*z{2*Au!;g+$E50EJp&S*jKM$``&5@6bW{eYR4gq!&S z6RsnwYb+tDrv>+;m~&$Z0xLH#-qz&P=GNM8WU5P0zU`*=(sL;BP4VC~E#-2tS+19;^J z+NH=9j)K;h0=4|0a(y)kf*#lpPU;$9Kj{1k+@h{61j#LpRVAVK0gU>ywt##!V9?sZ z!G59i@#k_{Jua|T6sQM{5f4|BfKm4WG!_l8E|h1`I9Hzi0fbPYs1`UOXav})I;-D= zS|xy1DJRs)1ZoumZ#odTgj!vB_LEj=Z~$@}3@C903K;Oh;OuDblh}Ws?U05E%hC)f z-F8UG%KnH4{sa(!$cq?Fd9Su6bPMw@!2`5m{w+M<l-Gns zA@tw`zEWS576pMJ%J=VYf`>o6XyD|91mNy>=+VjXcd-#H#@ma6cz~^?p#)F6?-7Il zESy{gECAG@fREKXfnMh2h)C`LwHSn3ZT zNJYQdxZy^DkfMG6`%lgHqbn>6HW2N+{?HzDxW6|@`39}% z%5nZX590s2Qzt75Lh66m;xudW&pc%k;-bQ`(zN6J{c!!R=YNOeM2krOb)5b>PQY}4 z0+Ieuty}|NBX@f7&nI zeWM@4e~0}KA~pYrKlFX4|BpWa|NAz(6rIJg;xWk5R*$~p{s}u>3Pj3eVB%8JVq(%# z64EpzM<0Q-sI;)O&LmWYo1k%hMxX(tzGTB9RE+RwWQ=9 z*IE(;Bc)db9{-Kjnr8b~t@R%c@V_$&>_4B8h2vGAtQM4^`bUXeAX9tH#}0g;LD`t;2{7%*~rjxaf{T-QHQCimb*mq)=nV6@emMI?e0kXS>Qh>Z9?QG%; z$Z1BB_F4!kv5KBM_R!IChbT@a)RCDw+nMS40ID05U&dRS>51xSACrVKSs=G50cMPM zf^xWc2?;32Yo}%EX$f-`1<#?}C?t^;nin+-2IyAb^R0hI^#U|73e`)SN+^SfarPz} zpf^CVQ3vEO6H5#n1!YT3Q4oO$WML^8RDE?9EXZ<-gYT4)L0MIObypb3sKVfAIH;rJ z4Tw~@AL^Jub-;Vj=rvrRtS&(h1_*XY379@0ZRrBy708N0-@*Edg3KWxcTvh5VY=X5 zJru~Us)>Ruq=h84eL&Dsqhxhg*R=yu_#L6_kJ)Rw1gTka%D8^al0%tSkmX-RV58+2 zDbfejCn%!|KAQjv(;rDybgBNBwFIMdqtNcCIa)wG)OMrgXjk&HpwB-a{p$Se4>?sz zULDGOLPRV#dgc=kpjw!8a=|Q_p66&2YFA8hmcbR!4l$rk@ zLY@*6g%UiXfZh(H;WPq0`6$Yk`74!xyVjJ23%4Q{~kG_3SIq*U|RlU$*}D?5n?QJ>63MW$XX4_20Qu|EFxdtb~;8 z-!S!3lA=J@12Q%3-yeOvf4$YGFg<>9FNw|>`F;m%H5Y{PlztbD`hfNVbTyEARcRzj z^%VmHKLa4ZoA}ubx3k>ia>{x2b+5p^>#j_kDg1(GQi9JgzC3sFr0Ik8nHyd{J-JqW ztyuhp2X0Iiara7@%I(d|b~El>|BC^KfwFbTd?BedAkB@KT;M_^7NjkA2AnRGH(o^4 zkEJ19I^+USMczXV8RF}h*7FB5{P~ZE>(jM@E4f2{@|ZtZ*@BS?m&v-8Lz#i`Pk)?V zyS_UA$WI@0@GJN2{Mox4%KY+-g4Nkr`@?_QHfS|uD<{9Q$YbU{+?JoU@&weVstnKg z=@^db1~U|uZHuba_{khN-slB0D99hoQTU1E@HL`u^A^q*C%uf9b1Cgb;$ z(-0@hyuNxP)>=mJClwe%j&9_L>%%iPDg3!^1Io*el_PHZXR@csPc+}NxjKdPG2*L%fY;lLR#y~N>)t{^M2n$KYoh4&U_4}EYic=)%4SOajZXf zl43$OqF|p@ezvO0{K8CY`%hWuRId54i|;S+8vyO8EPH>`Pb>V@#ENMC66dOo^Vh!k zYhSEL;IDo0T>{@f{iQGdlErrkeE;;%a!L4!n_hBzL%MU;5xuG!rX0K2Aq2zO?AJ*vWGZP+t zE?JsOLqC4GZF+vJM4oeb1QV3~*x_|j`vyiiM#3XA{_K^JhVBOrkNME^nw7{?G1H~( zA~}dO)5OzRgsH)tsRpZLZu#!Z;={%BqkENoH)NPUesM?G+VYkA{77ytczi9bs^Wm| zy^{)rNo`9<*6NbQX)CJ&AM{1*_rFPI_>8pdAA9>g^k&Ig23lk&kn36CYy4~iDoN^U%d~55yAA&<6=D=rs?PVc* zh}MXJcZf@DK!cq3;O!U68}AyG2*P4Zh!eRjsKd2v_sZUwgv8(*KD3`dY4T$0*JJeR zaRwk3w9#q5%w}o{(>4R<0r9G%4#vrPq@d;b>%JN^(W9(runW-Xe#&^@OYNsTt*%${S#^O-^?@~RusEgV|i zv#;5lJ!&}NQT*+5 zPL<-k`TX?A$ZYpD{TP=V`B`v^+&`6tPd8X$nxkZ~Q9gocW?4CKspc}gc0#2Y`?uR} zMTDvHXsO7s3ps9$l^uTFSKQgF%G0!$hq6j`-@R)a*z8;xHDE4cl~Xa`W?d2(@Ve*W zExjjF=oZJKk`vNVl5Tg}gO(Sk2h*}zd^-dBCIvcuTG42*kFdP%Ab{a7YaA0W-R#8c z)f}g?rf=uu)$hl(k=*Z6s_@iDPHU!GZgH|!zw++q%4oN{);{;&-xDj%m#V*|`1K>a z1Y19qD4PtAbhZtcioj+dQ|k3o*P0^*HId8)s78kNz3@8jv4y(3~f zT9MuE)7lL7{ZK{0^3wc#B_yzxM|P!8I+CRgvUIg~PtMoL_C-1PcHmvg^P@apY`E%g zUpV{elFwMt%z-So#iLU0P1SNf!>&LN6;EXEs7pz?lKDD0Hn1hee^hq<<5~8oAzOCe zdjE{f=XZpxTDEBIwzDqqc|Tixo1JqpS9y8yTVu(R)1_@fUYS!@q&u4O8?16Y(9!a~ zIS$tp8i*#TTe&1BRt|4GP&{Fp@5-nFjvjsGJrnh2w&;n^@81pb*GP1=y0R;| zeF+@5WS+p;E~nxwmi2+~ zn{l7@w+m?Oh#SfiA@~0}KmJZcoVS?ib1SB#J-?Zw&cIKk4=APbS*^VTx=vu5|odbG*(B^lw>MvOJD z?Cd=;)V%3E{w24W%pRwt_+3ZH&+8xR+`0{);EoIXs+bs?0QRC{@4{x;9*#cE2fQy@ zi~N24$KM{TH5y1d`@*NaiPhd@pK{Rf5ZMJg6$Tj;DrOF~KdgPPHq+!k zRs>g?n0tDqQlU1*G~+kpx1H%0*}9R=3xS!8efkNf2NLf_MH+7Uu0f#yqPLTbFttRGKaSX5lb|(UY{dQ13R6T{1kLElZ!d|T zWZgQa8WXpl`maz-dt(a+WyyiyLxC>)XkL%nQG)Je$8QNX+7ceo~ zk9+W&&7MR{;S?S?IbP5>v@Nh3Yy}_7poeLWjb9Jfed`M2`;gOZ@GNc6q9p#Lk@T)Y zwFwWPdrY&P;Z~3BLkC`+J!3v*5IoXozb}%(+AZFPomD_-;Y%qDJM{UC<)eMCyc@0W zdX<)CIfduci@Bk3i>^F%Or@$e8CxT)Xe^WsdWNOs0mi;N>&OKFy7+#?-VfB+vWGVUClyB&7kQUKp*8Y^sY_+FWTHc|ihKF!QMr|yjz z2MVLE)s_SWC6DOmbO*25EPy?`ueFh!`|hQtk`ke0qN9*#Ng|TatqnN%P+!&jA)XQa zv2Zdz`66!Y!VC3z)BX7^6?tKS&h;;j#}cajb2{X=3SHmYn!5i=W>CP*@Rh6-*8>Jd z!k$dl*XJmQLYaAO9mZ6_sYuQ4H&u(!Vpa@RTdgKUacfp5wKbG`6L7IICTvc+>y&p%A?VZB+40@rP#P>8>Pvj3OoEYV91 z9>%0w2J7*y=-fp2EPbXo6|L9gBN-ILZp^XGlS~d}_2tiHAC8*tFgIXGzau=#J3@|+ z*B3lJ@m~7S>&yug{m&OSGcS|h#syY&#G8seIkxs3YZxLvL$M}s?*#^H#5>mf#mtDZ zE4=p)?XDvbTTVO=wC|rQ{QR4nkxizXazMNPWdDr?vZ@DK+VRcx+i2frr|t8=(!%#V z^zUzJ@J=#?jmArUc%NQIO4=oXdjGKdOU_lpckJ!!zick)<8UNga24KjstGKq!l?KA zH`YpK4gtrc}In`6??k!UHv!ziw0t?2U_x_q%z3AaYdamnuy1K9tfPbufFD=@8Tvy4@(J{(VW%LN{MT{AUt9LayuzkZODlOpFRt zYgh#y8X!{rQ@jk(2TY3kd01~veK}UbVg3AZE{`&vk$lDr!;Tu!?}}|X=$BT*y?H49 zHb6YuvgtTRvImpEWCt=ix;!dO)xAX2CLlhmXu9S0$do}v_f`4KiruW7+{16*$v?G4 z?C~!>#(YIiX~y7LmS-iji2B~-8Y1GbKfs*Pn8QbE*T{J*dSS0UT7zpp`eiz~QEuS* zT>?kCZwjkvNUVSVJ%jzu7wF5`5D%uKNaX>2>oM-Ro(uDGALIt)ri*=1{)3bN*{jl|C@K^zzb*fF;1TKCzR!%gdCXWg*V#9ar#Pe4#OOXntzg z^vy$4-qD6F157vs%QYO5&IRzkGxJOfQB6!d=evpbXcJPXi+6x&G9TM#+5PHDZRTyk z*dnw=-GsH>&83X^;!4(UMb90iimpz19-TTcy%{k@_E$+B>dcT5-ENJ$VSM96%@*h2 z%#JeDau=I9Ca-H-0d zt!|&&5vTQ4F+%vrw10`t$+sHPOhvIU!?Z0V1!Bb;Ddj3}zJW?(>F&aj*cVbY?~jco zpW<4$JM+x6UAdl3ZsyHo=gkvWnpP53>yH7rBcMaeH}PL%B34Grd85j=2s|_<5p7>4 z`j>7L&WqFK^9ZmNV*5=R6VoPP9h@0nTGk3h$;TY(xdNo zu?`g~M3io-&Q8^xc6%H@%|*~t#;dVkN4V{rseaFhm_(%r-B7&I#e=GU7^xD$v$7|P zVz+&j8*rHb23!Bzlfcg=(Kh!Dn;EQQH-CU{4_z4Dbz*S)sISm~g6%x+nkXE1VlICw z@S+Z4B01W}(vtjbqOUc@Fu|xes}FN}y4fY7Yn7%IfHdtR*de;69nNX>a5}?+=|z$E zet6wKb&4?dCFi~N_P7$@UnH@3ChcMkFkv2Li>M!y{mTEU%niFCynTL`94-ZO?;+7j zLBc?7(Qk_X*w~vKd&__(ZoT}lmRx~*SoWzSz@sV1CNtn1RM<7@Po);=;hN6Zm#R(khyG7TOcVGZl0wHUTKF>M<8}X^;uEF$ZZO_doIN5-}h5u<|r$ySOFF$rXZ*K$u8mfP=IdDNh-Glf(Ty}tS_3^G1JI8)~`M`UcRnB@D=M- zMKGDp+Cbp;xC1-jL|Ah-w+zI7ym?KDVI>4Du+(yq7f)Oz7Mc!4od|p3T*4p&FmON% zhCGmT+xq;DIG4G)(9LCIgtztk9v3lTNk>0a!-W>z31J?iu3)aAJL6pD6(f#gJaZAn zYbHUkO>X3-NsaY=FvZbE5d|~O_J>o`HCYv3hZgE1V^n4OGGuFL6Lqn3x3#uZa z9L?v%2AB>`y;SVEu69%Fwy^R{4&iHzDtVhQ%KFoY)yVd(^9Z8<%&GU1jkodqsX2zn z&#SYK>D)Sy*v6q|5c;vBMP;X-DhNt|R&MvIU$`mF8{R+sR0t zll8~!bDU4TK3*wleTg3-GFCWI*=%sP01iaRHD>&BXI%2UV~B_Spe!3%EV0jGU(3!5j;)k%)Luu1CB3i*p+e+0JYX&mQRQDDcHV!Hajp-S0$7 zp7Qv%)qEqra6=UNhw-+^c=f#T%8JMBxk0#l_;jVy5%WjSHcTUUvW|UndUq!Rk6&I| zgrkvd;1mP^kE@|LU>^2b%(>#1+BM<{I|oBDZTd%Vz>ohzD#B0In;F~O9b;IGJG&XC z&{V5XcedaO+Io_~P(iy+zAZK{9J`MCdEVbq zgy;z@aIbj~YW#JWmla!gtA(fS;l^rin@-@YBC9?F_>@x_Er0jh(wDAMcu`t=smQ*D z8SWRDf{`5L%wrJcYhmF#eSJJ2RF3u5R_@54g|A`tL`0gdawMGl8;B7(0aSG;d%4x4 z;QidxkXcuRiC?DTJJy+Yhvmf?U%>|P=BFO*Eg;fm;k=x$sE+$K-fLRmGXi5jT({;h znC~=etZk--vjO>3DVwwm`%Z6mM45jq4~KIw@5^};v331~tLHkx3cEpA!IxOIc%BJW zqVKE@8flttaT5U(pE25O%zk+h1aM&1m8bdWDOv$mK=gQEeqi%fYOrFQ`2({kh~kZB zROnSq*J$xsKp`XDQ8SBZVdX5dteE$)N=hSVJL^gb3$tIHrsH!C3}Qwh@H776c~;3% zi%$zO8P@2iJ11Mt4|a=Wd0g65SEzYc}mxOGrpcp?B3Q7mPkk#y!5 zsm|bJ&@)Ds+Xa3iB@0h@PL*xhQJTyzSUr~C#|s6VPhU&6$aZ#O%Hr{9dfqc+#+asq zyNaqwC`U1W8OV7z-6!3Ca6=n=&17YwpxI2R2WMxMZ*V5dl^76)bJDYpy>T zHu@LVTFIG0{KU&j`Pi=;L!CwM}p;%x07 zVl^q+Yu%rD%q-O5_?;uCY@PtqFCRY!G)mWe_*r*hm-dI%?^(wTc5M&M+U5R8r978w z8*vWts^i8OgLV8A2(fmbJ2x6n#2}jIr~Dg}VUyXne<93fDq6=+ON_dSx3fj#q<3Z( zjLH>!x_G$!7o-j8w^P>?rkfHf&SJbbb+9_jxIJO3p8D-kXYz~9m$LJ(Vo5b{h4!|I ztGo(?ro2<#M#bqfMgb3A&o5jk($+NAg$oc5g*{XuKq-C5t;j@^x| z5R)QI_B$#Cv_}oJ=4Ju>^v>5zZd-|)$X!vfcFC+r!47@4S)Ow(f~n|m-;~b6%wBcx z%sDNkFVEKKmEgzTCxK91eWlX!!tFzKIa*3AmTEKARWUIxanrnHP49N%MSOLfiW9+P zzWrg%34&g5ZsPUgO#IYI?ZxyV7q$6gmrpQFf`#?6u+5FOOzA&x#lPQWCciHx?M-6T ztt%bk3zjBGwy}aSMfs^ZV;v!DMel&E+DaI*Md=DJnH3JuWVPwJZYozUZYvY(%OdtzUEO2@;|xBo+j9ze zMy-d+3=>lYi@_q^OL?YX$d+1d`aJQoel9!nA=b;eZC>wS^8i#K0@8^d%%6A4Ng>7r zcTeR!*4FKBRQ&a;!uv#~GC3%y*JE7yh)2xcr0a{i_FEcEWfIO7gze^R%`1sHe$N~@ zD6fE>5uCWp$aAeS5x}9!uR$OZQrwu(!ZEPtX5fg>AulVi(X(t z9}OCh@Q@G1>+{UAO(k@Cma;`hs_+FZobtMLf(ch7P%)EwqMNntY?GB9i7T#TZ zPz0A)@F!)-5JE}NFyKDB##WS z!t9$V_dy$9;C{*1leu@WN`dfsKrNQ78X=o?Y(O1t5mpR&&Lk{VyiU4 z=Q34deoUMPbUn}5OqITuFxis9a$Hab(SOh5;YQB-*QNm}+-C~M%MT-Mv+}u*+}(a| zKC}#lh(}p4kD+#bGAp{*luGPE+(;d4)m7`tC-Ne^qv5WJVTXyI8ngJwzP7|c)7DK> zzgGDOJT*xJ3R~2Rt-8KNWlw5>QIr3XKt^)TeF@}Ehgu&m0xpArfrsnI^>!P)!q)6StfQ(}c z>aCZ?Pt-Sn@M-3uTDSHwNwN>gbbxpGp5GN!3({>JX~A7_2S2lQ2MFGs@{YAFUW4Pg z)H0WHL%4qsBj8G5*0FE#h2^yl>{1kp@6U{FCXd(PwRU@sFtt-r7pGNN%u= z2w*s6Fs4v(mLfjzV-}>*u-4S98iz4ssHnce)a{8lsi_51`HhG{A`^oBp2_+oQBCf% zs7p7HK(Mxif&H~>y0|tGBQB}(hvuO8;>%4!y$5YGmfoVS8FfIa!f54u71GT)6=x)IYRY;|8|aZDJ>|McP@q1f+TDBj+@zyxT#+D^Vabc zR^$2};t?pv87*oVpTjGhDp|b%kCgJZJnhQ%8%UyNU#YZOd{oOeg6Vm4qw-toR!d;{ zH*U@se5f~hd!{meNK1v>Ff)?dne+0}cKH!2ljbbNUewtH!N5i14mBfjYqQ<}Tkag< zBhxIu5nE}^ryx^N4UbhXA&`h)3dHuhjXmz&`e+?@+`&pi_TQpqPCb~|upuMtj5le| z2mFAg3@`=Jk~PUHUOOyZcJ#YgvkM>!_L4RjO_2k0>ao_+c~702H!)`oCPvR%+)3~V zKJ>JH_uRSQtKwo_8OpwVYSm-L`RQ5nGOT-)8^8A7VkIAX;MN0jh2Af483}<6^D~<>U*pvN*bPy>eo zYXNLlHD|ucNC(nXo5Ft#lnaoWX<$wR@XT$>F1?Q5`y-3oL>t&0RrkX6)UH23H)e_? z`!3U?lGI|O?Vxz-aPS0`qQHL~w0$JL>35uLeklM|9$OsKTT6Y*6GV(lr<{C#H-Q&W zABB=#7pPvPfHr9C%!zHAe|P(ZUmcWloVvf0+L#R3|F4mfvfF>xnmcsw#n67&kHwUC zs4w1xy360+caAotI1^@&)pjPK>ILg-`wD-YXcQPS_CPoD3i|rGLEtE4$$_m3rG>>eo!4kTekm#8yCfwxv)eCp%_MMVo25EW zV*x=T20EusM`slkPw*|A{<8FJe(!R?$C7Iuwj8sI{7NN!`-oMXLxv#7cu?0Rz=%0d zaRM7~z?3m);oE#j3E%AZABz$;C9!u-2N&Z8jNE|tSf6R#+5zYiFy7OAe3|Tlihe;K z7jG;pe(BU26Is6y$gw!aGCDX>MsNo)nrV>h9G{QW3LX-l8>%f@JKJ5=$-c1oZ1s;+ zrk6|ehHqK=PceQx`aSxv(J!rvv+tP5q)e7v-+8)fgp{Jn29vzd;|46xj?$NofvIc# zEF$*c^h1_#L3NiEJ_7amL$IU!23O#hz2NoCxud7ZCh@OvU9v)}*K0kv0j3~&?7#~5 ziB&7E5X{BUDAYz~=;e*o4gc}dh;rgu7#PHXWY!|1io##M?@PwD_QHUoHNpIOk~Y7% z$+b^X74=gLLTw0*EG|^TNt)=EuUI<)um`rKQ<~ktgqjD^2HShMTj|9fkNLG^dIjqW^>@{RPU% ze|H6t{{RzF5d#7uQ-k&IHdMOR6MLhY+w!ru7zwuyz}+jOWZ#PGtsR(~nH;Ef`1Lt* zwQL!fo`c{MOZS^2^d6Kun7Pgzme60@7rsVNL|Nbc)+hf#=yI)hW9+-yXp^uxZcS(B;KgHSoIHL8A z&=nx}vTZ9vGKAzdHGb*~y#x}&buCCue9CsCFB3m&h)D753ln_iHGRt8hyCMlcisNfXJ6zS@2$^8$4_ zaiJ=cu0%rw))vnV9yadHU&q~Vcp;meK4EA{E?fe0IAMBoV&&9*Sf96M655I;H*D^U zxm50UYk8U)ed^T?pDKkJ6K7&!aSlgi_s!$Nk2i20Xey65JOYRjIUs(}TfgsObgWnT zp=ppkY@X>1!dRh62(ALh)iX9R2d3=>u8@Pi69hJgsBWqTsYJVjQJ$(#V2XS^MN@-yu{wKz950^(0k_gl)_;WL16+(mnIpEvZK>r; zAbn-?g>eoX{}B)-dxEMbI-x7iui7eHku!tjhof3Ldsr$E%@%96hIlCTp}>K{hJZYaK|Y|3(7*yKgNZ?&s2Y0(+$h z1ZZ;XU$VA>R6fl-P!pSU+sSK6 zOL-vR*SVp7>PsEAN}&;~O~j^VkfZ4gn6UXG1 z#9{9N6pCFs7>&D`ttn?i`ec#o5$zBNT<+Evp&QX4wwt}QI4>`R@&OFJg8m1WhLa*a zyrzdnLPizY1LRa1tGC;pwga*Md~8w5)}ZY7Qt!SJU9hW;(iyPb*k9eSSTT%exWP$g z+a)D|cxdK4%UlH_{Z~2f95z=3DfH+^R_uon!3AGm?UJ|iYA1Wc?M9&Z*ijkdJ!60{ zhGg0889YG_S{$;~!J`6aWPl4m!47gC3k=9&a;=@?KPaBL4vOI0#a{=FA4yf7Db3Lph%hS0fveN6g zwjMsRG}UN30=Pu_9dUWXPu@j6Gm~CR_8l8t`woyi)3LQ50nzL!aKxTB=N2b52oXG8 zU#Rp=zuJY7QJFvWny0TYu+iF=1o(pU!gn`$PsBOAzN*I`R4Lon^u+01)JIDd@{*8J zzQ7wZ#5^!eaOpLUNjFBwNGqPIv+RofZRe`5gac6a1}T}qJIXre%?nl|vbL(|ScD*; zcjn4U@0i>fZTw*W6=`MtsIW>4M)FnThQS+(gh^MI62NoIs@VT-g%SbuO3EW}R6+;* z_Ry7q!EPqQwf(HO`20RH?ovFR$K&@gMCTqvE(8JkzP0gv(Y`Sg-pr}2zZEG|BMgfH z3Wdlv#)4O434@0YrXV=d1zp&taAt@pKsp{ZNj~@r#OXhut71)PuWutxo4(036(Pno zfaJKD##5$`cU^1a^5|Ruz-moR(c8p4#Cpm51mI)(c<83ISav=2;DXqSl}W5Mob|1v z*lD+}2aO{IW5tI;u;et|=TBcakzMU5#;4xM28`Nz&mHjRwcJDQrSSG>kR~2kH`) z8x6k9mmkiOL39JMJhFjt4rI6?4yA6Y%}nbx%fu8!IB~Q}ZYcdW97I1pof|{#O^9UO zsRCG>rIKd$DJ|9+`dof#3dihIb`}AKY2}qo?bTm)^=4SbDh3R9_>XxLKLh`}uIF9n z=?Qr9hZC_oAy%bPQvH>%GPVmi?*4ElU&uA+p8YY}K4o{C~u;#8L%FJv=oM+zwD@)Rk9d%D|z+STr{Pr^SW@QeO^#ob%gguG4mWOdhBB72^AgflFH`aYmEVreifQ=cVeXQ#qe_RB(9 zp~rt!<^xc(_WUaaljddMc*w`@Gzjuv4Rj!^q$O0jw4%l?Fh5vd%^C4(a500`WlA6m zusA0?-_`0XwZoYE!&!8Q$+-pOW_aSAJ>lB~S*z=pPZYgrS6jA<7zW;r4*_}jO~V?2 z`larLiK<+P=YGd6IP=?GVe7%k$%eB!^-1b#LPqO0@9uwkyvE={x~PT1E2|v$`(7td zY7ZF9BU%WvNty{D*M;vvg##7z$n}JRKQfU z*|m9hCfpdle`;<2mJ*9c@+XJYyPXbH6L2&Gb5;Q=<>^ zn`%e)=Vt`yMoPVx!}VVmqfmWy+3z07D!MR#4^WB+!!n6(Bpt&7t{H=SnP14iGLrpy z5x3IreuGQ5_e>6(+IqI{GicpL60IpU;NIzPyVoC)HALD8Pz}~P7tq^yzcgpN=)YDI za&PMfaqDb{tFq@AieO5fh1=+dPMJRo3>V+)(zi0;StdXy3lFW<)5iQhbwvk8G_k&y_ZjXtNlP;$>{;8NpJ@dWMFG9+fCJqb$v0RP*zVo9 zB`$2)p^}%rEda>b3hdp6JIEE7sk&voJU9clDU5&RUH~rc9z~PnYSj2iLB5^nsd7{Q zh=Z}GKag<)H`^eK;oXvu!u&Rbh4JIhR+J7=}lIWGttUPMvfCxEWEILs*|W ztpx5q96So}%osW?Bd46qLbfdL&x5EUw+H8-5LJ93Z&T{xz)|0}Q(6b}8gl^53mo6Q zHAB1ZgF4#d16VYX4nPV_Zoka*ZCvw#ub+lhUJuy=(6*)$8g0H?Ofo^Qr$9pohw8NudBq}Z!Ryx)d$(j}$ zFl})##dLNN;2t^ly3>GD9bN7=wXv~O4Wy{d{lE3z9XZFT=XvJSEj_un1IC%lwi)`9 z*WsjK!$hCb^K8+)gM^QXmSrh0>ktx1*)Ib6->J_=1-C&`zO7E$I^eBzho8g2k9<<@ z_lyr^1oi?2_B06|*|NhW%5Ly^jK{t+gCG@Fs;BtPF?p*^*Ozk}IHLgV!T7;0=AGf& zV5qJKC@5&h>X@)J3VE8NfB|~^*V~PXb(<3n6Ev?zbf&lmXUbwNq%+=vRO3)ob^#0d zbB&rVNpEhgN|sHLJIMJ|syR$OLXb#%l(Q=IcYlZ29B-0=?Nyv=mZsZYju2%oMl$g- z_ai-U5eXmMXX8K8`_#iwCNpjpWTSI;N}^=A2f^R9@#f_s<{a=ItUD!`aZP?yMoYD` zamXY!+O^=pwnGpAL<7*JlK~Epl!21>`>!CBBWssSNE-@T{!+@Wr{ux>3_!HUoDW<$ zBfV+iE~X-fbFwE_&{4&`+#zXFZ#&AVxkm-X%I%R9QyEfWJVA0CEJjkdRL80Ahm zc-}TRbBv8ou?+&!6mrXE;x2ZGunV+J?M|>SmuI`#`_6}Y+)F7hIo18DGIdb_Se3>E! z<~pf92)O}(Dcc-)@Y%rqRe`sVYT(hS9du@)H>e!Q+{QQuXkTtbZ5MuyhruoHPXjAF zT_Ij2Gvc*XO<@#Klr=4n8hf$g)d8#41cGvx&@W|d=t_|v@_=_gZ#wG2I3?e>#%87s ztDoFB4=(?l6e;|2X5!jh$KfAhGzOP}R(hF-+AU6B-Rozc0r(6Diga*qrgC(May1kC z(J#U6-~xn{@92qS_F`V9G@BXdmJJZ7P=C7^AN^I}q1^zn1FaVodUT}{vH;?VeN{0E zKlrn!An$!)(i2tGZ=gSL(tJT^ zMeq+m$V6nYxBDYqn?sfea5aGuDsyRE5j+Bxo@JD?RvLb+{E;wk|VJMPZev#bARNyx9j0Es+!`N@DX=8IM*d&?uH0m^9Il~v-A z_5Pk+nrVjMDCejCcigUkwgWk!@=qMJS^=|soHzyDw#%@R;2J$_@cS_2kMScDOXcU^ zrb@$FKfSzkSYbOS*InfZLB#NFV|~)nb{p47bdH71<`@PAk>O!3`n;i8+Vg`*;#rLz zE{c#@&6EKXq`3cAe{f}wb%tN|iS}9$vp`FC;BJx7jlwq<^Lm?HwTRGsks{f zw4~^Nu&5zX%*C?{Sb30s8U`UA{ov9HL5mab6KWxY*+xJ-OkWTi9lj zODz6Cua(Q>fWzIT#jzVghZzZub;H!W22EJ@AScP2&D@Kl$Z1?8uKFo9S?^FpUqA(0=Btq_9)O8(_a#<0h(7mQ`>P5 z<08Pll|m1i%r{OBOao)rJ8hpMY^J<8)H+g9Lc(-*Y({k|CNvn|I@tP*am~%vXhI88 z%Js{~%UNl|>(=&1aQ95D?%jY0&SoNcJc?qOl?9j-$iBH2n4*ZNd6IO8r=@d`gKp3i z0&TYNq$Q`N8&9e3yNVF)DdUJ*A9^@N!obJBDpX`)*gt=0&Z+Agl z(DG9&5x_CrtTbr=t_Wvj!)JIEhA$q@s_>e=h}I0Y5tFtF{XwGx<MGDl*`kFD+m`nB^G%sQ}++DA~ z7=f&H?|Km`rw#msmVsDgTxQC55UJsCG!L@bWNCI6v~?X(|Lpe7@`nYjTc6 zn>v$0?7eiGkY!KQkUXYjMtOm*hjP7{QM!}^OKJO^He5V64TMf8!00ecRxGw^Ju~7 z6T{rLo9XTiX*nGPw_Su0l3whn==qlV%Y4$6NqW&cUrpj;v(>^jHzc^|12y5@;$XP{ z+gT8`1#v_7k}R9(woHIxrf18-bGkHlMc^}dVQFFS54=jNO_rCIda)C*x5P*uHPxm1 z+$rL8TR}UvFkqEkr0h3R!NilTu0ho*(~G{HvaLRVoSeB+LLjY?`EiXkxV0%H-5CX| zA1Ly-S_U^J2kX;V9$&gGYjR3)fjs0seoKFyqVFEP6o!D=3tN)H&L`~x@yq^{)eZU++7<|9}5)+%dR{df3mi_g;IgIp>=Dv!R(OnyeMqPrWtt z|9L$6WD+@=50nhF@@2@|4xpiADHYM*fwStMWZr>JXOrQMsc5%)u6iih?U(mHtW)nan`sVd!ADD&Y# z9kDJ`FY-!0h0;S5^APp&wB3WnDAS$F92)ZTQF}dvN(h%M21$;bss=9KSLW?g;HVJ* zj$^9dRq7-C*%|u#N72V;)LgRf0~ny1sQ>cW`lOlqht9#6l>3UP6G&V88Qqo<9Xl9; z?(1qn*_5Adb`r6r@iiLAv_Q$Ng_;GYv%~bScdL=+ge$7bBE5t0{A^O67E+%;p&`D% zq%bn)9Yu$~JKDJ#s@ir;OA2v~TzpIJhub4py@nm`Q+o~z6BYaOgmim@OVxfK30KAf zMVlo+mOK7xe|5_1ru0XZ!cS`H+DyXxWrY@2O$HV>`wfy5-97hD+&x+xNFOK0SD1Bw z)uU_?l7v1cN`u&)wG&*GM*h_NclHnjD|xmRg0glK5q)lUe4o*eVRzFb=%#2a^M8LQiCJ&o{O0;DsIx9|Yb{ncu&<9fv3GZn}5$@UZj);FI7iC zt8F~muK;IQgMdFE58_vCeQDxyq#Vi##C?w#3bJx;ep0ZF)1>ELMTz{VN`+c@RghHH*#* zok+hf+W30m6HO)p0|~s>y4vF`oimcGfM4#r4SVC)d!lE2Brsl>;dRxn3|aD+&FZP2 z_Om^0*7W?Z@hW4B83toq5COL@?o{5JxKPD?Ns+I%?*zWQKO^Ve*=FfYpWWJUXtbDsSWcLF7K>&(R!11#h zKG!jm)G9|l%+fAiV=A>AmWtUK4{2T}6B@=V-;Q?+?w9E$j61%fQvSF>a!ADu(Ofq} zktmy@6lTcROoSd0T^4+}QA>nwy8z!k7!5DJ>q_(I9^8aA{5Y5}_ygR8JvfJ+$*OG8 zciZ*)NcULboVd^f@|L@Auj_ojWv8ZY$%Vz!0!vTtvQ?nvoP zd;eUW@8h;=A{@ruIxU@=CUJX+IWLAzs_uoOXjHjFez9qjt)r|reXPiQ(^suQ$p%d1L(d4uPyDo z8U2x9MR3Tu#x=py)%J8v=5ek9JUy7N-PKP!f}Ku*K=$?ZRd+wPwQ(a{v1<{oOI3`U znYBnz&$9gc8Tl5r_!L`fSFzr?=@&xIhyW9{J9Cx7)M^AP?zsJuqU23~_)c)k1-Eu! z>e__L*KZziU73_AKNwBGe~pF}Oe0o-;FBX*2_=5%yOY~~S7X9etvmk{X5UNFv3gF8 zDd&{lKAEjE;Yz=3punywJO0+|b8NV6MTEYgPxW0`1769LVVD`kDSz;y`M+E*r1-AR z$guTCsS|UoZ`FBWtz~7onc(6WXCVai2de8(YyDq+?qT3K_*}KH)eP-(8i4RxXce1e zshaN%6>+L5o|}1wSY-ccw>&16ngvg$m_Z2V;WZmdg1I^?V5!{jmCof zgCoZjn^g7u-gXuc&`Inw3z+PDVY^8oyLr%+IQC9N_~j)mG4Dd*Vuj{MG73^b&RGQF z`7oFI0?3?qN^I(LhW5V@vZ`Ui#GkIO>RO7ozWG29w?6q(|3hzO6`Z5_sw9qV*%J@N z8)E!1!tNH?Qw#nIi-(i)cOh*Y?1&L6az7O%ar z+2NN!v)(TrjLzfr$brNJSM>=SAi6$<`ICRvu8JgF!9nZ)3(fg~>$hb~J#J;+6m)5A zL7JS&z-{BStY%=mI8F+XOFrl|1SGNrgV)OarR^GD@?wBOs%~!ooRs-~J~2nPwA~z) ze8W4w>3IG>TF3*WZNUKN98PrjSOhrq|5&?eG!A}0HwmhUrjn4|z9N2cP5#Ck-t?)Q zcK^Uu2W9AsE1*>oviN!^%{p5OiF(NiA&YKy(fL?A%kQtxnLBj?i&(xJAZiJcbMn=P zuZ5+Cz#>TT-1Ps-qd{!=_*3WY6O^0<+$pmChwRcT# z-f&166g~+9Oz;_=c+5GIf6EhxtD!*FB{{5_i5O3*c}qa`ExI0S7c472wcJ7|@+`08 zB<=Mt@mmI(mC70F0++rK+fCY@!NFI+lQ+6tFaaVz3z*4wAbv8eu-dScxs^`Bz?kN)88X za{sPvr5@mK0ZVM5r!3Cz(#fmug(~WK{KmWavO}~bTb6XM3%+t+CHPXgb+b<$BcE>l zT03ClH{V7^&-a7gWBl}#8ywa}ixkX^#cz0|a2{p=Lw|0&O%wG$^iERh1ow}iq1!9} z3YjRo%UxxO)zG;zOtu!CVKz-E;mT1`>Yf4(gC>X9n%47Vtt}X2%Szx7BxDmyb}Ih@ zB5uNaW-923y@uP*QYE;Lb$w})QMs-Z-}n-2eL!fE1a%)vLP5h(vb)V$czQQnS;=$u zjUx=K#obn~MdNuulN+ci{#Qx*@|qO#E3N$({Iwc#NujzA3%ZwFFI>jyA>=;U1TNwZoSBcO5*Wz2VrcdUy1*be`>P=biz6^kY2D;z{j=i|4i5)~GHvSsJW zQ?M{|&zG+2TNLl_B@Mf>4W5f1cTgH1R{*d+xBFSj0l;|mF|=f_d{BspzEz?jE z*B%j}`@Rl;eP;C|=#rARgjwswsUa+0B>;rY``!1RW?QWytTK>1|Aou!8F=HxWgP0x zeY}a1$yyzHoQ51CQ0^Uy^}P2qMWA<(P$VUVdWWL!$;#qb zZSP!)EK7e8`Ww!3hGu{G*+l$2y5BmVyLc$xzTMxKj85dex9_>cjN=}-<7A>CLUg-> z-v%7D82jt4N_hdn8S=HXC|xT*wJAn0aAvvH(>C&75$!b?U{z{r1dJU>B(Dnjh{p&D zt}-KEF5QT6{rG|2I_d&&@r4;jNsoV*&AQtxK1B=REHiXd&42Kdg9Qs?_E6%DHuVn~ zeY%x{U3n%mp{%Lr+7^oa{(=rud)P@Tb>`i%lk&x+3o`KJipyvk;NxVEBQDI z@%J^gPdy;EQ>~I&b$PgQ_aEj47iPIZoF3Twm#xUbYTTp{S_zW2{QB3CW_(>hExXeY zLvmy$-lSBe9Y_!uPqa2wf}Z61G+`F3w40O_Ro@hV&iXj~$ogOw&MmT)bmk@6FWWE#GKY zh}-LbbW*L7oK~ncy(eJ#o{UGe=Wb?$OOn(?_|A5o}ZjnKMk+J?dl%Sf$ z9ZCwGyVKAa%B&bo^ixy+T$!8fg9PHA%|?Ij(NnyzM-d* zsmdn7V&stXmG);^OUo_Y#R!A#*$!pZwT$j-ED5%+aSFs~2fCF=C>fO+D2~j0$_!|@ z_q|lR-RO98TJ_c^l*p3@Kc#OQKV40{;i!$wuA&9h--}P6=OLlnJUq7-v2b4c&9p5s zIh)CUWZL88L(yw*Gi?r)_hEX7`UxuOJpJZ{7K!Dz{#A1V+iU%Z<+_3;kQM9t&CTSV45`fdd6d!*Rz@ z!IUPX9d_(M^>d3~v|ZjWJX(*$--E|m%bD(&O9_<7LsaecO?qu-O@B>!J8%RJkw>_0 z$GL%$&vS#BQFOLHE;Wmo@^Y4L?Dv$Dqf>th28@xXNcFm@3WPHKxGHVTCLNS?@#h)Z ztA7oj@2pO|d+yx`-u>{GiQdOXAD3%hb_@J#mee?OSF%OtOh>y-$YiSdmPgA7UQ^}# z#(-3Z!Jyc>%(Aa<$|`2apiE*dGE7xmg1JZ!Ju9&u8A9-B6iNG%g%y!YMBX*QZt_W9;J#T~ z-YEjDCq;K-#d?>?P(r+uoc4|h|Y5gn~FPgD-3=(Zre<&C5iGnL3(a)=X&VEn@eMva7w_Z!b1FTGcs%EyX zaJo)TJkgOOo69R!G5saVl3}13i{7K*w`QL?EoU`9Seg96{c#b&krO|`r18Dk=f@HT z+1Q&oDj#0M_EO^emiA|i1U`rnM{MVwmiVypi8Kvf(2u=<-T1u=u#RAA% z$oD)J_6heTmv%3$%?E6i?+3)Q@$pv_RU7mz7d$WDgMJ;YYMYc$4xMnMa)syk zs@+L^PtV~g;y=G!GzrE^{uybLu%e>@VBBCev#x;#>cF;2UWg1lP6}?&z zk`R;JSpT|DzO(;h-S2s|BzEAl^d4wYdMjM=(Fw&?{gYh?tbMpW!I9%(_9n?4B%8=LPE5)6+8G5r3I$iy?qUedo;Fi!`63zC>d^3AVb zzn-C{cJ0q}re%m{*x4T5C*JcK-zFSlFszb#S|K3>zPX^Ee~BdLCUV~WhGEf{T-XK}5te{%{o911_bAPE9cQvo);FR&Q4FV6q< z`SEb1xLvDr`StCfL~jh%uI}sXP30he!arjxtn!^(-gqcwPNI%O&Beu2M;>D(oHF0( zp?#bSwI~k9_v?dBIm1)>I4NqKKK!=lrBfgUuKU*W0!tb3QvPri|08o@1Vur!>R}%r zK9S|=mlo@#hSwdF`u|o+`>z4(LlesSWoEr!+e0c;%GtT(ESJ8RegI@XKcM@bkm_F} zfgj?@CgqJSj_`eT_>Y3zkI=i#az}}|*#30_r=CZD=KI$k!9DAJcvgm-<93G!@I|T< znh;_%^*=xUZUmdR-nsBD-7miI*IT+61VM~&b0$yV*StzytU^uQxN*Z4PE@n}$CR#T zbQyjB)Ih+$&t;VIwtn^M*{{#|@>;49H3fe^#2Qs5+)xn8rlF+oGI5UT`a|#8{^Az< zdQN+`JlcP{bbkedv+%CvlbRzBUlq|uZ^QM{qf^wuV1{8(gc#yXN=h>Mj&rjCE2Jn% zjG>t6~vMOK?b7GD_6{A(RZ9fxJ0>_ZvHbXZCbEBNeguPd}A%QOYaygqw+SCsVk zGaW8gJfCq`WAU`vXY3BA0A`d{%=zANN={4ldmryz5{4biqfe^(-@8>F9)@-LNxu5; zSse!R9F^RMH+XG*2#$j`Yn$dI3?t|@^QQ+VJP;UAVR;b zdfTp}6latJEZ#&*$K9va>c}KPXaBcvSKcTeJxR?cHwa4aO%VBg0D_hzo4b@Q5qS$y zfHSii7jT&Tr&R{>=huL^DSwWLfAQ;8(D+cWD9Oc(ximfmU%qf?BiJ^1NG|)CTCA>X z7c}Bl-Mu9?hUBKhaUGf2&+t&9gX*p>AhKfu+dQ1duaHScR}E&<;LQI)&oJ%MI#T2+fiLvTh@`s#vImq>}3D6rr{o-8eYtLze3Ho!>2iR(&y#N zWA)Me8CrKCTN{T)K+nqDp1-Efv8n$6;E4@XRcAQlQ|bnw;b#d-1v%L4jjqsW>fr*V zUrLrDgV&h9U?Z|STMy@ERD=UjYNZe#KRHwpgEju%tQi;{g@712Y7fSBxxW}8=rC5u z-Ux-{1n5meqIgYzf_>E8kJR~F4dYhgmX-;KYx;_9C`glJXi#4l{`(d>?@E5DBsvxDZ_4a zXn&6d%yIbaU{2rffNlOHHLiQAJzX`;%;K}H-sZrkNaMLWgXKnBFj55MQn<)CTF zUk8r632^ZW0-K;n8^dlXCq2JGON|6W$T9es0<{aw9t}RX+38=zc=6pO`_HcQ!2@L; z`S6>D_QUB}AjT)vqWk)!_AQkndZvZLWC40esVTyz8lzO>p;?8(5kq>LKe21o44uLB zWW|E|SoPLSMmuQVrUy#%NqieZS+BrDLMK~v3 zA=+OYx|NhzApnsS6*@YCJr%CMp5Mpe*-_HQ04&%o)x+GH{OwYSpO#Vzg4yuDdX>C>A5jDt9K*l;A+o(Bn=ig@9f<5_5lSo z|H}h>bqzSIRMSWu*46(Bz<(c zH$QFD=-E*u^?S_xOolata=}Nt(DgL|`Z$5qzD#`$ae=BrbPOYPpT@^~H=wDB6J{zL zT%#M{W(VW$oEBnP;e<&1GDEs8_clDesdPl*-2@5L2BrjOk2&SV+4x6@^znv$Nxq@b zNN|`-$Z6w~K6>`-Sra4QY$vK|Z{YFKma=?jP)qTEJ$gDcciYWCFI3oIrCUs*sYm_ut=vKAot0TF>-R-!rp}>Vr*?_TZ=1gteCy_1dc- zndCP^#tj6dmbdd8Ayv4t1xusn@_ru%)d# zsr)DZ59F#^re+&0u9v9+*S}1WO!M#2Dly(9G$($7O zp>~b2LznkZo1bAb^-T*iXsvPOO>I`3`Y1Z%z)~jQlx?AFao??yerwYA=t_W!%$BdW zNUWF(&mbP^a{y?8W8$W^=A~n>Pq?5S7B+Cgl=dp#cW)uLFaS+2gGH%%>J(Gko}ZH7^Lf^6sf95qd5Z$*6@(`?1zH`+6o&?-W^D_q+VQ~qSv zQFa?zAe%U!khT?`y<@59cFV;JI*~x0l$=i5vfI%2+PFdOY~gZNwgZJ$`}BYtVUMPv|6I6% zdr3AIrqhl?PaI{I4$37PA@{AA5Oq2c)4V)V<0mUR^jX2csT)&CX!iTW_Ld}>g|vR9 zFvxmG$YJSytb~Vlwq7+>S=ES>{}gE}bMmZL0Wpm24%Ll$fcrI$bS5ZH6n zEyA@8wdF?0z6E%LWF{yZ`uw?`&(hG5a}}4m)S(A-WA=tedydR0d1nhsI-n}EJ)S7q zb2ufJH#-zp3ZO`{dm==Byx0RXgJZQAsEd{viRHh z6P>KIW%ZsJW#Df?6Dd2+CoTVkLtDFmwu(#~tzrYlOneDEx*{#oo8mCkNbQvnJZ%k> zLqwI~-7Kb@3G+-Mw070)hSm}RhgfiGDdp7OkN?MVVB^`BDGKIDWvX~Fo4*-SYiQjW zTQgnkTqe3SCZDFA&%#gz#QGOnq4uq@1pb{&X^9eI1#UQ*Hk3WIUbdE4WL; zI{%rLMJPtewbI2HToM_R@K81>awx00GKzi&)XZ3kR@zat_S$WP+;rc{d|8N|LM%GK zIIAIBF!DhM7z8$VUS8*u3bd+#z@jfmTCu7~kY$nW&{OFCs){wayq@1EkV6XD&RE7Q z+d<<#lWm_Rs}B*<%%ZbZr=eSuv{e%NVktUBqv0BrN|y|Y^E%$xW(Nl%G&eGN41-;c zyipa9?l2AQtro0Ofu&^P33#ZXJ=2F0himD*rOzs+TYlejw~>X(oK+)Hd8lgX?puEb z)*C>4G3gq2zdVpmN}Yk_GIOkX)yXS+dX_rTA~(}m(VjThH#b0q?`OJTqvb$}&0qLi z(1rFMRD_G+CZ>=s`#ZxmvW!yZh<1Xzm_+RF-M6@IIRerdBYOp}6xX;~N^ z>h$fpB0{}}5wLe6E+R%_^^qmu2KChxs4nAgFHbLll=K#Fl%!Wxsr;ufIy5BbI}B%Q zevuwh6$IMM^WUcu0+%EIdU0HS&wZ1zDN8vn^{f)=l!zT-S5*ddMNOfo_RNn%R zQcKd-!sm+XSd?NZwO+nOM_hN=Sl=D*Y=_}OeOF8V*23^@oT%N+8;f=DXOlvfErTTB z^=i}Utd{J;5t7#3MFZhqwG$qG27zkY-FII(*JIn3SN7PISJ9827-BF3p?#m!(?{9o zg^bYm%;6>wd>Nb34I7*%kUOtk>gL%`799z)65Bg=%ddJuTLB{aTg}A(a3wH)_Qno$ z$Gm#d5%cm1$yqNe&}N4#)Q7T$l)5wn{2iw{Smuy{R-|8_>!-}hF6!PUJ8^=SNey>V zh8QSjmXfE?oLHcWgsXA-8P$9p#LcapEIn~p1p&cVv?;ftd+WM~nG0CX?!5auI0 z4&6u2B&NM=XuSOUDEEP7E@EIg{U-Y)6%XUw^HC~slZDJjtGMphds!pvlT9(k;Axo} zP<-?!E`xnk;~PbDdxrG3gJ22vDl(Y9%uP=r-pnksJY&`WIb^VR7DvA;k~&l-eF%Tq z7B}r0UsOV{0;=`Mr&VTc$?b5@0)?1`b5;@c0y%hu&pz*t(FViG4h()7_9?Q|+-wI3 zBsn>`muNCe4&xNTHp`)^N^$ z4po}%+9a{RWA{pnP;a{}CUVB1Q~83Km2;(eHnzPQ=P?gEn+WZ>%@y~n+V_@nC(y21 zNGh^ws)X6pm>*28HoH&2$|{9io$*a%NpQYtZ(5cj-klXw(Vb)PMUn~1_`NgvQojm5 z{fmI=kqlen-dwdjK_C}Mi)4*%DtAgZSmNvg?nG7ZX%(>wF17WdNBbkG^ z6S_5N3Ht4#V=SJ$%p55b@X&4PP+RcF5(%jH5+Ul?aczK;BdVY(QfbY+n@~TVI}OcIdJ=tKprU@Uc~p zZ-w+6>V-k-T`Ic}4UgqpLswhtR+>nyTov<7TR8iRta!ZwE$Fr`2%cU=?q7=hp^h zm0a)c+KyJu80^FDFHycy7f+aJ#X+JOWh)r4B<540-~IcH^tp1~Yf#K(`a5OZiT1uh z?J?2xzS!RUiS1ImCYB54Ya|aoYPMBaSAu$Pl+FlB)Fm@NvSv5kX%_A@r5KZ;Z##*m z1oo08$L{`O7^Ns%d6-O_W4RkThgNH)`G^Q^NGYtM$xoMA=r>FYMPq;L!~EWLq2EpV z>-QjVXdQ*@emhiZ^iQ-EN_yRv}&m+RI3>DEBvCoW`GEXwf(D~nS5 zQR2KeE?VPfIc1AFV4P|} z{o>{dF*!9O#N}6Z1DU;f^4YP%id4Z5(p9(JJw+bca*o(eEEx+wT}X@-v$?D;S}EBv z1&LPP^UwUd_BN>UdB?%2nZa#r2)AJ!bG^gD16$wS-&%n0xGB76@=M#IQX&O@J&Gs` zt1UOIvm@{Or`N(0P9A|WjS;S@d6iz5?y$7V{29yzUxHnKOXutVAm8;eUmQ$7Tc6Y{ zw~lLZN?3Qn3U6+vB_zL_77x`fuw=#YEKIj6Jd~L@cuSqzF5^y)Ozlz?GJ3H{T~4jc zW%dUjgGyWOjk(Q-`TA483h#WIC8J+vGwec-K)9ExIc&t)RQ2VsSDim_?aBM_K0CGHVD+Ll3uM z#bB|dLrzQx`hv#*|@6N%bn&OmGlA=_)P=OvZ{<1O|Wa1+>4*POBXkdN!|M#~cX3t}5KAjr}#;!F6{v39p5 zzC8_Lkf4~mp5O8ld|75_xukthE{&kuRN!_poypv%BR8k_`z(?#x!y6O_O*DK{m4~! z4yvH!1iX#i;-Of-&}(|yCZ5ZR1>3vmXJy=Fkd;nxwBV5y(!ZoXhbB*N^%yeC z1?H^I^mfF~o1w~_A~X!#IQm!x5rd&iNlD4o7Bu{>1?aRR1fNeQ5|64GD;_2k8&OgK ztr$afYN8I@LP${1Dan{i9sgpKT6v6Pk5wJNWf)G-wl$eQ)%Y&?`|DoY8+<}YJXB%V zu@fPX2PkMZMHjt|dJy+Se4X2{_Q#A`MzZ1!rzCPZ0rqBdbKy9@{=yIdT7&|%fEX+e z8_m?qPlb}Gk9MpH4II>O+0|22i+Su#;U)s(GQ{vHbX zJ^mXe|AL`MF?ix8tYI44t2pes*OsZs8g)$%OhLNET7sG0oTQV`r53cdY;fM|PS37Z zNK-m<`t(R_Uue4O7|LN@`zMoPG+&-0N<=` z+1uj&0-oV4{e{{dCS69<9?Wa}3*q zcFhLOy}@bN2WEi6Sud!Ogw*8%0ZSy*B*Sl2rd!a z%P1hgLb(j~ib@lN?QX+~9By)>;KduZ)_ay8@DeWfDkf_=2Q~$)iidfmWDojH8*V=$Bjxf@=@HiVeaQ zV{o&dfdjpQcRV|%V90Nx!t0DPT#fJ^vX*wRf;Z~`5H=Wa!+LisXt7uM{8(mc465lc zA41}v;1yU}`cYEv?&RT>1-McyXq3pEDpAm){ni>5W$`wK&+1yr?ZBcY(M(qd)4Ao) zitPb>+U3;bjPA@=%cL&`0T#tw-6^~Z*lNV-E3#)2``7M%F#I*u$DDn@0VpbF?<|}8 zUAT_)q8`GdA_rDx9-OWDp1UBi#GaCUnq7^tapn92-U7B(2^L5hM$@tTN}yJijFS!~ z8xuMJ2gOx?YQCpuzD-FEXBCfQraPKG1K%0`Dujh1k$5Y_)caPK!RqbuX-AgDgb`0K z8|5#O+pnX;yqcTJm&-ijUg6&SHpKkd#2I8C%7DZem^2+Nc|N zEVwc`VC}kSP%bz%vAJqr*SJjO<~cdHtPovg{Zr$6wEVZK8k3t^ug`_f5XQgrPf4wR zfq4fp7_+?8wA@YMft*hm)cWk?`bzuF z{FW_(aXmn3qs%#9a((;t_DT5Sl{Glawdk>nlpfvAn=gzOoH}2b^KCV@BtK+pJ8rdC zN0Mj6YpQBjk|TTb{W!8{(A^k=npa+v6cqDfcJoXX%_+~?-G1c~S_oHlUbR>*5J)bp z67#U8F9Qj8baDnOn{s-hEx?H|H6`?^{F?H!9s|t};q!z~joC>Kx4Yz-$O5_dI&T9F zQpwMhy7RBeJ6c`kNe^V;@J|1OHw@xA@-y6}zVs;+=~?Mng@trh^?AlBiBkAFt$Ktj z)Q=wVtb&@GsxD4RIbMwQgy+UrcM-wS0pa=(!5s9!pbGNxw__d3;uE@!Wu!EWaI_Y&TmKmT$}^$fd)n(*s{>~ZNF~7J zZ=h)K=8F>zfE{y^((vbf|GTgQsqdjy6~kNS&MFa6OiUJ11N(_}ETY!I4TAB$lSOJlX9=J8{ z<vMayv$kj&jQU3YnGFMJ509xjR; z(1^Olb@o1rXpS@P`We<-T`l?ed4XAP`{sIJZ9o`z%6@r7Cxx;ED_7-Co)yJqsbVDs zZ)?=+E5AbK7d@X1$E5u20X@ZlKNzVm>Oj=FIS0}UUtXQ*c5vJqRp6=*;p88tBNrPg z&e=(A}7rRq-J(ZkOwYe;p1uAhhQiykzoupa3|P?dP$xI|-{8CLy7XqOajxI?T%Ao9~w~5J}&` zO_Y6bjgmbEP{lvSDt7v1>4`YhRQy$2vOlJ-2;ObKbcGv|v$Wd9&UESu>}&AcK?(Gf z*Z4J1f_Y_CJRE*nrLKkI6v@xu=wuV2t!-?s{~jyja2f7X=}+4pNcavAI6MMJ+^4d* z8;sTFdF^}hO4SE5O}vp0VKk_6Z^p;jjkr|k2u=;bVaGb}f8kO8^By1TxNtmF**V!? z)}Y>L1OW%qqz6IEf1J9xdO*!fjN+2#ps&y32*K%DTD#c%%8?W2LxCQx&qP%F3v6_n zcf1F%r%3T79!eyuAAbwb4x_og!uDjD6Y1(%eO6aCx5v^aD_Qd#i{;)>U+%gy$jOi3 z4;-sme&)r1Q+Wisd%a{G_MZ=I@u!@2sQ&RLYq78?BrYz~1huMx<5n!WO4imk%{xE9*SHn}g>yt`t&`bjNy z{#T6p95-5R6@nhG^WBfW^bfd;MxEkWvGO|8|xjxmOCZ$w}d2)t#etUibcSK1) z;_!Vt9OfVfP)9xI$uh6+egE+2ad_ zP@iF8>tY#RPN1{LS?`=cUBVSySJesL#&;CMfx9q#JFrA6ntv>DTs69n+>u>++an)RII%h%=?8ebXt{KsT|L?ZPMaI z9c;sk+G3)}Xe7kCd&!(JS^alPgvc1B*2hl7My8)mWVsz^_eZk$O9X*W1c|Z+{ucOP zez^bas8TJ}koy(5a=Yk77jQrLMRPrm8ieYzIs~$`>w#-*DsWrHT6uo&KGrI8btHHo z9`%dX`VWhH_$wORm}PI@em&^j-gcCfo}C=bersOeQqR(5h4kBTP23c#%c_wb%VEeA zp=4O)!wudG<{d>=nH>y5554d1&#*0P!sav{&9W7moQK4KGh(39C65p#&K2-4PXAYk zm7~I)v1<9#9_#X;|M9_<)^DlB`vk_RyFSU^y7hdzS^=5ezQ2mJqG1!Z&lEgGCt~!{ z?$fW}SSzwRwY?U`K*@eR5QTjI>McEQtqUy>cO`xFjW&sv>%*Bn%JLKUm2DCxw7dpm zV^AJ4S=SekR1+6|=X{=emAw}$X7+L0>z?K*fEge%!yVoA);jasBFS*Cr><*1o z_PXSx_3U{t@3;qNoW9KBNl|JeGd?Quu5((3$9H3K-&~MFu=ry~3O_=h5V1C~JC*ff z>e+W`6?yic^DX|4J*#ZNGoynar}R=EU%sIwv$V5rqoG{3GReQN=HxWr(nN8|X`i%2 z&;l|)=e@z%mffmR$(r50QT?3#)rmRNYQLeBQJ2>}rr{g$6hk#$C)TYDu>O;SZHxPE z%3D>lURIduA*8Cy>Xhcbo~f>6j@#bs^3GkSYD$)!-S*XE7Rz~#50=W~7j?w-QUjKM zr+lS;nA)})Ke7YzjhC-N4~~ZScZ^Xe|D^HWcyZ&lzh5+eKF_I7Yx;0jsk(l#2RdI~ zg(KSZ(0z~=Oq9=82imd5i8_Wt#THWs4sB-E=V#17dbCLOCH8RH=1N~&`uGE@d@Eb; zlyIdsqoT>X*si$?uOv>F=zUqNP>9iDly!J_a`V<5iDzg3*hl)5$2e4Ld(%+(TR+dS zy|;kFcTr+vLE3zyu{Zk1E&%cS%b&5Ih%NTSO zQh$@3Aidp2uF9F`Uy@Qb*N9#H$17W&dAI>jk8-nSXLD)v1eXwUdoA%sdzFWqPIt8f zMt!>s)1_D(I$%g@MX$_U3mO>#6=lpXu6Xz@I3#I74(M67bGD0H@y;NPV^R9 zL};0S_s2K}sI&qFRw_icSMzLd`+OlX*&$u11T2;Hj>h`-I{_3H+JA>NO`&8==}pH4(UsPbc&ryGDGX(Nh3*$okWBC`Jnu zqMo26_vQScjXfZQ&B;0noLkM{l$3HSYUqN>P`e z5tG__3d;u2E^U5$rBdbYqO)Vz|1OL09PmHS(OYgn1T@Xpr<=Q+=jZ}Rg^2BcPBRCyTV`ZMfwBo@3Y*7vsCw%X-N-OWA|@LS;9LaiQiz#Sr+NMSDhZG6pS?8GT0n{!z;9qQ*xs z`1W~_$@8~aQGE*(X#$|ftQ2Va{#xM-oLFgIzjC}qa_=d93WBjQo>w-{q~ZLW7>EW$ zTj@BGTxUFQjjTO@>1G}~XukA0%MwI{zmN)yWspoZ?EJUZ= zr`wsPS7-B=z*Jb4CKY%;=Ej`U=OoKZ66H)CPl>*Qh-tJNWr~9K$Ji zyDH=So9uEAGAv=REjhm>l4^gjG8xw=sGCG@#r>gLq;pu z{PsVv$wgdw2;E@RBq;nUlR0hqklNw|XS#)Mou$>4>0&*9Pz))+4PN8%uB(iEd=HkU zTILJcQg4(U{lTV@9SS`;^+}p{5}d8BGuS`Ky?3dt3=4vs@Z0`0byTqyrSS<~o8O%g zkh=9X+ShHFQZNswuMgO?wqBBMq#^I)F>PjN)5uxdwEIpRYI2Og-awxBpkR<%I=67c zTf%8t-^J@^S^r;lD0%%)assUC*WZL*4OP4I!YD-5l&b+tXllIfW0z+)M76n&b}6>Z z@SS|;_UU}koey?V5_ZNd7pI@OZzuO;k)*9WBWYFL;`Ltr#g5|9W zGk9KwPOJ6ajQ}6M$S!Yzs?_ong$ULwH*U!1%cG$T3a3Hl#IT;{x_{Gls(H?iMVYw5 zb~BGw$oZa9ywGV2N}w}&`Oykt*Un+aK(i56<}}2C%LxOAhLT^f7E^o#0R3JLJLUkW zUWoVh$KRUBKu)|^-w%?>AiEWVsQ+8b_)Etlm6V%0sU zCMAy8+hM#9Om&3&(qi3`^cnvI#y4xvZuCp;hck}k|D zMMKBCov@M?1Z#2o@nJt2knGPWIf7(n)Yz`7HB7wYxzx*Kko`88RVZs>S-ABC=w0=t z-v4qx!ezl31cr5QPw!5cxsJ(aCB;3k+OP6hf1XC!Be5DxS3yOR9(%C4!g&W8E&)PnSB>-*Eq8|Cxt7sDFH&y)7r z88=*<{!692i2EORz{ftgQiFlE1CfpMnzeFpp$Ud6cOM0NNb;dT5>Wa z5J5DK2;Og9AUVJWMG)wcXJIjO169b!UCL}k^RU6z|knd6*Zn_t} zk0gZLNZN6iM(wD{c2$0!omXcZ*!V zmfXC>skeoArUsX?8MTM9*00Qz3R;0=xxSqYS6kIXr=hbkQ>+*Q(S@zWn%OFPREsb*`Uh;SV1 zcnm&+%c1|&Kd0m_`}{%<5HywY9jQxS2+8GAYW+jZOyngk6N%BF_u_#T^C*4`^#Z-A zYX+sZ#!(C3DTBes@qP6viAa3>GV&m*10%?bQ74>PrK&y0Qu(HZmC0zu5mNdyDl+kA zs)JllX+=jJ>Ri6PU{kq@FyYO~`<@rW!>%6fJLN_e`{sNmV#rIKjG_ABguUHc><`4f zlpr&I2M@!fhx8nT6pZO-T%^?+C>H7naZ;L3*AF`W4kqvWF&riZ*c2ib)3w#RxjYfV zXRg|vb~nV1bY&yH0_b<1)%li$z^zh#6N{dY@7%B3zBhtK+wVIxpcChgh<O0hV zb&-P>mSb1(!N;a-y8=6AH$EOEC%rt<;KWj|D9z8Fz~fcUuIqBKEkdpa^iA~Yi`A%6 zY-ozG>r(P;kC#ASz$%Kk`SoCH=ber-LQWd27agumMI2|clW!x4f99tin=uB6YxbW^$uy!IqN~sT&fj|eF>}EX_lm%N_KQ;~z zey-scczR9`i)YHeWU4tOa9!yCI}Ov_&MsZ8$!2$cUjFHT{f%@PCwJ51WIX&$bQ5}K z#1^~psgp4Q4x~L6>W!v9bI}P|d>$#6cJAF;*_zpI{^4UdC4>0#m|lVGrT56A!=7NztMCvWeSgs{HJe&Ajt;u#mDyYB*P5Q_ z(wnOE-DRduE-&gPy(8BlB4adBo5EwU7_X`D>A6}XOP~N7$ArQ-U(%Z6Lx#V9YXOQX z(~L2L9mz}&i(VuYRrr1j_jy&}K39aA5lK*;%B++_E>zsCk5wstawA=Zxj6J{tlHA} zvGA4Yc1?ZhU^+SPc%zk*zk90=!wl?a+Qa>P@e*!f=nd+QXY%hg)NwGq_eNmVvqhV? z{k3d#o(`5ve=sZmo6De*Q<8m%#bCEUT41hhHzkrF17FLPs0>`Vd%$zF8PqkawUM;VVV%4>` z68UVE;q=c44)>{Ny>x^ph9)XiK8~+&+Axk6R=q+!_kSWI{K}gH4%edG_Ja%VrKCt0 zd8Dd=X9%?rMFm0XpmpAJ%Uju*PsoX*H(79xc1?GVs3G05$3>-T%O-7SV_Tx_A*#?k zR~NDkbFJdY0gdvPtjlNer^`@SqN%BiT}EULmmW`DTQcfj zD%vvBI>$jZX0}_V5thv%O~F5j*rz?8HCAQc^i^}aK8Vx*K~4~IfbRj^;d);r;=|%3 z2YEz&e8ktR++BbBy%-_H?}Z68e-tX$Ny*m7DQYfxDJWQhC&lVsf#`!>xp1JOC7CCHz^P;Oq% zoK+AtUxJF2u=9+=9)6Lau&#LOB>qC-ee@`9dDDu2!|aJsl^@^Gw7Xt3?RZG!f`E(1 zgbZt{cSD59FJN;Axuewf$U{euQA{7G91L&Vvl$Ym+l*p#=P1o&1zbg3d2Yz2SNhAO zcby0x1JNKKNO7F8V$(bAn6aSY53r#H-(pz%EQC8mx(KT(ahE^AT75ppv=8d|e-3gPvhcD{!1dJ0qyeOSHV6&2Rq8iNW}hq`X2ewv8|FT%9wcipG^I#8YY36mF%MjG8jU7w}!N|%01kKjrkK^i6Iq>VHz5nE!h6$YCrT`fua;{(z|~p7X0fA^o7qWOZB^+oqtb+EZ5l zT6`(LOu!aLD@Xb9)Yg4P;1!p^JZzH3Pn=9tN{B{o%isMdm2*>mJf7=Izfa}*;JehS zs#YYc)tS~1D8zT*G}zMqs^2xY83j8x8>fEPuE9L`@Hcvt+EP}M0Ham((WfQx=qUpy zdF?>nrele^#g-aE5iy0qq-Qwe?dKSwxrv4JaL-Y`tg|Rs=TMTj-s(3_|z4sa?U&fi-qDSkK{| zN=`Q@Yit71W>S!ibj-U#Jm3A}ivox#hp={IH11V-C;mr2B|4GoE_m&|$&y+%@u_pS zac2W~P|dSjdel~$bK%eS_;#%fSbX`b?7(<#+KNhVhg>naY-Y0GwwZhJ3P&-DB2O3g{bXqWLIXp^Vg7731wr8!7wwQwtB zYfRESIM&3!A8sW{FjycQMB3|jVOmn$pU2;jv7GI&Y3m? z0tl%hH~~`AW=|AwUp8ZnooGE}Z{uj7ScBmRZfWySn(lg?x8z?PpSftv9Dl_<_fX1G z*lHv)ag`87rxxO_3f#b>taQ6eOx=J>Kai%9LKSp?01&i%X{+An>+Z4=+{4XMF-01~ zFAmi9m$!QMlsk`1{UE;+fni_c$G^=xVPnvD8T(~|=+?x;xz^iaFKoqcq>dG_-}FA8 zi@RAE4y?0tvUI7tSZDtvsXXT9mhfUsP(pV<-cW0ZsNZeC24t9cWp|>e=o(m(4(OnF zmZbAE%zKwWke#6t6n7xqk9>WBI8C+>==^H57vYfh$)(YqFCWLVf_>6ovru9`=-Gup zjg??6vr)#gYat0*^J&B^eig7-!-!9?Zifjo?lU+J*v!k2wz}J%*%1SmJKK}$&K&k` zxm(;~w9pshk8QTaNh;#xC3Pe>hybHO29a1Y){)a=a7vgzkkx zHP7sKV$%r3+Gg=XPr^rqR#P4)V+|9MS9bnrrCY)Knsh<55X7#=Z8NZEMov}S2z~Ap zP`TsUJd$+{1N0rfZoWIT4eBNhlt0ge0eB1F*~dTN$v(M59ST2OYF?(4^(|d>(t!(e zMari|$axLAT9pcA{vpTSL&!+kUejBvUQbw6X&8r%wF>15m18{Gc`mpn`AB&OOIzMc z>F+}OIU6>>XMKRL+co|)2S3+;BE;_a#9_73c%AKcA{NW9bK<9vL-$TYSNg~>-hV|J z;1_S!9vYc;hMl&flwrc9-rb7>;AT^nK3B_}TWOn<=&Rm@Fi*}&K{t&8@_V|gT!PFH z;pi{oqw?Ft_o^^ryyAFlA78x6>QQM2E(yzt0;hW(T9Olmhm|r041?8CNZV1?)b*t` z$&)`p?41?iD^ zW>${W(9P<)Qc1dwTkh@f&a}1WzFk#}F!`80-kdhd*77c)mdFdLmdg>zC?=O0n_Mi^ zluS@`bj^oc%l~fH1OM2y3J3(NF24u_KVL;1Ffp8LyQn;KsM$deU}FRG#HLO}t>h1i zcI~Zs+#s%;&JAykyL@ge`px5+dF*lW0QO9R=a#0!m&qwmQQW>!VCN)}P$ zU$y=yZrbQvF_i7ZD9OtrDn$)k>z8Df%g|jFmiJLNJM6M>8UqTZsF<%yHltTTrIDE7 z?gHX{)j(ND>gsD$cn~ndnQ50Cyl<;c8)4 zFuf9rbquL?F@7s2_fgJ>-_&xI+)ZcC<==`l?;?_)TD}~2XNzVwsm5UEN2Yw*M&!Gk zS`IE23Bioe%=bk73ltu-nab5hA8UycCb)v)u9|1OIB%mA74GupFgL53jDzNkW-;5ru?qj=t6nxlwi~Dh44!g$=X|&$ySiKX!?|&) zkdn%*QPo%7GCh9~gU%@rhekVa`2#cpcw0GNSJVAmGc{wqGqtOwE7`f~BAx~7smBbA z%T4Lx=3bieb^8t8Z@W*2Hbijlj$VG~0CSu@c!&FY6SgZ{TQWs$_0lF{k9=3&Fogu3m8roBfa6-x3) zKjAzlASarqS{qtUd+}-3oX+XRns;dFFRz@2|L7;q3YZ_TO*JeVy|QbZ>SI8>SKDJL zN@)!kqX>ocB`HzF`@pLC1H%FAEc=K!J5J>wAtW1Fez@deK0$uR1mOcUx27fYx>2tQ z+LHUTqwDHyou=nuh&f3iiSMcX2TThb(BizbkE8b7yr3cOL1cZWb_t3_mhGI zc$^7DW`{EU%g_&k-GAJbg3Wi_@T^A(H0U$EGaLDdAd;o{qq$jEEfNx@)o(P^>guuM zmhkGAw~hR7ls*YA*ChvIzF#eKFwAz7^TS%Me#MY2UqX^|1d~V-cGDgVt_4-!T=lA@ z09|;0-CPvg&5iqQ9OMOjSB8f2h9clzAcQ?QcfzZm>QJN(bW+MdhDv3iKMCvz0tae9 z`){Zwe(4l!9}ol(ksX>u^@ZdD@GT~ZPo}>}xV|}ayHt4Y(~#5LRAz*K^9JGDctF$K zrO5c>i+wUC*OO$Mmn@o2^5f6{1x*(Qe@hxvY1yJDnkb8Fp zC^WkgtF*W4AMdFFO9TNd6)!*ODb7WMSkvCwIiIlrQspE&~x_z=9Tz~^aDEj6iM3p}X4C)n~3 zSmvm7@QQNX1(BAt8twxA8X28pmw4%{`R-v%K>9>$ideKC02=Huzk%4mhCM=2?3tK~ z|BgKqqD)=1qP{A^`VCW6yq$0~0KpoICT#mI>y-NCB4SU2_(pYElnDFuiq3&cdziNa za($Ef&R^o7Rm!k=vM( z7_YA762Wvc-&OXI+&9UfiHDL8res!UkOUw<)#(GD zfbyh)2^1@`_W7xlD(s%4>y<^E@j_jgUR<5;h19g3H;D>qX*a-GjZ!1@yA7-$P@Dua zBK3Gd-bWN~E({p7m8%zTpOG-VcyewzpO3jm#FDY4l2I?CQyVTYGIF=OP8RluTwI6J zMXBc4LP)$eog9}SSNyAm3=YhMoV-Vzs4={QQ^EU&HYKG;fY~%br?)}SZ@5hOSu^<43$Gsl!#8vyQ-Ny!>sf(gr}vBjUf#H_ zjXf1rE&Uj_{LC^^*870rOC!6q={;^kcS_s6>oD#9B*^p++r}ELG9zw7?AT_L|fiiq-%bL~9Ejki(Cx{h+Tp~L4(9%nEX7ctQyFtwaJ z<gi@OmkT(g1d7dQRU_Xk2%?H91LQn_J$=sQCm&{9+&^;t;Xx%g9py zY&rvb4igZ_51(}CI z5uF_1I(~OKw9D?Afg{q71%^fT)QOLJTr8X|#6+VA^resvF<(A|T?LJ}S{R~S_w?t&1}(hnCu7IfR_6$SK)U}Z}p$0~ zwp42ki*cOWxG_3PLJ8X@07Z@e^*0xVI`l2J^XH%X{6;q+a0+d1JfWHIWAa8ptu9pMCv}b zyk`5VIa6~n05T(VJ3%l#s{@3E-kgMBv=m;TfS`e}a*GR}(X3-@758-6=iT!5{oI)6 z0Ic)vUgTOw{}8*S><99np0BqY%ZRPFF6(R)3O5%%4LXdMUb4|@B2R0&er2@<*wFRo zoC_=1(eXRJ+V?+yUq33-THerm8{j9l?>u}&Fy=P1>&>%PjlFgdwN^xal4IqORKu*1 z|7?7VPD9;!ZBD&9qK(6>sIJI3ooDAsMQ(N^xZ1{&=zGcS#K&C~gxZG$nvy63_uwi+ zA!GL@JNmpjTacI=PpkSeYHPY(s(oM(&0syJL<&c)9CIb<4!hW)(AX2VbBLj{@zD!S z#&-`YS9z;`mbJX@>$y+?cC<*VvAdNJC?M)yvR*G;S-0W?_n9~WBe+6T>gZ|EFe|2= zx`$sjuo`g7NDi87RA-i6j)r3|f({#<3$XzBs`m7Hw!#XgIYbk7J+BnN1GgeJ;?%>9 z%kMD>v%Z$a!IdL?;?zT2MbsZ74!=Xq$~#fkfKKG-!zFOWd#D_e}1fPu6 zn~U(aJ6`Fa!p2wF1Tc9E?;of1t7a?mzC6^?NDeU>5gfk-mPBNM7)AwHp?uK`nhh1$ zNO$*@N~Vobo^`_Nia!MY<9lXRCeipbc0%#@Qj4G8B0(YWoq9#0u7cMtkYGnzK zPlH9;PS`iDpSJtljQsTH3pr(7n=mWBCxN`gDM%lNVjmoWOeFBAGlNy8Qg*Xl` zsT|EO3mgZKf)A&8@%h7cUtA`HN!Y76R;Am+ygcoL7Hjv;XFaX-%q84>P8G0)t=uo{#h*gm=O**+nHON{z)?UyE)!$}Z z@xbkEVLw8RiL;8AE-cBt>d?#da&-Ekm!v7ILIVzA1(};G6s!muD{}FW&kKp1D|pD)m#Wqv=bW%X}Yzhcc$=09fKXVh1e3h z1afQmeg__S>QDbV(G**$#?|wsIB2vUc()l|4Nf1}+e&NlbV zXC_;xR{_GWASJ+V+PSq(JGyQfCloksE%*wm4OdKCl)Bp7!xOiPyYlbm7(zIEAvA%0 z^QcJ@T&erJ5vKhw_mZB9J281z&$b`Zx8!zPKk(Y?C=Hr0A+p1w{CDz%N-}krSDl17 zMhA3Co;6exJ|VUj{zX5FKaDX5A}E#!DG}Z~iZ-vYelPkOa;dCq=Imbh>Xd67O4Mjv z9M9o!@KjfJbZDyzMw?kT+&-@RleGNdwuZJZXVHs;Wo17h*yiE~@>vrdgkq1oIwuuu z%oN|aD*3Ifoq@Wy2dD22<|HWlcOHo<*qLNHy!Aj&3%Y>880+a%?(?2Z1Q4^z);<4w z6z6dDwWV^*O_dYR(f8k&H+TW8aP)A#xf>}&^1Q)|@r}&fti+I7{jb*S846vcrE-1c z)nhI3Lq7V7i;4{rjWeIT9U0rm^M3f;c&+ovo^2MW(y9@7$LIJ;=~8iuUq)+?8%{V0^e_p&jI{tC$l@ zeBJ??pczoaskhT@WPs$UqIsvUxjews|CMN;CKosMb)M0=;F@arA@2gWKOs`;^xuf@ zF&4!5$Kyp4vbsoa5X4Nr8sHK7zsMmyrJH*0ydE9{BS z!v$T>2^;VR_vM@XZD=cw-}6pCq}I|T1srf=Lu7Q(i&fElzS_rrYw)@y-#K^qGtyO4 znY1zsM7mpb2{@kYhAE@WZa7?yvOA$p=uTymRw$SW1Up}{fzGMe?;np8+e`?r!av?$ zg>N3ITs0Ml_E>KQ{wnN+W$@cVlS@GiUlfC3Y@6ubaX?I{>C6cv01WAvp(^uM5=*Y?Ge1rmw3TDx?z1I5D7g#9X9(&U!Yp5bm-4)}K1ST` zRIF<8dcFRt)c}Kj?Q%FEJ$`nn+rMBDS$w)LL+xG8of>;(H(`@2xsw`hx$5p19yzxm zP7^?MDtt<~&@fy&{R-i27jeU=+Lqg^RNrQGSo?CG#^UlQNH(KJ)pmKtyb+YA?i)i; zqa;A(d*q1uqtxNNEsW$lS*^}dEm2t@%Q`$B)aEbdlcUn)yxf&IsZrI={Y$Gt-TW;Ro&h&_OXP*0;Zc47>0pbS1c zMjKO~c-38hndfvD>2z2u*R-x7AWEyrlU+W+mEWAvB$!S*!%kLUDH8PJYnL&;}WOO($|-!*gOQ2n^& z|2a)Y*#Z}*?WDo(JpY1IrT}Kv);Me! zM#<|@I8~}}tT7QSTZ2$uHiU?`iW5}E!a>|8;IY+W>fR)D5z_RHb$kDWSC={SlV&^o zTS1Rn!e06gF>PnwT_MHS{{rOz_`1r@Yj*9hG^_I;%Uq%1tyQ<1OgTauBYWw@3Kgew zrX9&$r~CNf55ukf*yb}O3 zjvj1m03L%9W$ ziDb#bs=B=RJ$TcCeT%DN`WK^l@_)r_@y83yhmA61(deX$7+sgc$iVu~* zRW7m69UYAWViaCPuVdZ<_8~##JoC@HsNE|EP_BM|U1C9PrQrVfeWMQxDGSm6)9e1V zJ@D>vbWZwNrg{jw)`K(0-q$SCUn_UYE_fQ}Kwo>UEH^n5WzDljTYlE2Q;P3}vZRnf z>DwNKmieLXP3&R{ynWTLDn*_ipazfj(9rIqXPLYM4H&vVsUZj&0s?3cE(MrfP04*k z>syc*2sQ7&b)HPQStz#dY&0(V1$Ko3lc?vj*- zL&xrB}E^6$IA55;}QCKXG4z~L!0w7v&7@}Z{ph}|E0UH8@2ioh<3 z!-$T;!MT}vbG>~ZbHQ8w{UVcUUsLw4Sy*Lr&hTu!cXl#Qzj$T>BuO7Z=V(!Ewb68T zPR$=COY_9IR@%O8sn7~#r@JgUSNh24i%Nu%boxJ({N7tdb^Z9VZk$?n%(miVQzr2a zj_UU+)Ejtp%wQYoY9xPgh*M%TVP1dIFp%}i?XR2jIX)owS?%GHf8~sg-)RmxAZj%(iDoiWGi;(4I0(I|4Wkq;|YR{?@+){`=Kg#NfuExK|x1;tEZO!IOd*y%b`v2pDx29<~SG%nU)xge_3z)j^EFVn zfY#Z3$v6$|6lVvigjOw6GtYlXZPypG@TNkUp_e27dnc5Z1t7vjt4Z2_{%3lYJE?T3 z?Egmmt3b_HFCu7u8?WD+TmgV#2&0D2( zSWa`^ycM1E=CN@sT?|@^#|EpwKl2HiiZb)!%C@%6n|Ch4QU0hS&cy<2i%&9N3(jQQjLqQN)E03mMso7cg!a5k{w22H|z>P$WeS zVLbvuK}lByt7)giPyBog=14dfMF+IK6$)>Tu?54KyG#xShlxx~3$&0J6X)lLi%d@5 z(t$Y=V_>L33+u{UBIBEuPFQmcf${ChZ#v@fwvJf)>5XQ1J3EXSgAW)zq8%LY#OaS& z;B6V}V?1LI*k@YrP=nSCQbVnJSaV0K$!A4ih{?G??T0Z~ODpEc0>a42PjG1F!;F;> ztkC9o;^g-ynpk&hl9Eh%I^gl3KbFm8{h0X>&P5hu3z3^iN5(jS761HqKT*TslQ8}N zbO-o#LJZKhPE5v|O##Aw;0&7jALfSEv>l_Sm;yn`f| z;OKz2!N}rm@esS);qAaS)5sU~v-~PzIPRM=a2LDri%Ttva57 zb(}O{rg%q3JPyc_E%bp5+RVmsLUfsuXO6KzJJ|wt^{EGGTdXBy`W*3)6r&0DlX}?# z>jH_p%*24w%vMN38B>rmM?0c{b)S3-Qy@57a>Ha?fD(YosvlN`8IWWIP4!%y%v|jS zO%-jO(60Pg^kGeYGdaAo3fvrSP7;EnNJ7qLI5TIIwvCXQ7IN}Al9DAxQGj4-he9gh ztoY3jOAD)zkl-6;PUfyCCsX(lI~7+YB1%r$*$i%Ar-YS(q4jj(8aSk&x|R}ANlw}l zr7bU{VyyvFlG7l9&+QH5__5lG3PJ`)k656vN?@Mqikh|tb|~o8VO4&No{OzIR><1) zFv<~i)X^Hum#A`7#>!mLQrP_H5rVR;>O`BFq5?l!)&^mr#dy}v5r@`uA*kVmoK0~$ zQ|(xylRnJFRYhABVFuSEnZg`xRgRk58ywcet69qsF>;Pb6`U%;jKuGXff?AFDiVd2 zT$Nl=dio?3_)J|E>1ux1mSCVQC<6MiH&d9HizQl51JFd3fIcci)IX|;SF#oqF~jLv zo6E}J4fJg7(1*e2))Q-nqxCfT(O}(x76K~P@-Bc55Ph6fwUjJDpH^mYh`tkZASq#i znU?{hPOMS~TBV$zhzjfzjTFr$$F@D;uiFp7e!8Q_OW8lkW%u3#M#w3V?@*E-^e(w62|v9=+gtfie)^(-A#NrEKQ zQGG|0o+VtxTFJ%SS^;gU#qXjjE69)1A`;QE{FCiieiyWynG?!d0fy4GcT~}q2mNTc zsL09SRkSDDRkRiGjQ(8oaQt8_4JTDOc>+rDKReDJ(q+c}egmDsextC0E~uG%?aJ6| zu%n-Gfy>0MDk2FOJ#%MMtPIfE4+DeuvEkPm*D-G>3 zNl8xL2_*;GNE6SvptLOkMfGRCch!d|4ZbVws)~hnPTB?Z2Ln4~iISacn~+{tv&rW^ zNihoSt_FBk-bGDIkY5!mO#uNfT8T%|11PTiX5YykL61rBtQt02&HK!*YU z(-Doen{dbfDX#+TwA1Gy3|E7%aww{?Gi4 z8NQ*kG+5u~j^u>bIPDXrj}La0#g7#F$95DrlDu$+_sl#qG0z&Tn<&iKEY=+q_>b-& z!@2#^4t~!r#}`};YiS}1GOsu@V3G{%4UU@2n!HlC>9fQtDO%a0^~~|+komWkW;M(Fs*rmHzV~I5EI(#6x@Lx%JZ=R-j2 z3E2XdiUiy%7trqnT~XH19#6PhE>OFgte~qZ;0KJHJm3eVS=_D3y@gzI11%XL==;Ep znyoKDUwIg`cPPLw6JyLyC)Rm^y_#_KpgEFIvVyQlK7i&T5B6o^GiaWlKAYi$OuC|q zKtgajfK!!NzX|o~3VNN8P>eRzE9AT>LCz)A>!;8DpjU=F0393DCvd$9XTSmPh-Mt0 z1pYbGApqk=GS2Nx(;)~U5L15yXK@Dr@F~DJF0vXErh)m7cmoXN<4d*#V`nZ6!FyA1 z5DQ#19b1|X9s!%r&##~$GX*O#Z9V{1;4%RIav&WAy?%P554`~%6XP>E2=e*#p&Uf% zsV&Bs&p;EW0JXo0F|pWv;D}6s3amTDY;(Za0;Y4Gj%LobeP0HHCSk5AuuC0}1@QVO zq)S8y2Im!??x6_s1L%a6%NT6N9Grl6axlX%I{G&7>T9z=!1;Magr{8HNwP55{%iAb zL_1hw9RI?6;2K=08k-T{?qa>jqCqd zL_og^0B2=zIRTK)@iV!bB>n#Y=fmL0&pDq5oTa9i5Q$`-xBf=X{|oZ>m-(Hk1;CD@ zA+(#hEPF^N5TK3!GGDVwF|#k6%jX&eE;I{WMP{Yz*HQ0p8&Z(}o0Zs~8*)PCC&~3K zr1=LG3In~KQz(oO9@A|8=S(RAF&pCx&&v2r$@{-Ir2s?{`dqCELcy#r81#R)LP3Ds zfX`R-M~eE-N%tS>FoclsHxu#C4f*d?DBxr>;fsDrqx@;Fgc()(ikJSs;&c2vRD{T1 z@O=KViueajB1jJUDhK~>VwNb9G=%#=7|x#!bpkB&h%*|d<2Zo_>DfD@^#p|hekovz z)0hfpYB9r^N4^2;*B~RQZ(-9}$AE9)SJ{f)$f65Xwms6ogPvw4$!P z0nCaYd=8<95Jf%(LML$|5RjZgBxehTf%n`iS20^}= zVMiuar{j8HmNpZC=}8n5gys+1Fi^}-2qqYF_Sv%{nA1?l3FH~V2BA=;4HFwAK}h5u z;DU;(_GTay4)D+kY;~eHMOBE)grLzU)-{2ve}-LSA?*6!5?(}tXd;w<2@?=N2n!+@ z+L8gX@CXPXzX~owDKsz`0}f*Kw1wfkaAv*~)3^Oc6PyGX5Z0gbUd+)1t51*%3*ZQ~ ztD_wqF%D4T3m_Cf9AGk&sLCgx1++{DCNVBp#|fwr&`|`!aKQUXv{6J*nDKrJZUi5G zLK~qc)iDlOkcRdt;yi_1@*)91$ABxR^#@^_QyoscgLd;1n)!K`|1)luppXDBbD}nJto!c|NdQp;wI$PoaXdl*i4vF!N{BG*+TUu& zAUAK)Szws4ug&7S5H*J1`i(B4nJtlsBP2 zaWMKzNfeXR2j2&K#Ki3W``o6l@!!g-?K+BR|P*;1wT>##7sc>EG1*E3LdKJpPB5zpvznpyxf096+9GIoYd>g*u!^Q z1rPZvpLsGfEY@^@=_~gpeWzvczzLZNOacUJk{B#rh=7m?uP_4!Vs$-`j7R??xD@Og zvLU`_zhkZxey$XLt`vT*6rOR{6EhL_tEKS&)L|AWh?r3c5AF{Ynil6^W+1T|lYe6= zJTv(Hr9&)BRF`ozB1<@Hy1($pg}&314kn^gQ(;_yR!qEsg1B?F@XT8u!G${jHu;Yi z!wc}kkpJb?@XTb~FG;~%IXuJZ{bw$MK#DN^amKNWSy0RLx&QC;75 zhB<-yZxyH+Q7Xu){j-IRka*3gbo|;hz6V(YKi=}yVCbBzO_1n+z+dDSm|5v40-NSS z{{5AXkgUxtb^OXSz6)9VhEzEgS^GO{$NpzdKti8oS@JM{EbZ@e#gIaum+1;H;Ya46 z-vzgRLz>J##H~{yvZ))Qp&;4hmAqfLZspU}FB1il%!^;3I2&}&%cnc0p*N7nJQX{g zq3b7c_Q~ooGFE-lR8Q)Ke(|9!Lp2n)ELMF1|0nDzQ2Nb57tG|WkS7s4|$ zJ87zF?ti^j66`rBg#g-mVrX9beb3GH7|DKVw# z{@$`!a98(?)7!+IW>aM_NN@q#q&xCGZ1y+YR`I`?bvSpKCG#rAxyvl)F0-8a`JDf$ z%Pc38q`tWTa%RDsz`wTu68hnC$bPeAN2#i5gNE<14D!>D^ZWXT(wd6$z&${Lf0a~c7=r)o zl~~hnNtpC&{?_}kMBq#eoUz~FS9!kEJCNWr(-X8%(kd!*dkq2VfYFiQR^Ul~XM%eI zkaV*^KL0v&Zz5gH0gnf_)X8)6OM|VP`pZlub3of$q44Gy@H2fZ&rE!3jzwEKpmB^3 z7+(No!QlQn=+VLW_{w?nw$B5u_H zc^>{C^4x0+tcn3DBw4@Y#cxXOeKtuqtO6pHxJoVVpL-De@b^Q{_r_`baKhMr{-O=@ zt4VP^7wc9pfD_6c%2yJ|Ih9R!;DoZ4(0Ft^H-~YfSN+m5CYOoB?>VGC1Qm^L2W1QQ= zo;rRgnQc}p>UdpBZ-goX`W?RMYHd+>==SaV7nNrhFT;dfAIZL}?n8tY+eZiZ2LqOa zZz?wp?3&epdB=UEEb{hfxiR~OMDsq|NR!EKKYZMAo;Q^@<3WJ@Y@>QR|IoUeZ2UtN z-siOG(pi`ADg!KG#h^jslYls56Y?F0vDqy@w9r$zIRus2#+lEi!``~w>z0wzZ@i)> zb3NJXj~4HoZCz4gOC8TN@-6L5dm=5ca8_}%J|1yk{ETaC4_djBFQHKrNu7PGz*C;m zCXLA5vyC&)J9>rV8M1o3s3!Y1DHF1<-F?ig>x$U6FynC#`@*5xw-G;{nw8ioleDfF zPPo&-UWLCG>N$(S1#^71(UZJAp=ay*Sv@DI*NZY98{gI2cF%Y9_Jl@xL`CAP>w31D z?fBc_6>O9)d-avlvk}|dV3O7yZdES^S9GRnt4hwgvy81LUYgynif9J|@x6+<^h$oo z4^=(Ca@gq4x-P3Fle|cE7TJ4t_NB#6(t7ZaZQIzQA;bMqT(j=%#MWzXt-@Pn_T+TL zWzn;}ngsvA=ks1XL9W_{)Qul0XHo~XFV4C*$2A}}xb@nb8u#!)h1_i9ntdwFVGRy| z%`lLr&Q7B*^_Oe0aN*Fl6|<9mRyr|OpuT9nH+6r+ex)z}1fH%LqoLO0FZopZ| zGO0J_NII+3Z=YkDIi{JNGiJ57lWJ*>Y37(_j%jAt^*OPa6N@>qm=g=;q2mkE@adyD zzjStq`DR@zyzZz3pT0Q9a__Po{CywG1lA<6p30ma-A6f-MvZAbWiA7F21knbr@fo~MTEs7;e|tbd??*4&7_r^8XmDx3zl^f zKW_RlZ0fYpfQv zdhA|XMO?>9i)UyyHp(^yyvbMAc6T$FdT@2SYMQz?RW*%!H_O3Z3J0iNS>b8O!#X|I zQ5gQIS3tP2)N=jY1ARlg7={xW;Gs(oW)D@}sXH4-vb;so%ylM67A&q9L)S)EgUE229xn zB4=W5xI3&H&pHZ&v7Tu_E9S-@^Y*ZuriQoe2k^(O@x^<-;M9YUyn_J|bYKPs>w3ot4m;oU7acZ>t-35rC%vUuye%gStk~KhGID01s(YGafD8Z0m~YvMzWRx zNZ#($bS+*@6S9__uM!KQr!EFon37bfdt}=BroPN%fNk7h#TtG28>@(mnQhQh-_8`? ztCx3@bIdX4y&8^Yz?2)0>8yWc_;@D;|N6iJ%5Yi5f(p9UYef@sbk=!RC@^9l;HJo* z$G^79rOCPxH`yo$^kPe6hjXsj&_1fzWe(@vKbjJm0w5E~`--OC_WritAMmK+;Fo4&xA^NQH#y?^0QxJTQ?@h&~P zLINM(zRN~+MV^meogh^{s{;)m3Od#UaYi!Cf7g{quU6-`B1*E{-;bQe7?DL$VS@OtwV&dmW0)nbM% zzpN~$z=RjPB>0K0X&&tKuQkXcIjw%$yZLqW7FG}H;UKCyy= zEkKnhHo}n$#s;nX+YVGou=xhwFInR$bU>2YWv2hY8ijrKj{AbIq*zK5p9!#U<;|PV zu#y@wpJH2PE{3(`?heQx`2IjUjTArh5|^~jfALU!S@Eb(Ny$t7ir-qV3>2{^5+trJ zeQXD`Pr|pPjRcb5@&QxKooopd1I@t*{XXoPTYIM@e_@5HI>^RHW zVPg1#y9fM4khcl?Lpj3x7XVY`Eb z_z(?;(grTK;JkNck?GepkSA(Z@1tc3mG^Co=_j_-hl$b09qy@=bJi2uDkCj>lva6d z$+sw2UxhCfZe7=8-FzK|*W(J4Xbb7SX`>ZTt{gUQl<100Yz_OZ;G}tLPHFIaAXM({oC$A|1~ie9NS?tJJ~aZl^Wd|HKg_{e3+<{GiE1O9vM z`pA781;RbMy}YRvA3Ofqx}6qKiHv=`WkG0zqyo#dY z%Acqm+#5?QKlh~nrI%QuV~4AoI6JlP?J?KE(7s}}!Gb!AqvQ))Gjw)e;y9Ku-?QW? zO(&${1wyaMtfj#yS`ytE;oeq4jTY9`7`Ym?sp(dMajEQOzLGi;2iaDW_{P)2&7!*R zbx29m(*^m>p=-Kdn)=Rnisb_bGn|1TQEsXz6e^LA5 zq2ZE>pzHI~5At1)tld@LXR^Bd`pP=1F+d)^60OmKl7nfDyoOD0w}!=XEPD}On4wa- zEgin1m`WpGD2spL@-ZV|0fkI`k~A8HuhZz;|M;VxC$(zjmV~yb9m#{~2kc%;_7n`a z6orIa>$b&?4V83@tt!60OjenXy)&8m=0dIWd&2Acr<}Gx_H^|~$AKe_)gCSA^zl<> z1_suCo_WRd)|8QihD$xU*NBf)tllx5(yv&mL*E7;?o7SbJYMy^i!_vmR7gJoGAZ@Lb| za3>fC`RPtmS|E+d)8E9On<@9Ks^XIdl(O7#m!qmt*n^H7phn}w8@A6+H=-Y%GCnh;BSN-$saLT)yZf4KvdDAvpp-Z zwRBx2UzwPw8){3#ZzpUxHlV5S92YGM$?Utwq94{%`?+eOHf$x+pX(iYJLG1OolQqw zOz#-kv02i&qcgd_q8dwyg+C$_kfbql-8L=jc!j^ zwDi@gPWH4n*i^+8YSZu9u=*#-YuM^L4XdajX8Qgq z)uNRF#vAt5)P+Au)JwHff1ta7(n!mb9qn%Fkj#7YEL)+)hYpKv-xIqul#A3%j~p33 z8}%Sz6o}MQYF_LB!H9?I_M~`GX^<5?))mtlA+cHFH@xeRmB=qSuBA0Ex`y+#2KE`T zS#|0sSscf1yWmb@g}YjJuscd^em zSYJcW4YVr@=X6aM^hu&y506ugRk5xTY!nm+mNkOwy&u>ay|sGSFP}Rcg`txjt?eo| zlD9Z9(y^FUcc1*oLuSlUH}X!oVOl+6LzQt*N}HdJu)(|b&?}s6y3Z4%J_M8$aWtip zi@lM;yEr-xeZ8qp9oML8l<*fkUGw%+ASa{k`@!1c4eHE+L!>Rwk z0i_((U_y>vGEkOF%YK=uH~eBG4{l*jS84RJJ-enmL3wQ*(=Kto|x;IlB#{2l^L{u0_VB4ehRGmXr}sU z-7;ayUvCSQ{Gf(k)Vd_nlCyZg)=y&9;vqfDETq6R#(PCd4J2#@#HW zp9r1YQ%k(8BTu!!;#M#*I236m!^0Ow8D^Ir_8^6}rru+Puz2jb*<<;wj(}E!Dg) z>yBsXi?*!jZ1k&ikh0@j@{zu~wuzjicd6uN`o8#pO~S|paQMq2->p|W`mA*W$T@sI zm>%2upB@+8FO3-IJ&>4M=d2rvsa$EBfCs!$E=nJ&a~ZC?Rv1rve>_P1*16hOA=mL) zj|SlJMJxIP1Ge1kf0RwgU*>0^|Ddfq1&CdiBj)@wns5AlghWs00>X>6??V)#U%o59 zoE@wsNsw(5+nDVL+`ogy7g>+>&nmzX3C9!7$!ex&E>!e^l$kfxw8jz~27+6Z53~lD zD?~OQARW|eX?ii-zGO(PucazR4&le?X$_9=_Ffa}>Gz(2?7A zw0n8EG&c#S;}#MR5*ETJl|9O7XGy_=_-N_+klNu8ahT+2%~g~W)-Svg9HZyOQ1&f0 zQy3~oNxBe|w(7+ih19F2-+yHZ92-LQs3M{PocQ!}wy=t6MC>AvFJqv6h?R9`YI;Xg z??^TZABN;yR;qvP^&Oq9p|`5{Q3-{HJ7{CxRC-a;Xzh4<);o0D@eFUTkO8bZ8drg_ z?tZ#WpG%G}j9e<#7hZi^Bi&$SC%JzCxhy80r~Hk#hePF^J$i%YU0yXC_t~A~3sWYG z9-^pi)_L74ydgd%*YiR5E(r&n7`y7mVJh8^yI2=9@X<59$!CvnjvC0Sak#WfhL!Km zLP-^?zPyrGSERJOsi)r6iHDV2I_qQH$C~aPJm7I$GJ(9)1}=eU&O6AL*2s6dzjo`5 zwQbqwI)m>Q>ytzp%i&GogGYwNL!ZC}7Hp|MXRx9(UO$OfOLbJfB360#g>BaxJzGYi zZ@%K_2@6RoBWG)q58*5M@?-LHJ&*UaQ7)I}wW#1K8aVrjdM(v~4SPM_J>EsOe&+}B zl|nEv0<7#*V*vDNto-ZQ)5(}mO6}Qn_ooE1xJ{C>T^SsIW}t&N%F~2AQvI5Q>?yl& zKjx+VVb`XfMA=JEKWf_3FWxUZMBU5eF(s~%KWG9llf zZ6paqeP}@GCZ^|lK5u<2?yqK{TVc1M7Qf|P$%W$KM7Io~dOlK}9lKs(H;2?%& zw;Owu2`TaA&cES;Us;>bd&)BpAxdu;%4D@BX%RlmH#@L+V^#c(BeJX$b9@LvR(Nk# zDWAn(jG!*u4_qC%=)`Hh%E|#cf+2 z{k_XN(}p&*P1EsZP_h+iIKO13?wi&U5wrAQc%b-bw)x--^XG?@F3&G~=D~5i{@tAe zNp!5<^%|Ax6IO8}!|e-)Iu;kGg$hfwc#Y>e>#$d;MfOMvvxmb|Oo@n2J(W8? z7!Z*sX}MpvuG^&|idWd~02ZoYpkWh5H^!Tq!DlWw?6(Riy>}n(P4no6)&i@=WqEt1 z_M6rs#RJahh=-JvEmeF{yKfHkU-QlN1_ge ziA9+NOm<`Lb@E2Lerizu!neT@Wux{$??aRoVeyrdOb&^R;X#bt%vMf!)pQ>o(wEB{b_33{G%d4c5GP80vyd7~df@-SJig+#?zn{S~x+o_87; zjYE7D;Ms8Mz^|bLg*M8(6clGrxO>;r^Yq_C$IB}*6@Dv}yLv{e_ie6<*L&g-DB*X| zZFd`jw@s3F^9dJN-^cR>(>2sWgFS#oqLSHP;|r;mY=(zT$mx%IBiS1qeZgtD{05RQ z%BweW-Ltj=wUQQzWVM$^@hKoK@z-?oNvS~g*5AFUdCK7I`7&-V&O6tWa`ShlDHeRA zAJrX@)R1YIcN$uOr!ZomsA`~e{^n~hla8-0PEerSe_CVf z*U@jFi+g2f5s7hFEL<~8Zyt5uzD6*e`_M}s!zexHBXpJ01b6;gOVh=+FXCxi6z`}R zl?kk>@Zvr|kn4V0lBHoskUQJbzV(V{o5onf!*Pl7=F;6Q57QTu%cYU9T}LFXZDTp= ze16k&F3sI~eFsv=>_`Xh`O9+)D0!}sCVG*$c(CW@W=Rh<-+-zYswu8dXz7v}d;pt^ z`rWx~$#B``Ju1;R)J@2y`&Y5<*|WDmZnxzunmzrR$)HlP%eB{4HHMZJZoa9UL`3Eq zkxQF^m2Pf8Wq68;HJ|FN*-O0RO&yazKabv$M92v}$3eY|^rnvLU)|+kY4Lhl2iMKD zqo|>BUHq9r-*;VWs~Wdzu6^f4OfAf-K2#ft@4tlGv!;_yC8f1QZYC((WDLZ-Oagdn zsiE-!gGy@?udyJ#rZc0;$_@zXn|c5Y_XSEX95Oud#*r1^krIPIRQSWUvq%$*_DqnD z0F(WdZfqWM%%6(zB^~Q7>w(1&BuTV|z00S*+w7M^;#IukcD{AAIXqzT5JFo_GP4<8 z{oq*Ei(Fb(+T*dyufU1|HAZ!Y4#eK-eyQP2T}AjYpdo$tk`K8n?~U`PZBHN%lug1rhPhB$uT8m($A&3?TQx zLF^FgKC>E^$z6T6-+K%_^tSD$8_el;uyW#VHFIoENK`*1EAe@`UD>0cfVUhT@k?_q zm#)&k>2#;ZOF*n8hIGHK`Rvx~w_(3NB2}*GX0(63c@GqVGD?8WyCNmDY<}SB1Z9X1kJAnG5a(+5h$|+%l7NQW2*Y?q8OKzhSU;ljKff zGl=k%53LWnf;aC|NTMr*l}KWA+uRPljNK3x9xRslws~yW($+ILo8#CC>JOBAoBfJk ze8hFgS9w;}h05#e#Ep`xCHI(zyr@LQ_TD*Io?I7%bb37I6@=?g>eLFRH-~|9RyA^` zA1tCevnn*DA#4$H->^AaH=qCsf)(;ZF}8J^77s;HyYPK4Vv1kHSPqMiOQIGg9SBi6 z9ZMTqfoKlX?^l+T?08l0P~nE~(75d{Yn$p8yJ)B*XRF4^x`ER~O8{(dd>LmL*y-9= zt~H+7syBciSX&ier8~`G)|LfUXG^s8m#t0&n|I{n&Ov2&F|{TxSkicxA54@S$Npm@ zJgvE0|ClwwQQ^bb*6Ut{x0?(>EaPKK(~Xrb9gD}u%mnxRo^z|GH(iWen&oh>2Q%z0 z`2L77A~m1Aad}5&_ARo@tvA;?{W(|tJm?#|ZEY1_el~AE!M1yUe3Hw}H_x|Ty?KD7 zA8`g0^0>EWl(?Isu_cgB)WK(eGJa+o(>jbtFPepH{3-s;Q+%otAcG{OE3+@eFl@hm zs0hxzj6ULB`m5nX7x~o^@Ad9TxOIw)le6Bm=1&}L^#01xX8EFEjw-rtSkWHf>^25I z7}dX7+s9S(uJfv4@ooBEx8~E;5=ngukskv3hUsE%P58um3(M+jxwPk_TAty0!iMBq zLS>~PcR~ikpT2M)o2ur8W+K*A@NFS#n~;B`JR2AADjA#S(R=L1zEPKaMD}~0m7QL1 z-(?c=E~*8z(?^OGKfF0q;pHHm5|)APJMR3W=JGB*$~_Rs^+!nh6LOMhcP@KVU7I55 z?!+YH#}BDA_WrB!add)byMS1;v1EqVd&8d+jJtN-mtfii$N}8~&>o`HmzC`^X|~d3 zo$<=BL&WBQEQ7GFK)8T$(eHhg^y~Vg3Kc$?Zc%Q)7H+;~bSECT(`)Pa!k)mz(>}Z@ zjmt;}Cz@56O%(?V+a0of;5^`jIWX8<;i489@OVtEVp)gRPd!hElN8r$PzPmSt?6tG zmWA!02G`|1YD;;(XN4d!Hg8@_OK+%Ob<>0MY70lOHv@NX36)#1fKpjMdW_cFNI$xt zLNgr=j@6x$u$W4M$U>wVQw2mEV$;6hd6!&i$Ux#e)>)hE)O}d{A+m zn|N9sMdn^@;mZObI`j22Q$>1l{R6Gfc@|Ix%T9V`C%P1#52d`PD4$tVYgs!^*|XZt z*(B#qQZ!}RV)=^%iHF285wvDfF}0Xz`Jt~-Qlp*t+%l>eM2UorWKGD``J${UD1ryV zYBaTYSTz;v1Cvg)plk%-nZ)~rX8PAw^vUrSkEs)S9hLizMp_mO@OfnK?tlp+J~Z9m z>*3+9(A2(F-Hx6j9>CZ9+@aCZK|8fvH>4!h^Ox+q{Wm*Pl`_xh`&0T2Xgrq#Wkxx| zWZ?(XTCVg}4pxfrAA;}9?$^F4A^#q4?f?S68{1y5>C}6*uMh#}rXOt)9uHVJ6#vv0 z$vqt4Bffu^gY0T+*X4jE*}aDr(8kW+Hw?V+W1ubC`3X8@^ zAL#Xe=#OtHO!w`7RhLIH?e2gg9|tU}Q|pIAMZ_Ul1kshSLjc5nzN>hbXzb z@wdG?t1J87n8i1HD}wN&yt-HSy9(7ivSVvF>JV;fTdwYWYW(wvFWs(9>uA{UdrC2y zs`UQs2SlTIs(ceji3l3+NAw&VtS44p9c?3Tt9IN5Qd}-3PdmkJ1PmDSON=0^_|Fvl zE$i0+xeg%?oWx^c?8?S={+vO9W}0;t#>3T!w3eJK-LZ*%cq^b>7$nlx#uux44F}tT zK>RimAI{lE)`@rYqFCWI@ogb7eGdqDJ`XPtL>he&L=h5gZWrn}f*yS#sjS<45fgKS z&Pz>l#2C3_uzq}-R<<{a`E;hERyPt=BD=G3XIHkr{2=OE1BK1cygwVYw8MBTr45xc zl92umWEqsM}z$yRvn-j3|h_3}6S`Z_`e*(ZEeHmOpmqD^A`GDd6eu z%oN}0q51PW-vnCn%Er5$029JFcm!DDl5%}R-uiO9>yY4C))^jtyg#V(Vf6zPAlqvE+*}Uy-b=GoY2SCwBLpu; z<9#2D8g4I>O#-=b>cgc} zW6wtdvC(>to?RC=rdw8wi>qh3@KgN7MOwPx>FMwCL|22D=<0eKM=WYE{GGgya(tLp zjt+TbbbwmWoOKyN-M45JPqQL9=%yF>gZGQe#BGv4k!h}H(gr{!=9v3lR-ezi0v!3% z6x58rtb3DXB0O(+$ho%MQmMUbdgAifm4PGig6_A+yqc>+gCr4dySa)Vx+602ui~%$ zK*7WL3R=1y$dB6mgMtDC+A<5bw#T2)9{bRgwJiap? z`5b{=Kv8_CyQbKuK$4Lx3L7;^#n-V#q& z4ORN%iyUW$KzOY4?))HewAD~u`qJh##dcz=c}mlG!mSq$ArNFYt{~&(J&m4pWstmb zE9xPRytMl=P|;8ft>gyM>vn|a^Pc-!#A5xP`q;dcdBqF4XqASErmurFFB%)!J2p`O zcw|c4#>$P)Hi4rh?$+JKUsf3g+n;IQ$bNCHr-X~3xJkDrt1ixEZN$>@;kbU76gN1g z2l#d*7^nLO zuo|1YrvOm2QQiM1R-T(dGAV90|DUTvqWjGQEDG+EN!c!|%bwK*$ZqKzY7@VPZ!YXB zkALb3jswNUdI0GO-&oC^2AvQnG!eJv1%q}W@s1Y*Ka7r}IQLez2VA$S=CiAfr#s4- z&{GdSU6w9}H}|m0aFGZ;F=~{pw%6*1oK|*Vok< zkd!2Q`nZL;#_FeBMUr%1Tfdk@uhEVp;5_X!hD%e8FDZGuIV84dFgPhcso$Qr=w(yR zf){YFqFX`Nyg6b)+=O1S_1dzwNzDDo zmagyT)D*taW}L9P_}LM=Nw?VpF5rn3{uO}#PKO=k`^W>c5W$wkaJB&Kdl!y%*HTb$<6a7QOFSGIU^&w+2;~TT+s&88~JW zo2VQR73HZ-?CBY}6ND&qWueWGCR$rU6 z-KXhN-{nY*3xG3Fs&7L}%0@|9b={9u3Jc&l15N}0o~;@H$BV2Wp(fW!eah!iUni6k zx)Fp_nm{J6y2O$@iW&Ynl~=u~W^hgG7E)BlsY6uCZ zc0agymfq^NyCwPkZi|sO`NlPOt;)8f#N>{j!8gAExw7Oqck|mPAoEu?`lf*=9GrHF zy9QY0UWx-UHS>R6$EqM$-LT13TAh<3Jn0-P7*Xdex!iwjw6?Ll8wr0O99ndmbjYnK z)gjXZCNgYc-PX|zQYR$nUSUry`<$P;bPNZ4Ma5s0@`~+3kU-jaUwjVxf}aA2oA^p15h%6&Vdf z*_o@W%^aOQ3*L0{TbMZi2;WTO_I9baD8Sgb3+@baSIth@ZJrTkJ_Y&y$3*`LILP%IQym3L)Yt8~`Y?1f$M@f6uw$?^juD$_-`E(*h3)Hp+-a0*&TwekX zZDpF=ta>h43NY~^tBje4x9Kh37R!>sIgsWK6mJqAPhs7tGK|=8Ei2KAR1s@fc^_+2 zH^f$-;Z*#~4v(bzyYn}TSxYqtxSD`SUSijh8g&g5vTN%8Y4LtGu-N5S1b57$Aeb?j ziH~B}wE~kA(;P#n1aYw*Q8z3%3qRUk1!mpwLu$}hjsi<H;iC1wg9R6hx96X2u4=UF_h=Uu0n<|n5 zby-pnayRV*n6JEDh!QK!XPH*+CQ!OSmdEJ@2H(&146IT0W!VsuVo*2K*f&&i0b=UVBwbz*%g?Ku0B?rPug-B=rLP#cjpQ&Ybo3GieUBFiM4t`xmU} ztQ=oEkA?N53ZTlF`{d^nD_y+EE~hQhokj>R{#D-B+I}z~OWLIF;feH*VvU8rpId)x zx^yttBgF$0X60jEVwn)&u`&;V11vmdtpG&LBDF?lVg&fo@o`JZVm;cRF+$8gd#FLo zEdN4bYOP&JL$(|7Y+GvW*0}M(`2NQ$_^#*I;)d%9RcN1-+N#%Et*R3-cbpE<>jwo89#T?yF#CYs%vuo{%Kr1$8u@TgQ2Bv^um z=$#Wpdc7#etv7FU=nT7Ea>)a;f@WXiG0nhbchel#(8rQrI+S17e5bp|i%wDAeY{IQ z!x0;oIaG7Z{?Q`+@v#mLo*prFy#pU3CE15xi{Mlu^4 z>Iy05C5!v*MzxQJV9x#l55NFZ1*EsVb_M@da7454z&vkV$l$T5=}nBUel9l@NpNW2 z7iB)$*L0`(^pZ7Y2)-=-CEFa;x$A9yMe%^F3foo;c|<ic)qDIxnNtgu?3WoujQc9@!<`D;a(CT{^g4Oow2=BtV%Q$FYqiy* zIXwshA(PPKuFUq6)YRWgM^2vdQ0&srm!D{hSjGl~RsJGhPVOD$z~3ahyStAjy9k`$ zz!Q9zwoS}=Wu|lY?+ZCybnd)tdh`Jv8gjiL9KHSRfJ zep3sVsJIfqXLwe6!ICWk%LFmp2yFJ~)+E1g_;_~b%IS(A>6*w(rSx1Tq9pI&nN z#QXen@4Sv$?Tu6mzr?K^u>C`!pIq;wpbNV3M%$=MR-XK!zd(CzxWh+>Ot-tAh$~oa zUU)4pNL@hpOS80J&DMO%qve-i4eN9B7Euh^SB=R`Q5B-_8@YvhtBAjrS=^nZcl&y) z`sj^A-POBRSr!MZ3Zaj!h>MGh7V9f$fBhrEZtJO@M!ot}ILE-i!0)-zr`6Mp4#oT^ z7p{F@eg50GZxdBBhq`)kmpRKWTzud+Z`qaUe?``Mllq(A)}+`hUAgk-@Nnbgr=(DK z5s4AnoAKPy=eH!d8kP;U#EM?9LD=p1=qvuQ`1;PVmc}vVht8DEmkV-RUY+r2tw`8D zS`G6|mB>#ixVN_I#L{@O3$?HV4`<7wzo9Pak#wOyqO57~5_v@}$Sg;C=JfWX%ER%O zlC@PI9nsxp<#=-5*kA`wP3cWBL?WjA zl4IM8N0pWAfWw>z)qZ*Y#5m{o;*a)qYgVV$43X(H->4ls`drSg+^VMGxRHyR>$5Q&W=ZO2gE+y_oh!EfGf_Ss~R|+G2N$$_%xt=2I-uqS>XVE?k zB6=iCmVTu94jX6D-%;6n$S(9I^4iI$Pk$ewZpHU1>|G9-2FsQgKuiP*>1Q4uHK zW0d`y8ZR%ei2J}^%}AAd!I#muZnak3S}@ep$dzZ2e_`|UNSvX2bI;}b`bjnQ;ZJ;4 zqX*kx|3E%{>QrZgr>W4H2~d{XiI z4^Mg@4KHa~Qg(Uu;ONIOi65NT_S5RTZPL1TBq+=qhuyhM8;u%%-{JhG2G{hC^4s9N zPO(wGeCIWC@w-#DUJf^)(w+E>yn4s{DjO{pGFa*(?es8L7Tx|Xt3H)vtos;A3o<%5ZvGrOS`rSj;5lHaed+MXxv zk>k1%_{%R#ukY1edF$4#zGs)s3VyYSZ8e68!1VGJrb{&>*gu0{@qA8k;^W-SFs2}$ zj9nPlka;FFHm2w$^@U}=e{~2BcfRH7bTI`|Yjsgd6A@uOKbC}H_u5;Pwn9OesW_f5 zbFa-76Sk`YDH*n}mdc)8t+Pt2<TEYeO{yJEJX9EGVB46!zVI5iufq|*)FO@_BiwlsNQ8loM&q`RRT9ko zVcCbDc)>E)2TH~=)ac2wrJdp)3+FE|Q0T28+bebcD4=M0_1W>6>faY=^p@ODw(A!@ z?+mB*H{nT^P1v1=8Bc@b9M_)es}Zui+{gC zGFoe?ZKW-qV)EgawGTILFi+mZ{+z}Kw|p1X`~G6fKv(6OQp4n5-ks>sjZGkybB-F+ zyAJX@yxO~Q=da6V&S>3XIkpX*dv>}9GtDA(?Z=)*w#+iQ-A7dpzGxlulq*0m3rd(CIdGFbe|Y!TCB=}lZqaPa|mx&3lq;D+t4Xi{1hEJlgJ8S zX9)bC7XJIylg1s<51o4gUf1YZ;LjS5m7K6e-LyWjF~hLmqAl#=Mx3E*nq>;Rb-{U=Os|ay<8dpO>ab^4!QPTbm zPXkss73<0sw6A)5^{0E!uifzKmhdzgr{{;pK5h5gaefcJAxApWV*bP754U;;DZb9d zqc5|@-QL5NJ4a*O({ZoIZd79v@}90tJtK)GbNLF5oi%eas}4gYHh4eq)!0p^n;t62 zdYm4jrygO3dS6U}VG8nsI&P;BnrpZ>bZZujxZdg{*;^D*dSX#(H&W62L`#1}ySJqo znLTTL+5WsnFb!uUZ7WqA{(8--A|3g(Ef=pIyr-BfEa$~rGrC8&tMUB$!1A|`UKV^* zY4=vadT8v&qXlEs7i^^Ii58I}ontl~@IlF1Jbe!r=2i4*d-9>tE-r4wt#AK^k^r%y z^d;r=i;3AB#gzdAw6&{>y*TmB;@%T_O6oKa+e(wDXWR_=c_uPHWf6tPFgcgzLHTK; zq@<*6Rr3F%?5)G1T)Xz+EgjM^bW2DK4ICcT1PF zba(eK-#vS8-{0Qv^Spn2$Kk<&gN)qQbzbK>*SXfZzy-uugq9$vKr=WxP+<7@64-x- z8m|r7zX5I=(p>N4Fl4cGE^tMrpGCRm!B|8M4`xLHz+J*G6s-MOT`7|AMpSz_!hsGr z)%Ie;;<&b%&AA@1VW;s8D#T5$xqu_BH0`5b@!fCM0ueuUuX2t-QP~xx$k|5;*F|;- z6NR{E*WlzZZEhRd?N5*5@VqE@gr|j^6!8P0i-Vg#3JzaHpFdh?cVN})YxNI~kKF5I zn?zpJvA=p3l;xwnq;vDY*1p0wOryl*jr@;#MvL|Cnu8-%YoE)ehhka|5WVyUU#?DR z$~3l56^#CD&UzVITac$jcfB~uVYaw@5lIq#Oe?OyNE!*FnIwjDskmO@nx z!4oA+iMH>M4%e%Ux{l|=Uq zX@|Q-vjp$gI^tOk^}cW*MZ?yVM9)i-7V|H(?HuXPOkKfSCn@JbzQ!Ud);=H)#ZtCO zzw0yJSCwDb;o~D8jVTHztCYq~e)+N3Cw(F2J!z-hp@gg@V&X zI~_Gj{4NJHR-9>5Jm!eY>(XeQ`)BT$?dNMU@lyyZ_j;mIFQzzLtrB=Qz3lOCrd2?*$2-$2 zHVpQKUO#?3H#aB#dL_)FT{)U60P}dg_e|%LdbrGZ(f3qcQvnX)u@Ww##qq@)mAL!5 z_hAgTH^9{k4_J=`e1q{poe}eXV&ggHW(paP_5M~F|B&-z%mC6P((QhW{MYK{-S6$F zYT4|SO&k_q7Yt*NO`i;_S9}QClQ-rJ%9F3BqC29Z9=-VJ(_%q2o{N7oV)LOf#z=~& zVLdvAH1v!4@r569DKu}i^c+t1lr4qp8~7^)cPR7xYsF8(jh)AW!ic+=Wvi{#9~y>s z)^ElAj_>dB&EmqJ*%9Av-Rmq$g{{67Tb@SD5R=|Yrj+OCoGROzmOdxf_VdBGE}mCh zSZPn(5V4^fXP65ZI&j^5N9>y#!4n+cv^(v;Nt^VDWaGF5)Ey@+v;{S$hHh8MM_8G5 ziZ|YtCXtWh-PzN#eDh*ormM7i-F6JDr__o3RSz%OYJM(B01XJ7dbN06JiQ2~MJ`?| z#amMB49*=roK~l1!EClEGHY-D4s+dJgs!N5>-S*Xib;ft~r8!Gxq`Y-iQZPyy)RMKObi-c4b=bM7> z)+5%wjxv>6y-dTb;>Uk~c z4K4KbcSYI80ojx1`?!~7_gZc<%exNknq<9=twQ$?w_}Kpza*9tyFoR zi*t?8FU%Nsb#&pGDStHnkl$0FX9a0ixSp)XPf<*3LAi99Bf~57oMQiwr=PnA*}I0s zS;9ph$GC3$(BJ;CLnl@;g=0VyN#^^lpqoHbXZloyqnv|6pKKuQs(Q8E_ZdB1jkoMY zmBX0ijroB~oWZrytdZ}9l5-zFZ+49I=BWBW&QG<3t|1qRA8n<$XC3V2#?)o< zRtMm8R`3&bV_Y#kJ#QeA95Pt^6|_#|0C5C8A!}g!J2B%W(b56#&Vjz&nQSx(F{^n@ zp`IzIBtTAqj>aU|3(E$ilgqr)4P~5P15)P5A0l<-upeXakfXBF851+hS(buz|4vS5 z&YNG;)|D(y#pz8r@yd~L9?+4`T@ejNQH^JIKN(ccc9M{K1$wj%$^_q+T*kzgNWC0O z4J;^T9%#oHS<*I5d^^v`!X`kxyqfWqF+U6P96jgS+;NS->c85!E^I1$6J=V@4DvMr7^abPt8uq_+Ety!N|nU%Ef&lTQS5JM#|kA9cMN`9#%S5J(-GlT77vL zOE~%32W+2kr1EX#PW3S-mCgh>F%6><3FUm=(pbVFDui=rTgJw)q2IvFAVVZ~K4s~; z-2#1G{1fAIQF_uW%Upenm%CqUlNfk;aF`lO^BuzLtJ zv-L@Ls?sFLn;cEK#2#bz&x8zf`*i>+#OlM?IymLK zX+lcc^N)xM#ud8cdnQ;9unoy}Xhns>cCLD_BUKXRoDL^`pg(;E7Nto3P>pl8FXfF> zO07;VfXx6eF}}@cYD=mneywqfIA75n5mQs@%fTvbScEtRLaE(9w-6&ZdcYZ2IT}B& zj$H80EZ<@uilZdN1`3Q4yW+JPK(-%?!E!(eKEx`XLs0sqA(4+8DGk6!$)`xxn1+^n zk}8A{>bypQaAq==1o8})0nMn)U3|44?kJP(?oq#Yl^10>C80N5 zsWzmLi%VsZZY2NdyRv>>tF@aFLv)j?wDXd)gT-=t`oWF;Ek=xcRW82fRzh=z00D39 za>Ek8AYqtsHDq};0LGz0wf)jb1pmi*dW>U^>7!ZdQxA&}#TmAbG7oyy(E1IT+ zRat_s<75~*n+O7Zk0+F%l>aN`OawChVp7}Gznng%J5W;o{vvQ$F@8%Wu`Z0KFT0|6 z{11jllKgJJSSE5)38ouM&0guwHuP~%I_yT zUcAilg$qwvpcf)pNb4>qRszDH96gp0| znRK9;@I**?0SNBq$3rRFOZhUjp|j$yZ;tGJl38O4XY5Cq`lf1WbYY2YfSg^}B26(c zkj(q|y4Yo9n-*JBOqyb$=NA+C)-yHdoxc;%_ALmpJcKzLgoZ5Fx#h2XabOTOSB$7t zvYw<=x?uMq*St%da;6ln*<=V)DmiyL`ZBA2xL@(TQ-i|-y)`srdjZIK1n|xX+^kN2 z_``(8)$WvWvN-q+i2giaS`m={Kp%Ouf}v6WXd`Hpm{@+7=;6eNsWByz>`RH4_m|=W zJG9Q;#l#9JP{MfbW_uq#gR$-HCD)x2)x>R{`^xlQErs8+aF3tF&?--m!QzWnx3}S& z1RbZ^ZV#6erx=)8C4HSd*s-1yThj-@T!ByxY3;~e)>!y3EUL7 zr^`5fhc;$6(fwPpN>zr0m3E2W$`WfDni{p^yT+$swXU%#^}`AV2C;~Gu1c>%i4(>$ z5h!wF3Z@desBvHOZCYuKR8ol^BuyP!>U2fo5NmzQuz3!9TH|J^jSUmfDsge2I8wxB zUm(=0@1*TlI6FgFX^55}3-8fW|!1@_wrdY-r~A7)LUWHkdG`PMkA z&n&91e_!CV;Jg0a$aWnvMRvPUmiF$a33Lh}(04#8HqJPDGsC$~n<;+)*$l9yZvTED zokcXDAZyj;!e5K6SP4C5DeHo9*qr23JlLm=kQ1JtMB;Oe6^m^d)s)_Y3^UXSDE09! zA%srSp169rmENB;gPPNBMQ`z?QA{BS(mq9aAn`c(khHr$7(#0H_m;6=wLO{K@3Pp< z|80I`cAJ9BCcCPVBPMJ-7|;avVV|w2G9_6=jW31yz+(ElG$KSYJQ>cqCG$?>wwDQn zhivbzVQ1a*L~v=j5No(x-{qR7j=*=`OkWELj)*Jd>;(}ZkM*3HNR=dUl`dY^9x{J) z<#J>^bVw*6pe^k)DBP1F`QH01Hch^4pB)E-`7Y>C-MX+TLaU(l+6M9s*N@-{&WkxH z-kHcxjyGP)ye*B}FxM4c!R9b-TSI)wf@i8EK3tWVav!4OVo1qXZ-U(-Cc`yzew>^7 zpGPPhOncpNX3m0a$6|WzqVlVg!|34h1&} z)HwNFfcWf$ol-sKCDU#PMpcHq*HpRQ3sV>rY*u~Yb!%Y<+;@1QUNl)5 z#-CU3&AE3SWiYqQItfbopizDd6V)`84$b~WOI25-TCK5Iqb5lWn@2DPmThO1tENFBxCxEY2Bs;eM?rH!@ZRraqvuU}lAe_%>Ti=KK z@N_)!*k{>^zijxh4{nmBbD)atS&X2`H#760CAZzqI}+~XpNmamm)sOc+$Z<6kG0q) zu#fKPwA_L-LYhAxavW_^J2b%~1utdZcXhnga(s5RydYW-2z_U3Y-IyVOTMeQMSL8T z3~onGtltFlY>v=EAMM<|mM?)n)De9~HH5e4>|9;tS~aV6&w@l#wWi#hoSz0nB8L%=~TanKuSEuFh8ymi3=nFO!wOz+gaiV>hJn)aZx(67C;M;e6R) zQN$JsL3X7{<}#X}c8-L!d???rpEd_mZ@V40m?Z4}(oZ!SxmFS8Vcf*V|I^O#9{_BH z;$yotUeoj(UL0!48h%rXGQ#bD&I15+a z;{&Z;mGR;5rYew(d}@9Df~geq`cuj-FXm0f;}^3G=TS=r=gU1EZ&zPf?KBzJUa{9; z^JP-Kc>U0!z(BQez5WLIsNsFJ&=#V#geBvL@*`PRjQ4HygCdpT;4Itsts;+=Z+%pw zM^st;W*6TNt$F{u*dR^_lo{whgQ;=ci$y7 zRKH;W63Jk3ldv%*(Mx5xA>}>1VY|d^MzyLSbD14oap!?wlpXzPEnbJ(Rc~+zh}yhP z4YPe(mQ+_0>Ewf^PLs67UH8ZxDRzv?P>Nv5Fpk2=@i8&fXn(oqsn6EhR>_rV_Oq$`SC;<6nA({; zzyc8(UFY&R$ClimXtS1BCPA7a;)1?h(tUAVlP9A?>j!{Nv2Fy>GW5x~J7dhZ#IFxp zK}#29t!_d08mZ5eWPrGTLvP>R=(vQuSNqd3@Vyj^7?*Ylqmj$;U-?5ADu3AGsRdkN zb1}4N&Yl?DCvPAN44BuRv@(u3T52V5whfY3nDroEGoxXO7mN*NB^5Si?Yha%nrY+H z5gLUq;`;`&cQE=RjZ5^twkN{QBig#f7c$J}d(lCfPfLoQ!AndK#HzSnk{kK3;K?KcyXz7nd&``XveU)KS}hKI$C%>;hpB!v1(y=bjkN@BDIyfW6WH&ks2jU zj)UyNbTdW~2#%_4Mh9EKG{GtY9Fio1eGRqC#(>G|K{qALYb*gD#4FvB?7<7pGvJ7^ zC{+RCkhXpQgW%42x)7xdqEyzc#nZ%yP0MX(FTeby@^NY~4jxLr(=|RL`2RrXCp1L@Zuguvh!n(~z+pvJSdzb2EVo$4OkATscz7R&I{4 zu~%VV;#M*sG9r%~$PTX;5J?_S@IwOr*+wFc4L~F#2TpzOZ?>9Ll?^*U80rReM>}$| zur?4wBbHX~#oGx`jn)RM7U2{H~Fx z5a3b}E8uBc0fmI6gNu8^=?%!0xV~pDoB&SbsrWFKNem*JeGxgnzW$xD2w0^SmY6a7G%k5EG(p`$kP&oEb9c%uY}H_yc}oTe3LOQO@Ji; zD;%Y0a&dAK>ICcrejs%L@P2(}<#3-YU!ZT@Rfuz1d7b z(6ikgfg`T_*^~DtK@%8D$GqYzBzWuHu+a&=o-@FIztqrh|5E|70b7`u+gk~k@nh^v zg6sG%8ZSs#pv>b$N(p(K)I-IV##aqVHN8H$vp$A2khC#+v9<3C zw&Cf@@Al5+V|iV%-rss@Hl7K71{XO-H&VR-6LC#efgV*ZM`8qtOHm2Pgp5s9uPDFD z37d}%pP!=QH~lB&aG(tN_}9X1zx~S@+}CgsEV2pS2px38o+2=vD8)`_<6V^_tb5vQ z>)7Jb%z|pAoXENA$iYz0SeBojKWWUByX1~eSwVvzpA9N+80HADS8h5Kf-&Nk(lc1s zm&%FMsLbY}XH;lcRqfRuqz;|Fb>H0ukQK7i?$8JiO3g#F`c>sJpZ%+XvE(5u1 zrFV>JErgWeZ+HbH4vZ|}VNqP`pHw0uzjZK2|NKk;#iE(H-*HNx(=Sv+^JL<`9Go8l z!gyJpFxS&8m2cLZ8Aw0X%s!onWFG7&xBo) zliK4YebRg)0I$aCG-OpK$vu|~zx0Q!qbRXbUmiqwIFPR~wpr43kQp~$^N_EcWXiHb7DO?x=}0|+%3>q^i&T-seLutkDP@Y> zx?I;|oIO+C)Y61)O_t-Teb6Cba^jpPa+2?G%OyHV;NOv6WOtTAUi(@syc9mRUn0()ocUzciRHAgwRImeljZt# zoH3($`w`$1oU`9C%YNO6oH7BzWrp{(Zc<8VFqL$jCVSZ3jz_($X(NNBl(WK-N!l3K0vV%UUzzmn365D%s0Bi`wfkV)XHIeJ zJo`cnK(|7ipHWW<@-IWaICAl-*pInDGsL#?uBIaib}H6bbD)b#CqU00w2_-!VxHk6 z#l8-aj^q84l^69zBK7#Ujc=Hht>kyWqO1vs1y+MW%9h5-SlxVgUSphE>k6e7Uq{x& zE>sa!Rt1GjZJS|TQrA~#dI$2>eKF+gDtISwrl(^)q(TAesv$EFLpUJpw2p~ODH}NEXcc>Y%5Bap7CpSSg zBKZb(MU5lUzd!54yk=2*b3T=Wa^itJL*-BsQ=rfdlmLFFj;9e^BAjRQDkZ?os*3UZ zD^cGYDB-N}uc6wQ7#e)>?En4R}&ba+<%!EyvM%Zue4wjy@K z>tlDuNR9=vyrXg7fuscmk9wrDeen(Z+PRlEuRBD z7hh(L1+wj|JRJlolV6yr?R#F4>Y=fyT?g)NGl>%Z@`W&xxUei_Nap$MM`(!2`-3|x zvw%9t{2K_7fzh+~npl?(lRPyqRLIo=fyT%$+~svJ@3pz?Uk7K8Ukv~B)CpZm>gQf9 zHOX099F^}7xi<--rEjF3P;nl|Gp)zwdauOpDG1tuXcwhOaU~Y>6GmP4+fS_Q zALNnO!zzKgbny1MOAcVHmo;`*g9Z1~K!@!|dU~b5djalftMq9D%{1cto~5%^R-DBw zrk2CeGNl&t)(@IwaJ=to##nWykAqh6$d&p>Zu7NA%$(Wz$&E0smy8crhz~JH6ae40 zXkUJu6;-XICkFblu`?7wkD4Fh;t1S|Vp!7dS&A_%-IY&IP;71cWX`{McS`;l;8$@A zvCPWL$8{-&F$#Zwkg4n2L~LG?`e$mSXst)QdgYQqY}k5~gH5)@g?Wv8ulqP7MfN#l ziCsQ}S}xE+6W5DtuJ{kei#BZUI7zwPL#uyk5K^r~0KQ+BJ_-E&>JWFpWZ8~`KwYD$ z!KlkF3Gq~+((`S&;b~{p_f)$eX%I zB^hNY*%XL{ZeHZ|QIACZ;b>}rJ0vTf&x#uOU-QC!Rl+3H9D zbC{~l0|$9|sXWxF^==d*J9q~wS_&3oEpga+8K;bQuCxX{oIx-0bb?3yJ6Mse?KJUq{mu*2eDUVGCH#L9{mHK&NU2-H#ZWLer8fJ-{&<0fEuV}`%*Z% zAKh$p+j5fP535}aRVtRh1wP85_7?&uWS;tMhCsZ3B@SIHE7!<;#Pwu=xzmGnra3Dm z!P#8%dAT<_v@d{QWh|4+*g$Bvwj)S`v-cE}sP>t_?S8`%zu=jf^9|Db@}~OIf%YHS z$BO(b<4$*uuxAKjp;mM_D|(}{^)sb6r}Q6{{7=owzbOmt>E;3#32q`STCB@ zgC3q}j7*pViz(%nTD-SFXbI_#ERMs>i&GY<6aM#Upv0xCV>a_WUL$axZ6E;p6|DMW zxeRsx(J#NUjxNL4f!SK`!98SQtGWDLz9HhLKvtKzsm#Gu_(TlQ?2YK#wlS4CzDk)G ztoL0z6)J}JgJU7k=52Hn6GrmEwOITuK4AU?x*Z!Qz)3oU8!!QZ<>9=SF>+-rK2YY! ze3+RwwHUtLSF#VGPYWXfo=@_Id#< zzaNeOgyZY$TkW}(%>b(|C zlDHnS7mTa2-5{j{_LqXX=>VTn^a(G0#JCN8c0tQbNRuJmdf%U1dC?bedqPJ~-v3Pt zC~4cAg(K;6LEI5Rp^z$U=epD$Zd-aNe(CCSfM~f4IA)b$ytuTjmQ5COVKA()4G1Bi zU1|u}Sp)J_X70)#D0yfw<&)n=G{n8(q`S&Kh-k#8T zKPD0-ttuw2E;GcGvd5z>* zC(7@N<{$5!wx@i*{{W2ids@u47kOpqLbU+~tdozN^=@dIjuJ^6Q%SO<)!9HAd3X!z zHlOdDqWK5W{Z(7|{c$p&xx#LA=!*_Vp-~l~neSyDy`dG^-$MK^IsVtjkCLdA+D09p z&HpWqSi}j@0!g@Sg6tE>A|9$+g&ta)_raXeWu66zJui1dxq7AJza_jTT=vJiv?pT}Qm(n$)w>FVoH- z?aynq=D|Uti6WDCO-(YMJCj*6;v0XujsNBacM^cnYp&9UzpBfI9VfA<-r@{P!zyuC z0zrH_CB?f>MpC@K;-1}ExrK1fzJouOKgSwt&1pW07y@L3naL>nBBmg>g_>rR^`tapg<_^>tH3uMmfsYvQK;hD^gG6qW=}FelIfcV~JyIjy;+3F_(#b^^Pb=8%lu zvh@sz@8?~G8J4%TSstU6BkSANuTQ;^wKz_DF4o*5o@MvmEbF#c@MZW8DK8Qs-huIgl6o8T3SG%|AAWW8ruGUm0v%fv+qd*{Qei>lk(h;O_O%lpix%oMXE0acxhZc;CI{f;d|-h@n;F`>mAkY@i5+#zetaqP~vT#JN^Y{B67EDvTE2|?8Omrs6D>2d>*ohao#bNt2U^s?tYW`U=pfTcZj zmNuG``RYmGl-=o9UEp_J6c68Qi8yF|l)VGnQ_mE}1?F<%x{g-*VKNiNV&e{f56mHp zjfxqRqiGWLnTPps#mNIW_JgkD&~DG=ecg81F%TgW8c51wsSbzGCG!~b_F3MtU9TWU zJmx&9R4dy5a;*P4+{7Gc!04BvtgLKBt^4|b((zjV@)#EPe*v?s1#qZjO1npk6iA5W z5s#`P)%pe)ihU{My_p-ua1Njg%)uA?X2<*w*iFx61*%veVAK0$}!3rwH_3ud7;YOSQt#4oT{~{ z57a0f=S$nZ&b-4SY(IJ#M}5}&ffrVDyiN=BK^KS4eTo@SWFjZ2jszWTK8%xz^P@F& zU+Y6;y2fWiW*#%-w$)!hf@hY#`9_ z184G)oSMSr>C{NkMG`YSco<=Oh%ey#1kyredQ`Q@K`S{Qek2u3`KUVzgD%xSH4vd! zY?=iO0OH`|$E!O`6h#fo+~!lw2sutFB@i-=qYy1gB9LJzkxnsvDr`~rHd1AUpdh}_=q+$aHS9lFwOJL2yM$PzB>~OKvu#$!As4%S_qZie?}cR-w4e*kx3X}5oPP7B;| zz%AjmWBVFhxpOs9Y@(3ZlNfbs)1Mi21oySS0jgZz&V&&x0T*OAooXpjNQ}${9EN3n zhUL5ROY^Z$2D&l9k&1VGqIe_@lb!#rh5v&}|Jsg?aR2YXj0{!sOEb-eM`nKwy#Bx4 zZGHgc3H#}YfqW-6Cc#Zu|3Ps5vBvvjPcL9~?0QFP(4 zvFB*Ur7z_8OP*s9(FDCzOX_KJc6Jtb+aiC@u3=vYjDu>p2xTgw)iN`c?J;&)(m^>E zK=QtEdGm3PiB>+eLW!y+p6W;bU-)Dq!EOIwGQU7mzQbX`F)aKaJ1koW#EcjU67JYP zTyX~laFg=%=i}6J#pkaxWM!V_!il)(9#{dRdl95sMkV0DOS>D$jiCD{fg*djUoYz#06pwBN*!g8A6p{jBUi#xyqN3Jc`nk$*72AP#-)70H%uD%dw5&e4VNy-SZ;T zh6sDzuT(K&wnKlkDMyAqg#%MXdnVHycTRDQJMq(-E$O<*E?L`eSROWI_HwAgv^jAO z)Bdj~^v585{LyoFTAwVG<3_O8SN_ql&%g4PKZnfjp*%u1lge*z(TEP8Mx1ag;~F}ydF|3V>M+}F5vqFxCf7#-7e(`%DgU~XRkfsOg6?SVPSHzzw^!gl?T z2oTHY?YEB~Id}EGK6`{W$^HCmZkWk;S^_-0_nKtH^3c)3tJWCnfPf7dbAR0=c_sK* zaf})WOtZZ+U5-sHXchMA$?x&H-L%dq0ow!f?`^qKKx(YWP8?9Be0VD@*-SaxWuho8 zqNJ&01vFBeDRurw|KR_7#*##T)sT20n*njSG~~b>m~LbnI5mj-k5dZNGElWL!(2NR zFASF8tE88nP!-Nw)vmtF=%KhsIX#S^Sd*}NrOPs9f=F5!Qwn6USyOcFcZcPvavSBh zX3$d#Un*&1lIstGyR>)n9w*{4l5>6po}C6tLyA@^(DF2#x4cojOW3{fVt#rp3M`GJ zLn6-M!lN~6pvyME`C6F8$Yez`awYOxY`hts@z|W`2D&6`7FK8Je{B5kBltUhJF*Pb zd%O3+W#%D!HgIT&-|Z##`Tl%TaX5yuQKe%`Jcs5A@{7*r&O~m#6_@|rW{Fy+AyPnl zejlSfQ6j@QTV}>uqN`-pC%c{8QhZgNg*TEzDVQxP*h>4z@vkw{NmcWq<^cUh#}vuy z8H~Fp16tA-3+O4j zP0uz*p0`0yHb|zc971(CG-=qLPM&(jtUoE)(nuFx>UhX)IcpHDXk$AuSU$XR{OeSlLn`}J+l844Un4h0Fvz`TY zDGG!gbEqf(amX5U-B-q_*IM}R89r1D|Huxk$Io01qf`!lLgWjkTP3PF+c`Zo!nGjK z{Z^1j+#Qiv?IeLAJ5pCRG#CinS(2sjQWY3Fne;ngnw_0}hVO>D7vN_Oc57>E_9QvA zO)4f93&41u=l3`{apE~N-fL1qu1>!En$g_B3f7VVrbx%W7>OzCQGyNG#K1Vijaj)z zXPsLzx3V92hLs9_le|X~uUT|V1o@*KS35Z1;I?59F2#}W!S3F?J=AK;RIVLIugP)KS(wm^BS1%9;2updD*kkV=xR3LM@$f$ehTnP0dT)e% zB^9xJj#(IRjS3-dE8TJE2IbaDm5x&ji;FMB&VljyknM?L){9#x26orY7^ybu#~$$n zGSFCN1+2QuxSnzJ9Gq#!N5;vsMy!eKne;?mN4tqBi5>2+(5+M%g6Yma>8@7X8%jXS3_q4j1< zCFg2%st7>=`N;VGm`rxL!2+(h{hGJwTQg6?m!~N04D7cwwe6YI9dv-q6!DEEGtPj!7miL*p>SVZ9VUK0HTt8(;AvcP!U$ z?a95+w7zV!JJR`g&B%kKZ^k8z1wMGo<@tb3YTqb%v(l6kFYL$6R5?E?mgdtVbYC0L z9aC^{FE6O0H8x54sjq$UoCXxLj_??uv#N|WFiR(8V2B2U8|1)QM`5)mQNVj^tld@D zUG#xi!RWmKaj^o0vxdY+WbEc6LE&GM33xMT2kn!ZN2l){j0=6aFS=~mju>anMLOe3 zo@d4k+PQtLgKU!edNXo7#Vtta0^79GEKHS>62mqvB+EI~WczCjrc^6_NvvD1UaRor zgZQ+xycImlhJc$7PB!NUpL{E&mLgd=$A7cM>*3>(un!u`dRa$dYBW8-CvEeJfLpr4 zvA9=+XJ)G7RK20EU(6YEakW5Cu+TB3oXPGzn;U^P*=eoken`=;I)_$}if5pExkN*6 z4X~-kZBH{xOPWP^Jj8)5SbcEJpyl1!iUw?nxV!W7Ora(-t<2IIOn`)J_V_7J%WN$P zF191*Ad|=Vl1^HNAm~$cYHgyFg9jt5Qaed^j6f{~3v3{#Xa0AasX7N!(Tldgq=q)fLZo(``2fM22^66g@FHQ=GVco z+FP)k+xgAa`T6H}>2A)?LwDYChnLzO_YA5;oWXzc;T~3fh)~;5%iS->;2LMBDljsx zDCK@q5alLk0z8b{yB0AO(wx6aW5y@|WD(Y%iSxIw^0sTOFTH<;-)jXJ! zG4YJYl|U^+dhr||K(f@wqsU7{pv0da(ovtKYkUKwjI?`bX?~Itty(i2s;wAtYPR~g zc=J~E%_iXy0`UiI%d=hOV7#LEjaM{GbnE1!5Z`pz&L&EmcEvENbvHIP>YsKo9#xUv z<8v=3-l?mOVAP8^-<`z;;;3@Xt5vPr@qHH@1rpuTC8diXn$f z`t?E79t1<;Vl&?UhIRwgz`k}jR=rQg-(uxD@*DX0|-WYu4oEqnrgg+dbW1sfjJg3%A$_{wpjnGmX3={p-JP+|+cu~9s85uDvM=TuONBbd`sTdLUIo4;HD<#}$mac?T z%^xP(b0ku+R|pe@fp}X>7=8KW`SkON*9OwCU0kkR+Dq-6J?|JVWDhWvSab*`37A+h6dEQ84yYgOTQ>eDU; zz9|eNH4ZrU$5p2Kj8!2h*7d`HUTt63C&^sZZQfhih+ z=&Aq2BlfSFsFDL$TsE~%b=9@3VvcyBw#Fk%1JueA+Wg6(0CFRPF^gV&X-ffMIhb

hH`wmj{h?=-bX$@@7gy?N7dW!zedqis8SYKi%J@r~TZNvdKvMnMG@-%dIuxc>Gc;WY&2LsXD zg)9I|K8(cQ>Jj>cc@31^=B4TAzfd$3z1aLl1abQEB*qPeF%+?to32>{Rwg5Uw0QuE z@w)#{#xuOx)62;JS=9>si!~HHJJ%=yCmmkXra#u39red;$y*W0t=pQl$vSCYl9We& zqmLlF5;ns!rs`itos28AL(7H0)2Pd#zB`P!@6J?3l{D1X6HnGZF#PTuMb7nfGLP&; zSS$@|hbItG=e2J!(jIn|0N6>c&|v=-@pz{B zJn{Ko3k0 zN;>f6a}Op{?x3bgu3cZ}K0m1q$*YoH_?{;r)rsPIcLFuF25Sy4VCcYvbl#u z9;km%_ZIi8h#d-&^?cotl?EX7$@!mW7wE+k0tiwfGMK`*>7%5>9QysicA^y^M$Aev4@1-wfVmJoHlD zo{8yAY)kl}!z}7rqIeJB<_wa>9rtpYgzt?X84UU0*Y zQ)vHAB8u^V$Rz|o_5musQl}XK zb&WqMjtC}tuHq9M+qo*-HVdc)$lyHszIWXs>Fxa|zK0g~pCpqShr>kwpQg%I*jBp!C9g>MT9VOSt;j-ym-90!udBzY;&&%Hiv<`I+ zk^hf|_;1V)XpY~(v~M4jVB_c<0Mvt09!4r@fTyc#7xpwY4hlVSH4Z$X417vgbH`q7 zyQZr3K1&_X>RqRdQ(&T^Ik1Uv2cQ1hEz4BcdXZnwlRNR#Hpq+rhkBNts zgGy--*78jZzWkXWUQ>=k27UlCMTMVhrq-B5T>m7Yfd5TG8h%X+vLC$x5&~4&|8Eld zPuW!m*l>T4@cGxJ)pe+jNtouFGZ)U+b43uj08_3}v|?6RGr+A_%EvKX%Y$7$!^+=o zqnvzd-h6KUwaI&!?Q?sMxLG4`UB0uhhGumdE-g(VnQ1>P4H=xloN$*DZIEg27;BxU zbicWObNkJxK=etbWZcHFp5wC7epm5ab<5>MWHXSflr9d+lp>q&ND`FRXRZI-o>*F@ z*xUOcW9Dtl=ySB%8#*X`eHV_2@licR@Dg3W6Qed}wrPzCX zKKBkA0xbkea$gg<1?*beZQ%ii4DhUb?u*(Pq&NuSrmcxVv}c{7U&8wpv3yW95ueQaG*9STRy^qN}5RZE&u+I$V zh0L_pZyb@AQ$BJg+s9^Ul}^K-{bWw{TI>Xd0donyVe;_-_6ZB#Pr7P|gkq^OaA5Q^ zvbAViI*x@S#Lbd>E+@Eaj2#@^k+aMTkJ!H67t~t zgZla(IiJxF0Oj!i2)sbm3#FawaL-tQ?fOYOvADK{*W@^rqm;dN_%-pq3fT@eHg+3u zADpzbbhRJSR~QMAy!BBBInA9H)83T5gk>QUrS`V=2&?dg4(@+;dBzy1@W=cof6e;~ zx2+rd!kE#Y^}UR(e`5riZCBSGJA)7u_0B39M5|{UrMTj^qQ_h!j;zfZ4X0~+5?P;qn((_PK7IAU% z^>`fMjwkbfCPhkFD1pU^ryD8+M8?0Qe=sHxwq4gy{DP{UIy$#F2SQVrx6gRF@_SOb z+$&VaBu$59m{QG=i*2Et&kLzWav!}T<9MR@*XeydtlWS5U7~SszGM3)B_N(GyD6SQ z8a=`Tdn6a*$xY#gTXFbquGYN6wLwls&;hX1@t-wTFLW;uX;N=J>wQn}53d)uXUZg2 zGEy=O04LYKLB_8SG)5+f#L-KXM9#f4zsP-5kg^?m5$UIZMfdg`eo5OtHRGaH#c-=% z^_*-X>5!T+#P`_|!gBC@J(SV6d)qR2pU4mcOPOqE`=w9Vb)7oq@zM)84UV1u8A3R( z^Ym2Z*Mb|EZD7I%II08Ee)p-HfKxhp@pJjcq(WbS?tyRQHV6;6`J>*Kfashpyw*3b z>yUc>yy-Hq_Wg1EhPsX8{A)R>Mug=pme!TeiNw_QBs2V5f?bE7$ zQrlNj`~>trL05HSA3p=R8936ZNps_AgwS%%YC&%m31nZ|wSm*KZ zd~~}ha1ibdo8N)L!VF;EE=!G*x0og|_=CJprTb`ZR!Mk0uI^R+LdU%0vg8g~QqlR( zdOvhVz-sUEZ92*78XTAUgl1E^@KvTs$MQPW+~|{8NFF}USQUKy-oS?h&H0-V|H5~Z z`8=?Jz7)29ygEOk5Ij;J8HmM7v$?Bi|C4QgMfNu}^vv(tv%JIL()RTzt7c6<{%u?w zb%zb(SEb)=GN;0n*C@(Cg}+?*y9&P`GstBWe{7c-N1JC=`_(XMiR&HPIX&e6VuJfq zJ&oOu2A1w?r!gvgsxexEB||S?{WBBGuXE@AWcE2JJjoseqa)pq$Ekd(k1o8GO6z6Z zCNan(IKC`5aPf`G=HY{}mXvpYYFUlt@;G?4S1+U;UtzuaRHW_@$v}TT+VuCfZ8aem zXUh+^D7^8}O_bk9IJQzJZ~Eh{r*@CFW0>CubMUhP;mhi=G?^;FJ+}KFn%)-L=df&IF34(A(Ouh4 zs?lioTDrUk_Lo;sUs`t}7x||-Xi|3MOt5@0e+Fk3yOYl>9#o{FGu=*7Tk$9tZ!s0F zJHJ=!{XfrQ`>}9l9!rC_Ou*vv{#D#)b3${n3P;Ybj{M(esD3XLCi8|Dx9_B?z;fNh z8n*iaQ?4jux({7weeT9R@}6Z4m%a%Hi`^3ZRFUv_%g-mtF+tdIDK+!+Op3J|PqxWx=E`5#oSzR=*FfmL7p1$z=DzRrId~OIE{2B@AJCOEl)E1UyrN+5 z3RHQ*@{uw3?cIMykRS3vo}9^tCtUkQol=|>*CjxZn>sHa{HL<;ht`072=Rt>4`?v# z8*$7HX~UNM-`?x&Q?F;=NnT&R348C^xOi{f4vTkT_uCct39rytDYpl*U2#?^Q%|-E z&V-vvjc>*TXd+BRix9JkB)(OXqOg0t z&=-mxokku{zbM~!;TZB}^JX#-K~S_#uA$NBx!JrE>WRKtSy>mK@EM9yZQuSC^tR`x zO(};PWB83NpLtsz;CdJeyRDfPvWHhd!h--^3dyd!!HhOBJOA@JgRot1%x3#taq`I? zi{sR@Qa`$=e;4535ZWl1MLj$h_aa`vNd67UM_e-i%M~VfB2le|=@D7E^A!Yp^x~!W zUR-U=sGvhsYjE22)=-RgR$a-L<%TG+C|X9d%|n9&kDlJC-As!*$%MP;buZKF>a%NJ z-KYO$cf(J$x{qy?+IR@I!YdIauJ~R5uZPQ`RyJX`JI?NXyJ(1#=aAsj6Lvw{$cqx& zO+(XMetcV81s7>MJv+9xR*q!zA=|#;@~cQuXX{PbmMj^fC@+QWP4kE&PldY8 zjY(NJ!D(BI&!=1a9Pv>v8e46Q1Re3`8|Nfl&pI|PuRlIx6_S>kea5XtD(aB$7D^h< zzkazBj0Fv>E#F34I1Zqs&XUAV3MvNaEq{JNJ1}!*b4<$}KhR+BSCE?TGw1bPd+ZD` zUSFIekYe+r@pRQkvx5(if4FqZ9+3>k65Sy2QvZ&3JZW4!5qV8IJOA-}IeoFzl=hXx z0#VoLNp{p|T;N%+6^F3D{APFt8czyJf+_0W(@rYa(IRWBkaOc4D$G6!w?{pZ^G-WN z<;V|uPnYwyi4;&#Irtl!? z$xZR0?%!sJ(_uG^L78~fWs?UkDKDP6OU6i)C>4iw%-`C-IZd1vXm7&O3Co68)ABr% z^E@)}-KP;)oM>uf{*?(QkwFB1)+xQzgB19PUAupu*`ISc^)3ddick~yeQgtk5KJiz= zdA{o7O>zEkHOGO1`Led^DpR&#iKXY0*B*gmp_Xl4Y`W;HdaLq6W1&^EEL@<_0((E4 zd<<$OJJWCLT>3UF;g~*S3ez0Yv|a*wt-rOqECsWep1JUA4He}{f5ZB~1p(%`*3Gwm z8X>JuOkZBK#4>wF%-KBPp)NBPz4*5=A^(+z9vv)2(s9Lk7e*?=!NOyq^H zt&b)Wvimz96G2fmXHM-}J$vx?rFg^+X5l_z<>>uxRA#?*N=d z?fP^yl9hK76R*9Hk@cU}(k+)pQ@#|kd1hBSRq!N3FmB??Xf@7bf_HJUyOnwYs+ei~ zbQ&h}b`}Mq;Ku;|T04KlkNb`Il!g>oIjOtc3RVeFNOwPc%KP>PY1SO|S! zzKwQgNpH_VA?tljSklK(?(kzu2a~RZ9BQzmHI#d`{ek(r2qO>qMu}yEeSvU0MoHSd ziumlsuI)=uIAB_nRZiOW}?)U%-CQG?t8bh3H+!@y3HK*58+)l~ z8{7(*$dK{h_VT==MOZX5pFxUsds=a=&)OJw`AijJZMqciG}^@Vy)g!d9KyFI2NQZa z=Z5Ps>Pc6}9tjVqMxL|HGkv!Wyg2%xQ?}gS%e}BRk!3UY?c*AFbqwxRUcA3&yd^29 zr@(fCezBH2yV7g*cKKZ0NjqE5rO8_({%KknvJe~rVXN)%|1P*x3D+${LG4Y3aifK}4k2~Aa^YXjr?D|sriXBTkgZgi9Dm*)7N|?u1|60l94K)qRAe3;D^Ug#} zhD2Hdhj`@M?{%?bY3X!zR@jW5ys%U06gzeab>{f;+b8m*_|t9w zuP~BpYcU>ZY=fM^PPrazRYaY z_(CxG6ssg8&PNd#Y@cc2b0#8R^y$Jjf1sRgmF9wuJBZ*aiL%d@u#5qySv+D7i?59QwNn7T$?+VqZZ%V=M5 z?k-l5LBBbszQV>~OFow&U*r^QiSo%WTLp8OI=@=<_IMprd_KtMk&WQ8ZcB-K|A+-+ zP<(qjeur2zyoMTKX)64T`PH55;$4PqCWNk+pKJ6Muod=f1r~_OUh#SlC_E2>W01ua zE=Ky#>Ag51g>g)a!{@7dO1zNKOL8(LmehTf-*9?Bp5PfA^`Y%cx#pja5u!IYGNgRF zCRtuBlMQ24{o=)ZJH?8Wbk=`{tSj-9;Nx!PE$sWEWyv*P>^O3F>Z%!CiN2fnWY?SV z&a4=_idBn^zQA2#oD)zn!WJ}ainMbw47U3RXF+2gAf7L4=3>=J417;U-K6w+97 zOo>Smbz{bZ()=$qL8WQ4DpJHeOa;rj~vCB(ElF?wh3VT~>rBdp?)~l~QES9yoS~3A;$3e5m=@&vPPEDrD#jN=I@eni_=|(K zACj^l^t*k1q((XYrkvpvjlHRhqkgGN#zq5$)(u?M8k0w%NqJUUrD2{)`;4stCeNN% zvNq#F;4VNmd8H{;(_2jAylgCN23+3UF=Q|q`H&7vT>+AQJ6s;cf3RygBSAGzHZ!Nf z&}-1~q+VW1FK)WP#Pw<{*YCM}g_fa~8%6T)b2K=`_AcP3*0c|Mut zT+7Bf$@FVw$ZPoS+~fhbuRA*(712Z_Mr-V)O{N;C?S_o&AL=Rb+Q#1bm@<1)ADg3B z!RRm-iGc5f@~_X3La*TF7>-E5SGtBTOl8vGD+qRBc2lz3an$s0kX_5vOBp#NOjgA~ zb5!Zcw-LrZW7Dipglsypi7!m9{f1DFSi%r~TpbOxnsUsO%U|@jOc2(fQ0j1wUR0^w z{2cAxY+(e9&9rD-l~2{FZWeNEq@xUU)?++tTsdJS9Wfu9+0@I!(Ih#x|!uIHZ;AH@!j^T5M3*|VxHJQ8$nKVpLuyIR9 zqCNRazI}cnSbB8=u3oce?8}JvS+EGl!?wo&A6aU9(=H^E(IjVH1a3XUE)ifXkg4iN zZM$9{L8h6$8|f=ghD^e=Y2fdH~vTB-h^> zuM0#q^R5|5SyyuVk7$V2Baz`P=Ftl(KPm`XGLUt+;6aA*Pha{nyAIZ+Xact9iBpt+ z6twuq&-?8sYhh)Z0BpKU6gsRtJ*rUEap-kyY1UJZeCu`t>Sag;1~*z?w*$6o%QO@- zuBQF+F%>Vr)sYzJuz*l$u0ri8W%)^<;SO& zfGSXh-Y;|J%hkf!_FE@=3snGEbpT_K??dzuwg9{6Vw;9aDsX+%o`?(xcK~40blzMG zbD!!j?WAtV*h2&WJra%3G}$O$9taH>^R8#^Le17NFHYt*u5kpP$mWRoI*gdK?<;Cv zCA@rO-@ce&EMn3~m}WKoYLHgtv*6rCqFQ>l6hm?BH*Do=?2DD;zZ**@{yN`7BT}5j z@lK|i9OG;{O7t>0SX?Or*k95AthFL}GsqmVr@&;|BbQ*0arQcvsPm7GOS{M$|2dq0 z{)ubf3akkt7v3hTTuX|$ph08lI2)I+eTi4Z-j%aJx+I{gHA!IvKNx9Wp$2p`-+``} zvp1eXTjNj_>B8L|#ov0&5R=Pet+mK-4q&#xUb-iV1A*7qAyrZ>9d^CmK4)3~GD#Tc zrNLyxL5`ruhu&`IXe-56V5kvHDF6}G-Y+4$3dh$Avhr28FMajwyM~wyW)W6i?stuu z2M$p#%ozaFh;>)C=_{Veyi|2gb4j%S1!WJSAwyxjR_E+ypsu;m zo`#HjafKBw-0H%Wx#vD$JUN^erxJON_bNSbE@kO0ge0Cx{i8nmt~XtoyK*gqZ;v!g z;l&CdB-HXsS6r*1)4qZ0+?CbKrt-@Rz#*9qCDKF;iX`t~g6kXsQW*)ITDml-;m{Dd5mZaz~7HW*Oroq)f0|IxnScCCp0Ly`f$LD>FvlzFg>i5O1{m@BuQIh5BR0 zvF6yH6HIeN3x?!jx zJi@s2j-VqTMuvUQDTDHjg{@4nfvoAbJuY6_I>68NZ~P0Du?cZ)k;kwkkEIBzUA;m( z!x`?~wYy;*fkg8fg!)w306Mkl9VRwu+F8-0m9O;9<8AWzviZj>Lx2)H_o|4;fx|Ej zE|Mdu*%AvHVNjgs>xBs%WTc49wNNUbea|vJP+saOUVtTqsz|1G8hI+kcrU$x;(1r$ z6o8Pv6;K6knG!)H;4!Z7dQkDW>lrS`TtPSseA05oo>*fP@jD--RZ}dQrLjY|%9FPItIZL?F&aKr-&i&& zdms7@I&cB~#8|-MB(vSPuT1(T8%=Q+rl;v(SvzI*LbFAYKz;Jf?wp(;-pQf`JPs#e z=c=A9#SQ|?w!&vW` zx7+KU3nY}r4t|d?b_pNU&$s^mfWNzDH=C$a(}$45X5W{n>!x z#O-;W+HW0OL&4z_PfBLu+5caaei0>9y``82yL!LzCGVnw=ad93ihjy|fFRG1b{n`2 z(g;tP{(hX_SXRYa+8N7+NuHUJ&o4Bz@_jneb;(6J<_IoPes7_H=fG0#)rCNM4i^ey zuU%<9@&Ui*C{ETDf4NnsHfvgy(?`x`GjtEHBmP}nL8#+xJ3(t6XUa% zdKch1gtrN3O|J{(4%Yt)WpZX35_9>yCQ}{9xtq^RyRd15-hll;@VGM5>GJtObfvu#&J&)VR-Sdnd!h3JCsc|s+&dt0$B5jjGUPO6w(2t6ky$o()s>mLbP($` zdA?Mq>L7%cMea!V-;nSOj*4b-Ls)p}K?3#|F+qQ^oYeG2WO{dHeckcg;j{;H#|_tA zuG?%5`V-oVyC%tr`VV?H2Kz`ag(F`omUA&o&Uo~$?~?q#uK%~pT_w&K44wVd+$a7B zZLOH&EDrpy?@AVL~e7> zUSXw#`sQ|_O8#XNsavdq7Wbj1qS7#V;-f8`LA&xK*EzxZge#Vibb$!p2-sDTQb_Jxv7#yc+aW?fG>3Irnd1 zi>CSlpe^z2uCqRr@A7pG^F)2bYRo3&kcwN8=h!{7H+f=d5%Nk7Ou({ku3AR$h4Li3 zujzAd75#Xw!~j3h^PfY;xH6Gd876FRBy1He?w;qlJUyuF+stsq7Yhr+>R$Or(S09)TQSA0SE_Z zj|^i;{FUqRz~-cqYpwIQ6J4*cFSG8NaGQKndlupW5ejrNuj*XO=IT~9-sFmlzl4Aq zTpk*XHKC_cR*K8QS9(7}JiYzk>w1cqAxb3D`TGvHN~e4O#!|8Vq?_+8yWalxA+FqW zd7GulWf@LsO0(L>?EsK7cCwrs1)YZnN;s%UQsFMl6SjJD^c2@#v-~!tRmw06U2IRQ zrQ-TU<1XvP*Yx1KuN|8Z71E$+TuV0F{3xCZDsAY)J4KLulP68pPgurhK>$kwN{UP0 zg|j2%$wy%A^dTpz0e95~k~^9AFr=9U(&2=5rUC3qE!h(KUhk-3;UUJm}LQy z*q1Lp1L1j$at)&RvX}v68|%KJH>bLk$@^t|e7kps1Vy0R1@ktIn*YKPZu|}lqiR5a zeB2oZ+>k4?_FrgYay}aZg+i(?SoKh(@%D@+E8E4J9Y@3D5t>Nquz_5G(M=u}tB?N1 z+676Y_bul>@B8bv=j?`oRw)RSoI(6xU(t9G_293XY8l86tpcN) zOba}E;{L7;paK_rY_e`Zqskf-f1n0P_B*vIc|a-QT*Ig>(zI>oK`TIrY7YNOlwL1f zsE?7V#8lxxe_zhe`d%NY4I!k3#l9@=oNbR4sJ=bro`ryEzbh-2k=7<&io55KQ5o|W zezo{J0OI2dYBO|B&r|!(VqwA^bT=$=<*2vo%j%BCn&hdm#CfkXEP1 zFPX!QpW%Eqs@pu`V};5o-v6LU?Fzr<&v?KsvgSiGz*O3R&c&zcGnL<&2Gx^YCAo~U z>o4J(wDpEkRSw+kZDRPcuhE64D+7u$41HF=+dYJ$w^Z`fzKt%k;9~tP!Zsa>fR&pK zUHg-uWG>;EiSe4dKUuYDC+IZ!>4+c>W^4 zh+Vk1V_49%ipsUw-;hQv;qp#U_H=*=c4Rj1nmwiQ`e9F@JzkmN|HhQw|6c3werWJM zwpB07huv_WxH@B-On}4-;eSZ{2@JqEirwUIi;3deKW|t6@X@ zHg*$n!k;N6?ZJtJ2J|URG~Px_U;~O@y>budum|I0yoR`|Khu|1q<_+=tO#>(W1&^0 zbevFOk;$}PFyr~ndQr<6C%fnpX@X&}=gmZWV^-|Y^ME7kkPnxI5Oew>{lm_{o{xhm z#o>O zX$NX#3s9k^-iUJj>;YH(>!nt2(}sGBfHKwddaMsn=&Z+rm8)8Sq1&L?s#(FXEwe%w zHAQ!hxuZA!|HzL%F`(8Of5Kx`!TqUH_CP;we?a)#P}11nqUa`;!m?0!;yVZC3oP)h zkVrcs(W8ui4Ypg*TgVhE!}Z%!!!}cDhQz_uIl0k;&YHU$YfZQO$ja1D^-QEno+B6E z&|~)7hj#%$P8A+-duK}~>Y&&!8GdQg_Qp(3n_B92E|$=)Z9K(;*ME-FyT9isg!yCI z@&i0m#_75N-Zo5UW5irDF%RsS<*S9Vr5pyOo$&(_SDi`E-?N-H@%3039h&Bu8T6;W z+KNrAch(vA*F#;(Gd^2P5qTJ@Ene&zTQp&lXz>*o{c7?|Kp7+!| z?gdsm3zmOzDP`Wx?v_ddOe3CWtk-b&00>6M`+EX*RUp`}VY2avNquu76mCLwBo}Qz zz*H^$=Q(XU(g!w7&QMaCo@!G3boP>%_=};fJn^p1kN!i^_7$eox>)mIP=_!QgX-(I z`)6#+CC4^NQB%pn7-v<+eC)jLIc*v5#0_`JU0XK`PbxXiRO%((QDTD_-s`wL4~A;r>EZ}MCJ?PNt&540>6LFfwc7*9=Z%g`5IE)VG7EdvyO8=0;n zP*=7z-9JG&qII7HJfCADHBa`&fG7TA)j|c3pOq_Lf;<2T5QA&?bp>zI&v2db=(>0P z`@-?HW`5S}5i+P5Z^zUEU+T?PAcZClu6tG=zb`lFlhJhCcJX?Zd6=#SQeJ!fjLKTF z#$Si@M}dW<1Ae`=+|{;zz`r5nu$;;ESmD2aj*=X}v9TZHN;O0=d28aw71%aeF8?!3 z{y$eR)=tH<+kAK2l~P+<#qclwf}tzHd&{pUB~!Ead9C z!Lbm{)A4tknKw`(%ih2xkToC__=7$oK1tv-^wBB zZ0hus&t!7!Za;uRnBKjUCr-2fwMf`PIlBia4}QLL1F?ro^c?*uZ~gF-n4j9V>9L`S zmR6^mge9R1$KpA*Hzg}YGEvV0w;X}=sMHMb##9?;8k`5TBoFm$@t`!w#B#8KmZaFB zp78t1#A*EIS^y>wZv&);7HNIed>U9B!dl*5PHMV+4qWTdiDumtE0fvdqZmHSn@Bbo zEU)`gY&Bqx+cjCcTm-xmIRe|2FLvzbFK`=vVYyIuG7B=mfE4e;upLxu*8Xc&{+1^* z;tXCU^ZX$J{cW?McOTcuj)jxohD3WSyh}YRU;akJZ;qR^2m*fSNWxwV$H-V)>x>w` zGnllxIMB{nHH&sU5Z+ulZ}(lfiY7uKSzJn`nW8EK#5#WCFi^NzWJ?4XZB!vnEkIlp z`2t>VLojaKd956k1}ZS2TOopvx7QLzU=tz)qX<)lX}YO$P zzlKgIMc2MtfxSy0_uH+X(0E;xP5R*;lDt%@A$_y95`;-RBRHz#@$Ka;7=!D~6lblP zu#YS!P63K2RmB!4MTzEDDwIBdTcBIy5C?_kFgwT;l}=;o$V>xWFmyRHZ!t($dVX3a zL%*;Cz&tmimGE-)MTFt;*-cTSu#_Y0lx_>^)R#@>9z=i-{f2LqcfrS%;ZPd~vzID> z0?e89yKar)Dl0wvrV~wEHD}lYyE;sJ*ZR`wS^Qy)Z?`XI)KwsRm(%()%hn7!J=-OS z|H?E=W2eWhUGL;u;8h?>h-@iu`G?7E022Rl!#VlIJ|&y8S1PxgD^Z6T8BbgeR~wFf zSj+h%U^2oCd57jYtUo*;Xt2MpY6*_eYQMMp@B(!5mDJ6-*cc&h3R|~bAuG%;&)JUq zjgh@kb|quSmKXh~5t=}8Ge0Q2x&W5{aO6N?EDEx^;dgJu2mK&kxU-}COlL$?irfD} zfF?mJ9Vmx?Si>d|SmxtUY?VP%!ZZ(2f4?{2{GOs)36dM@j;^MD`I6piDR6LSno)U4 zdQasez;Dli1GQZM;gnE&|3o&vlm`1AAY)*uBU-nnZO_53VEnCIvoj#!6Lu|8@c33=*E$g>eN=Ups-(ld|bJ z_5DN0JLFUQmc;w|6%zIY-J@%e+Dm;&z(@@9)G+gCeo)y5q2*lm_*6$=RBZNODblGB z?>g0!1m|&$9~;2_sYF6x6W%>E~{%3As_ zy;Wv-5iDWJte}%n<#TOS-ZFZK&mq#MO`CngyG1!bNRP29%5U{Iiu4b4RUJFvNrJ+x zzeo6H*Wf@z(%(PC&;atlyVcPHafdvS3}?~R ztX=d6_iR1tfrglo0_V(lOk@f*|+lXLw(4>Ijr{ouj_=`&14 z#wX8S)t6x2pZvhOp1LMlOz>|Dbn`Vi&^DRH@5}jZY@uExOF~{Qmim7O0e)mYY4qEW z)Sy^TeBi#>ZF1Q?o5)xx`>q))`O|0yGC#&8d11SO$siV;=|{@%G{OLlava#l&6-y( z;qoH`s~8AlXl5PEyR`TK(Zp6XUR*EOc z#^2v^(w(0uo9ns0y=@bshoLQGBl)J@>v0*j(6^gJlq|OcXxONub09c(So!9zVbOA0hd-*9H^rB`OGx@n9T!Yx~Bk`A|1d zw9t#4OMJ~Y#j{&SR=Hke%QZ2#Nm(Ai9|bvgoT zOFxz;OBv{(avysLf4Jl^oq%c6*ADpO5i+m<^~2$yC}CQH*MgN5$#|b0_2tdYN|T5s ztZCRTI&zklT{pgfR5sLHc-s4h;_nC$CJ2k#yI;&DeY$L38Gr@v)$Kr8Hv^RGHv{~b zZ{3+Wg(3l+Ll&+xi-!*u^8ZB+fPn+L8Xk9-9M?TZopd5NP}ej|{Y0$W;XsMIMbW0Ecp{Hq|0;Nz{L8^~Ofwk>XQOZ3Tw`>7sYlmN zePHIs#T$5BFn7wxIfm5g2>9m$yQ7F*WxuEU%L^d8hFYHuWWh1_0b_!(`22i`JrX!< zsHHF+A`*w%C?~DY zt4#HlYJ+0YIVNaXWorGI3rz{RSgV2cd>FUA5fb2Scvhtm2<8eVS(A_dd`sy*YA@u{ zVZ2(AgDI5Z?Gj%qeJ5m{iAD1{M}M0;F2=!i*(<9OY_H}K%yWCXmKTmP z_cREPacHZd!VV3j(;#za>b#Ip&mh|O?Pn(M1I~w3%CAJ?7RFjj4|IENa4rb2)Uprg;fzvmSQ;oN0WpPJ) zse|{5zGmhjS<2fi06CxRpgyGCUD-C5nu$8W75!Uo1Kaj1V;Z6WP0fy{gjH$?F>dYd z;=?zhT6=rGRIQ0Q_kC^V8}K$YZ!$ot-7=>e6W_l{@N;^RwV;eM3CO-5W*tt3D`?z8 z@YV51X_o_86))3#5z~&%x68V^K+D(@f~{jbx!{y#1gBSN9C|6Fu`>^w&|fkZ*ATU} zpO^R>0&qY}D3M+|v;`3aSN^YB4qeX@;AW%gUfC|f@y zwdoL3g+%w=+08F`@sfEvD^krRiFVcC`R4meuaLFF7_+yEtiz1ShGE;60YUxWU_XNt1)<;ZtsgaW z{|&4!#W^JdnQ~y0fn!;b^WPrzaCwhvy2M*(6WH0c`tf`(0d&sDp+vz z-IQK+|5$!Mpr5ZuB?BP{X7S_5IwhKTaXom5j?Ib7n;?>+VVe6?izjh5ZU4D>(?gq! zcIc=Bm}H?RuR*C!l0(WzyzJPAo0}`)X&9D6^!3TJV&7~^G*%59Dj(dwe51MxZ{2B|0Fj9Zay59S&4W}CHHOQ^M^H2P)PyWNUzN5=;NuBB-X>$w-E;Ci)D6pNPwX_JpEL&0 zk_YM*;|jQ4+w$Z?k2Cj5u75b3L$7y7`nJb~{*F>`?m3rj_~?H3Hn!=_jEWv_4~n4r zwY}m0M$=Ynna7N;MTfNho=9l-46autt%_7~9*vksP%ZHj=NZoFD|Yf}E1_Px+^v7* zwO2kl%;Qp0+l3l9msfE!eZzdh-Uf_?*~=}<5xs+-%YwYRI0pl;>`_g;Yce)YAA+X8 z_FF1_f68BGk5VCPiD(BVtFBn|Ino*i^`Jc3M{habmZjwc$NAeA5yOq0P^{#kaFT2y zZmNOwY%MQxEiatOf+mHD$rplllkqhV$oeqXi(1rywrQ_tf|kmz$#<^R1Wk14+dpbG z-0L#k6?g0riw!h&kW9IK7D6&JK12y`e7a@A@kfjR99peO9s{TrPyX>;3MxNd>}r5Q zkfRS*)$#MMj5)JWV=;kG>;+_c4K5Mw7hFG#>}jP+I}x~+nl~xfsVAh@8@7)>HZ_BlrwjdkLsmLr5 z*o-2lN4R&|gy&_YA1>b?tMJGb*g&*j6!OI2eU>iBnMf%bcbs&-BABNTb0gx}nDp}o z_00GRWJmI$>s{=JHtm;pqOf2}yB@xnp=K&Ixr=@;c`ZII!|smKQsC_z>0#5dsZVbs z4f-JY?(V{vy}QnErGXMU*wp%a@&S09t9^3P)vi8L%J@c0BCY5rh<=N*xC*^e3#F!7 z<%X>TdYETMZbQ`H%RaDe9q^b}dgQijDAjr|}F&f5WA zNw9}Z|M^dl1|=aE-3!)g>3asLlU*C^kPCXa^aQ>{sSBk-a-LOI7R<^?&(D;^`ZzM~ zm~cOHelrCAw42>IK+Yl`l?LxLlr)jfPVM-Vgp2dyE5j*LSKanegbu8y!Pt0wg+}1g z6cI7qT9~Dmck_UgZ-lXj{MXt?LC$@rbaQzuAG6j$BZqpT;(>+LZr}T>&+@rdUNsd= z_2w_*pW~-rNTGZl9TdC_>|jvy66ly|Mj0>ROw-}$EW_l-cXzNIeEJm|`)9=Xc)?nCJR;u9-U`NXS%pP?(5&=|n2Kiw|R+_X%+s4|w$ z{go<512Lvgu4R9g4_{6Ku(S_94@bNn!0~mlZ^mLY72;L<`TS10@+_&neG%Gh2FW+m zFyd($eI>f*%Maf5fx$-W01{9x#Py@}-W(cjU*rI4+}L~7JnXy$w4Llccuq5%2dO#r zI`TShdk)yzt~ge%UIyN+<7rJ$K6ExpyKpR2&@r7#Av;{Org}=gcj$*7Rd}|4#9_Tl zz;);?FnEh^@6f6h6i?=SS{V2cQc`fOX8*D`soPS>eeU|Q0U4#bjkUyPg;M-E`Ox48 zX6AlBVD2N!m>R7A{1=8RRIn-r*ZuJ3b*lj=lnL!*;2;M-;=A0gF?}m3fjpit z;k}dX%#lIwK#jmhk!RJil4BkV71=u)mRdZDc3Zy%cA}3`&WJVC8QYh9mFsheXY=*1 z&X2bg=Wfid;(W+P+^j}U^*g|PTAzcRBnIO31uSXmC)kg6tb z1Ow?B`ixIE9_}8wM6OQGB&uYoCn*@uY-kfCJfUN;?m5?mcvQvcs+e?=O3XlILt>t! zm=CzX9hj?o`l}}!w5jQsG$Eg@67Saf4$-9 zC4~rHM9)U$7Y`q+p@Yg($Lz>iaS-w1$ioWyIA4bA7Z#uT*q^!?s=Q>0pR) zI}>=`ad>nrIr?e9Qs{-;neu=o-ZBn-veI|mRb<6(NOt4c(W}qez6DEZy?>~NFDnKM zVS9>Ee`SB-$53ab0J@Lpr$Wc1O@2zG;J$LtFesk$i*{q@FydJEn!#_~keu5H4BFVZ z1?zrw|=z!3lT#SO)^#;>sM zgT-%;TO)GLtp;eOYS>JbILml$@UN{>v#dnzKFkNWC?zI1$Gom6=yhoCYQUGHSF6`Z znNh}8xXdW6Or6~mtJE~b4~Tb3X#poJWW8Voo9BJ#Y(^UCB!8us3{I;&2S^nj z&6Fn)4@M>TXoxwjWc%n=4n!TvM(lC9iSv28fVb)GpkC(hV4v>mp2FKq^%Qo7sz@-J zM?gO#BrCrN#lvu@dwb~IP%`XQtCRzyUl?iy%^GpJ@F0Zo)r?p5#4g>c=cbuNszOF)x2I6qDX!FdqW1f4W$m>zfP*gtNi5)0nv;S`m(&$M~bE$za5sh z_)61-@s4s&)q#y5A0I9tVaMmI5GBN=UI~bz@db`Mnj@o(SHQrU47zxUBLccq`l)+g ziMXpnvjnmv?*_8SVJO>Upn*T#D8H`0kwog7?=)uqj33a-Xp1#{7gSN%I}2gsR7+IY z;TYo?BH=o9~6naV0oNmh{IP6xDWed zs;xGsYnJgIYnKXW8p=_kjDG}pibg7*HXr7mLb1f7@3oNUHT8>~qjFN8=9~y_Ir`rG zv?Xvfd(jx+XQe_-sIx0y2+A3Xx-JDrp3pd^6m?GNQf5)rUPi>Y97?cU{d=9qw-7na z)wKzU1A>}Se7a>i&XI_Lz)^p){2(I zCSJB zfCg)3iY8JN8|k*~0?_*CK%(zS#^)PbGOAtT5h&boHAzlW(-5gh9WE)rA5gpr-R{JZ zbAkAAMOt!(9Hc}K^u#jfajAVu)S^Q<;3(IbhWRrU?|UdILJIXe$*{U}5$(TitiWSY zJj$0^)q21yS85>&yx)%wh-r1=9Q?VzDo2VU%j1y`3a#h0oFz{bZsgcus+>mHTvv2o zp0jx!5#JvUCm?JT50pDY>^x?Ex#JJ*?asx)*;@A2hhwb?4-G+J&bP%GLAq6k-~wn^ zmA+)G5a;AcTqE81{QSHIWYryud6c3gaE9c0b)SLq@+#_P_nsuY7>lshhPLs}QMcb) zm!)N?075X7&-4S-rxiN~JrqNQmjf5Su9}bzO|@o;?g=j6Tl;z$a}O~Qq5Z5{z|>-s zAz&z=+`fxd74k2*HHF(#)ZR%og30p(&xC#uSOlPjK?o$4M{HtRAb=ry7X<`1VOJvm zO#V`lHNhp$Mg4|0PiUrwOMl8_+H2Od*mQaG8|hmqsKgm)mRQEM#s+u>2tA?Y9;u+i zv8OANW%p^Dem%1BnAmH3i%`Cn27>?hk8VR9sTq|@7%fq7X`-yZz7MV(HKc~vp$l8} zR&Vmv@T*c8I&n^8r1DS%a7AKupMMo@PhUzahA*aOvfl~|yf z`%+D*p>Vs!i#DUB^k1I`v>8I@;KLQdUL>LzIghv{{lI)LCE*QrvV%6G(^Ok%!*eQ> zdVzkl4HdC#ULx{%C1Si&HS=`LiPj&!X+=u!wFNbBcNm&fy5a|>9dClkYP`2#skQ)?)qG#WDs@oYKqz8t1ph)b)!AvZBD`paAKPLNiXL4PsJixzDj=u|vOqS<93x zFp^>`B%TS`Xh9=j!1x+ka{t06W&ebeqV%3;%DIWdwkoPp_f1Ejx#vsW5rVy{Hs&h=p!lj@a;vQ^(d=KH5%~s;EfKKjbzG@JzlC zxFf`SrKbioR`lq+0@wcnSK*H14o7NEw406@NnM1n}T%b%3L^H z7bTXckP~EENm{e9?JYrW-^K1ULIJ+dct~H=-bPDe{)3T+x-LhU!knvAqd1J zUJ3c)CyY1Fl&7|zkB)s1KZ&z)tf`9 zz+aI24xs zjT<_o6uWb{bnD=BgR?H5_cON{Los<}_=&-`43LGR-NsLZA6NSluK;e${FnXC5va&r z;2W!raXVCe`i=4*wG;X@nQMK{{(Or{&^%&xtI`=X@ttS}n`mZ~=rsLz0?)8L@?typ zOHI|Wc4Uo#j+B4d`LX+gKWLK>>Uf|;pYLj4bf4N>?nju=v^~Rq1cf}QH;Uc!?yt4z zv_mTIojG3E0{OM1vA7ZSc-{LP&!VS~`2H83kvf)Fu zB;on7xQ+qKOdRu#g=|t~n_sHb$jqsmCZ!a21Alen*~zU0f^%KKjO%#y zYUA#>bvCsMskp-r+(P}Ba(x5lc@xR@$f=*_hS0pm)}&3!MQ?9k^mo_Xzu8^H$w0}} z!;x0MhLodhHq042{7BvCY?Hmr2J6)Xr>m)XSI0JP8gCFnswC{Zff~ZHpiL^`*xl28 zhy={7&|}f3tUrFKv2HENue8S;vqydpbtIcq>@sv)RU8C1B+ES~67KKqF8~W;!uzs~ z3X~MN{~1~Ri$=hnL>GelEf&3%*pDi-Qfu<>BAZi30@CLbhH}R|M8o8=NDzv$CA?dyeYhlqVeLpQB`J_sw(k&+1#u_4iQj;?-1*atf$BxjN7z zwpu}{L-sQ^f42Kk-e# z`uxdqmkBq&_tz|`olGm(5wi3wt2jtvkduRoE!{$7^S+Kzi-Yrq##L8DJ_BWH=RxveCu!>W*4U9eU@UnJb1rIS zG*>9oWoTvSr6EfT?1~pVbo`g0xo-Vy@Jj*jl8pwfihO2%BZGw6$4KZ*Hv4AP`}&a& zxE7w2Ydx(JxV96prL_7!5$>^v4Igv7lASv?7Au3Jf`;B83g>O@W4t*!EESE7t$ROs zUnGiN%e+M>a_Du;X>Wn?GXOxuz$aHlaEDAk{r=XjNnHA+kqav!TUVH>D`z|r-&$o) zs>*j8sNy8)RMn*Nw);14G7qn?NokWBhB3@PM3`&LUFiuq4+wA$hH%=Ap`)r74=e;e z4(LpTV+~CC9NNQ!S1m`)e|T+6Z)j}j%rl)*1>hvne4n)|OS3rVy~^{!k0P^UPEfb3 zT^m+}GE*IBQ1xkX_v?-}Z7FJACGt%L8T$FR(Z_9E&)KDu;9LMR6x46kpBw%F*Jad) zjQ6chIyR;v6H71El;*lkn}qM_&9gpAU@evakW(VQp3TiTX`61OBH`R@O`0{h++`bm zRDmhK7%#bOYFyg^0VKgP#z#+!;bZ63uv4jEn>g-$cL($2IXL{PyeBKhQ`~jBPp`;I ztt%snc9T#uBok^?`C5G)k{qRjgnPBY(J1k2k@uz^Pdt2V{KZkRR~K!lR|Vm5*}xGp|yVRF|LB8UAHfz=i76QEa8PD8)?cs?>gv=Quq+>-!MQx5q&j z0E!;ZV-TO2X%*;XgV5;3a@^g+Z9NT#)i$((wsfbBx#G0G&-HuDmd(`y1NQ!3s-_e!pjssBEiNCAa-8gYZ zETIbKQ@AR0r9Mk~9(_YSU7*2Y8CDD?q-gnUlENtO)5h>-xDCSMwU4gGOFkblM5XGy z@Lh)*mx^k)je=>Fukfj=F;G3ZOa>dJv;%I<2=t!5n+a{+?KHX%I)HV`>{3yMi>PPj z$|#d%+z>7pn#}*OCaL`R;v(znAyWfVE=M1C?iA5zm=<-Aq#2cSM;U~x+kH#z1u~pX z=U6br!^Zh~$8HY?kw?S)_ z$ci-lL%BXdxsaoh1YTc)(C~-(M`lky6JTx;9#0th7RoU~#v4CZY>jzQ-V4=xDgg$R zngg&c&!EPMVo~-))ahUx4e@^J&Z~gxSr0#aIG);T!!UHLU4a&Rc=m0Qj5_U^MpE!)Hea03v>pwEygzKeahB#EH1LYuX-x#)O)2E`?r|=RW6N zhi~Q=YZXpbXhMx1oyJm6fvJrdef$EGt0)UMPU!K`)|??=`9fVR!L}@o@YSEkV3G-5 z!9`z!AiZdGR9_q-qzmuh;BMlb>!#Y1G1l|W|mLyWHG zMDB77dwB}qP+Chdlz$K$78(=_xZgT)>J-Dh(Xsqlylt;LbnhTr?9n>k{0O$D=vMyn zy!oHaRdB zw81XD71nw>GzJRWImNI0wHmx;Xy(L?eZtp8IT(d&y%ao>=n#X6>gYD!If$BbZ7vF@<5bJaK=BfkvJ&^g;raOHs=cQsKyZd1Sev8iFK1#MR{c(B?J6bv-L6r}^q`A>5Y7-$*D2N8bG z%jwDQ5;HE7|4)(4;+jVF;1+X}E+f{uFQ2ay@jbgK^9CaWc(K3Zd9&3xB)lqsHw%5wUY@Z)-IHH(+H6m3uS_QYw)=^ zV}dle+0Qt^>aSoxy+HD68MP&ZOD~~U4COujn4_D}(NyG~k8PSIE~YvFi2lP_#mg)x z(?vZ1E?IV5V~!3tAi(*C+=|zCODq0rC^cJm^G15^;9vbnDhg1_0oAs;7r*`SeOXh- zqpPLZ44byp?!TI!BNHN~2m(PQBCNxa+ zn{5tx@A? z--b$g9Y>y6M4hbT?3`M}El=FH|Hk(BIOsO<4#RC>petDU6pYsSUaZA)g1)gJ0zsr} zGrIV%l1$|Oot}iQJUh<;+-7p2Y{#hlHJTx`r{1zZ0u--C^Gx51Yg9sTmwPGb?uz#issXTnMjJub|QWJg& z&w)eE96))Y=R-+L{SX%z5=@qN8@d1zJTLOMi*;+YlxT%cxGfifCfj5f#mp&aZ9>TN zOJd$&b>lGoM!6D$Yv`3~1@pIp+$Ig;6Hu{QL6_R1m|d@kJ9=(>OW@_st$KBXJ(SfeE8ePBA{&{I zkhE^3`;o0W`{MVw(r~Q7yDR6>8dt@(igQbX*dVF`5_h`^0-ouL#kI5<7NE_dd<-b* zeoAlapPwc{p1FlIY4r6J^yk?er|)eYo1At_`wUtANNw)EJN+>JzP^rmpDd;c&UN~4 zo@>ZTd3ht`^!Y$v*HyTMnq41oItZO1Az%>G<#~-bswWhfgE#-6C=o9yewI zkL)jrgTn?A$Z&_rELY4{CO44LZA86k_U(+gfc#D#L!kszSiwVyF5MLH)#rFA_37v= z&}sFY+UJ0?o?tz3&Ry0t*-bO|y|xvY-Jv=|36K1(Eqb8pSp%47=ks$oS3ZiHYn)(obB1_5`tj1aRHIPj!t!cdh390^Klp@DBJj~biv7#U^UO!qL6Ud&@X@$Q+nP$d##e zy@G-9q#`Ct?vo#L5Z@l}3A4$1>%_S>s`2PuCUGco`mi64sI;4qHj;b++hiMb#NB2a z#ONp|73PlNQ}~9QWA+t6(Cw+v&DUaPss4D3r6x(|j#${T4tzQ_2SJSntyVxNa?5;xNHE%0wTu&!w@bazQ z+}w)8*7K|vCJU_t?q8MA>8eVhT8|PghCiIB)OJ0 zN#XM~CnRqa#eP@}Moy!biRU46FxPrR+;TJy83pBw^6q;b-{tYh7EwDH`u6&4I(fQozmS$f5O^UBBi505gH0sPtrSY3pcVzj=LM;9FAO7V=-+f2#+UdHYf*NkExkfB|KO}N>jqK7pC{1N!{_x>X;^F6C6#}R1 z>_pBlH^(?MV{Uo5X50M)BMnF-v$v7&SqN$9!TB_+oLp}b5Grv3q7c6dz1&dyY5|?! zR+K8*`XWa$mA1-$ZZx#riNWsw#!oj zljgM5`#Q20h_^!t_n{RPBQJxg$D<$GPNTyibAGklXk{9HE=3`QwEJ7GUuaY}^Y50< zc}4T(@@JY29FTfnUS2w!&Wa~}{Mb_SO~8JB>T{GO8Yjyq@Cd+?*UbhecvNW% zI7r0$bOk?H0BEMWh_NYoKV46^+P9@4+Dq9*7njgjZD|i-)E*zsjrH5I8UB2CA*1S7dmR-=a}EMN*NU=<{oMP; zpBXfgyT5K9;fh2E&!3sHk*s1IbG52AI@q7!g^=WJ}lRq+Y}y# z?K}8n;p0qD-XqFEdu}@3b2fL6d5`YNWj(c=oqk05!K{F;iAARJ{+xR?Z6d=&l$l(W z+!mkZn3YYfgRGsoHWX8k@QiU;!R)O9Sq(3=`0%5`Bq0wpt$Z!IKIa-%1{G8a-`yz? zvHqp{aRk;4K4_Y8kH@RjI=PekJlaphBp$N1BO-Q!zKa&h(k9Bi5h^ay+_$qS8`mO* zO@(t_&l2|}_=@xjd^Pu$BuVsEgGNP=+lSKqS*=$TR#(WanWWcyn_8M%UxD?<?s3qv-h?t_Bt7d&Ji~vJZl6#UCjHg{T)hEOp zGQF^cq|n;nOMeqPXrW(1WJ5syEJhjpA?DsEbGR7rC%(8Oe(2cT;KnzrIKCz3xe26Y zpGC6_4Q9THKofkp=L{oBjnw9cA_u;3NeB;*ywn}gqQ4Plv*gBti0aW1B82w&SAEcF zDb{PS$Pe4X=5@g%8;9v*z=DO|D}nQp6fM#*Cz;4aFbeCko1CCZaH4tgO^I^aTUcAJ-BWI?fDco3^c(>bEA@aI^mnm28 z{k!02qAa6|*-~6o4Drw3K4kuD$J+%`@_e0p4KG6H+W4+j4f(WU97>&ie8*}dcLOSb zeL_Z(tV9zbC5?5`Uu`He=Q2cIMORkY{2<$ovNLI+jxo7!H_`Ua2|oP7IXz;slDw}d zuV?Ma3ZL02?WK=Fg^5a=^qrCt$>XrrxrJUK5K!2b5R9e>vbn*~35CfL*-jA@O zgBZ{+hGga|lDIoX#GXK=l8PLjQ2g;Asi=&|LL(*rR3s_wJDu6{FRWerCOy|ugHKF1 zTPRM*7CVjT{#-(TD7f&4A?Z@vST{JJsI>EFXGV8pK2o>J$jXWqPSjx(O*52Z`XMuO zdT_LlNI6-k!-%_e?$vN->_L|Qy53jC&k>DPHnCG+GM$u8$X4BfL-U&vx%Qr!5fUD^ zwx@z-Jr~zq_|2Z(W(luB;96+fyHp&yt+Q?~v}!ldSXoigp% zl7eV4HSw67+biPasnMnaS0WuR(Z9F6;q~uZo|G{erhr)Ia1^eW~ z8otkT?9KE6HN+vA+&+ZZ}!}9})kM;X5gf{H=VPPR$cSle~wxzi%>+I+{xoQYO#H zTahAyI9HmPG2hOZ3H}xLDLDWtWPz!Xtd1y?!EqomAJulq3oUK2(=`JpMFyNamV>xB zS=n7+G<-~g4-dDp3bWKL&&XI`SC+{UOnuU+mGl^+wW)V_(V&&Yh?#@c!Ca~bY);2@cwrahC4!}g4$gA@Mr&*|~t`>$(_ zY2R{)_sJBd7nc8H+c*Ax%U^T?E;s#<9WXRxG3ytSDF__$Ts-I?<)Y#jwI?5xNrv6- z2^t~F#Nn)4{iPj4r+LhZ_3H7^>Me)VpMg8$%6t1rjxCsa1#kNU*q5@(_tI@q$eoVf z`mOk)8bznKfgit*79lqtFa_JCBo>d{*Tj1^eE6dYqMo!V3o|u=bi}L&nBxF<%_K1b zxcBSBM>t&oY*zCZJq+zVBuS=le$04XI)bj^ps> zr@zt3k;2GGvgqyf95pI3a@%Z;6^4Vs3x!qB<1N$u_jg2YRUuZW&d$y{FKV54!gx(P zHVX=~R7;lHBaU^ z7|JY_(D|g1u4JLNu@pi|*(l~h_WsV$&kTADq23leA*$@cB~$Ikw5nqhe#coR_Kn;Y zB}VK&IN%vC);e+4z7VkN=&!9T&0n1P9vnw$(i(a9%;wqBjE{Yw8G+gTSQW)aFyeX1 z0Y{Ol1$SJGZxH}V#2F<*&G2hHn^DDHjQ67MRj>P-S6QR&1(ZyWzOHm+%y3C~c7qg% zy_D#;FNG*JVRkXw-F;w}m-eA&?SUbDUwGSkb4_3?Y}Zi({_T{|w|KWddhI5hY9?|+ znh{CM)fj}x=G zGJcj1T$Xn^6j1lLxVdsl0#P9CCDz0`(v1G#Kj*vEWsh0==+6!Lg@I<9zmqM+IA6wBuTo>oAJIcR^UGxgv(4wx+82u#U&EAFn^$7#Y6{K< z5_pSC8@D@M?}^svJAR(%W4v!;ZRJ8tNEkR%-Pb*Whdp8+edW?%sFURHlS-c-qy@6R zAi+#}Vk~wN17-~MMKW|e8Gm;&;L5Y?w=`arz(h)kXEMZ)%fE2FIg{?RxPAhiz$3PM zZw@in#H+k&uvZd$!H2x za!E^(qz&3wTO(C*b24Y2inm_BjF8PSLtQ{|N+_4Q>_%!420W2lUwVv7AL88zwIHPx zwE0HHkl2$rknLoiZD(p=<~uQ%O(Nv-@u4-PPWk12{rgqSP8d~pqIQuokHwzR5fhKp z#5;dPC(#&zieI#$^BbNr_1|s+AnWyK%$J)N9%ai-?T?0jIe)_NzSKZ|7UprpTHV%( z=C{*c?l*}?Y=yhA7$(pM1vU@-wLS_jsxpV--3GDw_5*Ul*Aq(&t97sGDX%nMPPf5)mXJ&|V=1z$9ysx~vyt{h z#eI#N1yNS*RP>+~ zWdTF0KVwh8+Bxg>Uqz`07oS|VR10+kR?M+aZe^Mp84?q@x%&T!L@^IA1wW66?}m3g z!aQcHVDhu8_|z4ZW3P=j3&^*n{wb~&7A2jOh8_G8+D6=6x5A0*bT}%{Xainx|3liS z9Ko?6E-#=iyoziFvt?0SqhsOR~ujxy!$ea1BU z0Fp8dku7ozxJag18wzr>P>|%0uE~9pw_lud`;#T_IsN{|;$l!=$si({3}@Hwa!ZS$ zuRr@;BtF$o&&&*DKW8(ma3>%j=uHwJ0J~X7pL$(r=ZiNe)vGP%^?dm z3yt%dLao=7zt`vH-qkBMc-$Q)dDRCV-idqs&|>=zNx0140Hy1{Xzef58K7TcWHh@&&<%?Jb@wePlAQIJ3QF_?})a;HBXZJ7$So0 z4do3EhhLAMbSRSdCCIT&d+Di|995bbZ!!+m;nZl@7JN84%2u~sVw@?!snH7eo`%)e ztNK_mVFqLN7!RYK?;0W`?``apV>8bQV*J~m{Hotdosl$(j3cp{RcGF|Ov9}_`fwhd z`PrX^*dKfjM1T4eyeC-?bf0DxgDc?r`91vNmP)Oeybn^ToUmSJ5KH3t+2dM$JwXuj zxICv5fphw~qLJMW5E#rL>5ZkbjKO)`Nx;ASh}I*GBKIlkrSd};xgo#a)bPTr(Q>KX z{Y=$mvGDu%hn2Q-Q7wrisX$(_eNQ7TKwa8+=Cj zt=E^k;*{8I`yC9TmCR3rbEjC%ArW??;@u;wE`u}-+M5TRggsH07>>m+KmAFC)GB9v z5sE1_OL;bBKaE+tmpLy?(==GWiIs?oiHol|0s84l?a7Xd7>kw)2pIu>uiXt97ODE{ z<*v;_8tVt#ZLYJ@XI|mIV7XIA@~x5KRsZ`G@W$7qmBuj|bP8J04eCL%DoRv`;@tV` z3G0&MMm)?xp74;D4i%|2nD481&evCm8Z{6OwqS28`;cY{{8Dpzfw~q)hEn{{M)$58 z!}*4WYpD&62$9JO+x+qmUETP)Rkkvp#cE!XTeKf-j4!WKzt$5J6eK}A`KFaT_V67M zt;2V38ZgZkP(60{v0R1aVI}<*SVUy8)11foME!%7=0SUD3U7fx6$W&*Y@Qn-TC4MGPQf=kks;G+cu8@)xLG6t>G?WWiH|%(WF^?z=UI;qAh5tUPQaBef z@mE}znvE*KH%Y6{jSe@#kWpM*^|&^^YLgUZdEnVxOWFbiq1eftJMVEY7j$P8&(vqI(n{bHft6%{D$Co3CQG0_V{U4|JZ3Tsqi*PKEgbv!H!4>{QEFKbnMF!u% zoajxaRi>&GnRe$5!dI{8vHu+!%8Rbcr8nE)h?{(YmO($bxO4mS77z($K)%v#$>M}l{r0!V1T zZvfTXJv{$|laKj19SpO6*5KXnV-t!EN{9ivq1ke=mK$mh2mM$k_MDMCsgWXIo1If# zq*OTj#%$2kYa8F!!`D@*nCLgHb}auA>#zk}+}Ej$aIOZTKmGyr;#?`n66zRXN8{7a;!t@e!CS0F)0|r4+Eg-E z5PyFk(=);a>c3As*it=G!Xa_t{l5MJx^j;%yC>aT{FU4PhCM0&zMhWe<9+09*%^=- zW^L_Z%Iw2eiQ$n>4p+00Jhlnks*0b*jC7&yb*GODjwf4M zdd1XR$?Uk2+?t*~G?uZk_&j;N_9`XZ`=gWWIP7vscm2Ef`-98o)?l@CDS!90TUzoc zG+2W5<4%5kL-6UyO~}u*$LVv#&1YdTu+wG~=(UufV(}$m8fQ z=KKO_^lustx*}GpJbTNFDTVhwqrt_#eXTqF`vL_(Y<_?2QTK6%t07tb{V~P;gQeS{ zZl<4_^K~@~mv8}k}_ zAmqPs+VS}zQVZ)qvx@wU*Kt1!v|sw~i_ZG%yQy4tO-*;==4gKKoo9)x)NyHP zOxrj_KhB-jTFPI7IYN&Ezrs}gKW6J1AdR9EqIGsKEXcEm&0ix3?<|&eT|9H_O%~M# zW;04oPBtC;EZ&*OZHVc`t0L}oS$zX~)3>py2~vmLERp_)!86D@r*k&MlVab1Et--Y~7U z`2bLX)O+%?6Y+T%(}KY}xXe7a%+)5`$ij{)gaq@Z#u8XGX|!^_H}y{XSm%fB2;8EP z_`D&_6A3+idP9;?6cp^lOiDTK#>Ds|oP+IHI+)qwy-QzJySYWxjXmxXd_y+~`_7Vo zWu;BREqFTinEz>B-|{SkT@O+>xJIRn*sqX&RA~C^v5}$pP*=L=(b5_$7<0Jzo$vk9 zwKiADO?+KLn=N(Q;zE_!V}Z*5HfHIoPmg?$`(wqa5S1~CRtd&$YDRwY?PBEJBfH!ttBogIkX#n zu6-(gaLw7-)XSrXfm7%B`K;oT)C-)1hh>3>A@}s?YL{SNdR*>pzA7#kIGI!GwAEj) z_1*3u8QJ%7U(&MqSfXlay%SHygKQ8n{o(hf7orV$(Jnq+cttoO5%djG1y=^u@}xkT zppgx&-5IJ4@(y_i=(L!xKRUFuG;E_Nv|*;o?^@l_UQ-7#Q~AjqP@4Y@891^okY;B$ zsHsD&8n5uVxiy1&e>EBc;66b7()EuYup4=!zZ69VxuuD(fOW;Gj}ne(B8mNPef=Lm z<_CIxgWshuo^herLoXd+UB+#?26i=1#NG};fmkIO$R(BHP9iG?1Sz&mR1vP7S?6fB$SmZ7Js9zN$nw?Cn67bLVT1oKTI2bH z@~G)V?2dwA#{-x@mnI#X&Rm+WdnCqK|H2Ojs_J_8I12>Na?qh!pFeF|Po`-+c4s`V zb)1aP#yO=eW%RqX(~;xHeu|h~FHrvTH~CrQ0^!nUU`m-mWFAD4(xv!(jphqNx94<-E{jZSTiZe;mlz9-kg_-Iq;QpdvTYQl>do^{v5m7ZW)0qYFY z9OX{Xb{c0&fea>P%k}ciqx2RCLelY}$|jOHe^Ns7Un>6F`quN2iJNcaiy2gICYud@ zPx$}|E7ksM$=_e=SEQ7bD)Z(~YCoYgO}6PUzHArY^4u44LWJ!ZqtOy+4oee0VjeL6 zHKy75>@`tLY@D`?ptGr?ztIT)(7X#TpIs{}x>0K>hn0Ze$>SK)ku$lN{mqNlQEF|) zl0H&7fNotlSDt`u9ISkM&bA*NNloZS_cv$*^NLe}-q zmk?2#Eb|h25>1;u{5Mkt`QnCGHWRIVg5X!81|F*VPROf;9R~t?(b_&k;uogg& z^gn?AwE=LM2o+{#=4;2B!_BA}>t>aYf`mXw;;C~)G?TRFg&eK-H-Qry<`r&ED_847d6y}0r(p$_(` zuLOlV!Ca!dvv7SoMI3L!y~N`_3-joNN`a+%LZ7_7*)8++5>LJ#Psuh14^HQJO;;6t zHd*0+;S=h~DVLJQIhkwpjRxIc&2xswut^{fWC8-72>&o(LLQWw!wkm9$JYzQeF}sx z!!l2Zh)AkByARBIpw3-4&P#FItGydp-kza|z!c+?(BBW)Z~vcfKi*m&F1hvgE#zJ$ z*-WEXq*9^YN4~R*<9zzcvj~0fQM=9+u;6rkpk5U90Zs1Baq~d!JLLpBp8SP(&;3(o ztQO62Apa%)(bC8LlV zo+C<^zMVN12DB>#@lDwty6;)M;(WCFyG9qBeic~-xYMQO^qV^yiZSNc)iMW$;_Vhr zNB3^rUn+!Xf!y%#ftYYQ%wN2`K2yijYc~=e-_gmczY=!PZV+(?3S&AW1T~u0yrtUt zQzeS!8`&nY>f_bEIVDWk^pgLjXCd0ZiKD*$PY=oHgltsX7cOCq(8|iFF~?j^QIKG4 z<6KwWq(pO;V`Iz2+X-&$mI8}Xn6<{Jh$a<40JIt_z$>|t%?`%RTP_17ucF&Q0hZ{w z*5C9H72HUO(Q!^-9lvhMvjzHm%SNVd`;}Y8nyum3s->b8iOD@^ zNm_$%;7m~tv}Z*YtWs!Oj_-SpxwXx9OaIXDx(V0c!Y1n5r*or+l8&Dq97spbL7r<( zP%V7i5p|WNWr@z$Jfm2B{KDrbi5Har%=Gd{rx5k^^}J5)*F%~bUWe}DV@y@rwPk@q zhyJMjxF2YeV3!1ZVb$}#sQ(Ky_}2jU5(1h5pL$RZ|36i0tRwpnG*!`35DecKhIk5sV zU)}Q)DgOI#{?+*OHI9tFB0roZ2WdmdH=>8P_)NeU0oHi^a5QG4zp!!iZiYh98I&cjEl1|Vbp6t zyJCJ}f%NqYe)FGU2e$*)`qMHsdlE>Debu@XID-qPDg$$6Y@Tc1S}vcOpaBw2{I?~d z0{<_1FozP*i@1}3IwJiBJD4F2wRu_Aa{F=EZHd8g7bFk|!o?#>5CtPX*R-^>O7f*t zs!k4$et>X2zqOTL5iDRm((*Qtz}U(vFXvVW(vBC(g#20%`}gPjTVTF9{T7hOG}~Ed zP#_tkr#0bhMLCr2^(vM6U`+4cbnRUO4EWU?x(UNo^oB6#d}8|GnDu|*#95@@u~3ZF zG}M}occ$^=%s|-j@J$Aj6Ymap)j!_2sT$Kx+}AGGIAbgvZEibgR>G8*HWP;>!7w@g>^{7_HdtBBD;odqyK z-+i?uWG4$Wi(7}?mM&b%t*5j+c8`3KH+2PPAgAx+*53L2Z74#;K6!dH$2%o~higkf zbue@Yt@6`4I#?ekI|o7hs?e>Hg*}sY1BCQDN^`G&uz*>mU&MXifMVSDYK(WeuV9Ke zvI1)c1HI9BcbD*NZJJcf3rX8`jl4S+2ZOFsu1e=;%)O89*z!~DM244$xR?A-Khr2=b0gXF>MKL3Ga z%9~D}&!!FXbOhE1>vfaLyu|f(=h|^#DxI$_1M}Ltjjh;lmV4gI% zQJkp6cQcd-iVwU)J9QQGQXi)kRB5tjfj^k6_PGdq@6a1~H6#{?Ix1R>F=>V;hVKg# z89WT%*G*XTc+gF!oV>GaqkRhu`1hJI>8pb8(2af?>S`<6zS-~C z3;MN+cM2GV(HbCzycRq6QfhX>;#lvhX2vljoYIBg+u-N$iP)%nBE+_Myg;|Q)F`UG zQleTG$3S^P8|s*xXwl(XL5o1T68Uc?pLXW<|lQF|k@H>H# z4jaz!eY%ry@}E_hj`uWZXL(y{e^_@sKd5#;*`;8$)%VXF<6cCVt7HkO1S^bY^A;&F zjZ@ss-L5+L<$C?aLqfJ3WS~A(RO|i^1Lwk#>pd4y3!)_d=a)igiE?&8YG1f-t`SYe za6}>cUeJ9b-E?ZJ_yRxI_|4`AW_e5jW=3;Rw$GXW+@Dzu6JR5?QulqPwDUrpK!8D6 z<-t*3{sQZQ_V*TKvc*d#SAb5X>Nf}D)Fb2m-I*j_9}&>D>a5<_pvfVYSo{KwF1fQ< z;y!uKjUI=qNdo4|?-uAqU9S^i;BfTMIl2XhhC1q>E6%MZp@_-$G6U|LQuNA5zoU7`EVbdvP_6sR9WjZ9 zR==Pfqf|~wF&|0Op9>7`S676}in_s@cWg5mIy_Fd&TO59XqcG>3&L$+>yhE^@C^*E znfkytSmBT9#<|CH{I4(O2s{gDIM!(u(MGco^}^*OvXco{sMwny;Xf)Ey0Jn)(NRK2 zwGxW^lVjNLaQsg9KG~2*q?IyYKHvWI`+Be(3OSxi*Ly^#SM4R!r{BE&-SMI_zx1FU zY%}(xf1Rte@0C3{2t$~2U!ITAyL)?wi}svk$oJLhM0

!BPO(jZD#1=eG#ob=#q zMY|5Z9eUtf8Q<|y*fnhJ?(OLKJMhZR4+>E#`Z*~^`(q_D>lMx!V&}_?GszYRYw>YP zF0N>O%KzTDbON+0s_6NvO+3arNK^;RfQ6Y|mFg$750kPpwi!RLZ0*s&_PJ_)7|#U~P#PWQX&#)TW8u%wFSL5@H1+-W{sWvUb$@sAARUP6hKF^iF zrFwL5;v{FJ28*R0&iYVltLgyNyE(ISE>kz{pck}b=`y4I__HCxaH5- z)N%Kgm)MuSoN5NS<`e#f4ll$pp20zXV&=)g`8f7T+vbH^g6J)|_Iq!9dASCni_xym z>UJ{p9vT#^OT1Y^e^983Ap^#1Cf&SFNbWG`bdu5jP}t9q6^IJ@0AKnw;#AFJUZ%IN zuMctr4!Hgo`CJg57qhTQv&QraC4_HdPSj|0;MjBD+ZI3%NOslQq(pe_Z9Z(+c8KTP z?|5yHN!t^_V9h&fiTBzCL3Ya*_NAQdGg)zHh6H6f*2%~cN&W=!rG%SF8evE3fN7U| z?~Vj{tB$OXW%1;aSJ#L852C-@g||2FFB@#rlu`fWyn6BU8791k&@S>IP=UQ&Ip^d{ zPYZ9S-A9_Lgx&Yr+D88qw9@_hFhTi{=04{?vZtvUi#38N+84-3-~yP`YG=NNiA9Qb z;g5i~j*JLM*8*)S*%b~=)$ec2#>qLc2?)a7w~{SRf9x*-p=7=v9EU|*T>DyX(%QGt zFGd9g-`qif&W6?^=|K6~z3x_wzP`Tk3a1?Us@GjXDb)rqXu!hbpetwX`02>rYQ4a=;FwH>*b5-`&yOw0C7L9$2;>8NSYZR~yfLAf@O}Sv@s%L4`*otPQ*4=0hKkkU_;mAMm4yOs2_ujZI zVe>FwFOXTx?$sgfNXoZJgNL8v{M}skuQmztqclmW>B%#j8eo!KJVFS^AZYc0bel25 z%2S-h<$!MrXH5-BR6Qs0H??+rEB3R*CZx+WXa-&yU`eG|u(X_Sno8+a7#~YPcr%BD zsI~rw_Pxdf?a%x_c5GdC{#SFrnbV$8wjJp>RWsrpSEgKK%jcQeOq)>-r`O9p$y8nM z*;LkdoBR8T?W*iKcM{lN@;xn_T}Pbr8#H==`gmd7eQl!rv4YT}tPmim_XQ|@br%7> zNtx6d7cy_gapr$v?jOSY*J=JYIliHnE(NT zTq6}3yJw)wEmfe(9ah-{8MunPxfznz3*)7i`Q)bdb~mzHyY&jMr*)fUlH!qf$;AcI zKlE1VMpiEPZ;HYd4a!zOQYxoQcAR?yAQS6#O>T+H&P#aT6{;pIl5~w0gu-^# z!rhc5iw2oDzwe)Mbrad$*PfwrBGbfU8mB^Z4OFmNCFJ>$4UIk?*DRRkj`|YrRF!Tr zpsrvf$(nyIH$mEfs@^h!zKgN$51A%UHsPz0RHs|g><7dZ1>C6Z2H4YfnZf; zU9Qw9N$+3!?<$@VUob$>uBi9Dh&Aq?5ZoI~>e1{$zThXLg3Zc0`}>fp`tF>g;jjh~ z&RY{@$wzs=vDtKR@7RoldUO`>m@<5Kyt%q<5N#M99{}QeXX?XbJ^k682^m1XaP@MW zmk@3jSERi&aPcJ`GB|6x^5;Z;>C*68uIvs{EA-5e{oKL>zk1a0qGE>C%^%kvvA5*D zw@DLrWF5ikIO4`K8I|1J(5 z3)F5$2US?Kv>x4_u$aww{I>gRB0PV)Z6KmQCjSB3{{n6wssaCF48=dkBGL7i_MuxG*rIw<6`W6; zVRSNGQpln;6-->CGFgNEp{gh@KP7ymPv9BAm1e?XHBAiwmsP_L@IX{Up-I_^w9b|V zlVgt_B26Q+*heA&$13Em{rK5Kl3&na7Kli~Jb6rg6){CIZBT=A=YUdulK48&Tgx6p zRX)Q7@XBuPTk0Ac79`mZRGLI+k4HZXJDee<(#F5A(6$`D=@}4A%sAf`PIY#9&JWgHVHz45>I>yoKvYyz zF6&o1-tw}ne+F}|vKu}94?eLf(Z1@9!+XhR{v`DMolL@w{Hbd1jT<$t8yOEQ;~(<( zrAi|C_2(u2#ln9EPd7zPP+afb{MXDE!p^LPPsJG&eqeNrM&A8dE=O?z1FlaM+4l7V zvYXj+P9-cNvXmaDc1r1*~yh^@W2l$h6Xp&-08gU@KdZ&aYSHjZIk6qVLgP zEf?a*3fFnGeH!O~?U*FOYV$HEcS?Ip44PJDuJ7)99KSSj&xFFGRr{M;oukNAx&k|B- zsrV@pKC}oR#5gIRDk4C6Pmf*O*c^>f+&kn6Asq)foQPg(p(T*;)9Uy@CiTJpW9_ZO zqT1U3VMRhvKt(`7LXj3xX-N|$mF|>|p?eq+0R;&~q&uX$V+KJ$TIn7H>8>G$8QwLh z&rzRq&h>qM*Za?0*X)_S_geS5<8#Ma_e}iplPBL!o{c|$P@;bfv_G)?JUKo72a8`; z1}_PnZ!184r@YtYE00oi4MkkGWP--AnHaVhraU=G3a|mxZt`~9U=6){6W1-pDw@Kj z&z~P{YF{T1?qu*eJ`(WAfnS<)S0kDIn9XX7`gz|{8Hr3x@zIbvLojmxI>XN{ZyFbbL9w^SA+m%4pynoY9jbl zNFx|^PlyM7`ph3c7Tj^-J`)S)VnD)n7?JZ6L2Xff+lkvXFQK*@&7wGsR>is9oR&mV z(SL6E*n3FT#K@v-x`Cp~oQ9t(Q^6L(n;0~3Y_Go0_wI4fiRgUh5bib|d2vN2v+q`UAf@RwNQce}i)2zGyBVyIF6-?fY0XS{o8fkr4fP+!l70=~%%)MCT@ zob?2XMM3B(=z5Mj6KLx;V7GUqD~11FBwk+xwv%Q+z&u!vkES)D;<%#!qtxRx@3>3@ zmrFEiTP_`=k*8zx-Y=0-4awUj@~lUikV#~7h?gXbHkK@LHl0%zte)c~TC^A9^4>*+ zu>}L()o*`Ix8pu=fj6dyL7j_7UnN}pOSS>2rC13AMpe$IJ0x;esm3;?>47C4`b3O? z{_I{w`r|G#(S_oVRh#OmqN2+F%NV{l9(kliu*udZVT}!*rrjm7$w%2J1`;f^_wZ zeE>QMLFPj_4S4c|c#H!bu1vHLF)v0lU1K}$9p!ZUWwp;Ye>C;-m;}gN+cqvqCE=rV zUEz0j#fLu(cT&Un7oHhZoETq=4p-Y;F|L?L2&yM3!7p{a@Pc}Ko{%m6(7>Dz+uS2? zy%b_>tDR2@LJPsy;s)?%hOhXe~cX4(qJF{m^O;@ zAKjZ4WZyH&34Xrf$h!Ff#3aJrUpleK%7^%bhc-xkTIt+xa*WPjuK=w!1ZJ5uQ_|$!-+8^*RaIu;+tc?eI*D7^7t1&H z6Hg`uP;PA)H+w;Dc}1)&vfY^kc*RdWvxn_n6$rD`)I-FtB50NM4nRcZq>g|zAwLEW zZ&ft%E8-AOO49NSieE~H-2xCFwnTG~64 z9C$<1!ns~hM+So%d6@aKmv&bs@V!pcQjhOVR$Y^~^4&uyeb}e3p9(wiQ42b3Psc8+ zaCw#lZQ#KzR{h~4B7AbScf)06>E$c4?$#_35QrrQu}-#ZkTYGUYj9ZzlGZ~2FWTm2 z3HcPs(D(+m?(P`pm<81q{rRIxJc8URb&w4UQKM*XtmpdOBoG*4ye9ZS4CWa`!J!%c zI=F$7HS^Wt$pc6xHx~%X-mS{q0&X6y2vn?fyQC%@*ucyecE;29l{j(Pg#RzR03_K>_*BY3YE|azDnHQGu=N z+fW}S5M4j{0O*%vQ8Hxz(L7LUwQAGT;8gj3DSdn=Mys4%Hl}5thrlc4j}el6Wbh_r)}S7|_7ivh1Sub7 zK#V>@$d>b`<1z8L)>uMu1iE{-Zx%kGt2WcZ5L{BkK{6|s@Em&LeAGepQjl~*i=IPaWo;+)6488V{-l^BMJ-^C$Ra4QhEv+G< z!amkRDklF%MZLss`Sd`XpyTj8F{-cIsnGjO>gC+;4}_fYN2!BDFCN4>YPN8uyf_o; zWO$P)%JC%y9=6I}IS!v6c=f6NRwm?$n32=#PiSrH-U=p4XzGb)pfiG_Zx3#K3LUs7xe`Srd|%2uEsP}k8LB43#fOtVa3dya@s~K&m@!}M@z1`{8aFwH{+{1c z;+#XOFTax4^>}1-*JO9&>%*)^d0JuD0vj(2a^K#znn|x)!D&STQNPKOe)n&)8j51! z?Oi0D*qi=J>|k8B=%l80;g9CEz)fAM2wZ zWmf&#PcRr22JK6_M-$7W9)qVy=13rm%C-*+HmrlJ( zoGX6Zb8TG-w_htf?#of{Z=QoShaKFjC~**wn&x^{JI?rIS&cFtvDZTJG)k_>Pw*v< z0onJ=bk5&`jyPltp4B$zy|=VhlhQD)gGZ9DNIm=whOeW52kQI9z?r z0IW}-%es)m_w|u5Aby(<2@>v9_JWofb+EKN`=in;e>Bk%cSz02fGLRd;N zCNj@Et>{z<4ee{lyDnKg6$cqCUn3&yJ4cO_hXL;wf@*K%5cJWF`T$VbY{lw)jt!>E z7XUnno!Jfcx_wuxny0`~NEozM3e~y^dpx36&C@a|QIt!RMV>JA>O(nZ@o1VuannvI zbjn?Nloi4*xj>$^BJhc+h-OKjj3M}_y%49I7C zJ|;jlP&!Eo6~CP#lQh82V$K@mNY#*4ZCD)JU2{8})+6}w8A)ZDusmN3#XHXE zkC*dxIdo6QM8WCLcc-eNgl(q8dE;(8!e;BVYZr}HamRmB-n|!Dv%qaBR--G{S6T-* z9^W@%5!)w0gY@NNCmRd(Ue2b_bdhR`IJi5rY78|r@Jc@9IM6ir?dA4zBA)g7IfGi7 zm(^VzpAply+jPIg?Aka_!Q(H^e0Q8f2EZb+qE6;Re_gWwUdT-~U?@f7F8tW@&!(4- zmwK>6R~9!GUSC!5g!=C4o9`xcQ9V*&h6tK zdN!w84hB_r(Y8<4&3m{s)iVyf%cu(-u%wBJiTN@XUepW0z|E7fKzsLhG)_RHr!0t1 z4{*N~B`4X;4Q7RiUIW%lX5U>1?4zr#YCpgwk8`}Bch&&6!nOw~eD-*s2P3I@3$nR*x4Ydp z0jia|AZ8Hw$mRu$O=+M6b5?^PHYr~gEKgKUif0}u>Md$4m zIMmwo8t|M&F8K(fN-Q}s=`HIlOB>BnA}X^kjxGL}5eC29xKQx`%27I^&ZiI8zv&Nc zt#7^KT+;=aIkEUhUYNv%83V5kmOJb1clE(w{u1~WRr%IEvssSV?Ruk&iSS}90Z z%S=+s)sJ(LH3uA-_YRj9IERZ2Nc{J@{>I*355RE>Gar8J9ZryVcH-^%9uk3g0G#@% zSMHt%$ur!%voh*e0Hw?9J!9DH^||SS>B|(D7doC zbwq^@*3f?hrgTMvgnGvMb?-gO0qVSfkb@*x?6=aId2CP#D)g;&xv2XKlKP?6oA*vb z=d_ZE*PnC*b?SQ9%#CqXys1(f)P5TiSvdZ6-us$t*iD(LQ40adXx)W-H}9XW%(K*H z>FVceS_R>q7nG<@%nD6r(0t}%k$EltW)4yVo6VIU{}#iW_v)0oo^BiLwP)b!dc9@? z*vdPARk3r&F}~YnAjtHxgjN4#NPp99PvOMCmOyyw{;Cg508W1S+D`6;xvhJ`kJ6r& zoPKrltDnpE6ve_t}0kjO#vOh&oG!?|3f6#y=2VURgT$QSwc!5-nT8@r(5VHDtslD%q z?iu^H+E!}tOb^IeR_Yf?=L>_aUrpRSV(Sy}2_yvIGn*kmq_Lq~Aay(q zTdl%K%fgp#ft(hl?dd*US5sjeh^eBN$KjvzZCoJ&(oQ{WW`0h}wBzBo8|vCZz<%+h z0(dK{AxMsbh!E9`F$6?b83qmv+uJTLQFqsRnwqlVqNWzXN(U@pYgO$Suiyo+7p@$* zmIArE)22TIkbl{WUzzDe7*It86BCU;FMjl^<%ap&j2%2tR;9LCv@!#;ldH% z2OlH@IJYBU6!`PcfM*FAamGjHlHWg2`$ux)X)YK~f7q3uN7X%IR5)4?wcP8M2|_0X z!%W$BGL_}T9w$idN`;;+pIJN0e=I7=B=()!%rznFutvQVvtd=k{dY!!yk^Yv;oa~k zr<0kx8L~fOYlbe9(T#;%f3;Q3jhWAlhWl^BgAbFDkVd#*hlm0}TMzJ)fE_R0eHK<7H;m|&P z!i`LF?21s`$?+8)q5@DzQ=x#RKFC|&LUQ(h0EHc|`*;Hjt@=6;A6T4^wk=#gsZAC1 z0XUXxeRI5GF0d||0ffT}m3h$8(FH968{=uh6ds;%$0b47*?@!5SJCpz7uhbKBPg7{ z4PeN%iEaAA`1uLIK1}>qYr$^wuan!909V(R^F!AV)WO%RH@etBj(cnFAo~Nd-Z&Xr z;(M9}Y!ho--Pxgn#CCkT?jK4%Ei7!Xk%4j9oc39iY_9eJ8sgZHvQ@%j9@!$~953nl zw(f_>DsG1Qmbx>6R#AI;$r^6PP??yg|VYl#%8u4T2N^G>GDEkjfLoap{sWR2K-WJXLbIS zxaZ`V(s!5zTs-)!m)P@11$11g02g8Z$YMP zo?9%xLS#*ECY?b4DFk?Bh2EOU^$^kmqghMf+a#^^c-@ddmKgKwYh+)5Et#a%7y1(0NEiym>(IzV2x zdWw>G-Kd>?#u%}1eh}68q5B&gBq9pt4EO0|vwtbl2Ihzbh<2Rp@v6U)k-r)0pQ0^> zGe`18AK*U>`>VSNb@^n#8P*I!tyd%TRZ~(v1Z&Zqp-$Y6mUe1Zp6E3KML}%?1ylx( zJGf&J-V^0U1z7}R{g^^kIXUYCW;EMrF5Q_e3tzs4ix-v>pm}QpwjtNjWFg?hJc$g| z(X`_UdG-+}<>Nckd6SsLU~3INLeY;wap@z4#H={%hZ4nbbq)H4&X^}b^bMEu^!vZp{ulI(0#y#QvM#7q~h-^F)4Uu1UO zcv;KOn?e=m!5a(@-Z2$-#s`64-LlN+T0g@_?MbWONyU1f4rit}h;SXe2I{P`EhRI!TH^+YJc zZb@(PPeKyEsHjPB<_^+jCJq-O`a8n^xXP#j)LSz11mRDu{IN^|S6V*>Y#oo%~CT7(SY z;yw1B_ZM*yN7W$KDJk@P()j`1G02s9nb|;~f+pKuk+Lb)Y7AO8!@15CJG~Rpm&i`b zQ@_gw@7Nj3|L)4X_HsL&O`X*npuE5*{k=%yNwF7n%N%Rq11;!+SK^RbJYuKTaPncw zwd=Q9BfSe|CWuG0E6C@%Q%Jk}qL_qJy(`H;=I_z~Hy$=Bb@{oNpwr|fF{>)Jg)dYC zodby^U6GNKgSwLSi=4R+Ru?gxuFrhJe2kt`;s{zJ%=Sy+GB8jd!*Na^bFKcDI%_jN z=AK$X8xAMMd<2krvy(a{tK- zoA`P`zj`$MDz{(^(gP#+fgm33PVdgwf12)vShmI;_bmCU+$i)uQJ;MQ>*QvgYG}@p z{oFg~w{PA>Wd&zE7thy(ELgDQ!>&!gn1E}S417E^~_7pVvpUwCUs5D`n1!BZTbu_XW%mG}xINq|0MK zS4dCK{j3EL*?+Uu6Giv><~DYLZ@%TC+lF|srmlrp5~6e&T~_N@b93>usNiZ}HzkUd z45qNHWowu#c1-s|Y9x&7^Vd#l%|vvy7smUGq>{ZU_m)+^EJ76Qa@?58$zSCPA^6DtaE%s*6#GjV>){%&~W8pc8buD=xNyQV&j6&mlBdO757e#iE&-W;>*F z+k4^pwb;^QRlN>7lr5F)i3vrWv;)ph0vj+<1|t7ywsjPLp<$2D9( z?49u2$2J9H{)(qbo&WdWR$Y!#+}Ax*(Ks{{&kal4&@A5G5jF9dA#y~>bkpx5w9upW z-xB6YtJK0{+~J9N#OKZPyxs8BXZNjzwSlQ37peIhXqkSX8W|;jJ+eG&yt==C*{E zw<16xv1`(SF}x~8adGL`SZ;-)Ds*eB^w9e9Vt04h{)(~+-#(KfOf}43pCET(!>7ox z)k6MLWUZ%)4@SqT$`l*GKqV+YRtsmc*xaEOqP_bcBCsI9JOtHgb?;y#!Ux zEe#jr(L!KrKC0*)tge~%R_28JqUaOc(a03kw)XoO-&Z}|-oEkl8wc~yKgIs4Wfs9 z%~x5!5W@G196q`Ph$#I$?A9;+pMT>nK*w4hd~jZWqfp_A??i2RE3w_=HyX#|yD6)T5z4}Tp6U$xeC(KY zuZ6RSUFB$xkNEspvtdsDUU+bI_J>ildM97Sf*tb@LFMAI=*X^xyRM^+HXOGG&<Ff1XnND_-NF)mSUOyh`EyBWti5fLG!P=354p^$d_ZR>r6B;V4u&>lK4uNVF} zfCmp9l>H^LpA`Cwkg`$WnDpcIf(QS?q&9&-{q>jgaDG>jQyK|PlXtez8MWAnHN~Eq z3k0b4cH-#m#m_HVi83B<-PFkUtPs<@CT+DK&^s>xFXd=#Vr5BhUTvjxzaf`QM5~ zd^8~>;!QR;6~?svU_a#byWk3c4SnQD@#i%!+Org}+s-<6IW%{B3a#ZLY7Aa)$>B}Y z5wwMs)d3xFrT^edk?UWy?4$z9Z*Zn{`4^i1$-fB?z#0U6l*F|N!f6ki`{PNh*4-0< zS=qS(jnE|e9O0WhGLiG4%1dL^OXdsp6n zs;;U9R)z8#LxPGU?Lr)L2T815`LX*`QeR zyXN=0bYj!ZE`rKhO+TpJbx}ZtZq(_{(Vg@oez5 zlNxZ)u1Oo&cMWJG>@@~#;j^tsFU&5tXF9M!<%iG%u#o24wO`q+)(Ysws`khEr+$6s zA8)V`2Yq3domsMve>dL2)U!N$WbL|TBSSOQ)M832_8p+S?_>NUHJf|E1z;%GC7bX6 z`WD7Kpd554{uw+mKCM;9HBy=Q@n)|x6y-~SU*;XF4fxI1{^hmfFTvu8t|<*td}kW# zOZhe!k}Ws$2q3#%5z$!po8`#uxdYR&A)`JHm^&7VgNo|6F!IywJ@>3`ntdGz9(_W6 z1+*>xb-oD_;MLU!@A(j~iTpOuabqyh(M1V0vfnQMj;PB+0k1gUB<*|l9Y_0-d{Z?NN92G3 z-qAf`dDu(zCox4dfozz>b5|X9SN?-*e-ior-Y25PgX^BJ~rN7>n z;Bg#Kgkh%b>hCZ4ZQ8Z$V4`vbUk+QK0~*9oe#*m5G`2T|;n#UGjuYY*b^MeX-fx%x zSkx@sqKcmH!?j`q{uEf$9MHrON-kK*g}p0e;pG4K6g#988IEibugHFo z?U53WN1an02L&yZ7o$}B|Y>f7hI zZqSmCG7sPW?f)$=k9cA1>^@sk{4Vmp{V4{wT(4+;f~bT~cxf$ID=6W7sn{`p5vpUq zOWE=AM}Un_tVPoN%Ogj$Yu9SAi4+wm-i3Z4jT-B~J>4#Ox=u4#qvv6#p8f3)2Mjw0 zOh|?uY{WJZ{>H|KeI)hV^a9bw#xZg6wGBi1qn@7AGbX=(%L|VxZZMv4%w!B=TA{4+eW2ZnL%+6jY{5~`o2;Mc0J?fWgguzGMKYWr zH`~#6HeWX>;+qTebLi*7bnaufSF=Qd<>zX|F1by+k*;r0i^JCb^Wi$usrzOJ+qf+N zN33B2S0F|kXw8g+#%SVy;npKZ1t{3;^k9A2>KdT?^WOGKJcNMx*TF>S`qbROU@oqO z7(;iSsz8SFu%gjfhFMW29`5laHk_T4iZ}Cu$(B+Zne1u^TQ_04Z`8!a#n(5Oetfu% zbOw9CCegwO@yTt!sh#cj)+n^iJMVwt)8lU|B|wMVRJZ}lck5l-i}%tmWobn!V@;t; zUp3Enx3x&Z<`{ea-gz&~x=h{JzfSQFCU!mpm`v{d2aQA7Zt<1qsP)|RFDx)tnRCU1 zUsP~m1x?+Y3m1PF?LY4R+pi)I03#C7v1lIp>TJwj)n3r}Q|t-m?6Mua#~<9RkOn83 zNgw?eHvLu4;6%d49Y~io?CzCQxSML1@Yhc)sxE(XYJGBxo+E^YJJQ(+%p#Gf?Kche zn=t+PNQv4|oGt4zE2PFv!mA4io9@kywl@eI$T(e$UBA{}3&$tvI zSZK80MW^HxeWCr~CPRWf~nz}tsvWz>%_bAbV* z_?!o=B>(oYf4AOj{9u?3_nRdSX)<-cmcR?cY(YLBo?2C6Gv!Hl)2&cqKH-S2_Gh?n zhwyt}4FS-iitqMWmFp5>V>(mQFGSpu0Z`p@8NBd+=Si1$fS)^W$~ztEs7Ew-sb>e| zAIS9j@d#M#aSuBP-c0-?%oDbQcFIZ);$rHlz7=7vl#viZ;(3og{HT;VST1&N9=iYg z3mM0&!5e3mW?$l1?2!(E)Wv*p`>%2}>vK^&&-T(3JVPrJ%^zhY(e&n~ux#CSTy%L; zx+0pprRP8q49qHrm^#AV? zdBkf1xM{lkX|E0=#N%^#%x4G0-9#QAxLSMhFTD`sQsWYNkZdg?*^jci49QFKnF?;a zY~Gr|cpzRCtm%b?p)RNzC}b{CWa$-%>+_)piQBx{}Y4$^LU7w_jynPg{Llv$@1DHwkb*VfA7-#&Jxx9kf)!A@G{q>o4ZdnU!zmtriB#KkCYkky!!?#WeguQs?VO8WoCc~i<(WQON{l8uBAw{kAC_1Mc*{|H~sXs zvX)X6)h~O;_w8P_%&gl{EPQ;AM~~nSK6=wRRWE$vI;(2r{e-t2Lo9}D!I3U5E zH`f$+NZhQWQN}7EIqAXcXx4B8!Oj00hsJT+%xF8$t+B?h?gtju^Wb+-4fv7#qdxJf z!x#CwasnT9Lf9zodkBFsSi+VFh0vu)!!%*C)$uT0y@(~-drC5n($4mZUc}1`e7CUR zeCUAf0*8Jaluh9jF4hffV`_kQo@kw?{D<+ek>ka!ZW92L`8BMC{!kwLl@kO(K`}Xjx%Crc zM+ZgqgG#b5nKTn|`j}^@v}RsQivkW%TQJkyAi6c_bTd|C7onqrkB)aBZr>DNh`F9X8Hh6C{g}0fv-@ zgXe0)q+kU<#0FPfd11}*O_HAEGxi*8Ntm)vd{`)=7Eau0LNJ>}_&!rb&40;I`r$^` z>+(gZeRbvCP=%$Y)%KAsz_#~O&$eC_WYmU_p{y_G*E|xidZ34tCHFP@Rjo=Sf)zcn zbz9(}w+AjNQ}<7*@1Fu`E=`$M--qJokws1}})D{iDt87tF~%?~rnQsc{g zr!=3&5`(bT4RN9;W?LUg+k>XoI`ooAtMrcZX3@Zj`-W>KLaU9GzXo^awlF}uB+cef z&-TZ36h>E{^b*Uf+-*?uAxv#nnibI9P6?=mv&OQx|B_Kk@E~@nJK7g;{cD7`>F z--SBxcBmG-6mzQ7wBp!#pLHwjNiT`)!G{hehwpSY({o?NT1zYk@HsXZH1gunAd{3bT7BRyu8b>U|$tZ z+%|J^U6oW$IVb;Y)o57Ma;hOqHH2fm$w+ld{z0=x6P|E*MxAb+U16rGRDpHWwGW=U zkZtmHih(lw%Hm(v<;YRzv#ZZ_)2os#)YT}wFoiZ!*{AqsL|B}o=vnC+f0CQIZ8oQ~$I2l=iy~s5 z{}_48gTfl3&GR_Nf?4g>c6RGx^YiU?1Qe*sQ!u+Y+G8X`-Wk;lv(br_;HaPLy&9p! zsNotp7Wah+;m-!(#M%)Z6hjB}`EWCT9i_tX8D_1j( ztq=-&QP#_D*-C6OkC6DNqN|Eu;PM+370>o|xjy2f`d3bLmDV4u<@J_tq-;RckT5I~IOv=>~dki3=SrIz;24ZzC9-Yh7WqxS9-15PUg!n-yBF`do4Xh;8lJ~cuvjEUfU?tC+MXHni;-&mX zg6}MABm83}%iPrq7!Oy{nVQX94~ah@zF(AC(r$eE;r#H8(vM};PLL4n2)&&fy`nNg zK7fL(-J-8%S0aR;{`gzs+L;;|$2~&j8};ZdPS#eDtFt$hcjSq7Cwa2gDOWHYKWhP^ zo1F5FAWvrP!FNrRC&=Z(Du_QU8(D+ej4sxqOE4`bWlxZ@>@c!cN!PjFkoifsMj^BA zSy#3*Et@6Msqtz$sTU@Rr0X|8uf=@0mSNiJ@!=qaAbzXwcUQl)Y9!Ij}C6oxN98IEiyuXVh!yFkcZ?qYW;@%ej&>b4w5LqIqE8MgohC~Hfp?kCl`Y~(cDlT=c;=p ztKMFjk5g~IERc;U)uDKwSJnvm!l;ErjOBft_P_ZqfdPh0RS!7mO`~ffiDec1BriMf zn`u^)4b$J#Yh>Y4cmF((Ug8YTaGZRGtf+lHEBiv6vkgKox$J+{VL6*H>=`EK6oPmo zdKJEFYJJ7#+fXr+#_%@1INi4c;q^~*w3qFI>}|^`-JZ-=WU4ZKeEqf45^QHQ_1yd; z+47GF0r!K{W1K5#z;nn&PyLRcy`B%leug++;eSZUxntJQvmkwv8RCd>4J8y*dJJbf zAq>2t>Bi>-oGA7Bo!wnFX6E+9i;(j2mr(*I6}y2CImW1!coAEQ=0@5)0EP*RDft>g zIV)~^qrnMAF}5;Xl3Q8)G9PcBWnkq~i4`~kam+(a7rP(qc;{9h<+<^!@cWM4sWbid zPs&HEh!=$+lJdV|wtt<>DT#!)I9K$BVD}-yaCs_m8V{XeHfL@>%6lSFG3z)KYk)j+ ztXW+frk8i0Mm$sVWqTO1w!X1VT$>Bl7p=<1%r}||tm!ypkdjF;QcUcF=L@)9>Jh#y zhO|bt))^PjhK6sWXR(wbY{<Uc@BpTn$Av5rM`Ogs+)_G0BtcbIog{l>quK;FA!N_ z^Zq^p6TW4AY`StK&7OB+k3T5zjvn$lx5n@JivQLQzpB)$X8|m{?UD8!FC^pLJH7~8 zzmw7ks~#HKp`N^|;z!jhg|FX|{U8v{W*_(3d&vCTcq#LZ&Ot)$LR5lpU?fCTG{NLf zjRVs4UL345QP64_szvL3p$HE%ynUfR2wHHDzW?MS;Y$OV9lAy41ijf**&52;IeE%? zXHq`H++P=l<~3NnWHfqgwSz*mr%IX*U4Lqz402EUf8n|Y z9M^dqkvX)lj|d6;PYp0&>uz&tlpu#Tk-B3E2@=RNN6Sq{4B9o}{WR{47MPwweV3PQ z_NBMPBPlc1-dmq@+3B-)oayC~w#1GS$(e2nx0ZO+U$h9ya_1|oL+xr~v0@~7=Mq{H zk7m+PJt5d+;vgE-(6sa@w5Aj7%-oN6934Vb#8oFJ=U|0sp(6H0I(y$B3(^-U_cy_! zX8_@Jp9C|Txy$*#%#0M5Q2cN)A0Ky<*A13OAZQwpg~;c($gJp$7fJZYKQ=WDd4e}R z?H^;S__E!;)GIz}CmbGIHtOcK-Ywdjd?)9OcD?fUK}ya+qniDdSi79MC0}H$TJI!; zt9$!|Q_Ql^@|bmHr8ASCq}$FGb5xB>c<;(y0PVu=fm4Y9p%>I$uK4!^)^~*VPbzLi z0%QPaFW^ZZ{(;R9PY!Hv3RUR!TvhEec6Z9m*#>s`F2D7&J(he(E){9r7G?n>^(5{Y zVGZ_+ZZS4KStXQUg}j(!FuW)1U0fo6KQ!aj$&CA9BpN#(YTrc7Z=)f2p}6TXW!$cP5tGVl^fVg%j}Ql&mLWH|?N5Byir&D41{$ zLDa!rE$oG<3pD+i+5dN${{Cw@NGd`FgpR)hH_>A7f+=+FWTK%G7C{o< z-x5k`gvzZFq5ef5I-mvf0(PZ*Pr~_6?``hF8-(`H8)EWJ!|9=hFSoXY2}^sJ?sRf} z*|j6Hwmy4J;H02MY}C8l+%k`>o#$r>_Ryw-CjIIRC#r#k9ooHd`hP%DkCZ@+{T^kC zIJhT-S&ub8KEAJHDODcQOqM@mwb5&C_PNOf6wPY83g!uE?`-C_Vussh3M>EAy}5zUfI;a_ck}OThzr?9!lTRT z=M5L`li{JscDv5~gX{cv;%t)&m`Zh?M*sx#-aRb>hgRAsYnn}K@49QP#ce7Yf6_b( zf0I!T$sN+~TAl#`=OW>ov;&^8KfsFjW)G%2F@9gF3CKtPPd2> zw5nl|(}j?3ERJgP&UW1%yO;EWVhl5Jn@g(#Ni$WY%B`4nKP*5n$#B$ujPZKDDpMds zZ+qg=ce%pp!|{=jt+~OB(lPh>q-SV~0q0NQjsF*+`hl;X{>;UlmZ&YlU-uo%@_oQb z-(1sFe%WkTe=Zi8io9emE&zMmlV!G?7dh@8`$fUrZMr`mF5`xsS>#8IF=>xXEC#tA zLt};?P~?gifmn&zsOMZNG9@SS7GxoFoSV+$apt**-2pkh1HJ5?1upjWM<~H#ov+i# zL-(N_F~Sf%*jK2+WF|_7w)b`+v zzZ1X0mu&#i0r}hW=g*tFwukraw9os^`3bC7yL;6{T9ugFZc(dL`BUx}8<>mDSXrE% zp^cp1OKX8wz|T1s+$>I?-q+)IL%}W5Pz*t38o38<`TK3cci&D>0$=K?0L-vmjeS73 zRUFZgIN06A)3Z0!*6*8x#YfStr(XXbMD9OHJp5CuSB?tnqq6Cu^UE_N5T=@?ACA?e z^yfBPtq*z3C7zGe<+=FH+c1?L@zny9* zgmSfVpNke=Y+tymCvK8n1q&v0oATONYM;`}f<9iG=kZAE%>uq56m?sdNRrKM!;{Ix zVg{~ekr1Ysr}}^ZkwotH?sQNSbJhY^r2a08;~hS94yTl5?lVI858PpXV{MIoez+v) z&cZbl-3tHT>E=~ex9IAO?z=PxZ%Zg})E<@FTkaUi843>X zTW;MSV&+QGU4D(-HgpPuDjq%ftj2zs5hg8pdr_Tf6DGfBYlw1LA$zk7zqVm}%Y6hU zQdH>KL4uj~ea2q)K#V|1#QB~ca&c-#RsrE$v^_V)d@tx-)V;IVN{37N3>7@UzQq^@ zVm@;%ZN*z?P>Kapa7|-NRGFH%OWnqPU?PfSK_v5aA=xD&*)qa(P0_oE8t1SL@4?v$ zJH@xwp60o|>+2^L7E1iC=6}iBiEfKP+>w`2GbR=JDaQ{1^vnb4P7Ua^Jbi*j@3YRa z_*(d#Qr`c?iTs(t2HE2{=5bTKgFu3=V@M;~kskJ-ZjP57Z>N--G(fhqUAm ztQw7Bn91nW;mT>qoQ&SVn=&Bi8w>}Q?jy9J=lhUOf>rVAq3T6tsvl++Gi%}M%G&}d z;-w~eEA0y@kEtmSDTK>jilU|!EEXRo1N9SBLK5HflIjP7$%&IcxsZ^kT54l(cBU%( zU?x2mwn=UAbWD4GHkQ>*P&^_qPPc7WvQt(^zohy*@K;FHAwV!<;5ou5MX zWJ0K(5IW>ov`uyK2;GL0w}T z87@%JQb4&Z#J?TtY4eCd(yNNR0o3xmT-B*f{a}UkjZE)eT`t%<N7KQIh8vY%1{^43}4)Elww$}0mK^?Cm zo)aFLH8eHnahJ4xs##WHnaQ&y&G>gwO0D}E8kI^jW^;O$)00@M6!rR|VZ>^{=H_Bs zQ`$J^vGX^<-M_^eB{-}Re`Eu&-^}rEq(#DoMQArEh*tFIYbA{3C*KAp2Iwb&Th zuBjE{yaG+{Hc@IPq0<0PSCQ=<1p}b zbD_Ppw^%2Fr+#3$8#r2Lf$)XmwOARNX>CF#q#OG4hw!jQp3rRegK>~El|HIk&^d-xmgY)ih>N>MQ9ke+h$tlRUuBQ3V#X8W#U zc=Vd~Lv}M`qon)71{x@;=H%Q*~~MHsy%!T$gi-t7aj(G$T^IKVV?4flx;rQ;0yD_3hn-xKB0W5N`JBXWwS*QBZlTB8^zPZTRWY zRA=i?qn&auFin992it{cAA*O#Qf*YQ`4z81`wZ0%Z}UChJ51{7KINO}lz zs-@O*fjU)|s7Q6|>nSs}vbrU@lZ(+utH#y?aTrJ81>zmdN&Bn4;Gn@o@m7=|w5Hd6 zVp6oH%z}ShRRY^RwIA$%6-eXHX3mF}(l`h?xr@A_Ee3AO#>-9_j1EPHNS6xlQ1(LH= z#%0oWUl+RKBPqM+D%%2&u!yY0PZ}Q)_JZ;>2gX0>Rxy%ycD0yms_Kjx>!4R%d41JI zbXyo-q+6cG-W5A+tE>l`mztYqAGEl!aw>mjx6N6cZPD&hKJozm|CM$n;83=0J6d^d zB`HgiEK#8_mDd`PJ^Q{yyqRoSqcMs0@J3}{vc?#Lv2P=?M0R5^FH>Y4Ot!I%G5prjZIrY3Ab0WJH5)eg8-9)~WEky&wn`!xSo+WggA_JumN)LrPGTx9RhGiYj#VMlH=KrT z+!>CdXiBh*TBU-1$?dA3#KjmN{N$kH*EAugG-dUcx;?yGZn||fgY(KDqJpA2J*;v+ z$zWm$>^UBA=h|2KZFv*4#`34w*XpuC-WLX1jRPPrN7_x~kDD)vuzGs#noLkyA=_>E z&HF*`zE2Oz)o8ZtV0TWRyt_BJ=ar4LX`8T7zR9>2gIwTCo#=M?bl;Uw@4UD2Wf5I2 zlFKCu-SFnq{hQ-KNHU_f-1eqPay1RTYQBZ)TX{J%sM!BB103;uH9>< zor3(crw5&KF36e^W?XTv=62G)S&X7DQY0xi&0V}Rfq7Zjm-UW)#BqOhtA@@1WQwI6 zi)2pDt?;0Rbj%;aN*YMi=>T}Dt7*yf^t+j!UXY1Z-e_%UF<24jDxL}r(R*fi$Hw^s z;kBs9DfAvbK>A;1bB6|fsr9F&);t`|BR@aqE?zD0i+s~Z%~%D@oU@Z=c*;vZ=RL{e zbHZ~lm0XJ)`^3wRMU>bblv?f#SHU*-U)fx7WWWi3DMfmtW{fH^J`Te5xy-C;EVhn@TGgEFE5$eDFjFo_6hMIVPDyXd z1FpE&N)NEOUINI{K-O8T=9tF#?d)B9o6-1c>c?qN8Za_%+;N(+Y*{s&=<4FGDFqRU zMNleaSGH(@7i9IkeE-ERK>nsetuBe40NrZ5n4%%S8~m^J=Zq(SFsJR+<)3jZd7z~8 ze`sXSy6@P>Ba9JYgG=~@QMVp-4`-!bM2-yH_>-Le=CN?v>8jxb+?8}alW~8U0u1$0 zpI@F+Znuk#0Ne8iNz8ZTE1N?L4Vz;!smF}TD^Kc7l^@jD8xUJN8;vOHOq>W--);{zqOzQHa4()%d_sj{?mQNM+ z8B{>$v6Y5Sk{>FikLNX3Ew>Q0^HA)(1BQ`o3T6A!xoU`~(Aw=Bs#B;v^$uUy8U8=y~A{*W=t3m&tVm5^8NGbem=?8-fYPbad>V#tF$ zx?Aqive$Y89pYCe#yi?Q(s2XqW;yjcDtGKS^7|Dv731mN!8p<@`}#2vHQOj0N_+K> zzBY`N5lcmNT=JHFc2uGsD!BAADW!-{Y36s}Zv|?T5;r})L&GYr)?3q;Q{MXYBxb`c zVQaPH7I8ttF_5_FC(BF%RZmYL%l{LAz7xmYj{{wlF5A89+yC@JkU?}O%qPW;ixOJ=7CM3sk~GZ*Ngw z#&7hRBB=LP_r7s9;U$FugGwb?e=4n{x7w^QNzqBwyUK%{p5UZIxsA8abOXnGW&4vs z9R(bzMagkBw|{(C=j$?7R3JaYZRA{U_;MhQSWBZ^!kij(3#T>?fSu%e$$>agXjdZF z91gBv9$Y&je9=xNlwQRxQ&i}5?a9{Wuc4~3q%uF)Lk~38V>cI2YbCvn?9kSGFTMdj5$58j9(5$$pD5 zT+Y$73X+YDp_ahyLc4F>)xq;xZ#I1 zGUq0)zj0)m@oHuvF11PKp>Rhl>r9pQ|9ai*9bhKrK(%q1Q26v^@^c5bT8)R6fh(_n z)5wq_Gi?}p*;gGL%Y$Pwi4J`2YAR_Q!cg0Ib|prMmhK{oENJ5K9lNkW zVs(3R-P&dEG#~}Z>Wx;zAg~@o!{u=TaDlF*&eH|)it=es_t^Bj(}Muhn}4q4$4`%q z4JQls(1T}4k+11Yg+Y=^m%GbC4Xd)^r2Cp!P%`~>Lt$-ADM1gqWs-lSx3ffi6W zyb5J1wF|UW07W!;EW)C2z^y5`Tq~txBnoQH8H=)z9boQ)fC4{O!py+_Zsa{i7}sY~ zI^t#>(iP9J3C1O6%wafZH-Q(bT zNBkY3T4lhZxg7YNWyQ&*rck?)3d1Z6BLB#e|I}lqw!CSNIfAwRNOw2ckS-ajwJYd# z#rU+AFryCIqa=U5@Yx7X`I5J*T6ttb-O|*#cIHtsKQu=>VP<9^H-1PKVR=)t4Z_zG zc7xby3FLYO7)u!zGi{<>tjQ4!V45FJ5Q4yHfULhQI1GSygRcR%ZR7aIy&QS>0 zdi%wTrB4i+Ut#lPeJaLz8$tb3H5FwF2$)Mm@%bhY4E39Ots_h+n2FaHfF@^XrfM3` zJD%igrsnVzoR1pI(fKpVfxp{!?%n^o6&(q=#x|P(YfjSX1{q493%X3~r0^UIv(avh zSCTr(s7{p-Pb0$Hw~RP@kssp~H+tYiS&WaZcwv9Gj#$--gF5_?tvUvnTDNJnWX zZGU2V+;dZifPiFX=Jf%d<5G2INZ$KU>_mep#jid0j}7gZp&6?K;m^P+wh3+KA5wm= zBg;&K+J=9FPi96|TX{!<69xq$ykFKYMR;M3flk%)d`YQhN>&JgL-Q|~e7XJZn=u1b1PeL~RKh03BJYA<#Tl9bzokrc1(l3fc3%7Nl%DpO&)HgK;o#>rDYQldPc^YWGc z#-RB0Z-hY!CKK+h;H#m5hcV6Kv(tosWeXENJkVLMsdoj30V;>_EHP@eQ`wd!yrnd{ zEGA~Ae_!FfrFPyhgoT1poRYOK;$cf$+lZ7%xrge~bNO_j^ja^Yd43Yy$m`a%S3(?s zw>@yk<=;ENvJlo`!MJVQ~XpoUs-N7eD09%S!t65KfYd&%vti^HgD_a@97?U zy!%Y>mrPyR<<<#T^Qx#C-9xXj0D}SCWtF#|51H?=@nPM&>}bF^JA%f`Zuh3`%o`WD zEQm$FC=1aNEJ!hHJcy6f*X#}f5d*9%DliIj2A>W#ol*u}EQ~YF!*%ysLtmOo`AYe< z-AZ`JSn*AfmK3g0NXQnasL{<;2+)s;WQcF5MPVoBL<8UG$6PGkprPe2YvcHP0PTVF zXOKF&ZZkY&iUSk?!ff(lsfR&9$z7xH4^{i0@nP0{Vjf4X8W8fygI`f?f48O&xjO z_QB2ls8q;SzFV%939)^0w@udKR+Q}C6>5FbP>|UCvn*M}ZepoK0wqk{v6^Sn-NWs0A zP}_ZJ_LMpuu3)2Zpsh!XFOrn_JgVTC_Hc=J9`&0*0;uTc&hK>@zBIp6Lhfh}#Jh}$ z%M5xEoA?T$o5=x3jBa&FSe;*XXS^*MFAaZ~99uBE9Mf*881x!7M|G0b(bO@?7PM>o z>!!oVusskY^7Dq))jHZ1|5Sxa4B+egYdYKgjRu!@w<_DyZWb*toxB*ZoUt_svqnG! z`bV*p5-5!czt^FjBvMVtvvs};6qy2_mG1`_S&ZyjN2_j%biqfRp3KR{ehHp?#Nm5` z)8YP_u59p9x3x1I%}s;eU&VRI$3t~EBQSu5tAr{47MH*6tGOiMDpNR+gTP;a$5+wSH~GIE#BS>LW{2F z$iJL3h&3xJ7$DMvF@L5dQLbHg*K4WN@uW4i#m^|=iVXoR)*sVu?Yv2vAe|R_>mniZ}yWXMR6^iIDFv(&^u13L;oQs|5l6m_XNJ~KAmlT z)Y-Q^(btVr6L*n2{Vs}f8u?C5U7?~U%eR0k_Nf^ON3JO>Wk+k7r^Y9MwgB-(NDi+E zT#545cj?Ry5$pdApD00(h9T^|64YH@hKqp4Te~`Gfu%gXHB22n4wM|7Jfk6kb26Ki z{SoXM_5`nUfj^TjpP{$29}mddZtE3mU>pZ;4kNseYh3{zm3?U$pyV6fxzr~Yo;wj! zVbwLp7-w|^4}59QCs)%>;|X?uv11++khj!v-n3$fxGkVfocgc6K!5F2L}BAdUo_@*27ae%-@%Mb+uCI8t33HsQ1ccSY8c@F6~AUy0!o)F@m=~*HU4g>WUIF8Ueo%?5?1S80X z&nUZSZ6_vY&ww80mc6lmzR10#!C4F=d4auDjqVGe1NLU5722{O9`~CGdQY6-*2GGE zUxA)*oEFtj5`b5eH97^HF;KsLdy-Hv7wZmpPS#7*DNL@+u`{BQ@;m%uZad2}QabS6 z-#a4X-#wM?y<*paeVHsBKHJl9lzt?W8k@9&&?V7PqdeC&D?fE8pt69M={H}CzS%xG zNklgJsv>v5oz=Ibh)V#emTttT2`#xZ3fWp`WW11p2B4EY>?(9>6-PSsfji!o58UqZ z|3RP3JOwOx@ivZ)uDGh(3FbRyMldTQOX8y3l`8h+t_`>5VxKt`#Bt29gv>iTI_kRK z;3=EK>w16PN`}PZo+l6#Avh=kAQe9>ai3-_-Cy-;cE-Ml}c z=Mqz=KcPqM#$TThon1Q3c2@AD2_Th z%LAuMVUbs_+S-;rXeoPMQSp&TD1|PT@%nz5df)372xOfQftrEd)m@=xt<;}w*j#DoE4o@PzMH~5L_-it zr-xB;Q+3a0Q){Pv@Fu61*XH<{=RB$arotQlXD8BsiGtRkL!W>Zt=s$>`Sd}3HclSh zSM1Z6sM$|P&SPXp%gXuGLwN%(K?2zN(7YY+-oV$)OpDP+I(IGUa#5*ZkMaf>snAk3 zH_zpPzhRZLiCd>5Lh#qQ9B|}7|81^kur|o}sXpgW9r@pC_-Aod? zW1V~kPEP4PzveI9w_0L0k&Z6gU!{b55ZI9oKQxOQo5|U=kK>r~-5m^!-~Zu_igJP7 z&RmTH;KOwgZjMpt)q5Lqz3c=&3Exu!j=Z6-$$t5jQbkQSGp7e zf7j8kRik*18VFNJ`mf`BwZ%^C*Z@scC-OM3EQD!4$E<$KWen{@bN0M;3mit_ppgX9 z2V8xxFlOw#VB==};~L6L5RyGtuu4{LRsoeZgqH5)#|DtE~SqotK;) zGsST@sjmI1nxot`uXAZ7eBJZU+)JvCc59*x;E7tJIHVz%Z^H9dluHB1m( zk<+KbPt*cd$H0HwF8^unn+_kJ>4yT~`-QIRMy~pfhh5zdI@=Jo#~qK^tZ}h+wy`UWKldDh}Zdzxz&&YMVv&}(QJICWo_Sqe?fgcjYTDi6Bo1Z?G+xR0gKwja;^|&SS z>werkwO+nC;N1Fktc0tgw{wRGVhN$Cwr!tBWLv#_pta$x(yz7aDo!4YG(9n}{@me% z#(SSRhlXyl-dLk8yhyk<;f9WGnu~} ziPp7u*lTJSdfj>G#Td{1^&nhJC4cycauj#U!;4wbxnddW<-Yrhh?Y!0vij{VMttFUmm2XwDR33{?BHq6CQ4aZZ zbb+jS-jS_S2>OhX;nviq2*(1utz2MjJ*_J)!2tn!7pKoAEGwNW;5$97Fg=sXNz9-b zW0UBC8>1?hiGSmy>uOxaeX(FmvAyYMI+|4H`TysCOJ7d7aa@7 zp7im+&W;LAtsR|2&<}Hu6U4E+g#(2{9y~<9`cGcM^kGV?i4H+nemi&2>6I8k94VP^ zOwga440(1kq^x0d12MQ)ten*&W)cF|4k|}!sJ*DKH)~n}wy3VPptavpAqXee+{+9rCydx|DM{Y(QbEzY4+VjSKtsDpZ1x&x%Ggly#c$!s@@aw7lLxBM8xB zg2P}VVXX?qk`qBD4iERQz5z;}PUQU>FsmI)>zhu{t#4Mc z(&~>}=hi>L;CjJRG`C3Zg?poKE&9Z1s-9MNwV_3E*>%~bp&r&mL>yuEwbo*kU{C}# z3GscM9ZjgIz0l|x8a-dL4BXQEDZ>`lkD%-m0H7TPP&$F#h(S52xR;6=XI8@!M@`XA zqN^v*Ep*sQ5X>7nDf~lRM3-cd96FiKd(|cQgm6sFqNHlA>?s7JvTZW^gs@n{l9>z} zXLN#4&ybS%e*jj7w+niBaBd3NvP%dJt0A>QODdT~I2{tp5{0cuXMB?07@RUOU z?($8IkMBUx?|v&&VIp&VGPu8?Os0d@qa8z-&Jo18>TbSnQIgf@SLX$M%in~6?h3+%i?Aw62y94tqTzm z5fF3*1%3hJlWr*EiZceqtHC{0Fv#Vw;dPRJ*>(m6?Tt`S@$#| z`f2?Jc9@>e@UH~0YotFFII%-MkRGVOIZOpk*E*@V^Rpi0COrW2tvVUC_L@sD1gB)& z;CCtDPRtu`y|@X+-8cVozyqOkONR?WItxZfL^98Ok6acf5GPQpJBhe)raoeyMZQ1RdQlf zvlsl!dKfk@vqq@&og0nL-}lZ(nSB@e!Z)Il#m9HT-M!Xh20`e{A!h^q5Hfo)lzH#+ z6NKq4v!51Pc6r?NO;2HLz)Ue2oH9CEQVRmr)zm0fB?KJ=2Q4ftayxjP{!>1V@jo{u zCFNUjpkT5s1lJ^T?MnY}r0VE~e)oDYrfW6~8<~uG1Kh&D1hNUeEZs<2JZ|}K__A;U zi05?*Cr96IbT=C)MNaCs15=;Ooe!Jtia2*LU}R(@yRgs^$eU1j6s9-&m6sM^;-Ewu zS28d3tM`Ib8X0TifN+!#ZYruJgrhJy!TzK%WirYRl~!a%VoAjbG%4&zHuw$(6|)o^3~BlaEW(Edj=TmT!pG&+)Sjhn)hF#We)Ukc0w2?{s`7&yfbqjtc7(Swf}qu*yInxk=abte%?gs4#Bhby7w6A9XdWB^|O9z0gBC zM4+ts{d|1%l!?QaFJIJNScrviJ+dh5%;^Y8)*y(sqN)TPNIoSebIB~qzkz2v5LBb@ zfLW^)AV(A^lb1HQ{e#KB>4$j_zOT|zxg=XK_zf~(e-Wg7_{dyzfUP)*I#0zwsYMp?1BvvkA3G*%OpXL$Um??^zAkP25M6(-W@!x3K{X(Xz5Yj`K zUegAmY8i}L@w~eF8g6)W73_%Etxt)Tq}9<7J=@~KjAX7OaLCDKFQK4SO+8bZ!Go?KZD51UTnq3N4rD^4(&-Bd7J{@O2w5p5PKpxi}+*q z%Sd?$rnW_R+2>oGKNws?2|EbNX6B-5PP0?=BA8Tw}P|{dFN&}THiQk=EEK%s|F`4l9#+8a}rE$ z5UNS31sAW&TI`UD>l23MsI@6Kw*~_0U)2)VUxT?V({oY+%MVxKj1osksz?CI(WFoU zvJwS|3fQyRc_C`9tUFw9!_Ws0Cmi;YjB0H~)=sHn=cleWfxHI|GHamp!34#;hsDLK zmK>RmjtJE2^BigS`~{@`{S3__3ks6NgqD6@}})+jH(v?~H2WuCl0DPVeO)A0zd(1In#Oj=4Is4`7Z3qF_4Vy~~enjHm&FD##bffn|v3D`9$IxciyP zYMWqj=k@;J-02B5_ThEt_Q4rA!{bmr*qb_RhoSqIXCqfYpvx(m)uPZq>mWwyfnopd zGv;q7Gd`ih2wfXhi35#-9N^{ zpB~?V*=PJ3F~`knJPEWtDL)%(Fo(FX`9Kus0t0--9Vh7_Y!>xTD=qSR-4=xIURZdU+fI$hL~N;8#N7Pq{A z+DcR>yGwkO1+gyR_ifCAMG=BaS;C4e;5W|tnaTFakjGw(Ghz|4nxBqtL^GpuZhyV7aKuCQfa)=M0WN$3d`=EMQ!K*yDG=7RV3dv{`R@pe1}= zaTbQ3hr`b>G&BTtPD%qc)HTF;OrJzWeaBFRRoam}Ze}~e;}BvffL!I>HgQ43h*O7_ zl&-`45iSWdQe+;efUK-6l840M5#kXI(wTj-I1QrI3Kpv`0fvBba;+M9k^H${yA{^8 zJEb!3aCPy6MVQ~s%*={08-pR>!8URqy9`MdX;Qd2<{yf^kCm7tRLN@nk*w4TTn>Ys zl!=#nMp9bGKcfClrE1HwFdg9HAMRzuLhT@2I?)$FYNLmCLAS-Duf+h%NtF^dv4$fa zm$$*P2xj-mD{SDjWLVVbrFt7S_IMy0$wY!z6zsr?SZ^^gbGG@T513iiCQUzntVC@b zEd{1_`i(|WBORnnCvO=8C7Px}lA?k!l#<6CDUHSr5(M}Fv&M~BoCxEG=+tcEeT=OO z7(A9_!frB$QkjA9ID>Kl93H#}-SIFfDGA#TU`Kihr8aBUf%Tmmf&lM?M;?WsCe+{( z4_b3bu9%ej(gHEisev)~$O1_CBYGcc_0QtScp1Zgi8aOhg@0gKPx+jSm^Qt+jcx(4$q&*^`mbiBROgTZ1EPe`|fk3 z$+8=Q#`Lv7M%nJ<+%?hGSoB$aoMacrI2ZR2f2mPH?v`n>Upku)p^ zQGNu8!tBibX)2H05uvdhoq37$K^Fc?>?xD! zuY?RYIdTTNS`V^fU0od-{K);z5wtDkGGdQ@@&+IaBWY;(RnR%hdN<(P>)Uw`uroT7 zG??A$I0%@0%n=eGgjaDAU^E|I9nFc%KwDT&2EtLstQQJ-99xPw-4UUwumWQARHO@q zHA`{0?L6t`nAV(+Kuxv;@iqWQ@ViNlbL(UpyTen2F+$E~y)h#54)E-D4%tbNSdcrG z%W?rY_#(mKe9&vigw(3a<=d#yI6xYHF~V^k$zYKm#XNY>67#?kSSW!-FOk4W0AJf@ z+HZxbhrV_02v=t-*%lP{;~CpTbw}2(<=O7jQ@#n->GT!F?m@@?vBqzzMRh}CH_u6p z(MG`{@B#p|X2g?#O<%FX?* zB9RQpth}=|u(Oa|&=(fU^d7VD%yZtnr@1pU94A@?>}&dzViw6@*9 zMxJ4Z0J@9NqF5~J|LZer)>8f9@$Pv2p}Qm2yZZ)&=|vvHy>?0<9nAAQ-eFsVmz2)@Gu6*FMf?ujODNrOKR8}pI9gWtqL4jOSn8v!^186HF+Wc>{ zNpTuDc-G_GHrf7Z<29w&z47_|N}}6>-Dg4Oh(mbCpu=~#7qY5zI?A>g-kH#I)B&+V zO2oow@a0VUf27ELs0E?`>oRyur(3=fHruZ7EqgNfpX6@z-8=f zXGDDOWCnY@lf8rExvycKlSb3Ee|dkdSTSnWBjjhHFrOvR??4dL~oNR+KsxqVK~u1@-o78Q&Sw+{Y@a75)wUrDOZ7$^u491`MKO=HE=D#e&Fhz%oqU^Ay9h|jvZ z1Mk)ljI#^REfp6BXJbR#$w!eDFdbb$sDwhn#IF{*(oUbKwxuZuUXZH= zm^KtPlQ%n()eOi!ycxWsx~^x)6sX}e`FVhaohy%4(a*m|=(b<%N>;7Cz3$`@@))H0^Dj3~o)u@U7YfY>1Vx3%$J*Th*fNK_Ea zm(Z((J}W(tBxTE}7voNzxGnySPgwlXXH^aOlKmih#&x}m6iw3eSH&qQvA8Ru5UlrF zH^ZhGXMg>jY%i(o!^>>2;wK{SLO$(3KMPwV!N--OuoWt^w{ZZ|yHgD$Plsg4KCs4k zEh((v^uUFakQ7&9a~FD2!Z%?ay32JqB)N$6NL3Dr>031MhE&cUoDTn~ja%2h$= zO2a`3h6Cdn92wy;51tDV*+ecYIwEN= zd1&((=(J80%^EcW`8Y*nT%=2Em>PUVHb}#+eiW;~sKs?HI=2n5z%c%NRv@W55!>X1 z%t!moc_T#&F6M~J@&;&?C%}-5(=)qQApl@QH z!l4r<4QYr<5&{O}B%- zD!Z|ORk)baiWU_t!OF0r7&@$a7vbjwUGo9yYA77bl~yWZ19n(4B7Xl=Nl*Qht>;;+%1^$r`5Wd{Y9=+o!Rfy zOgxQ&z6%t}CxnZ~sc~7D1gay#SoZdP5R*+NwLoC_TvEs{V=nB`{XMzQwgw&Zd zehz(lf5@i;)H`DeIr|1EU9h^rrXWGwl8k$y5Nt(LAU(mH2y}l8u-)1fiuTF6T6WZ( z{{UbyL@s=M9svbDN2J7C3(Asg$}Ig@ShI+VZ#LrdG#-j_@Hwq!z;|L}xABYsMJqwy zgc`afT_til$|@)D2fb$#&uIr-!hhIW#3N491EKm_o*o@Mk5`~wIl(sN=ZG?OP_-O- zTUQZYdFl|pRbBLxuuR4?*FSx#IS)HWCP>NAM0$a)7FvX09DuldYMRr+dkIzy&kru) zc=Z*Owp3%7=!^!xf>2(MWy+kx|M(P<;Pe{8(`5k)M20sMIGjOBF)s4xNdIvlrYn+IjSt9NPZ=)qCkKfrKTI|#RK;P}d)~>&Pm2y;YYRxdHju8YZc^g%mz#xK_?(%z)c!_qZbUeS6 z;`y!$vY#FHJ<>YU1nUpD7Y;r+FKbN15}XfxX#{x*H^Nbak+dmkGk$1( zK{~FaXCU{$)TAa@h*LPtbgqD=28s9?pSBuWAV)Eb5x(Bb;9&(vI9~J0CnfSM$nliM zz{A8LuZpML^KK|Zcs|+$hx6zO(9v8%=bmAkbI*Sjil{L_-auypx|baBAZJG*ui*li zlU{T3`h>>_M=ELZVl4Il6H74SQjSnEePkxQ7mvDN(7`pCHP9G?p3T-ND|ewGv?-=s zx1OSj_1E;gkcNRUiaI>=%Er4CU}{TQ&UpeChT&VXAx*@?xgPQ_B*akCiT7G_vh(w? zDMRPNV|04>Uo&x6bBG~?(*rQ<^A#f-eQ!%TzC~fKBjS@NWaUYqc?2^)J;cMMInjTp z#_6te1)>8ELE^%oNeYcwfg4ysJ`x05!h0QPxVBGnJcz-!FJ%6tsJ3ksJrr%BQfOBo zNZSCCZd_3(;aM5M4EkUa6ZX3+Pt0QrjM??*t{l%CwC@E=#XK}sO*KUBdD17C+Mic5b21l`29my!X@R8 z)zt=^RQ@rhpwpUaQZuG#NwO%v~Qg#2v@WiL^*rG|_K z9mH|F1kwo@q7sv+!UF30lV;~%i7KO$(S+On>Ji)oHra%WJFF;Dkbymm|JTM#!+`X; zoYD$(NZ4W{l9Bd3Qq24fWHdaNX#To{=vs!u9WkrLt^?!FU;dX-tx$xsK1>$`9?y*V ziy?VwwEpQu!G)D8<9aETq4uJva)xQ&dAtcOK*Mw*^cgqttqy3LL$`?8ppi z1c&flRe(1h+>f`V%L|2-9 zGH;rSDK?b58X&Yd2SVP^1K}tcg>_OZ$VjB;e;o691}j6lBR?N=C3NnPxtN|Wg*q$Q zmhld?^8g%zan{YagRN;s0h}9<#U#ATf&o2`lu!yYIrE~YA}Toq8$TRwa9pHt18bAw z@yM+(A3${qZ~@A?{*^3YsC4jt`ns&#mMFB=90Ysb^}kY~AGnU}u`W|&!TUI5pbO)v zS9MedqOV~WhppcY`r(oZKd~ z{AIC>SG?jHlW57+!G{)ECk$T>y_Uh7p5(m8TqD?zUvYVYso8^z`Cp0!o%i5dBnknsVI z3Sn<^^e}l6diN7oy-pAMbToYP%!jvuZk+6E02AkIl%oz{6g`KF@pb|jg!D^WHcK3= zj#{b*7b*^An#2Wz-4=cKyt5gq3$BBtz}oriXWkhD+PNK&RunQ{9lDCw9ImpSV%C(| zjc@)DKPM-R^IRe4G7c}U^y|;~AWyAHvP=)2gFDW|+lfCxF8Ke&n57{>=s z7L3Q?UJn!uF#^oEfIz*`9wc;_UUx(^ny>?+H%t+O)$?ZGQWZp8Qf zdTljuj@K@9&bvcvFFZM>4>n<*`mGdFY;^@k-5N_;xL4P}VE@>!H4qU@HREu6o`;Se zVCja(;s3)lnpQc=brtCh|LC8JvPmc(XFhW~jN?32venq_^mZ;bJP+-`uUI0q)dB zcPa#?OUERxB8gD7bAvX&fk82^U)Sjmy37w~S=-m?(txt4I4}ldO0#DQc!O~>%x0mR z8QKSG+64v%>be5*5#@Rs{`$IPpbAYwI;i+|q`c7X)(2gQfDOq48J>&BxnA2 zV5GitN8OVL*3h!p2E91gH+`MrD$>|Iuig#K0Sow(7J#Y)O;e)^mZw)yp?B_0qKfZb zSPB5#$@30^&B>nJKI1a%fe-AfOieS8->E(^4c-tLPP$xfD%`?Fx&W;(d`vlNHKazT zRW`=d8e*Itx1_e|Tt|zQzD~#Jvs^+NY|RS9zoj(b$_++jr2WN}U>NHudRSs}&i!O^ zbwTP?>tBz%-Xi_ZpyOyxi)4;qY*@SQ>y09D&X0z+)?OLPi3=G^&T8)c^$kPPxGy1z zywS!uoMeV*bcJRx<#lUUSMwK%DrOk7O4ndxbiWMpdKk(+0v4-H-N=RU#K^$Vg2vT) z%2*4~5;Kg$G5CKzh4V{zB@12i_MjFbj9|Z<7a&;N#0B)q~o5q=u;)$fu~)g=H9 zo5@)wvL}2@=aH}_bZo1mQue}t!8R~UbRj$son8!?pG!z*(L-T@vp5UHHPf4@{YL_h z%+QWL+Tk`x-d^~Q`}nwDix5G$UM8W!__aaXx;iQrZJ+uoU3!0#0bT|EzJ=}tNSPZL z=n4R@Uge0EdnfN=8DNE&}+2U9TkrQwd=Dj(%6 z^mVOp@(?B@m?tXU?%{AKIW<1Y^Wo@5F_sGatuw^Xh~^IF{6z4G0YV`%ZnP&ApwLsG&%j545Y z)C5-!>V?}pSO(jlgZ>*_MLk~z9@9p56qLY2s%)I4%YZWf_0mL@2r4_m^0+8`ISoA= z&X@r=sH&+Q;_M%-=tKdR`P;b9mW?PH}$K^@mrW>gpi|WIV zm;qGK|9}`%*EQ;6y{ER?djo&Yr$q*q6#RTG?vsyC{^o8@J_eh)IBmoF*s=$4QyGUl z5f>LPOGgEwFf9+V2@6%c;Z75Lwe4tdR53Iig=qe_~ zf%4>xYBv#e-Pqt~3|!h3o136C=%Sck!3tID(X0d!WMW{@k@NC1uJX!XZ%>1*(z{oc zt$m&Tm`uo*jjGn`)@G)wIK%a-+f?7h}!IWb@Lri@Gp;*6l0l>&P8;6r}P7y5>6iTf%%fMhh%AReN_)}C+ zV0$cJub@OwMEM9$uUkfmQKOMe45 z{qIDD`#8(h!R3N7+IfeC?!T;R91ePhBD~0F@0?B>&?>fr{dT;89yXQozc(jdj z^H}xzOK=a`c!x9vSim!X_FOdbTMIWc4P61S+;-A(oZMakLJ*PtF*@dIAr(S?_P18H zQMyGlh;6Bm zf6EW=m%v#AZs}+M#qdt+k>S@tq|o{P$2#X{6~b6Vk#4OU35~6PXhX!sb+J3fAzXcn zB6qCWQ%vCkt|JViXdGU-A#rn0a^?ye+(q|)koek6SaAcaO6Y-f8HopyKuYdTEY;tR zT51ALv+M~6G+`Xj%%H~kYJUsFIe81%gbVCQG#z}08Nf0dECy&Ojh=>>iTxKdUGpKh zF5Y`YT2gMWc9oi0ZHcG?mJ$FGULyz>p=q26lCZAXEpj>-qLqH-H3gRt5|`VJ!*N2O z&00zj-$4$B{LzFuqhuSI?JSjU#RK!K11K@3lafLZHcftn!gEq$BrkrD|0#!dxJ%gq zE{R%`bKp&S%pLf#jGi#zX*A)PbZJykZEVmd<#&`;Y1*2%*e$>H1)JFO;CCo+t=N#RLx; zN|H2u&3bK0Z@BIRxf5>FBIJsU6|_6t2666%tZkY7?_}G_$pDSZIP2MoA{uUSU3?N( z6KqiH2Jfi=76{xIALgVn6!mgPwX0%DiKjYkf<~v|Y6A{Y(if7F`9Hkmx)(B!07SGa z)>%Ps>@&4Qps3PEu*>Z}o{Kz)Z*H9wok4kA26rYD549ng6uNeE&~zD7bI{8_Ji_Fr zQW#@}RN2~=oIOx}f^FsipFKtrwcOwVydTDTPW=FBA~L zuxdn3v;^LMEf1docB+GrOHbRh}ht5{{af+<{?yvm;J4r zH*C%+_o`ZdArvQmE9hoM^EAKEO#+XTC&9DH_ayI4B%GgD$Qt{D{7%$1J0`jjGyYbx z4u?IFPv{vy!sJfXI6K7$EN@^|g)AiMX14f>kQDmv0;gL6j?ps?*CH7rau)|D%gKED z9z-1I)kp?{yUWNFhhU21=>FU=y5(|!E{Qif_XJHbp2E&yl2D^ zw3OqwM+ea|lc^wHGJBT;j7>b;4vA(Nc?rG~!5)jH$Dg6kQbS)8T8QiSmoBryrVL2} zF?!)~WL_W~AoYdW+}u2MF^Y4rE+0Z2KlB8ti{ftF8?l(!VY&7u1y>@5VllcK5cx#* zT1=8TYFOMpC({}6uOJz*CYghPjifJ@l&yv3(C?tCf$U3uL<|7h(~oilj>dPg1ecpj zt;8rR-tHcyMq(aKLMu2?Rjj7SlVgT&`Aou6sI$I44L4F=hh4*2uF2b)D>!TS>#nIi5{e~Hd=c%N-B#knG zR|URpOAu1~3~b)f$PydBWlp97^|Dsg`UPXtFdIxgN;BAW7RZEieTo!tNTz<_Eqr~(!d#LpHTi$f|W3is|G+o3bLdAZ;vPuazYa`6R@3)Y@J)iP47qAl|Ec}|y7O4-~3QNqkMV;r>2Rqs)& z-mi`Yi}?7C`7Bcx9=x?wq_W#JW^>KfBlpG}Y4a+@dhU)Cc2|BIFOOIp@?qLV{rVps zEp0pcTsnpG*a^+H9YaG6ae;ZPqb2TZRCc_cco%@(UZ^E8*CczyF*n^@FS6oYn$;Be0pCE1Rm(tsIH^1#^9e& zNYJ>G7#}bWKenWL$W^iK%Bw@pUn`-G11%{ro<~LJ3>?~{H9thJlquw{qP$b&;F^M= zcc(w_)mTYdgvfVgo~p_%%)h>Qvf!hP4E`Qol?ycAK|zNhp8_%Z^isW$Ej|NsKg0^= zyN3*YtjMkX*6}rUqsW7-yh>H~(XqZQ50=TvZC7NwUo8-o=-V*xQDOh*hpa;O*atqZ zRwbK(dy?M<;8oS8uCA_m^G+;W8A_HP#buR_r4~=f_I1!(BOUXozI(4%8>W=57R#Sk zI8erR(Y&Bs+nlO#J!2BX=C|laNB5}0`R8c^h7Kc}hy4hT_g_oTr}g|C`>6QCdP_*d zKt>OblHuE>oowwEZbGRf?ftnv%bUJCI~ohc+&ddCVUJ2T8zkJ%N7}+Wm68I!WxcxF z*e_}pm@77>bZ2C+346&U>6_ne+H;&SgI${?18M~#qf6mZX*(Oy1xa=mdN^b zlbu2ZuGL3yC5-r^NHV6Ps7CAiE4FlEYG*8LYioNkHZp)ce*h|feIZSyqalAW_DN%W ze%*E-aq;c#sxQCvB)_L&OZR*E5G+WberD{F%@@VzTWp|WLd$7#){U#N!%bTB{EqC0#Ox%k7qdV)p@+Em1ji;|t`A3xd_O)TD zO_sr1MK|zmn)9ve25d^{|(cBMwGUZzqOP`4n6ndjad-MXT$Y2d=Z zR$^z_iCJd9lY_&*o}7tH_Yf z)V|+7?^l=^xzH09zOF1YG|v{L^?mB;F8w4ot_1CIr-7OwL#iyRuy4H-(WrUbUsRtk zDZCrDpZ?g~&u_~d<=lm|^d3D97^XMoxovH@->6N>bYf3?c@+E|4f8@lmGLUEgy83j zN5?+(u$Q}G4~4EfR5GisyT)6LJlI(H#kc!uHapOQBLRb6RDYm^9ueKz0VG4K$-7R` zN91Sc%pjk&+9Ic2K5Id(WK{U6yqy#vGSwADg}X%V)*kmBr%xIj>d4yIZ{+T17P46E zOV@Z0&-ulpUW^txHa4HT4%22Hv(-?sXRFZn+j^@p-%B@3AQ!8%qT*H|!0* ze$H9uDC;X55{BCO+|>AB)ua74PD-Yx-aYUzT>kcM>!&91!Os_B&Q{GID+|Hi9#hKP z^Q+frZLw_BaJP(w(yx{ob;_npg`^baTH@{e)RL&w+gBCvxDsv_oV!6+=Z;?q-7>!_FiX? z>xl*1rR7t1iCOGof8%A_C=Kec<^7hq!5@mjkLBBj(N_^CI{Uo&c1U~K?lQh0kYn=v zr}K&Uq{>fkv*)usc*ZvL-FBpzFZBLJW4FhtgxAiNSUB8@g@;hVuk|6#&g7{Yqi{MydA;AiLt@@DcM)$^!%37EL}SNuBv2mNi(--*X&u=ij&H$2Jad#GKDP$VA7kssk@Fx3N+;~1*a`^#>u z8W}h@aZ#yciVohjWCcpB8~OG53Lb-U$kD;_uhNf*JtmDZbLh|_$MNswR3FpwSa_NG z_o*^oSd_q=+tas9sCd;y=&C9uH=aF|@P+H5>u&!@Gg`yp^Fya0=+}B3k<o{ddX9B{8H_O>#b6&OwLF$^%D$i`^O~#5JN`P$*r8Yz74yA zYN!B?dQIP=c(*+Ir9Qn5!$9@lFj$!zIuV%s*^l6N3Lq7po$zGL^?!|e$yi44N^X^n z?f(RO&>Kv2Xz7HB#o!>&CBhEOq)&DAfv3;&lCKINzV=f+{7Sih(R=AN5CESCo^Fz# z9kPF8D?mZ4=GcV$$*apA8?CXnuPzLwN+tm42EnxmRC)?d>Ho2={?h65(X;iRB5&BaYE!^FMKGA$5{zriibCzD$pY?< z_`e8zrJz#7ITGhgyetz8ySZGylqvr|27kL0hnwr2>wTiD>mbRV0Gr}O>ID#~e}m@o zn+a%g8pDuhOk^yfAcc2fs2&oK!~HdD$b2E^jJ&o(e)FFLDRL#0SuHtxgj)7C2&q}9 zN8y*s%9_QU1IKS;Pl*ebvxGFmKcouMgyYXHo&$zi-|A8e7Bm)&n2dI`7V_tAnfeF} zl8%fu-RBR^3F3Co=X%HD)UEEz=J4`1y_1M~A=~IJt31j){UHskfBDN$y7vU!U_oKE z9e%6#m)W#^X}BO=_ARs4Jn(k?Z4b5~+KoZBd$AKuh- znpZhswE23|SwZuFx-D7O-rif32fK~m5db*kTsws=ENf?Gb!4;Kz?M0 zz>xIuFWG#xsVai#8*kQ0)7+D57L=*C;3?hWiM-7?g63AW%^Q54oSl&?=vd93Tbp7Q z=un$d($I1I=rOZE_eSqc`%9oCW$LYgRJN$}XHfEl{v(KzZyA-!@P`(XlWMITytjyp zi~9c7R8up3Iy_|F1b@n_spZ=06U{Bv*}sd~?tPy#`Bet41>m1-Dja3$sEkO9ZuRPY zK^yp4rP2LLFyzzxO?PtnQuBwCkBBJ+2wM2aKgj|uSka#C+}y+Zp33fboF@TL{z#op zz)p79ZoXOa99ldMy+1=Wx_`cl8EmVnwDNXXonrcQUfqGZ6YVg$S6|Q7@maEYa}85X zFSORCme$nlKk9g_^Z<>`{#N3$$=adS1nrYzp1Y_L9F5K$%v@Z!pstoQ{qY7LcF4$|`eiq1 z*^cBLi|%?B%@Q(ybl>x=YF8;E>ELC$=d_(iUd)O;Jav(M&V!WroTT{lmFt#WpFYs# zG|=k4CFy4Ox5(V5-qJU3-@I~r$Y*(occ&ujbDA~FW8bP4+mQJmGUF0g$w=@=x)?b~ zC0&&+dl?v+E`6dxuiCAuz=hlYnfLVP#Ai*O%uLDTjS}_W@^aJG$W3xA@C%V(v3SmJ zhqICO!t#rPi5sTchvtheJu~;e=}QZ^6A~o8C~gjCkB?ux99;-M>)!CFFsoG7Z>XcJ z;~d^|Ci_Ph^YS`lJ#+Ya?zh#yD&EP%Q?j{>ae%3biQ*q7#Wc)i3CDcBEO+$OppEWY z(GaPNr(RXhH-565XZw$yDO%eimn#UX-_+lqID>tjuf`;0rD68nB7t&l;=qAZCnx(m z^7o#A-)3j4n7KS0D9?i5`Ry?8gx}}7m*NoVvU?@}=K47vI&;q%vF^W~87EM0&dZWk z*S&0`IP-qb%wy{V)z57_mnc2s`CMxrU4d`@i4UFHV~M!+Cad!te=PB^TraeD{)X49 z!vlkS(w5gOE&CMt+N;64i(Z^=?w0Loz|>`m9E^5fIp4_P!o7&qOSqq9>{s90_3)qo z?tbpK#mw*BQk|nETe_-LXrIjZcD}X1pOY8={_{F{=g%T9p2tS{rxjy=5}s1(A6{C@FYd@;wc9Aa?PN3=WMc<2U`(A z@0M#i$B6mMA4z_Cr>8LP^7!T@V&@Kyyi27$elJx2kS98`yO zv;+Qor@1A}M)M9!K>fm+)$ir*J_*iAxwX1C>DtW6iOz0U5yW}uckeUmFqUw zAMY{FOp=s*Yf^PbNI;=3$VTYcw=E4>rCF=R&*%=mvDKwa*xk2c8|{CL*|@XVygNO& z>)Jev7qsS$1#jfn6rLOCbZ;sJ`?Odda24g&r4T#u+qGm9aUKG`D47& zS;wMRN%nm|tIsFT#V@UANMgiWXKTMk<-*Xq(Jq%o34(nUL&fV-zqTG4ac70`BQq*aeR_6-)abI9$K9X3s==vG(K&#EufY0`jJQch=&*VN;= zjdj)o;sZk)J;Pn{-t4T3c-DW;%YGzkApfJX#=F)STA$%73)<;tPHMhx>YHz>8uv&B zPnVTVtI=!x#eY|*-)nijfd2k7js+FHqe}y&V+u|0tyMQO?AsL>Haggq^K#;tyCv`T&PiGeJIwbTY1d59Z~6Q!vRP^R-o%@G z-|cPZCd%w?Jxn!@FrbN4YzaHHgy+?@$#Go`)|0ol7_Q#r(GXcaNvLK+XYkav#?2#5 zpUivR2f^3nsd4Ar;{`2m?J{N`8Ps%l%&>aiSDQT0xv#x3>D`)Amok=Zd)?>$If9!) zJWaO9{vMywKNkBrH&dnaj9_J3>#So3ZpUPgb>_KWWqrv#@Of0zFC*FgYM`LWuWz?| z)9scmR$()3BRg-hKIX(H_zpa+9edb#x-#9-VWg^KifF?HnUi%M4I{SsUV|4J>pqPK z7aDaQU}rm|*3z>3$7lTx{jT4@8vQlUb^D=j#d|?og>vc>^WM!*M%a5!4m}tdZuDu* z)NvcN?RFa-5a|BZOH=gtWH$FdpP4Nd?9+ukQ`nW6BxfI?b-B}`RL0-2%ZG|>N2a+f zePP(Rg>_vvch-MOwYFm_$BS)y)X)C(8!VHRv+TLYp4`1Kd?))|mWuC64Kn}hiJxwEMy&7H5rpe|?0J)_M5qm{D8q+I_Y=^T> z7hcS(YyLi>!t8aYUH5ovt9(@0n z(+>Lrc^OMb&<+e`T&|XR^Us zzf``#`-kpMfwMo43vP(IB3Yb1dmI*Y&B{vTir!%2^OJfzJonhY8CHnrwO!&*UeRY>dC=C!{#InjL&S)1f_wS76HRABVsB^PIKo zOp_`*EYAJNNi=zb_d&W|x!T2^qZj1QIm^Y;JT+CO8|~oJ6y`s(wB(3*>7y46&XKW=-z4LzTJoG%b0}4 z=$U!lwT*@B&T;S2EcTd+*Qffqs$J?+xC%Pf72ZodaW*n_B){%tT@TyfzF)7QZ$W|P zz}y0_YqjPj>v|0qb9FZlea+o94h>|%u9k>VTlP7mOt&6(1?kT$$EJ=3>JQSC z;g`6`pU$nVFKpx$E%3E% zCjDzM|0&6%vueEeYWt;!#xF0`=$*s+%XRb5jCCJ0#Pnr<-1zixMr_uzwrh6AYj?h1 z8Cwy5b?c)PCa>jZ`>rHyd3wzeCI11-_4^%sjCB{C-gqpa(C)IqX)UQR`BtrA?Y#}{ zXBsbU6teCT4SFY(adYn5jTfKXS|XP`mi&MV7RxP&+Gb1&8M zPt+>WJQdQ^_w++eacaY~ZHynT+BbaNQp#)GrV)+7hFhLgWL@j7UE`SlBuVUzZA7PF zE}PvptTglGTHqt5xe18V<#5eJl1bwP?kwiklIe?0Xc0ohnj0^E0(SDp$JX z4Sf83wRz#-$~Ft*^Rmu~Nm4cjy5AQ*-58r;m%HfHf3gdH9zWk<^=ul8H99LUd-2)j zn!BTCXAZmx`}SCRujITb2d~6rE-fww*2S0E0)^b`cL3q(0_}I6y|j6o_Rkr zdA^o|y};)qlMif2+N4l+Pg?hh8duEAM@Db9`BxnNGFv2Uq34|#*7Y;h^KMse+iv>i z=d`zJ3n?AtBQk}hqU8O_7i4C0#Dc4WQ7WG2UR>8)>G_Y~>NZ?bJqmtSD$*$II}pq6 zrafO4cSGj-p_PmX`j*p6U%irgA{lUVga4sp)1S{3nR4uB9hbI;^5!qr><+WdPgW{; z|2N2dwpl2puRL0b?h+ice#MIz-6KohJbC^m@e)%*B^21HpAMBe_K*|!`bdm`p@?F)6WFmMmK7w=rCH`AI&OX|JCO3kZ>xj*~a z#npcGuHJvAGV|cvvqt<*VQUs{IUjO7g}Y0sRzl^dPC&L>qQ8C0r!D90Q%gN{EO{!1 z+#>wUPK(`2uhmf*2z=kp?O)ds{wkyIPMxD|kMP3~$BP# zj+A8j;h;>byNp;Vtxc;}-A^{=X*F2zA+fRiNa3c+2M)8g1=MaI|8gp>^3>!y#n>lv z9Df82^mh%xdzp7-gkonTn*KJKnX+oge0+xEVLhMiq+>?=7UZ?f`Nv0p6rImC>4Fin zi|oac!})AJq*@lMSinoL;pY!i55(7Cliac{wlPle9s6{gFnuoZ`! zLUc=1a~78uh%Oj7rrtj$Ir&!JlXr_+>|3K(9@R11bZyXBdkw*=Pj25_yDvVZ&ey=; z?&np%M;i32H;76;pBv+*uS;7U9io?a!s$`U5;5+jMPKjNXZqr*ZD&~)){FU$)CHA#FW2O0WKTM*WTkBJ zXj9aQp`T}72!&HP9%wez!Yz4V^B{R6Dt6ah|k2vTSpE`6nt(|pGI@@%&@&0hvLJdA%goc65`}>l_|B>5N;04rt z%WZ5LWB*i%eH<>VZRl`yeQ{^I?wcR33G3R9&QTRo=RT-^wjuM`p-z#G!5c^9mPorK zmWG^Qu?UaRo+QTVvkfzo7AMQ^=nQ{oJO4=I>`d>^_M_`__upk3#0|S05u1LBUTo#B zcX69U+{UQ_-%SoWv?qO`tS3D=5pc)N^ZO`zo%B?a`x|j8XlLy8aiZ+Px1X{K`37*YT7s5IW^a zrOTL)&KCCYqR-mn;Wm@^Wms<&V~qS5`XEMAbNU@nQJ=eeuUfrK|F=lVi$6=`XBJ1t zylh$2*s8nw?Ak^3t@jS=AKjSnJVpS@y&3DZ93Gn+{B|ro@Sxv3*>)Mzcgxr3j{Em@ zRWwDG4jooMb-(@p(e;&KQLx>*bPGx=tw>9Eiiil3D&5`PIY>$)AxMYPp>z-3Dbn4| zFbu;0!_1s{-}gKFd}n`q|KWm*A8^g8d)@0^>nSztY%8gD|9<%43vWL9Y6oG*PGcvg zkHp@NE6O?Oo9FF%K6t%@jR3o0-mBf1^yJ;P_Ib zlKe+E4htK>JSL!HXh;B=F2$<#+RI;FxK%IuG~Y$czEztZ010@p3-oY&8N@wZoo*kt zvTW&`&`A1&(pujlR}mBHG->^%Ue89{vAp^RPptQfw{dMalB^zmMjQ)p6Q{n_*5<-0oJAb_i7s?+Q+#?~E;Uf#yf%M}rRE~5)*WaQ+DJ+nA^#F9%|4co zD95v9AcZ;cs6xB-4jOKT4wQVzXif8UPodMD(>26XmbA+#>7=zx?fMT zjuFhNgt9E_dOqFHr%$+whpzCpi(b3auamWS1h9krZ(Na*~BUC0+Byd(avT>4-6 zb(_u=yaw{PG)3zEk?-cKk2f*-eG5(+Vb}F5n8u5=-DF@R;QxeqAi4zyf8N~0sHQwB z*5LQ2AitjC$dI;Im{hwrJo~r`)UvyMGYp{c!uud#Y02f0Yh_3DZ+apv|59Ylng!? z8;e*zX7`gW;dtvxeC66I`%9j)W!QrpwEXV6GUr}$3SdGlX4v`-ir>UW#i3ch^Z^du zoHud4^RmpxQv6UDLXTsI3q{KI@fQh4{Ry<0eJoUP>~;9@`2h_L&LIDvEb&BrJWOqU zi+JyX-_MB_XMCh~`?f;x*3 zFPmo-of&;&>k2sH_FJ_lJPp74LrAD4{I#}o9d%O6R4Rrw7rg1t@efuUwTUc+fW#m^ICR0ikxPK8U{+pqd49B3*4FkrD0g1d;ll?pd?IvPe-!oT zlK`#dTPcP=W-lot|1>^Nd^TF~bnQ6RH?OY34I-g_0%gUt<3YtwjnvsC#OvjMZ5JFUIy6xp1|$&8rn1ClvFvbg4MXxD)EBLp2=()*tC= zQ(R3+FYCt&vMW=NG(A|5(j+RaG1fCgUq@V^#=(?-XqNlKB_BBVQ^WSdy;rQ~*N)+l z%baoHN|}$|%37ieA9gY$MH(9^71b#fbC>`bb|Lfe8@rUw#6`1YS_XyJri#8wIFm*D z#6hw{0aI2WUYjqEl1R(&m3SsKTIlKPOhwF5?(WwO_(}vUvh_@|MzSbobT>}ECLy_h z1wI-(9~8^`ySMqT6!1^kCIBaRgB^i`atOr6L24y;m)H}}i>+vJikEbu*OOaS1A!Yj zhv94vg%^JYAFfHf@onqRpy}7mIPvMk&$WFWhx@KZX^2k6x#EVdct%C+(_TeUg=0ls zzeKb{vlNKm06Ugd`K{V3$~Ua`6#ZmyQ_Y2d#<`=jyj&^#GY1k3h~Zrs zrBQB9RWm2sg`LE zB@wH{jEIk7$npHsNo$yNG{_RS7dBuaul3bx>^X1#2kKaESK9bQP5ExKj-glFzgcZ& zKYn(faII^|ISGNg9DOK;IVUblZ1Admh*L)o6YcywZAF}-;ywi{{@2S zq6dh;r#-mMMTQ32mfl-GtOs~U0>y_6qD#xA8F5(5DVx$4W%>nX9Ba)R*t$BHvy7_V z^#_u1jS(=)JoQi$&vVp9oV4wW6VMJl($A~s;L?2lMywFYOz;^GJD`(MIqOwQQKJj{ zlLq?>$2oAu*$84j=?wa7jdW6S-}=}3`D(={?L~S5`q`0)hneFC5&n~V9`clm1(ZzK zF2Bsq={pBfc7*rRx6n*^IDZ7cmCiz0N5RUO=7Pw2;BVpQiI~!BZ6)(hIu1Da%haRm z2f|2SE}I|It2hdi9@xFwMA{eL8$LxWRNTUICsweV7HU;GA`bE)v)Ya+U9YUmUT?Pm=7@U%URP&-`*$od3pV6vOMQt25H@-sZ3Sg zZ~1x2C7kjP-!sq)b5s2J`b6*i>`^qP-a8kP&bsej)Wsq-mmISZcMMPFN??sz9JL(A zxKA3^47}ybZ94umVrmvNtgDig#X=(pje2yZO?w4}~W|ycA z4ruxd3u$O2*U}V|FXzovw;VhuQmiG+>E&DdVb|!;*&M;HvwC^)rAIP)WRkN4eJ6@j z#c|uIf3wkauk(H3IkK{4L?J{RK@k9n{#SKT{Aa%NAJs*`MytQiBuOI#1akvIS0b1? zrc54Q?pyRotJAU*23^S;YMFfU=BOqp{#-KIQF`tZlbFQ+hQie7p&GC6q&Y92Kt{H6 zPqEU+9f1#^;kx+Spv16^7Czi1(2MlDtgSrDAUW6(K7N~U%5N5!;@YDJyI<~KW4M{TyZ9%25L91(U71y$wQu>hZDAfg={yzJU&voS(9@Kabfq@JIHct_tZPlTz)@C^%~svBK1Wf ze#B<^XuI+P zU50cUouv+bPFhqC_(xZm$r4Yi2+@v3Wzv6$}arfqi^!{qf)JLof%zDW8A9Ji%pIswNPnr1RUfBRnd`Ex~(HRY7yi_=* z>+454oHcj~ewVZ-(v$PTh3<;0M@1JLCvJV1BQuYP4yA)WkJRUSW@<1NL2{Pocl{?D zDl%2s(3INbkma^8OYGA&`_bGTDYZSM=pWa3HkUpSw-`~=#{T2IgG&B>>7B~dk%$?K zo^_9rqrK-`Q(D@QKBQ!?C%3B=IU^g@2s)ZX=I8%3*+}LJ=Bi^3n9BNxy^rndQ+SDv zowq3wCbjL8O|XE8@8P!=>a{D@U3$}JUf^|#=K}WhLg%ouSscd~wP&Du9CbEbuf}~Z z(dScwQS-klOlmI-y`c!n8z5tIX~ccLke4*n(0M2O7%|ZwOF6YF`9{88h9EpQTP*%5 zwKk$7)kF#wM-Oj6-r2-qfmYPvXPukrSbOdUB61b}P!)k{htJ#9zgEXN_y->yZ1oN}#!~FHJl%fUu~WXx`i^5B`h?WoZyzF& z?#TlQ>vS1Mn#4Y3pW>QM6m+w44Nkh;4SqAG@wSgwqX_$SiL-}e*LPyd4+Ul)Ck6Il zw-1%Mb?D>=#loNea^@TCR>sY)_F+JC&Y_q>E-{w%{fa#V0Nm7P*C zv7Qtp)9Ptg{W$RreZrfY1rtMnt@aXf_D1-ZE5@wJhI5U&y7;hQRioNrd-XQRc-EIp z{J?#(I1ODKJ*jP1xQ^$Wavivjxg%e>2Lvp~o5E+0gtbvxv7KPrP?P4k_pu=>K&4df z^FtO$+`G0lUh@`%neN$Y$3b@zj>Nm*Fy_s^fv_Tu&((YAf9{uOe+?lDc%vuNh=+Uu zsttxTX=5+X5x;T&fGbz!K+seyG2wt6q8*01{U9znA-6ZZ7UEPQRW;cx8;#ZRiW5k; z44dfxd>gc0rCUhlj0mP)r*LVcj>2S98<|b}F>iOm-^4bea;a^NlrEjt)UozNcN2Eu z$Z^rq+{xw1+V+!}qR&M<$|;%ri5#P0;)yeZ)9)y#$Da3XCD(Dq>|~<%s4CC{|FVh{ zc?;TWii)<~%S-Y~>^dH7T=ZK)jMd(rFSOp$M&W!aoITUjc}`=kuB}5-MBps!8y~6u z_WCZn-w2Fz4bbm;u_V8Jdu{&s824kK0 znQCpcTwwgATDqUK9YrYghV?awi2?@4(SPG{Nf26BkyWv&t)~A~+!id~EnluINodc$ zm(IM)6Z>=0oe_s*8QJkx3r0f(l`CceID3aW#|?xboP0&XmYkYMZvyRp@2&5wq_w(k zNP(24(5UM~wyb(V`$yp1*Z1h_Bj}UEY44>aq%61S(d8mb8*4kW&m}|m%`=QU#CjWG z&4orY&04W}r6=(1vg4f&EmmGzjlVM>={Y|q5p^6cf_bx;UE_20bN#icTulTU20-Qs z>M6^8_OtVa!2Ko{HgOD5A}wu2+K5W?HgN8QnCoRbVAVkgbJGAg*Eq-Al%?mq(P{f6 z@>O%CUIAqctc;mimAsDCW*Jmm^~^1im5(3}%hIuz8N>NyJ+!_YS*rtrR&a+1QO80d zIy%o)b`Ty<3G{FS$^pAiVIX${XFn8xk1XRcJ_HS4T(wnl>c;})mP=L zi(NjXSeoR)#bNU9HYP+DiAQ#hpj$;<07`}6H{~$ZzoEltn*TndM`wx&50vcv3{&Un zU#gHBa>Ug|a*+7;#UU+xCfY4vv=WG<^IB;DTL_mN$h1}OlbNZ$e2DW=`PJpIF_z`q zTHdXzw74ab18K!C9~MN=O>^V^#RaMS!(?9S%(1at+1*Y?d&3E&sK&$za5z4+)K6y` zsQXo{3B5VI7Aj|^YmO`#P&*G|D8O%AKL@K622niIt*B-IYOgUdYsc2t*F&4$QNr=z z9L#54Z)eli=T&eJAxZYyg>hjn&0`j=-&f8=DIPA%l7QnOSR(ZA7esvV6g+;k3=72; z6;ulQe-WzYx|C+uuf^y-e~r<&d~qd?nhOJiR{dW}LV%lFcYX*8zoQeFBq!0sLlaL%CLyfm4~B&&hnQ`G zcS>G$;uk*4mkqR5Ykd^>f@rW|OqKtV%qY-)PA7`r4bw2uHMo1$i26gH;O z_j4|W4v>I=fLIG57IdpHedLuXHPqRsfM-r%PQY<@#u|Ftb}To3@D3gSk`2HBnM0p4 z$GG?CmO@(_O$7-#jzDr=IbKSamOhwmD_1u)Q5#Ojlh)6(thV%w4z5?}p67R}QTTPi zX!}C`VQ3gfyy#9Dl>v9oY}N6iSSxhp*{yT^jrJ1!Ai$>qb$v}m6#3v;Q1d%UM)SMi zH}iF+Q~@4};@Re-DI7#I2E~n-Kls-RJMkQ|9T22ghVo+0=e}RU@t8`!6M6h77+#FC zRH=?hFXeG8+xNqD=X+zXsI@B&T6S~|N2qK`aavO)OAz#i3LZUTf22E>;~~+f#91== zHkSN%gi5q(T?zrQUl><$M_ABhgu0j_XM#q+cl%c{Jz9-I zb?8Z=zUy7@lWi@as2HXFyLT^*Q-lj=kNEF*HT?ZRu$!Cn4OZhEa_xGWR`%Oj?<$via21^3r@usce?H&D-2RKSftDT)|*w`5q55u3S zHjiEHB+W2&;d30f70n*G`T4y~`HpeI1?8?xg08h6#=SfI{xNB)pvILR!ox>-3{Y3_ zrY&+^LiXS@UCi4x)V~0B7~vy)Q{mZ+61JuVzAIaR#`@}|t~DP+jV>7{p~o);awpLz zO$sRG`DNnfWi6V6;L~AK!Ro+s)c8@r^;;2k%pqmDg~s%{9$Rpw*t;AZmJCl2;#$S~B3P7Dra@$%cWxr5K-Ys9Ru|(ANEP|KgF|#9-Iwdv z^q%O42+{o9iD{Zf3f;=p-d;ko+)vUx!*;@)=Ey%wHC;eBvQ@@z#f0Hx83XQfkuN&k zDKP~-Myc3aREtYUIKv#%bi96-90T8@UGek#(~nSmO#`7^^~a=9+0H73-a@!fV|#P` zAJ_*}yS}VlaMf||uJ@(=u+Uz3KSxByJ+RKm%4r^Gn##&TfF-&1!9?xDF^7{*A_107 z{ZYVpCG(>FY-pD_IXO^J!J{k z5fv_CE0jO}!afXeiBnC95HHc3h#)K$L7#nJvHi_g4;6n;sYxaNV6<$)uYoTFI)3Wn z!o&|;D$p77J7z`)6n}kFt45r}r^bRTW*`^wQ_#;zbLWH_Zj4ihx={zg$oH?c8XmLb zn$tGH5$x1*=vnT**lHCjbDN3qMXas8*mWsI~ zr(NIe9Mxi0A;d}rTvi<=d%^g_OxDy0?vov6+SoXIQEh7o6zXJ*S(o8ZCXdZWUJW*P zz&haP?Pw)wgQyfdr_s*Rhnh_9U{sgRm0Nh@eBJ1iDZoFq&(zt`@^G{{6)S5Qd}7pe zSq8PjjC@c1gHm^oDs=?s$L35iMT5>29085^j22opuMF4)TNd@6cYZu^Uu;up8v4+j z`U0cq@a|W;>Cp?Jd%?b)Z0~1P#Z4miv_;FKV2sAbtD&80keG8#7;5Ff&y3;mv|%t! zi>2dx&;kWkmcU9CDDe%)jZ#i}v?S*1g9o2HF%>dB+4%^nrpED%`B&`^iAB zFSSv1gln#H@nX^5urtZU4fS2U2{!wUK#*23_Faut3eBIm$1#_hVdXE@=T8ns4cd{3 zo{7u^T134ZPr+39YdERbZ_}TbeNAJt(V0(^@4d9Z^HWLX=gt;Qui-bKpb@al7E&!P z=>pz2xN{p^T(&2Fcdg3L_0E~) zb|ukK))_%qk&98VJl*PB$%P=TMw^@p{a6$RttEPT%};U!gR4m?hj9_@PtMF{wR&Dn zIMBNgqnh&@41Bkn;NCJfK*%p1eU1FjMbLe_;M4k{ofsI-`Pb$*Dv$elAX*5unv} zfOHloo=)VHNx%uXj+ljwk+>)ajX zl5|_u*A7C46$VH4g-d0g;&>iJ-`q|SHazEGJCxixo!Ho!GrcF9>Hz)&0~FcGFHkD~ z3j*-D6gzjHIU(nz$#lu!i2cUIMDc@Ax4UTeU?g>DJTdVw5q8LXa2knOJoA}9R`X@G z2-g@U`n^4pisNqw9gi^pAz`RlUh?UaYKOKBb8pMo^z|T{j6FI$&2g- zN3vCi4Ubk{}{Vm&tSIFJxZV5^2H!`Lcx!531 z?XX5F|Fc7hW~tpus^>cFu&&(x8C5*HJnkWVyxDuA3;LvJ4%}thDm0OM2n`HE;md8N zlF9ADYlD&icLhU*K0Ljc*d+yK^y0jDwVFc;VVB2`#f<;y|5pB8XYjY>Uj=!t0#S8= z%xJ3MT~V~cuoNZ_`$Gr&iKKuuI|+}Ov3Fe*zB!`7fyqK{ahL| zOquTcHEABj6;L0H@&s0CSWE4anX#oBCK+nqxK@!vvtzF{a=R~zSWvk>V$M}7+Q)CC zRuqr3;ajzP3v=q;cP05Dwk}~XwPYC=-H&eWt2)(W^R?dzP3(JF2QWD|mqF~61&De5 zo$E#u=+i0X=0xy%ah#3EFq9C3Ys%G$dn^UL|35FEHzOrs@3Skx#7?*){G*DCi`k$S zui)qW`?Tk6v-Z4Km*n2=pEg#)!8ZnfP?RWB!;T@65jo`$w{^9bp5_%>pkwT6^?(#Aekr;fKVH~ zrSb`hX_p)djD~II^!dk$scq;Uw0qYK%nP;1$oKnelw+*}1hIdJGeX_xi_%=!u*Ku% zv)0`{PqEXVo~7y@@bqE+;8xb2Kn_g#dED0uNZpX`M5FHYeP91$GsAzk*>>Dtq|Lu+ zLtG$#34HO0lL9@AVkwm$_6^w)+eF>T>EmG1(9o#;xMtltM`Ge57?ri<#L|Ej zr>MCLEbyHue`gUNUw*)$g@CE<>c)lP%14S(B)w7XI?&#`G!3OLSL1qZQut?LXMSbD z)V{V*&F|zXJK~1ID5VNpNLEdgge1g8Gl5ncidI4KOQn#D$FsT2e-| z%+NOKz0^;MW*N8X-;sHn>Qj|rAl<5Jahpd1$Wih9x#t!|JGJnR2DXPKN$ z|3h@Dm+J!5St@ntq7A{f{wO7nJw1IQ0?*dQZF+^QsJ^RZp2f76>KXKJ&SMS@Yj4{f zFW=9@@pWhnKXQv)_r`BZ@BQjjhoG)Pi>R*Bnm;WWL zenk)c#P6Gtyh}SnImRY}5HwkApCz~|XBOo5`J1|FSv9iJ0h#~e2Dz7h13PlT2>xaC z8?gLK>=m+EOH9_q72FqVXnqQmBdKZH(mN-S0MV_q@k z6~-tQo0@xoW<18^WT;wq34as^iT+$2-&l$pzn-a*@ruu@my1_Vl@}`U)2s>odVAc0 zk;?`-jj!EF)_0PUzR3ji>pu)_>`4FK5e$-*3%LmGsL=c4?P>H-P*!#@Vd(yHC&~ZE zLg~hdCnk<-XQK!!;PxBjRd>8Bik}b9u5E;u$BJAK1yr(UN5%K>q;a&}$_I`^2_?c0z^* zTu{9Tnr^}}{4Ihhst(px&wY_S#}wLcr*jlsYu4!!fe#3dB$%?XkPk$ylt2B$wwqd+ zqu%^Zj#Q5q-Pb9*^1tL9D4xA@=b+=jLgrqJ>rarn|Gyed8w6b}f^I81c zB^T;iHucvyp6@7J^qR*pJ+r%ham{$STWXGI)WL{g6*XZDFzHqFL6HN&JY^gZxQ!sgYQ_4hgF$l;GsvUiS$y8 z0>V)ywb5tiVYst$-)U~@oPlzjlpM{~n1+36d0;fn<8*Rv6^SvGTDiKhZq?DQy!n3H zOm)>M{L^?6dMOX4(ETMq>lcXqpx9Fomh0KFD$pcL*B&jbdr-D;aus0Q79B18%SpX*R4y2GI?1w-~3$r z!gQIp^stGOh-|bthyFf4xJf^;#H24*&_lP@vTcn*0l9Z#>#nGDm#XS&~1&a+Z*cg^*so-HM_BM>`kwM7d~ncwnRnP z%bz2iUqU`QRqynkev_+?3zM0fBK}Q;mTc zAl<*=FMf0gx+T97Qyd1aoG}vKFQ|0`t{&*;eetFKRm>aS^U%@SB|a?kjh(xHs0cM5 zLpWyk*GOJLK8E+-F-a{+^dFjY0A4Y^ZYc=!OqNp0J2>@HqECE}m9gzFdu!L9VHz^> z`#1RmxdRv1Y$?*300FpYX}WJYEB-D5J1TwPgYF-+9nj`E7JhQ2`|pPO$7FvrRCfBv zZrTCnZ{3zX4mPoOr_GZx&%jv3PaT&)714J!r#` zf7xh|iwA%3$Dy$}7x5{a@su^OV~s^}RkDt}e|uT+`h4&sULdVuP+|hTqd2WwOz;k!Gkuf6fn z%HhHeGu5JYY@0A&0`3)7$ca_D=(-yyqP_I5uz>DB>^#GhWN!#$;fPAcQAf3KA z?M`__$`dDp_lrRsLt&qBB=#K#cEk)t$BED1vGYKoMfnl^OHfsMpqF zfY3X?pksJIr^%zb3<}YDR8~dT9~ltnQiaG>t_L~e(+`|47Gs1gzGWS=xxcL}^< zAVfHvPjv|}rsw1Mxpuy^@S~%ll+rwhZB&TXCUp||1@n!<2=5AT2&?)#71iN@+T(O3K+W(G6 zZpHfJ-yaMSyaK=A|Ia9YJ1X?)+Ncm04ezu=qh38V>bG_8yNsXn7Z+O!mjMrI*Losn zVpcMYyT|$imd@^nPuM+j#HfOgc}+rv3D|%jnIOOYK-imSC6>IsNJY(%>sFevt<@`o z^gWE(WaL$_k`At)g|yO;&G<|*u<~HEYzIKis>srPOo=NYL1OHiy zF?{K>iTy=2ag+!MC(4IIh>h4f7*nZLF!I?kk7~$}#Oinucbvf}6>C+ao+G&G$NQM_ zegSuSilImD^dHJ~%JIJr@8WcknWrnY!<7bS?SxzWz)z7aO6-%5{k`!xTi%{Sw(U}b z4J~UCgRN6q|K!%`#Q(u@Od@S43|{CNMa+rVi54uR4&_Q+(k7TdIp)TwhXlzaJ%2V4 zRaXANQ!uKX z?0FG|ACI7QJB=sd{VZ^F<%xbPP5*772gcfXaX!lIQ=Dpff zsP|1i3Zk9#iW7I*rLWNuJ@L(yLlL(G5i&Y=_eHm$z;b4e@4}I_;VQViCJ}UER*d%p zrqhc{Y=I4!KzQ!>CtH#`IlJa^j$!(mhCe3 zE$sVUV=AE^Hmy;0>j~YCtnV3t#A`P zmc=tt@gIpk_TZT_#euJRX?>aQv^ zr^d82`ZyHd_9xZ24eGymgFLADJ83B_F0Ptc+uv%F?KGDDM}bF&qg;o0lnqDu$aA!kNplCmAZYezaCQcX9IIUL`)k!sx5u`nq{Xv+pHo-jF9~ zf8=D2CvVgdT52-EWSD_q>OH+h78oN;L)Fdf$bYR&yzL_jc~2cRqQ5&w>Vw+aMY!yr zj)Q-&vcIW6zHvaUnFr0;7;iVgfb3C@_jNk z9jg4exV~ZQEnEaD$Ya~>nsO8F6~bFMQ?Ki^-fteh8HG&c{sKUQ*No{kB=1(%)=InN zlv7GO`cx;m42+6Gpj_$cR7C^0zmcK28^|VtJEnx#d@6deP^s$dJ5F`7LJgSUgzLNZ zYXdC~k31@ZE{$Q-+y<0prwZbBATv^`^D)O$?m*&?ABK1i%`k;fs#U#|*@I`W^~`!Q z>H4tOGu=S(P>IW6vso5>+HgoLQ{l2 zAye?{#yM8Hq?kLIUjF{MlT2pjanG>sXt3X9$UzAUDmBv*)BJ-EMt<-`8Z#IijQpIk zRs6;4m00OV@$p2FQ?D|hd%}D)6F+Puf97^+>T^cMcg{N@ljziS?`>y(Tc93epy;kC z(l`pH20IOV@}b6|z$C9!HLlbBdc57~^-QW1ujB>ac%!>{y#F?Z^q#-9(yQBV*V7JL3nz=) zv`SLPQ+W3pqzC!K>8KX=$-NkvG~;>pPe>2oP@Yhfff^R_nv(%BHi?o;W4iML5UHY; zbhUprk?ej@?JX7(t@XB9m&yI8)DF%5RsfWCdUPjucb}>#v-T~W`Cb}xlOIwhEY*iYH z;?53LnZzH8L4Z(V1==JGf~sgJPyCxyev~Q%#PkIu$1FrE4Hr$tiY_+36u>*t@8Dpw zYr1e0QGIlUCR{YmAvZ{yoG(Xm-p$sJUioj>fVRFXNJYK*1-s|$378GOPQJ}=vz0lR z)e-X3V#-x%yc=Knhz%szqsw8h^wGRe5V#tuH@>%JdkcomxFBb1kb_wxA!Ah7s#K&DnsLiTgaLq~aA7W@R+%@m7AW$zx zoqYNqQez!0wmHEB+c@9L>T65Ybd(j3Nmp1SUQQn=-YL_mWn6Ep`&Y}~uT%D{_hC1r ziEDI$9oZ<)=Q)5ycrM;2dT2vBfz4HbOt)I^b?V^Vke*=#Vut`Y(_N{pL3$_WFK-)? z!+4!9Qzm8p(B^k}Z~(Zp+2Oj?elMyqs>7#i@^;xA1^>4CiRq?t;+>M-$w)9v;b?NI zVY=ABmEIrNc>Q(=V0miQCH?qD?oRx!kdNr?eR99596sCQWb4){qD_CCydGH4{p(nl z4tKH)TapuQK1dzMUp`%)pFBHS`F95Rw-k71uWuT?(rgOlNV@|I;T64QOu%a}AXiVa zBzShg+5=cqSTs0Ci zs24zr5NXcupDpbgX;Gy>Ry$!ZdY9L%ds_;$*|_|@@rilon3V&ux;>S1$6VM__Cz=^0`ctv!L$`85b9A!pbV;Alz8%7fGe}N~*V4!9BHjB# zA8Zos88v#$C0`$7TDh%VDZK6%Ua-`S$FeISUo4MEIQg#V>vzDsv|-!PuJHRTg)whc zWc@}~l;C2Upw^(TR_B*_D4{|;lz*N&UoLvg)9CBg?=&ZIRyxuVeC*#QNlwCe89O;r zPc{dqNflH(6EhBewtOz1Gm{=nc*9S>86acy)trmUKLWjJxF@=h1Q89BBqQusRn+^(I|GTKjMI$)#I4du95XsCAhgP~FB=@%!GxMX>@ryLW_N;G$`9u47PtP~c z*P`LD&G{GpR{>Mh9DI+7yU40VJ0PM)?NP06m^wPlHE)Ndr&y~x02oP3JLenWa`*C# zYc)8_Q<6Tk%9uToaToIs^nkJYdZCe#_M02DZmkjG(F%t!b5DxqR?OzENLQEM{Stat z(M+bHixXfE8bI=zM!n0}+*Ty~VaRR2NG97o?rmilx+b&gieyA0L0j!0b+S9LCmyaf zCgEbWmO8q7k|NofF?)AuiVqQt^z>+1;CcIs8(iwZZFVfTJT0gAmhQ8gix{dOp>FEliDTJy-ewu%NfX$DWu}6NvL^6zr9c5@3&*&iK$-~H^ShO!q3-UkB#PW)bVSz zhD-vnU7Ztx0Qo__G|jE@*PECm(TkCa9X}LRDz9q?M*orH9(o1Aa?~G3W5}2(8u~ZGwYadTMTEaZB_my#nAV@R(^WMmg%w4lZNT zn?ENHPKzH5n&8sRnX_&@H<84V3;0**e_zY~;EwxWMgIReW|oh0tchnvr+$CHUg{sTvDUXzi{t*AkBI(4Ryxut%39MoSfQs4hv6; z`c_QhxE8&(aZi-2bddPj9V*xmfd7fo5gi#JCi+7iFh=wry68(TGZ^p`%!n898^lT; zqB81KHz`kOg3bL_V%Hd|X$G)hFxZj~&aj=wPI2|SO@qY|($D|md z9cN9JJ5tTJPPT19Vl13kR4WBbhjrWj{3V}fZKeDagnh4*?dKhNJn-%huW@e#izvbO zoi0y5ch!!D*NaE0QD3hEu0ZPp#A4sR7soM)rkwS)N^p&Ff8?#w>I{lJ{t<_hfEUuq z0*3_?>d~y-L%^9%!cW(iEm~UTr|m2d7!)|H`0uN)sRU2dV^#=?M`+y<2 zL4ny-?^*Cy{o?6J!8*ENY8n9uB-4h1LNSv$`2;W7dUuVtW+i>0N~sHx8RSZ~02=e% zs1ktbwgwS61mQl(L}$6PW;Ya)>4FcK&K&gkLiXLG zuObT@-2;zoLNIHLQ~71JI);hz>skzCn;EIL4mkle(dA8M7?nokxKzIwND;yErIzI%O z7>%tWx){kfm%V)*i%-4ZLuOSK9sRSNI}*=Y;0?V(Bc84Uxt}Qzi+ijET}b+vw&LV^ zudk0_#U>dNZioltd?AE#@NbkHJUqiE_D@$bdJrCppL~d)cprN4D+)xyCtS@mDH*Q< zHsom6?1rHoNVfe9U?`bv#DL;`tAx|TWZTELZlCE$_X2KYTO0lGj%YVr%pJAwb>bT4 z*jCn_FD<8F_&!?AvkJBC>mCa4spYtFl_uM!l@g2gwPpZqD>@Z_DqnCn=UDI+XVv)d zEu6F)z4Chh66-|k^$P-UmKs+^?N8W}?XLYBkDnT%w41-vz>}omaI)@CV}eDu{zZ|v zst-4FQhDLobn%QD2U_SuD}(LrR(zJBfb1BW5g@a-W$20da7?`<7>f zz9o%wMxDp^<*}4plC#L3l(TROR%j8&aR0BWOwGy>kk;ojFDsGIm5mfvr_Gez)39&( z;+~^S2gnGTmDA^stChQvkB7{dVX@k@MiK3{75~7oWo37Qces;g*4#3?}UJ#wC zkMJ5-tcBU#Mw8ETvnd?m?c_fUYk|kQ1l7;VYo#F)|IBw5Qt=S~9k`-9RUI})ZYshQ z)akQvQxw(xoogw>0Ss2ku;lAw?yH2gZ%*(o&h1FBVTC-DuYJhGPy7m9QEZDmg93HV5@|2q?xT!*y&!QzEMP^BH_Xm-|(;BA1D1?b(_XK z3GYhFtDMYU*odd>=vE5udpwVrcyV(tw77`V4Q+FSi=LkK9qLWXCH^4TL6GqSp!u8V zBQCqGJmH-(eituwD8;2i!xacub-8{v@W9+cOo$#}?Cq#Lpp{W2d^t} z7iug*ki<7Dz(`YsLz_d-&X7mK^>qn1`}ovY@$9D`iIfQ)keVvI>9dhrXXlaN5y(Mi z)xe^vKoiuP^X+Xr3LAMk)h&Uw!9FEul#-0T8iNQn+Ek#VVew^>OB9%UV)AhFH)ZV- ztFticViz!)^B^w!=nY^}8U-fZ;!{I!@rj(?Vj9&7kL~= z7+%MXq?i+qOeOw5Y`texlU>&}3ZfLLBE5sz<|6xR{%bE(`AGi> zXFu6TP^)8_V&>(o>@2}CH*i@rbh&J8OYt!%)SvGmP*U+`f#S& za1(|~Hpp1ob2$4eF>m8E5E$R_{U#aHnOUWg&4p6+z{wN4?CNvib!=Mf-`(rRKxAS` z3WXe?Pw08G!*2PyN0^-Xsvz^7umxT=n&K`@)i5m?b0x{Lf{A#tI%XVO$D|ezw`HPXk zADFa(8ITsE#3LeJI6SXzpwWG)<6W6pRN%&xn7~Uj1|J$ySZpPq&ZJLTD;FpSQhz-3 zr?<0tc2<@C{sB4@<^J`sfbYI4Wb67Y% z?Dvgr>=p_(w$v3x$;dA^8+s4;GimyV?aNQvWN*4RP}>=M+SHiC!1OTN961>&b2}%u zpH1-n-@5wT+}Uv-+9ZVoCUw}Z>&;pl#o?YL0expvqrY9jnnw~h-D_4R``^D|aUOpT ztgY)LBwi3A`7LWeHrD>-a=3DXW^Iz5NzBZ|QT4&{Ex|#dXwK!5osqjz;@yPj=YNk! zHa5TU$Pb0ymyZrv^8j@|7i4~D{+Obmz)k_ZvL&5G-jbJ%Ryhf$$i!G{y-|4zcet?K zRvEMYhn;KpRoJZgU(CgSv3pJZjhJu>Ya2QKNNO1I&b>F6zwv7(pe{7_oQPL^7ZW0| zLXmc0xT5}|P1Q=ZV_zzKqM>6UHwN3_mA{)2P%g*Ar>U`t+Pm8zynIx|OOs84kYpl> zEeV+9XPa{a0p--#19-lA-Z*h0D<~ZHg7auV1VE^J^KWiw-FNApyD|*dDxoAWGA?h- zG@}R%#I2I$CXyt+WLMcK>7E4Z{1}9RAHZY-BDJ+Q(701%eivC&9nFQowPTX?sEgNi zbXa~#lq6nU?OZFInskbpn1ZQSDCEoxg1F_yVq`He8HW=I))qG`rpGT@aFuv2A!e0- z`F#qLS4F(tlf(?o-d@(`Xa{Rypr5vD5^95xI(PyVH~IC(-MiN%_J>TD#z=H=W|s&~ zk+FC`61{J<)Y06UE;m_~~I@CfSYC_sbPE9R=U79I^Pmx;IJb^ul z`4~v{<4zO0L5fermjKYSHYH{D8O=FGbC2#1gN*wT4i|pDS&J~IwYM2n)6R6@XugQ$ zOYIM?1Pb2R3Ij~e(AF)AyHLt{}`MO{c^)~&5x_hjPMq0k!>T$su9_9Rfu z38q>_Jl*Rm(h}W=47HTpiI-1Qb5htn+Oe8|4B^crJBKL4k0|XB@vz^}kdiJ!#F}AT zK_sQ*bbY9KLfTC>;)=~#1J@KS`~G(Dhd#Z(HZ@uFw@S6bFPf>(xw-n|0u6l2Ufrbm zo1y<>u4@@sFo5|*B%lW3%{1eyl^YwDaI@jOi@cz3kK7e&wPUKL){nBE|KNge^tWJ& zB=%-1pSLdXk31&xTpQy(g+E+9&(4R*aZt6e-{oLW!yDsHSq7FF^hxd3;FF}ev{-n? z^3hlTAi9w@@|rk$&taaQ7~|2@8F|BnG|FS&p45U%yZl7Mv>P_9QzcGL z(AP~@;u$1j=HJxrEiP`&d_(0)pQnF7;_seDVWjt_m1?1am_U<$HLd}oLAhaG0Af}< ztJ~inyre<*tZ-M+N@DV8^Tbszrl#X!L)~#jya@0q9~T8GGCl?LkY%v&Z;;SFtXZ^=Cyg>F zA~O{T`OD@IOk}l@22BsuCB7H~Vl_y6Y78^eFU486Tv3?i7s=%rUKMK|gU;h3e@}j$ zp5AX%tSe5|QcA9xsy$I9cB|u@Z}bUguWBM?Gw9Fp-jS+f*}g|P;=&0KN?- zQ?xbIoqv4|k6*&`Fc`R&%as@TBykteDJgOK`5EQ&`#;ey7IIycTMWHd{MkUWXLNmS z^(;GrW;rm=t-kL$L{@xMiu2*7Z2B10w7r+w_luogoS0gKxhLHj#v4|dnizrM@q>|~l zRVbdkz1_jq&3i9NSD%s3zqYQ+->qN?snQR`p<@|2G@>8Q$)MjC1Z`;5>7&1X^+`Ta z|InfWl)P(FlFmJukqS@S>U)-!DS+|hNeFx$U+Wtr?53V;{AZ?JaMI2iAYS={_oVVwV>}Zt*O78d8S^7)IAvtwlWnA4U&G`S^6_ zIdvCdmiCu+upv-pu%Ds}I`7by$B3+TA#3j-XE5jvS)Ok0kSV&8vD7i%n)|OjMq|2# zCv)7dNrLxe(yBTeZCnyzTh>`Wn6e!Z`Vty;-Li(&!#o*(As_0`&%j`U(j5AX#9%Z$Kw+Q9Xz-yJe_UMakJ8sq0@Y6IpdoakCmc_$MeJKuvMm{`l) zx8$JnXXJa}^6TjMM3GVzK<<^bt>Rd5&Y=f%sKpO3$X$-h!@;VOc+C@oj9-n7{Z4FXOxIEq?kg4sVVX^%Q^_+Js25T$Ec3$0Ph(4x%2iEUURs{gsuD zI}%AmPrfy;fx8E0yUKR@dS@}5emIK$)#UE z2iw@!EK@ht8xhass%^lB$s%^Y)$EIx!yOK#;vF2{OsRkGyZ2@|M;W00_I?fW{!O;X zxHK$U5VWflqj0RmLB$d8DjRx)4ok;`1x*&Z z?3s`1$ZQ4P4_f)3lf(OO&XVw=J~@C0%gqz|v&*xCF%0e4`3&JRyaa_Zr!OM2J1ZNQ zZ`N1|y+rvA;Z11wL|z4zp^$ldM-dTvq8D^MZ-Vk<)DG1|V*SUmJ0bOA8NN2%ZSiG0 zO*44`3I+Sq00v~r6S8nMqr{Gh%POnCok@Emmz%-vp&SFx5RnjWh7cU&C_jFA8i9|* z4+OSkw09)Hin3WRbu-2758RDtXOO6z*wsoG`U0y@frgms5D_$82di)+=H_5ptP@G% zVngZ0?j+0JLR4eeogt1ECogu_lUJfyI>~TkGafsTCU6|JQTeE!pcz)LEojVy*(y+2K$@z=+xYeNh|zUdvzkef0~^GU8* z<^kx(yAN;5p^!sogmdTqf#Pbr#*c%?tzQB7NOw@ldZ8cRhD!b|R;j0)EK%*SxV_Tq zfYW@rG6^q1H!o+-tIYe$wkxhSdxRsNUB7xxdTY%p+g~{Qgr5QzdOw$) zvb3uJ?JU{eG)j4>yZio=&`y%P0dB`Eq#USbD>Dz$?d*73ef=g zlaC|Ts4Kk_28RFIkbRX?WsdOa?Ipajmq)cjr;k=YJ*5Sc8TeGjT0s=^X6W|B@=M7f ze`&aip(1x+x4LS)1WE2;{lvO-YF~{t4SGXp(@zTF-W%#?+KOXL`oW0p<*R_OLO%Bh zAVMF$@W1bvfJ=GE|dAL_Be+6yF<|9tk1+(nojeulfng~qqRo38 zVEE$sFVf5TWqbYN&uatuk?PVLZCz)Yj<@Y})H+Rs^)U9hH=jCg(heqDAt;kFYmN9}aBPCDSQA8{+dm4xMA zCyHWSU*G(;@TOeF(ljR{d4$K}?cQdl5!zLt7sDdhC+-tH~* zTD##*a?)?JXsr6aWH0NN89)toEK~2PbM_0w%4}?ZAhpQTrMyzL5%>W6J`* z0pv%E&@=q!AY##2A_b+4mOTFzl}nl8+Kk=@8iBkOB%0*_Az0%M-c`%dro5Vq~&*W(JPl5Zf=&KUuZExZ!0-I8s}f*DbO27 z9lb6kC5Q4ycJlB%DJqRR`MVY(ui_Tydht2ZSCPY4N_f96ELy19=j>X-1ugS2iVRd6 z7+BkO$>n9*P49-Qw6x6!95a~JR)={aA8rvCV9JPuFg7(Av_ezrz~MeI+2LNf=01Cr*ts7bv4}(tUv-~?Gbci%zSClJPmV=tBVda9x^?MO$+yR;b<$>;FR6_Wp%r_x4e+TGT|bi zkm*oH@%_h(jA*6dXw~%SG)>&sf%@;W3mNNny8rM&1hIc}7POCgU%Ls2e1>Wwj&LDP^2^xk-2^RrmFBjBy1A{V9;K{#X!8DLc+sBd6SKMq|~ zs?SvTKcOtYhFj#@YC^5(3qGv875IsHl}aF#?RwI<_tQ8s%gSX{-ks8n?UPq|xsUA~ zpEtMn>>q%D=}x*3uz#55fFbwb*Pz9)C>_8SLDLtp__MZC#Xff^tZ-ExG(1dQs15+H z!*>`CuUkQW8I*etEXE|!*28QKv?tGKteW*&_IkcTA6>FHBjxZ&bce}YUzjyh{_jeq z&FODHCLS==wl$pWtP-y~pF4;xh3)Yc5-q~JA(rzGLm(lMcJerMFWMM)^mY~Z42bGB5n!`^8}nn(jPpl4SM`ulL3jM`Pkz)}qeOU(=WvX^d7=@2g*-Y~BhO ziUEhszhEUte_VxRb-I;w#Zxt(1aD=MrjZlBAyE#k2&Dq%RHr9NLOBFsnqxdb!*!fr zCGM;2O_~ZAyWWap=cNOV&3a8$mlNsE28L)7H-B{W!eq2-S-{)(!8IKiV|+)dlA$YL zVv-QE@3@pFqYV}8BGnI55{4Mgp4~lv1U@R^wQEuBa=)Cx4^mX*7#_K1{qz@a^$f@@ z@VeI6fvV3#`-B=es6{amvGuqgeB{V(Gurc{{~>o2%ri{dVGDcuOCNMNV!U&B+ulLM zuMwah8Xc2GyZhy;ZTnnz2MYZSbwIM6$hi+8c*W!<-vIw3;njGG!+=X`OM^#Jn3f2l z`{BcJ{!W$Tp`!uNH}3}G$HP|BZbX=L-=$GQw^pm{WG#}iW{wd zjjE*pmrj1j18t(^=9YYHM0{IH3OlL1!;qH?bexU>It*vut=)VBvm2r@5xY*Kc*JW4 z$IpO8&;F=VjfT4>)BQ7tf(p2x&eYf||U3C~5+6Ii` zPPc3>R}Dp|a{LMgy50G|Ts^q3R5`lF##x|FJS?_+;@B-MJ+Ki^{uxCzIQhQV6c+*Z zzq^Q8&06c-IxDBfvtxk?%w~liy5tu%m5=nPsDPOu$4Zbm5LO^SEvroiSiN)r$Y3LG zCBd4C0j*F|t$B2ZMid-$#j-F*nm$7ZdURo)R~JQU#DhaW& z)P`hs_G2#+sX=RMBWBTKBMcVNDtwrb<{xuwoRt5J3w`=?^!r~-TkWHVJU?!7ID$J$ zb~lOYuZFW#yDQ!WX^Dj){*M=+LrY@EugV*=ThHG__rbJL3+xMDZwUgU7IURB*gfrr z*Ok+yh#39rY#S~fH1$6&ReAxlAx1;BZFCY67Sv{yF5P4{Upp&GI%Z2r^E_=N%?)-~ zVYPyPsOSP7f>oO*5uN)#oyuZN-_Aot2q|%)jlOxC9IeW*NVcYXZ`?rHEGqEyd+@#EJj-NswLSNwe;$^TT~^X$@p z#Y5{Ymlq7mJ@S!Qfn4dOLcwNLm%+QuBFJ2Al6tbM_WBr^PB}dJNqpm$nquo*3_0r&T7Y;(y$7_SkjFc$(}Wpy#uz$ z)2)>4odr*qYNzCo#W&q?qH$D=OQ$~b6(!wT7ZmetVpz<_r%4v?yB8OK4v{85z8g+< zwI3#z&;s-kgPI?ekoP9mE;p#x905_iCwXn^s_+m%yhi)qy%S<3A-DQtHL8ZHpkTIm z9&RS-frpNe|IWyhvtY! zmunXbInx0h>rxj*7J=}TG^TnZaE&U)$nx+v$0{zgukdzs4E?3=7~T;azt@rz*eQ?J zSFYbh!_@lbeiUv;EqTb|@PH$4JzLC^G9IKW(NW%peq8kQPy##ppF@5fKq% zdHaoD4oMAcUh0K`3h2Cn@Z>+OP_6Mzo_6yG#cr<^D6(iF*{lkw}Y1cJ{q11KHJwl+jKLl={bMILAR_GEdzSD`6P?ste&7ZbtB=Oem9)TUq z5aHF$mYIh4EP5BDodpEgbtVdp!)RI-=9AqcyHECRIQAX0*n^*xtyOG!L+$o94huDA zdDD7LCznoc9zNRod`{n5)9O$O^^~$1$aS?9zV*gX_?_TwIkiV@CCwNj5#*$9A+k%EyuQ>v$ynefX)36`V#@gM6=N;eH?uEh2?g&ey z%G#DwQar4@0);9M4IRf{8aTYYUZ5oA(Eh-z#@zfhVB%1Axwfv%5!H=9xo4Sp9cOpf z>sa*W)`?kl3ioB@>J&T4m7E8P-?dufsP*g}1OiUEPL$ zS~GgASC^<($MQi7C+t<*uJvTijd!)5)!T7^g!@F$Vjom0bOe6t9z>B@6|x?lo!WmD zDq9KrGr@9)qqIa|6EgSxl3NYk0pyIa7l~A!z1wDJdH=edH%LL)_*H|xSf8_U>6_11 z;;e&}!Dm{e$$AW)Mf_F2oc*836*95E|! zbyF^Ulb%JZG8}y(Lp-^W5E`(?`+ozL+awS9$NHL+-A4Mrydfqw^C1Z{aila39fne72qg-wm5fnmUU7K@W2|bV?;C~j z(*xtw!8DJky8_6A!On{VsyKWs{ikHb8z~k{@Grzp%IVY!J2j1$2d~p;^BDWQEG=d!@w88?WT1J_VHJ9H^_^>j^zgkIq^;rTQq*Fmu?HwyKKZkry67a=xP;^b=vv&@5?lkWFB_)y{8CW0mXs*JmW&da=! z2+I!Y-h%a;k7|qbzadA_#$g(Lxc09l1oo|rjg+TbSe z*uGiUYtIVR@uHy)525r$jr3ur?fmcsC@&oBUSkFDQkFH^O(3;r@QMUP&n3y4&i-3g zi)FT65!?)NySemL&~yjzvp&kjM{N7M;N|`CQAK~Y^0KJ}D(tc|3Y@1TTrkqv$8yz7 zd`>PyU%o^IZc;W#^wrv(SG~IKnn)A&Ma@{Y{2K59#yqz3UMtd(Mp^%Ce2(%l`eaD8 zy(Rb1uVO}Tcdv8$vxbv4nU~l89{q3+)lv(ZT3@0W%o=?xXh&W4mR=jx0&)|aMb_60 zd7#~kB}nPKUD?F1o8)B$aYONeGN$ZVPqs5M~Km_He31%i!QpP z{NGFq+hq|N98#*)_33z(5-moQF6-4VPk*z`xb}$yxc-yBJ$i>ABnS8r?pJ(lFW&7h zX6+Ik>yf(LoEQ@%`|FVC*~sxUQr$9Rgq_bdbsD$?J%p%29dbw*rxG2FwGGY842ODH zWXI9dPKlg-YisJi!Sgq2$?-x0ybSj#qgEW*c@47TN^r}q(*0O-7xLG7R&u?)azd8! z?86y-0cI}bB6MXO&l7Jyx9@fR@Y40`>x20KYLb;(8|K8b$no1(wiNh_S<%iTS(p0< zqc%G;UVk2#qDDx1{toQ$fcsgOs~V&>e?9jOaL7|IhA&_yzZXEtG83=X*eAoWZjCcG z41Ktx7wOpS!D^^F*e_M!(s{gQ^wKJh&-@#l6zI7Y3Pu>FL<>J+aUPD_=7}HRd-VMD zKo52&nZ`)OIKQ;>NL{U14_>hmUA*!0+2~`^Y)8p6yRrSS(+5QPr4JvzPx3+D?;0;C zjkUJdpT2qWSR~Zq0O0|8N9-t(p39GBRIl(mf-FW&!L3`cJoQyCo8ZKwD#!50(Q>Q6 zX=YwLvc^)^{VHJUHy#||<_1SkEhfxZsu%e~4j{9wn;$pVl$$V8|8p&vR-R_UCPxiM z-~5w{$W$}qPfdldt*5ZFQ~VBX^VXenszUA)!p=1R*!aNlTcsrD%n^?9A4Rj1K?mny zbm=`@XLh&u6xD@hU zr`{uP0hzqq>Dv>$`~6a4=ichigKqDN<4Ja&5N3XMVWC%2qc1_Dg}bGX69DUVQOFMN z>&$MW$zO2sHW={Ee2LeE?hU@CKX-zWH)s{MM{8zxPI-NSU}2qbeq`WV;e9M5jjfO~zc=A2 z2NZHbu~fQ0&)e0dP(EL?&I5{xuJO_E&VxWzPD^mui#Ba#%7^bWk6TkuvDDVqvZ{SR z?#rKTmg(t(*PjNG*fPL{F2O^$x=(_yHgK7gk@c6Z<_F0N?VcF6Iy?+|G0qRyzCzBT zV^#O^s;=GLtit`41Py=Iq%WUtSv~$a^Fs6b{r7WT&t#Qx^}C$&>Z)s&SL_Px>fLTZ zMVr!|(*l}>jCYCYF6qpaC05ALkd}PTJ=}fp)6LO-;X(7&o7dpxU)*1=HZOex36Rit zI;MX}G=Zb>KGANUgrd?*j{X{@=cU)Yk37g9{!c!#hB^blaW4!^t^T4Dht zYgR58+DO(NP-c-hVyvv3K)6mc7^`(x%Rq&)N1wTU;U~;?Xcnc@-%T!Cur{lOFSXWh zD{(a*5kJub;-dA8H})a~l^EhTTav+#94EMIBk|!2Y?P6h2rwdKk#npz2CZG=H-??O zP07G0=M?SXCK`%~!rT7w+#h}P$K4g$CPH%-J2Fk#6?&pz{L0dJAUI&~Sz8Vlv7d6$ zlefuMk1_d+<5)4{oszxw$5t(=^(~2(mE@Ek^8WmjXsFvLGjo4%P9szV;t#8%GB^6TE}pK2TRPo|{?ZE99>hBlR-2ZjDx z8UX312?lwiyf!|Lz5DL0&zho~H!Vlt3y1K_zdoeUXly%F|8sbIbee5+@ao{v&YfvY zIa11QKd^YL@giRwJ+#$!w0W&v^k!SQ&wN94rce+Uz4Y#0ZM1dQ2&Yw3#9p0b5Gv`U zeJ6=RZ-%&5fILM9_56rz#;s0*wnD^mOME21I@OjyEx)Cgak98KA?XZs?bkD%9(@Wr z{n zf&#mT=sYeVj3;?l8YxOfA2~FK(Wa++J44LJQNcd`ZH`S{+a*!n@eA6{Jxfl}iMYc? z`o$7?>LE27b1nQV7_o?I!Y3or5f2biGoFfO#B%SzK3<4g91hZBU8;8%V@MF72m6c|qr5#5O!&uE)II|uc5cm)X3e5|qlXwjBLxRPCv=Ybc z3<$#5+MYdjWSCk9-|s``Z_k()rEBCF8SRg%HMjF=m))&FRV?9YdluJq$SI@dJ#&^0 z*}D3L7Z0zBQ=3^jkle>>NrQYpgJnVfz}QI!|1{JZ_Ip(=YGRXYy}AX*~;1O!2d)$V%RD>ejqk{lW2g z>%@V9kwGli=yFWWs^q30`lXpj5&YuBil+dsE0#0zw9M>*x!HfRAvY+;Pw!Ul?cAO_ zIMA=6#pC|dnNbT!GyF?-Z7MXsnPGwcmh3CMs$MtAUGHm?Ft>Vpo5k4`fb8bF+M-b{odi7!|bTp_*G zqE6s^*{W2LZns10VjO$~3!9|uSmgkNmrNmXP^`Dog?eX!km8rrSkEc&`iz(-WGtzh zUn@z(^ato6C%ippFz%piVQi$JaWblfF1~C5wcxk3)R}}jlKcCIaz0u2r9Rjj7iMP{ z&!|~DbQ*qocKA$<7avi>Xv)`9o~)SZRMmanD&@V2E!Bz%_qi7<$^AqW9R&z@a0q)ll>FBjCOO8yuxAl$%9V5Q6!-gHk$7krp?<(!wQ>9NrK{D<=e?EPeliRDa%*W=~a z!WC|MhKw6NnAme(N$48APKiW{!n*+PfajgTnd27+qxF><1C?Jz#a zPpLN5X1GzQ2SDAHkpcY__EgveENSRbn^XqIo%{-u95FWZsDmf;0JQU++RH27kx|Ly zM!Jt&{D2$E-@GH^o0Y$kQh>CB&Li5OYWTgn7vc`ZafABxE>r4i9Dj9q0>r&;Ix|9o68JBt>YfD(%1$zhbC26tUZI&a z5Z0!PgPp@R;nc>wNMCPodPDjv5sazin?Or?MCa7#kaSLZ|7b8~&ZK-}Pz7g_`x zygX)5%UG;mY*46fXa|FoK6`*L3u|XcPR=K2;M)`xUqV}7+d3tC%`8JviAH(eFI!Oc zAi@G>X$YzKv)B)q`ta*WBAud^4YU&YBi-RZs5t%K4XN3%OKQ-3N560Ku-#4LmV|H8 zT{#k`jSbJ@u~bz12)BF`ahme5f&ymvH2!E|r|<;dC=V%frWGWjfsZ!s>B2=ni)_$i zcZzh$^SJ|{g;(FEyuT3t-f3>T;^OX9F(Ng*SM8u^SZbl4BLVidvjfvDNJpN3m1=u= zUCpv*s#0->vHwPaKfp2>a1C$rn09S`#_7 zec~V}nX})W33OOj<8SCj44>+5gH}Y*BluMHx$y z+1I5R&wL@5+In65sZTf~UnavLLhUWR8C>qG9B^~C{1ehaJpUQudrVxSXtQ|raYk?} z_|<#k5Bk}^yEFsPij?u`H&dsN`87V^lE=o)@2yWuU3g9r?Vq?bLx=p`l7U~~rIXcP zJ=65%VE$u613V-J1qs{Rz&D8aNZP!%;I}sc2wPbuZs6$*y$YGvvhBqhGWz9%tn=KM z75ll)j5`R1j6dgln`x&$o6e-d|YLY&^d=z;He z`VT(w6ZqE$LDG14cb}=_>=NiMu9$vwW?ON#y#W}0D?7!OP9=edzzZ@7io;R3AG@d3 zZ>4xVjSCmBvuAx#n!?uEi8(e}g_SrnIa*UBo{-A2VdL z<9(^`13h2^Zj>Mt)hsdoM@ClM1TvZ8$>*WTV#Mo%SQj7O#V{)0#UEwZazSNPod&gW z4>t!w9lZ6Ys~->}VMK6t?%6MizFKlozZ<8;dpxGL8=`u8v9~vOQ2l*Y8kh5W*B9kp zdJ0}1*=Ky6u;TTwq{6U=GSZC+&@$%|GK|MGlqtn8vzu;6X z2061_sn&Q`*Xz$ZkUWds^`^G7JFV*?E9Yqrnc>srK_X8TFScP%d8i&q&LJ)jK2y8i zHB||YEMoXJQ$JMmefCn^3&i5jMtK$>WwIpdDruL0C%|}Yc>m|hEL)s<Qo_O9@x39t+Xw`a3+# zV!Fe1%&%EWz@d+u_}?&4I`1GS$y5!^zcy+U^(ksBx@xTaX|D__`IFfNnLkSd=~6uA42~_ScA`vwJX!ujwoG$4bUXxdHIBWP9Iuc&*4+md zF?7#~i&A}J0UjYr)8g^=h`dEY1aM7sIO8p@+UMme+S~g7eaHhkk9w%^Lr*t7-m<2= zu~Bw`p>>j%o%V|kdBacFF(0Pccl?0g0+ykvs)N}r!=8E{3~+CHJZEj*q@&EaCtpvo zhILRNxIhj|ZI2PziG-TfIyf#oZ5!V4Su#N8!??RQIDo(ccK~f@dqN8U>KgCzFn0#5u}! z(z?^mFj;(;cQQsOc0mJq@%x6t+QNfEEM zuUnp&yZZL^_*m)(eV|lg7yFBq|knenLJ-fH}tS{ck2=FyL5E~|8 zNu%ii;(_OQ4!b9WAI^feVK1(9GewT2!)&k6g=&TtJNQ9Rqh|X{u~EjFgge~(2cabI?(i{`i_P;J41(yib!5JMJqAoUn2^Bwa({uTlv z^WM{|DS~9jY+w3Qg7WFFYi)y*bdP_VPcJ)xRC%qeUw%+${KNxrCgMpCKV^x`1ia5u z;G(mW0u+5ZEO;xLaHk!QeN{joROq^DCHj!1;dL3}EH@CD`OnS{=p$cF^$__eR(P zpvLo_a}VW7xp}BfE&jBrGiXyk09FyI6naO5U`9q{(v{ zj*Lpb4D`VDSwz>xviunVvs~ck>;^B6PjpyH(=aHBO5&t53%FDXOuo75p1QbGkZh6T z9g5kz$KhaDPZ>RTh}su^(kz?Jcc-|V_fp|6LD1plvi1e2mmBBV3N0`e%iS8{5V7dn z;pIl@&jZDLxACXHh4lyxU`wE;dhf#ArA`Oi z?#r=Kq5Dy45!xM&EZRJvaEF!W*^5f3aojmWQ4Q=rgvaJSb++)TFL8S9h5=OVr)E7e zAfBuVcop*eQ}o_$udrQBWnkFRG;XYZdhuSQNYSH7ciuyO4*4k*M?Qs#&ih+sce%0> zsK^05OmOV(os!R+qFhuL5sZA}P)Nxl0Uv}}c-9Q_i$9%Aq>EWCJniOqSfTp@%lCPq zyFHx#XBQBakej!=!>TPS*7@pY5G=#vjv>FgP?SIaf_ta4^H@cw?}+j<+)f|cP(=}k zygX*;XLG`J`h33`Ot?v7ezz;@C2016-Sdo$D?h_$wT&LP39vazJ&AEXIDY+rytdb7)XZ7 zZ1NZ}#dpQqxiuQxXB!j5=(WIg&8k{fP$U(O>BqP_sSQ7pETaAuD z?KYbC5IvS7r`QPz&2Qh}s&Aq?QT6mdu!)3r(CfkFgycRWe)h3tH0|zOqQZ}3q%;kH z)aq!u>XcWYKMT-fRi9(?_--2~#LalU&+uvQIefZ~M(Ev{0RM@%6N`NPM`kWB8FYhK z%7DkTLU(Sf6i@_V8GDT5uXYEkH!iIR)0y`yugDcjtoe;XmnP-=!S66&^EtMU?p42y zjP9A=yXIXMzv?PDP`$3um3nifT+lWI2B2o6pwRmh+b$C<{s-djMpu1mQ*Qy8|7VAS598YiIR?))|&zJu4y%atoi;0(K$y)qu z{kHgifc+Td*M|O&G+WMhZ*$yMRTolKb^Xsj*)?%&^8OHaROFfXyT3RYh<%4q8OAN5 z4048;E{l%UBPS@cXV*FC#tjTk<((C>Oo%dO0-Qy4y#syP3uRJ`W**)(0ncS9LS{dy zaV(|so2PQ)-AWE{>%J!KF~fCb929vop7KWYZC5=`&1XCto(zHuL-k(w2r@7259l_U zAhQ2UM63J@NKVL??FVP^r+F`t3jDk`7mj4By(ktQ80#E+c={PW?b$bXok?4rRBPhr zn@Cfw$BvK-a85K=2tW3K@fse!TPZ%!t|a9${?C2zH3dNBOQSJGGNrz6BA|%j+ z0&N+ip`FxN(o&Y+^Vc*S zuOM{n)}pq?BlgMQV>PP-ZgJ@#06ZqLT9QLJ{3wfh8<(ESItK;a$8L9yURrAX;>|`T zzxcVmBRFgJWQBtl{?R=3J#9?oR#D+#F@-!=85a9{WFz#H>aD!pLMBY>p|#m{I2xa- z;xU#pC|`y3v6jp=d39Ja;yUwcP?|j^ARHAybALeV6I`asLIixQ1<=EGWW%8)3+4|H zA^l#68b+#YDa&IX9g$ly>=TZ$gU%$CbnBPsOo#3Nl)KQt|GjSZzXgz5p!d7_7Y&}d zQLKzEpN^If9>?LBbiskvJ&}o@&R*RGmqZh`ZpOIfuF>vMK@ zdQ#EA4e~!>@h|mty(wntC_iHNR{G>R(93$)2<5tQ?)RA40w(`}_s6=4WDiF4`_kkZ zX$foBo?E{8%bIXe@|2AXbi>elL;bZsrLMxbyTao!w?5_Ay_1&(#uEy9UOv!yH@uR* zapFYQkp|L#kiiTs?cUx7#)@{o0h_T2H3N zw|`c&;xa@k!x~+l%{=cg%1ISvv5qwq$X;c?i$vK~33H!Z@>Iaho6eiPnEvPcTbVDc zXa8qI#s5bp0;Kx02T0^S1B15`tnWSkAGY2CD$4F%8>hQNMp6_BLAs1tNS}>j74psSxoHa& zeJ^JqKaR<7MNU2Ox&Dy5LM<$~NmCQ`=+8yJWX^89C2$r`%W9Tyk|az+YU+=$OJ{U@ zbHAn9wrx3@WhKa05ICdvA=^ls^>tJ;!lBQDPuhR`N?Kj_n4edeUa9jF#u7!yWIzTO z#>Rh_v;jVtR>`J!q07G(l2ggfqmoOND!i$iv=$c`x8Ph9oc~t%ZP{Yj^K`o?&W~Qm zNP6t1xW(}_dMt9y>{ZTH8`lST;_8p~>3j#p>)@q3K}%hM*WTUEa}s6gbv!RcI-FKM zLyUE5kIpjbgYzm&&ND|lsrHO)&S+rkT*t@6%OOgl8J=ix-}+adcZ%aT9uE3peaDZh zNgwQp7cRorWp&PSG7~TcGj3L-C&2rsQHnl2Hbvt6gDd}^$NG8}{1Ul`M*ng4`4q z(yTRQ8P|?)_n49y2{z+0;jGvN(D==iub-daHVEdGG(97kQ_t3s4S@Ov-ezM50ozN~ zj<*>`LcYh~FhE!GUmty@+U1GAXQuXLe(k)dgl)J98B@mO5H0oQjjYG=4G)F6F_RRt zTlc=xbv*c7`IAZIMUi%wdEk|+@xtSw21MPVaFGGuPq>!|REMAU+dDKAv@UKvC4Uvf z_s<6%{0{}V!H9eBfp$XdN3xFc&80xuE~9+gMab#ttULj*PZPU4J0#19hK`QW*G(~d z=RZ@)RPNoKxVPs$sjKqEAk>CF1Jyi|yg8hNb)}kU(EXSvX`p4~(q!<~C(wzkBo1B; zHnqG)%2n2I+bZ`3`a@WwBtt~?)pw1`h|ih6$zos;L{|fTN8m*R(?+)^_{f&LFFD@U zosXbG4ILVbeOam$2};FR%8!+eXS=aa ziYI-!-w*PyQ@_S(j1rM*mz{Xm`tOl@$n_tk$a?Ch!O51{Y(|_wFTn*rUHz7g>YKfn zPS_im{-~)&&((PiFoH9c2+j*oQE&~XaVj@uxt0wk7u<6o{M-|uR;*&dXfL@?*SIQLPq1>Tg z#Ugr!U{xrzEO-KB2jv^(sq%X*16dk_)E^q~kr63B&XStWclr^sFGCK^nJ^Xcim&+Y zan+oPSHh5ezBNB~t-4eY2YV1FBEV>@G+fY>D}V3&xxmAk9DkXA4?qU@f9#S{H0;8e z%y5F|OSk5*&2}(5aw-ubdA@iWfj)g4e4ea*xyIDvTkV{?b!vv8Gj{+tu%$)NtUJ@O zu>+WG(z{G=aUfQHVP*R>>mZ$we7>KjGT?k%!5!Mkr2dNf%uQppY0Cj||eMmE>7-ZE?XtNBJ;+48*#NY7QnhJkFCDTUOL zaqk)Zz3JPOgR#g;F+KvL$?sDRC1i1V48C!vS410(PyN~O@YR#nS`Q7zSAQ@>Y!c#6 zsS1fvBxfq5JY+T`3rxmIu0s}wzZyyj{pejb_GE_^&}=S`O{e&2`u<|&LX7R}KW^Gr z_K~g7zg?*Rav3WMQ@P#qYcM)-WAWHJA1=A<)pI(jHqlhIy9n#K zx&K>Rq44@UkJvqU;2AAIOErRrr8{C$>g>vS66UpfZ+Y?lGrH;RTe$(qxm`~?Ils_Z z__~ZB_mL6J?feX?j(q-u9`m7>7T1n@g~yF6cyyjZny2kN*KZBRy5CgxFn=-Y1%)N67`<9G zb-ijTxQ1Ix3PfXeh!3Tuqt1tLsJqNihi|h)qay7jY=^_>aHf^TZZ+RwieS z3%HHV-3=ST98@Fv5>A0DwDve}C~yiZtU?*ZBiP+kuhcNVS&6v1+Q^7 zcSC#F0z_=eIBHGionI~Po||o&YstxKdpR2jLRs-E7K1FT{AeL;X;1U*WpgdUMF4~@ zSt+@5j*GW2iFPXW0Td(~p!R~H*FZPqHWL}nNI_gyXX|`^{{nwO3iB$_mm)cd+ltI7 ziaZoVq}}+8Jc{wxT&5q~d{tH{-J_~t()#~8Am@8*=!pLr?+0&};$v4`08_9;xdvmF z79a8b#9j$u4>Mc*wq9b7e*|^M-6aGf?Nnv6taO6qbS{u3C#arGZ-RZiWoeB>42C*p(QGas>G|%yq9HjwgKQHKvHyqF#M}UZ2S9 zr5@N}d=OFYd-P5#nr32e5nJO6Y)0My6uQ07-v37Xe<_%+vu<~wdNKh=4Aw($CX1!} z8JXIsVFG7xfL&MwutJA~ft^$Er0-euyRL+nyal88{kz!J0H}5c`LmnYO`ukxhW=8l zr>EN-JB9G^^V?#5{w2Z;?y#3%TmA-HbgY5V$_TH4r73I(|Ij#s1b38SDMd+d91R*G zTqM+~sMRr-YEQ67)Pp@&l*c_7{@t#C3>W0t`%Z#AiG$O{3M*EYv)PODaiP|m3iW{8 z%&p%=&r;N{A$`Ps$K(=T_$Q9FufG(mt6Rh$D-+c{vG_Upaa}K-OC9H^-VL(H$QPfb z9Z;?$C+pQ81ep6e-@yUA`;fEqcjv4;@Dcxqc^sE!P@~LpsGu6JMF#1Cke|noeMIGX_++aPAgQjueEHFP+ zD=Ia0;m0*JV_xUzImrdfDJ$EN_Oh_=3KyAW|Izdic?6y?wo2hjlTWxjGjQi%j}Ja@N*=8A>ew-*?&|3=&tw|iETJ8aw7IpyI8i1WCp_;& zrA4RxOql{isN15NF+t=$@&SCD=_Gq)`(A_y&gj-q7R&#&_p@xzactaOWm>zYtjZL! z@C3zu2BCNn=tlx;vVeRrqVWH8IHUhN%JOgCqCcV>g@{XJzfj?H~v6SdfrzR z9S7PmBnrVLC`P5|Sb+HEY9+{@B^{vp%39{N+`X2-n=Jt}T^Ps)BSLb!f^t$BmjFFu z5iXL@p+)l8pMEP^2et(3W_Kh&mNCg8J*3LhZmn)ct4JmV1^Nr{MNVG^AsZ%f3z2_; z!0&k9*=p|XML6wbz=&Gw(vl4dPV5Rydw{H(KHl%k&XY|D%KPuqQ$5D|Qq zvx(3%93o}#vsZc_D6xsz=dePEL^rrgD>(63KH~MI!vdrNYV|7r0o{pm+(uyvAQY`9 z^tj~UqqjItaq8C{-?MjGk^fl7*kWh}l#tD%RO&hF}KAuFQ4ZZvJti4GY6 z^cfAx4&+<4hfa_98TUX`=#bQB5x%a8PkJWYN+M-^2N`Fr?fpn`hTVr3-^g%sfgP^{ zj?eeJJ5tI3Ez~>G$Dor0%!`Yl;Od(5w%VSNgh0VSSDU0uhx(;6(=r>%Z}=GRH#QFn za?v@=Igcz#36o1Y3}AiUyomhP%h@ z@;p&PLQeBqc#e9`US;2D1f#hC{E8#NQEy#k8D`iw`A{!?-S_# zXX5S4oQ6~{M+6<-)+h??ian^(={U_dTe$jXFMMxH3OOHP|DGs|&fouA>o0G>(+6n% znvZrRxMBAn@B+Dfiy@HSEFo9IZ0Mz!>sEJbH~o0c@5Stfb2=*GPB~4&sX=~%KIo8= zsKv_tl+;w~Y0pvrEw^rA2)mN4H~M9{-j^SN_tHnL?OK=w13HU)ULVCPprYj^zl9;m ztdf6;aY7pIEV-OuZT~#_5d&1+K4cP%7aXqm67;_mnrWS)JLK~*!QV|GABL~SkY6Ab zAF-MIIdxM^!fmR1jCSnvE|>=&zST&DK|vtNi|;iDTv|3nxjyGUtUmAJ6KX~e{PmN! zPLbgkc;7-XedPlssSl%_amRl0d;GjzkVCiZ5_NIMB2~~~`u=fjc$o5Q)6Cs^=70Un z_<-Ls{(srfzrVS*UmaqY=DGshHlX~A%YTa=a>}cG+c%OQaw!Hba_Nc*2tXu{-K*844yG>R0edZVZ(hDh5*d-Z` zr%bMX$9c~I9Zs>0E7S4B=UAQ6`2qQWLcTM% z97rJ2#@cc=*YEq0(2tT-yXPo|fsg({ zsk=mIzn7?a?Zu6Jz_0pnlrRigW}Fk|qoEWbmNW64dV=}>8mant`(ni)ierbS%;Cf4 z*Gmsr5j^Y!eQ)P@f`hWHd=jOs!B`|lLm0Bnn%77v>lmWD7r5%8Pu^B7dw7Gm@E^{T zN+oO8%ghON@v(V76+@skw{`jc%Oe^n(z7Ixv%9eD`3pfj+n*8dCNb|460pzs8Yk_n zj?{vn5qIbIM|UMl+fVX!C@mAPqOt*lOY3i0Z>sH5n~6 z4rP}GQ=Ww=3X#Ak^7UB`!15oQV{vU}>z1#_eDhCh(go8S3cu>Nc+3QwGW>=M%5l^@ zuX`0((Zh_O?6V7#-Lsx`SeaiHmR=Yht!8XmE0O#1)cQLABjd^3EzDp<$#Gb9!mF+e z+%p!jH^-KI!3smP|3Dv|!7S;LrbrqBx-+JK^3(r% z2rYTefw6z3rhS_vuY&}gU8hL#0ESi$FBpG!E1Ix`TA`ql;kRkjO36cwy6`DPVp#uf zAMQOXUMCm5>m4DT09o-Cj!B0mJIQQ;heEUjglS)&>jyNf1`r89z_RBA0`MaK9MyHg z1|2X`21*F~mWS9tVSJxoB=o!Id^v)+I+$HqEn6kFrILMted7B5!zy0b z&#Q>yCL)TCjuCG)Dd?dYUt~hRm+`ZN^)5s(QwEg=i?Bmq3)*-eW0jceV{Q6@yD*R5*~5&U}~;v1fWw#wv6s-Bb;b!BO8Ou9A4|m?A0d zp$M7yyn)X6VuQH~5MHg;i^~_ELVma1|Auwd(^xN<>%0~mH~z*^Ao8n`h!)&hKl0kn zZ9%qmmj=vMZ#HLMg1St>|7WPBHN*SD+YCvw;{X5ncKSZkA4TjRLeMfx9msaIV}rkL z2=6G{EPt8O8z>{jQ_awO*3{}GoGT=du8sk$*Z!^GnkXy`qIK2MW7YC|dwWEb|Mk@E zGu?g19Td`;Mj9c!>O{vE(bkyYgXYe*__k)AZ}U~PWlD8l5^fXwtVF5AxQ{wC^YOd= zot?PuqqOh%!{k4}#(=pF|Mo2zA?<@to{&{bv5@k0Nqv@_bpWf=8P66kyG+@)ltHaQ zsu zQi>4mm3ZwmbX8UBe(c|;FKqi)C%)&l=l5$A63!Vha&P3z-(EINyu*Kn<7V8^WXkFx z408Kw3U2P)WB}hEbsIjGcezMquTT!FZ^Ik6i zk9U4QHq%3um2TvWH}!8Z!+@rf5YaTDom9fSe9EykXwsj z?4!RwVDzPJO#m+tLKY&r*bzY&d|_M`zPogRNZH22K+Uhlmh;Fj-V0}v&2A42fr*ky zqACefn#UcQm5*y`EF^1aB2}vm5}c4IgDJSTw1cFyv|Pb!lOmc(0RV4NQ>)~V&;cEK z1rRi)HW2&AG-TxoiE^9}|7>DrWn&AF%OrPU$sm=_p6YHt?I-cN1~K~0o~a+Nu7AXO z&Y5WviB~(VPo->I19zJXs$we)=<3z8!Fsky;J6vIYt%J_$=WIWuKUMX zlHmS7&fzlQ;o;x<>rKsyLmdP~t|NT8-^0D@?HA}dcmgHjmnoS-6wl18^@SaLefEiq zG`KKi??TvJ>78|~MGz&!X3+W9-w(P>6aTpNx=DYY-JfhjQSyJ`7GNk(d1eeu>jhEk z^WyMCZ7+YR-kYF1$WQm~X!TgeqywC{;>^SC*Ry1V*ZQb&Z*#yFI<@`>Pu7E;D0nRJdytQ_zn`b_}PaoFXzt6$F=1B?>dxUba@#o5s7wP3c+5RnXO{X-scD3 z9PhJ-0@sH@FNyK1sfgrUTH5d_FnbV7H@98{HPzMe!h_#hu`Aow25q5-$Uacxq{<`- zn75!PdZ+JR(&(GodLrKbZCdE#Hsexb!42scfB}!L>ce{Uh1)kKViZ7Wzcm>h%-RsR zH4-aZ?(TCkBscNqQnRD{E2Qc5n4~?oB6ingYhujVt@N}z>)IRKY$aw2%`~;OdE>XX zdOK?I_vP^y7i>b2o}g8TUft6#ZzqCYItp4xPy&oeV{wN0^iDxTCMed z)bDqM6Q@s6_!lgiRH^GPK=l&L^M3|K8ef0(f>Go851ZaWeSKd-_;M&cAEKy3(i^hh zZZMUSHxn0fzsml}r0=}jJEg>z#nNP3bNR~DZuMGMk9X#_yb8^QLJuYs8Ru(*I)1

w9lj_=iEgiQ8F97@hX;Qio{RT|F6ey2JjY?^o)mzA9^EYHDicl zBT2nnQRal5^8nrwP<-SWF+S@sr=H--2$5Ftdsv%iGl%;Y563z?`&v7dqE5l$K0x{Q zb^7Qx8R5bHdZW`Fm!81*$F~Jl=|0l`lPgU;`QPXjV-^((*3+W|%wPU3(xY3(w_KQl zPgyXKi^GS|`h#u+%BLzw7L}uqtgblB%j1u_M|GbPZXq{~6UngH7_IXDz1*O82n`-9 zC-u5=UJ6cVDie7yXQ-U+cl@n8+nv0jv|Mfoxtkp5=Yge70HpD81XjY%f?4 z)&7G0LZM8{@TJe}nWvA}?2SU$o=kesjA;O3%EY!Eg2i4JRDy1P_l#6~-0bwLnzB;O zvryH2;mN08UHhW33taMB9fe6u04Z$v~+ZeXZtGP}f@ z!0Y0wcX&WUMciq2>&MvGB-}fD{7+Sf*H!+xd&f=oafT=b>A*nU#}2Ran*FS>xBjxw zALEX&40u0y@jV2%xuY?y4O_Z-*Q13_j$rsvSYujaBnx!tCgG(az{`reO`OPQU?yD{ z^m8BCJK$y&wsLi<3F?#&YZyC61g|9K!RILxZ}GAQRrUErA*&yXXLv$f6DA&kPExf&t0II{5A-vr1iOOm=iVhlm<^fCAjdf5Gm5rQ>jU-4Zhcye9+jNWAkq=}= zCBMr5yj?e(Qb3&*m-bXwgN6X75>GwJJg%?#D?5Q=h)CogH(y~L9LZXc;~kthTWMx? zDn!eB?Dr3+-g%a_1J?_-Ws4M%VX~o^*}%aUKL?um$$cH&XXpqyo4$e=CBECGGxLrn z$viC|c-t-$lK)Tz*BGP?$&ca_5C|iu7yd~q`)aY8L8M`1V4}wRl@^Zc_xd<$@J)1) zzz)*?K!vky-bRPgXvdd~OwT;<(0W^P^&SYp+I9Dz#Zy$!6aC+ooDH#JpFZLcLezD< zEp&9eUU2trK06aJz98mL&!$>-iys1U1CWu&3-j|=IyniyHXS+(`00I)d~A|7cL%s} z{K+HZ>q~bg!H+^!<{_<=D4{aG^Ivp*7m^krx=31eqq@fS7>|V9Hig1ECue6M){kCX zP@#hp#o@o;rJge1>rR7y<|lEFlBB041dTs@DAF2~ZOYPoh(v)Lsb$8si8D#htf&aj zsiQ6yGnuI(F2{bDPt9h8)p6Iry#qk_%P#3IEsF%msk3n_hk@g;z7W%z2{-B9fE{E2 z#a>pMFc2@B`9&Ywdd0VU!`06W3?oFmWxmu`mU_tU?SzsV8fqr)yT$kaVd{uwqRJZ; z4Se&{qNRoO>)tq<1Wy6!Y8hYLFpgYDt4f}2R1EF4x`v7DNhdJ0{tS|WohtB;eRp{2>G0&y*LeL+V)#Ceq?d9A}klT(>>m>A#a4%Ja%AHmr8t@d1- z`%wkU*iCs+J_-?{DTJQSRO#d1-jThLz6WGP-VZK!e@=NYR(nr-Y0|2;Zh4Hc?q?mE z6LT2tt>Bdk@G;GND;*LKmYM1Mk|Bt4)A9M)%|pFMM==9(qB*)boj5g4X+gLTRK02O zJ#2&ROq{p9^N0=d_;9MIF3Mg%F3I)``c+6j`=eI#G6DL0QbPq;>>;6;e{JO7=euV% z9Vq?-2-p>Z4B%NgjF(ys9BiPa^=t1s3FA0g2Ve2r^sQdMx!JY*mOeAPn+T1Y$Q=m0 zmyIL-Q%a*_0ivvOM8 z4WdK1^k3ex>U|xCyd^ue703+DgYSU7q#0H{cUgeTW%Djv4k~UE-fKQ`J+ZLsjEie&zuU_4)=iyy@! zc9-!WR3L+D_;`a9vm`&AXLc>vZzgWKntiQ{C#Gn(4L5q>arg01q?f;y10TfPO#-YL&R{scsxRyx6I750?>u!|U* z0ZcOL-86O2v22+<~LH-hzWd3)V z#;D66#-8}4;$3^9XbgxdN=0{2D@{Lz&?w+$ye-UeKC+!2_J}0FW3yPz!`5^2ld|7M z=5-Mdg+5S#4y#Vupt=%sKIsXDGtc+KzWBJB zCk5&0Ya;clfHVdg;9EA)47iRH&(~()30cU+xV`pwwDj_+l(TCIbGi$uxcELp#)}Mew+Bkn-SelRe2h}) zo!%cpI%$N~M!E+FI(>GzsJq_B0Re;R{c9tPok*^6&4DH8V-S(F?JHyBJ0!{!KjG)S$}QPR-W?z+ z8DNm`Rqw>j)BJEG@c`~6x3IilWrCI7Y-cm?yLD+xId-Y#D|rL2p*iI|7=uOcHhjzm zGj0LB*BO=IGj$O7GdPVTqX(u-T}+jbM|Y#d=kAMW16SmXyuDgw|T*CXJcV5ZaFP5^7G;oEa5j} zy`+&V#oJt}{nJwhLsf`Nf}IQ1FNW1!^9_=h3|#7=#4@>5MrpcfW8ab)*+T~SRU2hT zM_KWN3+=-&tbvW$;h4pcn=^O(4pe}F;rAIkjRpAn@#p0fic!LMGwUB0J7k>_$>-W* zc+6WO=a`dv=^}Ag0vr&vlD)4Jo1Aq+k)WkMiB79biYXP$B3}4+M9H06Pl3S0Uoy)y zb{xnRD@}a@04?WGk{iwsatjlZla1n|9-r{tvVM|k;ohoVe~SB0SfYORKMl%Hsk{Tb z+%rpg>Vo4OLC^&W(!D5<2RC>rS2d*vt+@Ym9SHn>(T70o*l-!vWf?L%4o4AdtlFrUN*9qsz7b zMobZ7L~MI%H@VgY)?Si5gJ{g2HX)2L{|(VcGiAxiS?}B{1ByN&(gxo(7lSK zq#)1DNT0ct`8>4rX`yv|-<#NBtJ9?85%SNnFALb|ZDa*9IjbWBA=z@TZ7~bT#I`5@ zSP4(re`L9e>{dS5vL9c~P+lvTL!?#!^WD3)zZS4)ZNPi%qECeMU0g&n@~spSc6x4Z z*B2Ev__1s_8qa$YQ}=T_9Lil*Y3BG`dcfuacEvoKTXqf(el|4kR!k`Na@d59i-BR4 zO+J-FmKsyKV09TT^^SO4n4GGv&Mc#sNwW2$`HOM!LD#s#WbbHz+axrkaf(xmP83G6 zaF@_AdwfGv?MB3c=HraSa=WF7dUPj`hlDlgWPZz9W?VOlbLO?oSJ>P`vTMcOU?Wiw z#jAWX9H1fb6Mm8P7?OoIX1uXepbUO&Xc)J!u~hTm*J8{3++4xJ;=m)dGD>JvFDQB; zq;rESi=pL_r&8jZT^nvaaJCULs%BC=2jY9FE(__5%I!U}Y$5O7-35#ObT&)cdbHAJ zKZn&h?$ubkIijHUL4m*5U2ouBOilOXFAZGU{1~?j?+A*ec3thSto~DJQPT2Ml$Gws z#Kza8US$*61G{Lp#A6_W;DqA_%eix14tcx zeK-P;dMTDJvEr0Un=_ni$CKjwTC2IXf>Ue~THhfS<0O&fI zh9FlVmm3O7;2S6+$1eM2&qdR)FbnOc2G~0G9P$p`278J*F|!nBJ=s`xu3yadOb&Oj z{&0?#FK6u*bocG&f-*mcJKU@Y8cIT|ss?_E5{1pr%X@=m{U%r1PhpG8!F!pKl<**W zg@g@IvXh#@zmye@Ec*7vQSA{(RN!56MLWEgO8u9;%tjfXZ{n^e&Qtv7WdeLL zNk>nm{5yvOW^7_m}+}YE;cZ{AdAoSA+SEPnWP^bWS&X{7sYQUZ}=O}p+SKo}p zit_AZOA04f-NVDARvR;yW)%99*jp`zoV?Bzjfv&1mb~S+@A9a9p!ssP+^M+9A>Hp` z{y{cT(IaH50L{c`!s7S7G35xth6KN(9c9cR4?vHDRcwK*nrf>Vym-6#21ujMi_G0E zJ{_*pafuwesk|~&@sl)B4V@$@%0zziosP4&*zA+;eI#Q~{41sM8|i)#-${mZ37D@s z<6+K`&Q(k+`&!7)$BfWTcj`AbTVYuycxYTM!!7W7x!68A|4bosjApV zwTW|9LRC&_+gcbb`U^b6w=&S3mf6u6S+?V2rw4isNs)ELv#fWJX}QbtD**_3g@)kw zKEr(b&-wC_)-M?S|F9c^K0Y+I^bubFy^K8ccmA9H=G~HVS&@eG1@7_f2>n|b{rl7| zpRdJkVw8_k2yeg%=-Gb)P-H()Ls8#ZTDCragUwI`i5knQrEIm{`OFUVkvQj91bvlh z2z(KwF&VYV;zo{E!hY|Aut7^BWF7o4kPw1?wbSor{E+qqnDrvxWVf`-I;*xP-#a?0 zmk2~L9w3wJc`YYQxtngSZfLmar&!l9z#I3ixrKC(`Q>bi^&|9mmSK_NrMB+vz z-T1@>U(OtKQ@uMHZr%aUc$!Y3)LQKFq_&SvlaU`i#*m(Jr6c5_ZI9N62rppQ(kveX zv_(NQ!y=PzPj~i|zZz)7t7*!BLj+iq6^QUtB`!bX-*WoI_JdEIv?6EWQIeKY9xO@* z&{7rUsU!oqbFWA?*xn;sTa{^Vhu$H!D&Hg1-xMEW8+%4>t*gU82yGrVz6JLh-5C<$ zCd=6OzNEO{g~2P88a{N5zua=LF4>?v_rOIY47~i&IQQ{Yc}jsZrD%l;~+7(O0Jbfiti+}Xo~at zY8DWs2T?6NltaP=SG`{&p%!t@PzfSO9^7qiH!$gI?a;}Y*8*!f1COM{*g;mio_aYR z;TGYfcxgcOG@8_2%@>o?=l0a_1%s-hDMO02qEXrb{802;ws6yPx)~&LP9oCUaemAr z^p5$%(RnS3Sm)>-@{cf|N8PfrbGA^LNKREg& zVD)btKR6pAU$!rYeX18}&9Skvo08llc$QNP4+I1RaKyh-H)Xk6~{>1@Ixj?)Y+K;*k!w)$xIH~rtzrHzLW z{nrNmF7^oimurCJXUD2MJo7J%mP6aHj0WdgV1aP3-wCi=#AM>!#LfyqekSW>OPOeV9{ddvN)64S% zr~>x6w=W)s-f4BL418ti3nM8mCp`%uS#-I^B|5aCD-?X_mC(+Fq}6KL5^W(LD__Lbgu+JcI+MDp0VxK zq)@B=ilWtBow7W%3-#izPAOYbRaGV@TQ`v#L$VCL$B{M8!4J6d1fmh?^Gcy5^ebDn zfZNI+*3BUj7^|wTFmoc`S2`FQhs=bVXZGwYEGq%4sz?+0*62yg;znSWD0AX&jY$rB zx@Lf9WzR+ylWIfH^0G~zil4~Qsl=Il}#sr z=ffO>gyeUDZQZkg7QF0q6m^Q5(QxJZTh z{2Wbh6Dc;B=!(<3Ld0jBUt;aoz@u4p{k6L>hw|eAogQ&etG$Z5RTaCAl}*!L@uxr4 z^^>GIDFD%$PU#+Dd2L5$G=OB!?u!rsWk{|TakBLkpVvsek^3E2c9savLZpFVd{d;m zq3-zD)cyo5MHH8M98#l2hG{e$T4c-Czq&b<1toc6qMji!5I9 zii&L5#rHB7#-kiHTUcV2kV*y-^WPw?6CQsm0ZuRxx)<`}2N(oHp(W4#AA%SFXkh>P1E>?)>|=DxL8W zM9H=X)8}j+-xh+JAELA2@qLkfg;W?e1od)@q@Cc}r(xS=BP};pG5P}}F<>o4VZ=9V zQdzRevqp|0@VY3)kfz873AGKyw`0kbYtsZ`%9Fz*1cp;iF7+(`?<~L~!?NHwh>jwc zt1r@EA_Ns>;uvNcp4ix1f`G*(^0creTkK_;MuKRRnk}Z;~xAbwnA}j zS6H+{Y#4I4DzA8I*SyMl|Hg6cVY(nBJK}mdf!JI8COCa09Wt||Ewt`VeZQ4|w^c)r<>lB&daQ$t}u_2!UL~);l-VAOzc|MYF z*+-p7cC*=62odNSci(w2BYv{;qFYZkX{)wOHWGhS*hd<1H2w*8#rFO@LT+QGDm&aF zx~ci0o}JRVB8^5*WNx@_Ss3Di*Ja6k^0yCV&&0F$jZ>N9u@@IZ7pOD$kVZbER)X64 zU*5<0^HE5F#IcgjmS;Gg?=2P$gNvvKbvI^pR9j^p+>#iyhv+ zBIxMkL=VNRTqaQKTsZW0Tp3oY*sEp2@nEfdc@xvu$&FGV8Q?I&?Nz4HB2zh(tFf`6 z2w7<}O!M)MPR`&;APxQaAg1+&Ve4^*aDwnSeQVYrNWC4sYjh^0WrBYCf6p~1hYz{hC zbaY$EeZW;^f5f&;C@ZX8jjooqKn%~*{uT`cdQAE ze}2MjWcFyilgxYz+xC7t^tVKCJtgsbKbQ&X_bt3>&5!LBd)`Z7r2dF6j!_;%g=jo! zSlQyHV(<8g==Tdr!bpp}x*dmp;jCLE8CEg0Hb{?O!)0RPk;>W=31E3}a^OW@q`cJ~ zIl8aMdEd>ugASKA+jxr_dbF3|c+NLhi+gZw z9BFOZQ7kqtEVa&{o;I93=@ zwqe;c-AG|pN|6~+R*E|4M>vB1eB0;{Y9P6;#A9v15Et3;cEz&YBxXhK-1q4P0xK~D z=a1VKT92hY-QtdojRlfRnkSqB@&hABWazOTJEed6XSRb^O@9l5Musyc;EVk~>yO*V zy{Us~tuPt05gyUSWh?<=9guQ0yS{(Pgk7hd*#F~q?$|TFxQbp0YC-*x3Xb|0U$_SV znUzSLv>P=R7N<9(7=UCH*7|#2Wanaz68}ZJd`v9UZCuqP^Bk+M0^d$SFgbvf7Pzh7 z|C#S)@&=Zz}d?&H1`s9y*79{d&@XPey< zZS@SHe!|*W*iQq8pFRW8gs1f~hyJwG5PnEd3#EB7*;n@?Cw2q>q|pK!21kE}^oU3U zen>l(N6Vo(di{ugOvq;27?N{*n1lTeE?o7}_qbW+jUyR|7N$^70y$=%vIc0sdI^uA zXr@FFhbunT@_2~9NN^_4F3UbeE#Sq2ORmVkdN>E>lMxp4x|Mu{{qb2YPb;e#QPNxt zfoB==El8#Fk;h3me^Lw|jZ85dnsL*RSSWtxzqE3@whhb`f6tP&iS((!^a^ctj%^Oi zcmiLJ7GE}s96GrC(b6UUx)?lc0^tC!6oU?FePBC>-P)|fDQJ&_s;(c%QFfS;?=}x) zWMcl!;8r&V@&qUm#&cMtB((y_LjOnGOmt)VgzrJ4@8_&Li}n-iy4jQ{?ZftZ-P)?q(WMkDN9R5 zeHT5_>BzDR&hwXZIUE*oasOnxWYPDVA{n$!VnwNHWI6miuEuzP`pJ}A%aBzSr!bMD zZ2*F$h_^pLn<9WX`<_nV>;C9bpufFL)}%yH4-Tir``b zs$RPZaiF}0;Q`y;3=!~`;z8ioj`JLbAGyp0R+!@`g%uy$P|ViHNs|~Icu^DWUF;0e zR;Py&+ETq>0Lr6zSHng{$dva^O&RRh>#!>RBI(jNnG{3y7jf<@`V99MWjh9;Vk?V) zKw(V1c}{%x-4M}xEAd}`DFA46)dTO-nEL8EKUG`6}& zsrNq+gUvWui+q&W+MROWTZz{|uOjy^Xb>$|&{h;Orn$X<0z>*|t-IL$SU0v|$LuG; z`FGVx@M0Tqxnn>Ng>*mj8D`-L8yf?+mDqWv)itc~i`s2o8G6QqcJdx|lb*ngp8VW3 zKgl_^n`6Lh$zxwx0nk9O;VDq^{*e<(h&1l@i{%}i+u^Dtl_oLka}ys<{RD>!t6KD%BEqh|kb8@@rjwRyN%n(`SboDac2u>YC#{ ze>F4R5s>0M8FQL9Y4;6-Q8+E+bkmuYFn^j9UQt1Ur(Kq;V|aTW&h}L1ErxKt-Q1Yv z$Dw9uJD2xZ1-+LE?F?bDCut0AGw4@``)wH8xa>Ob-PiKk?VVaSR{e9rg6|G|dtu1c z4W{C(E2QMpnD==9`2CY_|1G$e1HoMm<#cND*A&=`=MOQqJO@44>wTUDt>qh4mGOje zx2Lw!a-B-O_{=4IiZnW0q%*H$T$qI4cCl~peinG1;{i;s$W3JWB(zqzy{uWwwc6o) zK<-@(v}J;*iuBsIabLxDxrgni3w~mFq*$g* zMS=2Yy~8E+?4*j#r3=eh*E02+G{;9kMWi8MFOyrv1r-FG)nAnni7*Z36*hr!>z{W!PDIeb5t7hP7gs zigL|v9t}pHf)h3ADk>uRUw+%S!FEX#QK*`To#c)9k-_FBJbp>r7)%owL6g3MD2X$K z?FKMF^DTN~$2`B;$R4-%57moY5@ih<^WqE{k`GpDaL)S3Uw*$Tiqg5mz50ZO!~LFY z;Z;(S!#iRJO981zIl13F_vThBE_xy3#NQSP~lmj;4a*_Z{y2`;CVl@A}DE) zR(>NoIl6q#V*GXcd`4jF#Fg;9Dm5SZs=L~`4d*@2fOO6_?SHuVyYGm`{^A6-ok#r} zx#LzR(CnU&U$%GezRNlEr2xo&aDK{;eaAs`FeAnCtuQkWuhHy_)~e_O4{5|7U`hwG zwko!=icb|>Zz7R)hhpxOh&nF5urUqJ7Arx7=-Zfg>X?SuQ8Y&2`LRT5`72ySuv^=C^sCbDnd~_kHIxe+W4Deb0{TTGv`@@BKIh(!Dku<_RWLOPFbe<6Eif z+ZMj{t9HA!u`y8;Z^hoBYQ@rB8dt?v9f+fjK{mTv$c|~Hq=(7U8h}-36+#t4JbYB* zi9YYXW6Zhhr!%0*Z)5pRYB+9wdHRv>8mEd9M&;u21HU|;Lemgx`}ZRTE}Uo{g*JUG z<2i+gg=9epmUb9N4k0%)Hkejuk-K_j4|&B8t^BgPMVrHZ1`T)%whx};>RT305f=zQ zBO<3hc_oodyGC0Hs61(Hw_EQ0n@M0_LHY2%dJjh#*}Gzr+1q&!xNRm0=wyXFBKOYg z{>E>cnSxGzX?|B@QZtvw4_f)IIr?s49!?u9F%OPp8un)`(PJ29mXt*U3aUxihlRL65z8sc3CgQ6nv>?e$(sh7c-r5LWSTh~7qx4dh|5uQ^B z61J^d59K*AZq%ktFI>skEMz@Z%X2QRcqH#-j5u%Hb$Ue}BM@%jOKQ03z>-GU|# zzuhwip8hWb?>G9EtpqFQ$fs&Tx}G8@>Qv*s5_%tiw_4C^Y?87T)NwBkG9dqyK!8N+7O0l zVCk%xZacqTDY`*UBKZLKGf2%vHSg!X>miw(_LO=XnC8Okkwv!2TiSGzE~)+fyJ2q= zN@G0>N`L4BZf`pw+g++Tm%3x`ByaPV#c}qRk~qck<0~q@p?bn%UNT&ya-t7bP6$WE6?bqN<2$^Su14h&BJwdLf)2MJSf(NNTtj>Z{2Yx z2n`0kRyH2bf3}d{=KYY+GKtnsW6@Gd$LsvpXjl(+&o~R0lQ8#0dcJs#+&6-CS6+N; zT2D`@3yXF>UmYgC7pT$Fv92db59etS<VQZod(YuI>-lb*;nf z5mLf*sM%+7t48xXYYPjH3YY%%`HRC1hF(F!iffJOS|`l$8=Z!J!VZ@+&1?4Hd5p+Q z*M-Hn-iYO^WGxN<_`-$rgY0$pq4SyBwL`1c9bH-M zx-BP%+|R{ijX(8ZQA*>q^M(yi9~ZR*np+Q@srfvEc|+oS$!vOE1yKhcA7P2|cyH2T z@h$JyhWQ4!odz-+53Y@7UMY0S$5X<06K61f)5Tzu^v&DJ_2PrGw!J2|_zw5gwVt!x z@oAG?`}#F^gA~1m-7YGGr*jjoj{A|7*i(ARg~^us2sY65y;IeN;3k2K+i|WYmp?PB zXIAI?OTmXfDu+qdm)|++x%NO`Z<0G|T`zZVZzY+ooo89h3v@W@v2*^OC8(U<*ZQ%4 z2S>B$w?nh=&<`(RvzIyJb#%#bIdDd+BB@NJ)Q_8i*7MZv4l;xswwEujpPaS%of!6& z4+`L!FwV`^4RhQW9!~eqcr;q5^Kj2$mtMo+i-Wh4_~(X=_*fS2vv_=%(g&`k2)&L? zwr`qx@%}qxI!)Z%vN_?;ah!L-b@ntp4&%8IJr*5fY;Gy;I=)Gm0Y28(~MQ7D;Ee(ru)F4vn7k zHk8(O6uDa3bNW0AYUzN>JTOw^Ide-E3f-Ezl_{$44#isAubp+#x?|lutK~kvop&TX zj%DwCd3&yT_kQk%uCedj{Z-*k6Vp5#WoXxd$g$3a0A>X}4Vk`kha$q;>F!wW+7Z{R zFTX>N^588{M$M~7bRO$5G6w-!^Bp{JhtqEI`7GXPK7)|zwe#z;O$@E&&_iCASiN4t zasSXooxW4OZecz5N%dtPy<`_d1Am9l(fd4qDEn^1{CGlZgU)5|B%MF4@BCU0Sy;M6 zLZ0DWSLz=Qz0U6~il}es;Ujv2#=17VBF2&VEUu%&tyio9dQ-0^Rg2vGY7()%YFcDV z@6p(~-5ESad2jigu>CC?QTtn{WnyS;@uUP)TPus5Z%UIGT-)Gr2CDSJwYwJHqsi7bbiBy!`-uOmpJUcpWOC#T&#wS z2U!NT&-IF3wl%l3CVUq}ad-_+ZyUQt z>D-f6Ve`6|M`~!ya~(XqstNP zD%B0O*R_y78q3QggU{eN*TOIE=E>zYc{6oxU>i2_zammjaYIF)Z_OniLvtW}KVvxg zJ4iwTEDlo`>`#(nxO(axZumy-sxNWi->x4&F(#ZC%w$2c>gp6R+pG6u8#}3i`j}jK zJI9W1i=7xfx26pHmqP$bbn}qS+`Ra7NNLh}Gw%T!{+UO_jUiuS^FFjdNE}p$3c$j{ zNEp0veueBOFb7{ih@f~!m)!8>!~Jss3&D4uUBr75`JWfJIh#3io+CudJus&6_%#^L z_gAhvU$rPZ9rCd2F5}u^^SG|8x@nS;`MtY}=HAVBTh=SW4G5%gkrt=^Ic?}_hQZj_ z7>CCqx98_z^m}5;$+WMiKn6Z1DGmJ#${PMz8zZBJ!N4T{H*po7)!yEVmtO>h&Uvg| zH#UJ8`tUcw9W=ifE>;g(|K0)oDqLpgmYV1w9eVS_;jX3Dbk`Kj;``DEU@f2jfaK7D zt?JRg%3hGl298!MQGITU+z+>dVl=r{Roqva5Hs95K8y2Mv12L2s|7zQNLXphyK{Ro4*<3Tl%L_T&VuK#Qi6I z&1UMXrWC^d4}K>W!Qb73lY0N7_6ibafT%YkI{^3pi^}f=lu>zG_ffZzjKE(HxgsfE z36x+;FltCjt&X2=ci5gnl^brb`d#5{-^h00b1{v*j+^BjEcJSSHCD}k+^|mE{~-vS zyv=7D+Wu-B-}@ftPO-h#(7fwY%AEbHfwIPC;o}Wg=h6m^|9pwFf}(=5RP#F-%>T&K z_YbuKtV}$dSN*CDH)G5@jbI4Myx%D@|BtsHO8DX`@Lsw8tD`~h{rw8h>JG-c?`Xcm zGg!?0((1me4|s|S%`2*Xx6A2JngckS`(aVi*V_4;-T5UYIJA!>Ir!h>Gm&L|e5~3^ zZ~1rDJEp(B7zYAtC9BNeef8Hv%OpM12)K#chqvqP@4=T4YcJtbN^rvE3_9+m$$wwx zM`wEGe_#+vg|qqT@2q4zV#N+ ze2!N7%WimoYw(gu3Qk~ChCkN0C65MozfVmmh}Vr^9y4h=?_z{TBVD#mCf;zrx)8ZA&x_QZe_j6-h3=oDY#I3P*vw56&zM(!9Q-E# ztEcWC{D{=$EKVXnS?zrQvH46*7dX@m7x~%ndN9L@GmqwNoRWWYSWO|Is&7`ZVsH)h z>dw#c`H%%@HC%l>tZJsMoqDCCw6am)6-#ztsopOD?OO!0r!8pdNm#Y;s7Lm`B+i zap>5i&8}?%4o#xV)^PiZZ$e{*e;kL+*V25$trC5Ry?^`T5Y(`Hg6pe8ZHCG`mEsYk zGj(>6YLymcd=t>*NJConm1;vM*PybL}DH>ax1}*&7>r zeCy*eDb_D{5zad9p6gJThJ442)G%r^+noo?hp}o2 zmDOM=zf-tOhui9^lCq{MAY`cnG)Q+s<%jq%6JSlIL|%!Lts=;bN9 zV`z20lx=(Hhd#?FM0HW)D(whXfuz#Wru6sftXXdtKKn-MNxC@INTfzudS@N2$nm)* zLI2XVNdg8>PrJf18d_5 zQ`W%DA`gq&MB3ck+^s-tE(qJafJ^yA`A- zX(bec%9v8aVPRqV{&x-TUY>tyw&ODW3%56Fq!+gws?=#ESYy%V?uX();l8@jvfH!|%_pki6bL|Mz=FU{Lv|Xz$ZSp+$`S5)s1XP4Z-7uzo4j z3Go7i^E)c3AO772mm^s?C4t@0;zR>p3QZZ+Pf@vA1V=?9LU+ zeeqm|?+~+`<(2!F=R!bd4*ZorjsT>CC zF*to{e_&+55q4()Yc7T4e|*Rk`60AzKv;w_iAP}bI~qk2pB7?t!dm>Ib(cB$NkXI8 z0^WSx*`oQ)xfDdPt@8_gbTp+_jo@7`8)Xu^XGK-<8n3#`*~_~Y_(Ks3IvD6m-Kbo?=Nouzzt-WbTq zT(x&3?#6RR=N`ULbjx`*_W9(}sg&;md#Il;l#{#eu&|h`Ma4svk##t6ZHHtM( zKt9|`6$8T5$)pO1eRACHi8pE%x@3`+zUM_|=VxJI~3Dg5AEjhcA^BKFam)5_Lv(S76H%sJn;`g8;} zGn$Bgzh9loxxR5-2U@SKgJh&F_m-S!)oVl<<67y1@%9l^bY%!`HnF+>TtUB`?kmg= zP-02^Vxnv(Cues%Ltdv%CU<6e*)VBnrzJzw&wV(uWwUq7M09X9ZE?^(ZDD?CNm1(6 zzn-36ki=7KKRi7vp`eH14n@mq@i$Vzd;tQ$YjCM5c1QosI3r+`jrfJv4iQ6F1e4^N z4Zdr9IF*D+s8Qz{K0farIWaO{JadJDp42agyqoE~VE6j0ii&6t_%uAEMs(Ng+^%3@r;@i9- z51a4$$%DcmG4Z^5B)MsZ(rg{dOH=va9! z4(fy?aW~C0<5wqm?TycA%wMz>9sfza_HR$S>4M%;#`rxIGaRFBtvQ?Fvt4+p1>YJ! zxU5qre6w=RcR@~zqDhvu9`+tFp|_pRt(&I<}9-y%x`TO3722B~A;Q&UzvG{PDvo%2YFK zqrUTIqDvu^M-1fLCjJL1pDCgPAhdKK1eZdV?Q3&hJOwMY2Pfy6nr@#t9w$|@+g;t_ zaZbX2uUc~iWGuxeIgO*skct{I;DgAb+>ikO(#1bCs1 z%MASQ|HO5D`TX4@;dNj~C-%`cp@K?uPT`9Zla9jCkAYmeikxpc(5>)MJL0bqFA&)A zQS3wy_T*XuuhhW(PKwAJXy#QT(I{GNH&@@?%bJ118O8_Nvv9xt7j*;xa79BEcYg*E_YPq=Wl7Z4i0wD ztq4e>(j1o_7rI>+JJ>04!d>cP+jKL&F4&VIcC9uKYN%khq@3Jc$9A>)=1m%#9CF`1 zwtoA~0H@QPFS#W&++&qIn}nqD@$zg$QnCDI$bLyR{VuD1wRM4Vyzi@E-Dq*kS(bN` zyP~w@rQ?3-SGERHc|`oAXMV=I1t5WYPj)js=fF`9wGLk?NO?KV>{oG z271yw@!%!?@iqL%mjC*uRAY0pMlHv0_{+D4cX7k`JXZNbuib-}D5Qp|gv8i<7K&c` zfxW>{nfV=9NZpU;kB;(+ER8l82bFCVmd(t}Q;V{Sta%}UQ=;Cxx3?ff}+Iis=HsvQ|Gp#A>H5+F?m@nwQoWLzzX-x9|7*` z5vB`QO=&1k3zx{e!9n*zjS!Nrjyl2d*q4t#$k71=3bGp;v`f;bs^)C*Y8}BQCo?>AUhWZISLk0h-=cv2etag5`uOgXu zkI#{))?rULf|M+iEH*Ko)R`qV8;`S;blH|OCkJ(SaPEVQ5*ts_Y<6xy;db5Cnn~25 z8*-8+9g4;mM_X@6dmGPw&`J<2HMUr2*B8g@&f3;x2JzM2Uj8ugEP$ydPhyM6CD4O| zrDi-9UZTyMKPc#>`PMpeLV6q+NUDJNLg~AkwBL9Bx1t)qqWeOmbxC0Gx$Ebi_uU39gX5C0zP_J5P{lo@K7!w zqa5J^k3sT#_@NvCe_-AopC(F^`w=<+T+95zEVVkcV9-w9(WP&Jf}3X?x4O|C{V`hY zbzqz0`i9Fdd9kbL^c~4xRH>?d1e4nWh(5(EEQ=f4ErYY)>oZ<=t&*M(!7xJ!n?y;+ z_Q#5hFy|Z*?DTO+Y_`|IDDT?+i2AgIg?VYJ5=~8yq_hz|R_3-%D+LwR97j9m{WDY# zgos`rgV^kKT5ZzE3F22f1qJLCX6fAQKg#`0gi5(APfm0#j0DEaHX;$zA`O-n>v86Y zYYNjgg^)D_nm@9l%xFGCapST&IoDe~+Mu@jRq8WK&@@~9OfRQ1!dM{2jQIM9$&o-8F%VI^Hb>*so!`AbLa>G+iAHd0`=UU~wp-b< zHzE#fUsy%%$cs{>r1V;sV>854{Z=efJ}DmVdAjXv5Tz7WgnXM1&CRVl*`f{#3eE?Z zr(e?MY6dqVXJqSExhq+zCd!3}FxN}*Noa=@DL#m3QCBt2Z??Al$(tgarJ=~0E0a{J<#w$;PoP8~KA)49KBpaQ2QvNw1B~-j?bkHDG`4oOLz8o$sKW7W z5@!ymX#2zSZPuK80S#0&Xx8x5Yec{1dt@@vwX9xeYt?(+$5QQ@OwtirjINQYOl9T_ zjg$19yqvTPwPKA~t=AJ#_7|dz63;si@BPxUYP)oN38FP9`%+UIlBYx;`?Y+af4MTU zdETYZlsCVcHb~JSP1v!1Tw?s@OK>pz>?z3#8^jQai%q-`O}*@WahbTYfxmzRz2s(Dd@~fs+@ePU z8alCQky=o1a8wpbD)t!R1LrhX)&9aedz78DjGQ=fA{Q@7GJz6heMj4s5G2~}RYu_Q z`-T)l7a^Xp*S*dp`CYfQYR9CGl4pKi1YH0ewUTu{5tx2Mcgd!y{p8HhJ32JG=V@OKJ0}IMu!($qQ_9qRk zOt(AW$6A?=JM338_` zxsp+ZOCu5&5|p`R$G@`(!XQm=0G9n+TrDthdpc47O1~B_>>-8%UHa}^5gZjB1pSzB8l+uh>h z;_H~+uWy;T;r4YhVffavm_nu8rWcC8)^tsnQj`@VLg*N~IQT01b2Qt{-LiG<#@5EK zhC)=Saa<@))+efxg36*Hv&JH*!sU#az^Qpm!dfO-vil8X#i_Y~oPIl5JBRxg`#PKxp&1$b{s+ni-{*q`pc>qi1COSn}x?m?5&o z0f6w4-#h_=j|2=>XLG`{hPB4Z9h#a;_4Mi)`^`W){)EG~xjjwmOKx&Lb|Ju+$?N#^ zeo;%xSUV619U2+v1m%}S-7OiI;PqyPHLmaa{m*5r4fGv{g#r@7Ve9ONcVfci?VWR< zzNU0WdHJ1Hu-flVw9RR_Y;10=4cvWqAT$y8ni6w(vGgx3hcR zGIM@}U>RJYBH{gar1F*_e075TAL8jlRfpgoxE7kmc$`|SAt1wA(0IBFJ(EZyy0}oU zVDcH%7A6wZfS>y{M5*a?ORoN=PLMH5-6lz$*P;B_I->7P+Sr8HJNKh)g#)9b!H-1u z{qKiRthNF32WR$UM}PP+0G9k3-(I3X?zlM`6PJ|GMjwRd6&-B=;#alhB{ASuNrwWq8W zC`~mF)vd6XH?3%eUem_=vEw_~G^P&5QkL@7dXa>a7ECDHD=}c~{i?|I|85ZZM-W|s z_2FiF|MrWe5Yv`5L_J(8VGh5XnDEzJ0mGrxGr>zQwAn{Yf-j3AimN|XJ<^~+CCb!n zr!XwGeciPtXmw>ZZZ2T&NZHmgAdzEd=ys6}!Y}|gb_Xv@VM2?&Y+`(HB~Z#Kn|P-c zSjP!6HU$>dd8bkQuB=$LWj8YY3gFGzSPGo1qac^6#4#ww{fLpZO&E04LyvFCedd{l znQS+NE9aLS#rqEcDYA6P4wx@6?_T-~e$BVgo=>g^3?XTfv<17b@72>}rzIojnwrC^ zS>(`=gQWf2_e^C>`Zg+(!*z?*c}8y{ha(}hG>i-^{?ogeS!D@@ebUM9OO&)I8mdei z9+lOR*cTtqWE^uB6O_H3%&Nl`d}u$Nc9_t5)H-yuo{)On-8h7i`eTbUb@vo=ZMWLp1pM@73~FZF}TE6(wzRwPU1P zg0pL8_M5rURcSj;3vk#->4xj?P=m7mxS7 zb>3h~MCty?*)*cntmy=j=QaR)L-VyLel1NqGms2<#M>>dto&$PLV`sAJT5QW$w2YS zPmGKGH=6htQCyK zXusumR`Hl8qCN{q)5am|`V;~7AosWUqJm|tVqotcvd;~Nr*^&oq%SDe#8-!AFJj@w zoq$Mxh+xKYVmGdX^Av=zwn-a96?JvN;omIdWe_Bd@hxXvWJ;pGDR~Z zCU(z8aUbv^lB#@ER1AS~hqUZ1G$1^~ov26x;Zl5+vE*V`U4#dDrv`lqWtyL8}HUA*es&>8v%B z8@&<{T6$8kBPV!t9`u;{HgoMSIc@0d>=Lj$I~P}$>yj>2+B!5Q?;I|f?zSyvi&$67 zo-)suzhPf4KU{TydwIq!k4)A-&Qo=oVpREo8m^#!<8eT=fx`2Hkfx+mw?h=mh!WCL z2t^?I78kd;@)K!t)3B0s5w$$^ebxXhF7KT+qF>`H4wDa&L8BXF<}}trn@gWk!i`y4 z8g5>E$Rbk8PO?t%$3DA7cT}sQOA--Vecnrx0?`uYJd)8b3&h+d{IY$;el=hrmm8q{ zUL1!N3AWd;$1h%G;#}g?jFZ8f(aOGhGP4!CGxvrYrPk_VdywFXZ148xD63IZfoS!O zOPsa~9945%NFJlaH#V;#Bci@stRQPF1!~=`^R-E8jwDfDqKKA-m*7J(G-o6S{_vLD><$fp}^$AKe)0^QkrW3n!`Pccx=>GY&g%B7> zgI6wEr4_hirj~iYIW+VR`z)vhynW2R}S%}zo-95 zhVF)`@gz!1KgEOVwET2uwjNt*+=Ak_va;&JQPc-Qj}wNi?XAtNjeBy5`<2%D)PJYj zm+tmIQX21d9#`>J3@hha7v4Rce{q@3jm80KvJkAe*!Y#1HXClsjfYdJsvI{1B%peP z{S?o@t7)7MF;I!kte)~$mcum8HHp9eB|xlv@yg>%ZJQ~nyI)8VFUcdr{rC&SaJsw9J+XMaIXPt-uUQp;f6>ZG3%{Qmgi`_>F&Ikmti6|6$}7a}Q$q57%S$Bwfcb*sew zm)vr_QaSkpcm%#VMjKmyObbbrZEaLeBj{Q5+dP>@d`nz$VT{GqdBxRUQ6ZN)XwlgD z+f(c7lHW6Wm|rP9PGI7voM^oa5vi78oWM%pw|ZRiLS-jM3>@nHJeD()R3RoVqq{TR z{Sf|iwpILV_THMwvsbljUQ5W@ah$6s_{LujYqaZpG=HRLW`_SXH*I(ze`YKfipVPR zx^%UT>NO>K*5EPFFldJP`#UJev#fllO0JCuB`AA#L>hU=^y9U0qCC{FO8LGOG!T*y z&Ra$!w$R5WLG`SR{7Y5mhFpx67h_kfIncXEqm3319j$6-w`qxx9~*%JwV^OsH>b0C zi1-)@2^7OOOOGbiqvN;ecMHt&1!Gh+Ra9)aMpKRB6XLUr@;XW(fEwa(S;Vha->cZ? zg_VkCF(uYoCfA4(m=%~M@;XG9s?I3q{_q814u(sR|tZ{+)<7s@LP;IH}kSTj|okvs)v=UOSIgpj&4 zxr_a7CQyaG@qHWK6pS9fqvjnhrN9dO8c+7|&Y{ytVS>=Jcs|$&=NF@qaEFM0JL~*q zjWUFhk+s_azUK57A4uLIS6*H#@1YLv8~qx&WnpOHy)=|7uyA{4x<2Nv!R+GJ(`9b* z%Fs(kd(9eCCh22BqTt!J)jr=hbk#<^%Sn&kIf9MWl|sah~F zCNov}VM1W9co9XCc*WcO|CM%gMc_QUpcX;#tQem2awj5fIvR4xX3UA5i^_&J#vBO=X7$m>5Rd#2^aK z_$wq`+n8&~LSGgyi4t<1eSB4!@c@0C^GqTDA^j&nr=Q0)W{V8cR?}jgUrnxkpu&l2 zip64ec`5dJAP^Cm#m`_4C%aM-fu-z+K{iFNg#rnI@zP zV)rC>pC)_92ahs6>LY5`_fg|_Cu03)~iY#R2j5A6fv1nYvQ0*Di?TQJYKpD=+MZkHn z+b`in4lA7N*PTZg#r=dC2zPYECg;o`%_hxy3#8)Bb%Bbkca`1akQ+R#=&$G`1TITX z0;1)O|EV5pg&yDj_b>KJqQ3qVm0DRQ^gU3pq;bsH=3I_kMn**|sroHSq1@*740UjJ zv^-;1<=$2T2v9~A9-ryu#ecA>gAS;Yg}N zBW#@;da=zzu8*sxff2HXYRM%RlhvjErrLmEc!Yiw5^a!H*4r&{;>m3u+{sCC_7ynX$ zcCFQQyn0R<6i3S{1e`{>{AYdD$Ws-$xju}?OW4@o z7Wu3Xs0JW$sN7Dj^k9OBN)ga}W;P9KJaq@I#VuoimT)q=K(Ou7N7ws~ivl1%DX1rS zk~BUk`E;(7BBN-fDnlN~@*LKW7JHN)t3fQ_8Ua&d^E|Y*l3-^_p%OXT7)nee6Z_+5 z&;43Jgu@Q)XxX{JZ_!K7<5N@DTsm4Xu$9UxOONb33vrQuuy*QfWSrmAw_xQ$fr-@9 z(vi{ELX)YchQ@6N&tn~eifKCHf8nsd|K7YNru;eM z`yN0;Bi<%oEzItc^*Pgy;~Yz$i&9ik7v;+cG|BrJT}yRSATtPH_&Ii^iK$0$m%VH z1bxLMNqDFtY|R<&rU~kIle}?X(swT06pL?m2nZaZ&gkP!2+B1fynHfFU!S`f9k$=< z=~nB@vZ7Ap>gi=G`IfwRvLgH3#gH7>JAQX{sYREwvFccu3)wsVVW#L0iX?)5t7r3Y z#26kZ#zf4`Eh)FxajI)A<5)6^%pG|_Q^L@REvnA`-Oc`uk`i|CsI+R{d(0Su;gK-X zCm<_OtcRJ=>Q8DKiLHE+-5LGuc1(SPJ%`n>61IWw7!*P`w$z_JaYU%<#p0TiD%rPY z;LPl^y+d&s_kQFfVgl*A*%S4s_XsRJGrB0Xh?=ejQ&SNdU{X{n$~= z&sJPsx#+T_lJAP^vhYeWCggq5Eu@lMo#H)imioNqbzCX!$pE*o9bz`nuLeVC_S%^*J#GQ;+vrQ+G-nw+C z79C0Iul-h3PXNQNyc{!7C^IulrOw>=;45?Y&J6OVWPGl6Si7&VG0Cg6k_no9nb3~F z@#Qu~sfZlX%a3;=2w`60ri(d%Ib*`3zYEAYtUmYQ}4tzg+%Q@u8(?W;+7mXWjD8Uwj{nRukkW)Yg ziXMw|pWQznR-WgVuwnAmp>L%35LgtVO47Cd67NVXO@WzKk{S*uju zn_M-0d5=Ea^{zJxZY`c<&bw?%`cji9vAb`zMxR%POR@^k#t40EHm_W^uU0bTsuEUI zT*F@PS}Ubs^^sNl0p60VHq*q2|D~aLo4AkRk-4h+|ED}cY#v<pwfA}NODv$AxLSJwcF>FxhmDIZkQgQ!(fX%icSOh-@#%MF7G|BY$<9?9P-cBj zqXy28vZ~*mAd3K^3M4I4+UpYgR0|WMWk68;8p@HP0g^Asu*Atfig16OICBH{h!~J@ zmz)hhai+ zi@QYa=~CUes%7j`yB19Mn{!ywAgel5fdUnar*V=KG*~MyYZ?=j^>CS@QmJ_T)p{34 z0;+--X*ajZ1gbydyd$AT<^L#;|F%mx)3^M?ho1&p+PK=PDQXm{^x|sdI9MSXI?rpz zX==irVklET!Q_$BF?hZwH!$C$Pm#pwgPz|knq|2=6)dk7m|pp8e2(XB*9Hu>aeT~7 zOLOF{s;^@e4#ZAinFIo9P2s#8J>j3s2}^bYP?`Yi#>Vz831)s8z~4Mf1Hbe8%V`&`aMpFa!?f&l+do@>qf>N57;FE%VlN}(!N#^urdMDiK`|N z0HZy0v|*C(l{_@5qJFfeNlHqU4sWN^%1dZD5XG6ERm>YUkLmzfL_*DEn`Yk@5wR^3 zq)br%WmVStHSB4AQq=qE_`?RfuRsN29o({)Qk$0$QUNw6cR8ry*{BK8!P%%Onfpav zxoTfKS#E=!sbjvyjQ}aim!*o?a~^2?L?u^4n{QDG7}A}e7YEm&h1au?zrf@?D8{FZ?;58Q_KDs#WHk z&k1<1dkpVI4dB4k`MS~_?G=@21bE)Ao*77oH2!_!1xD4B$~-^W>^FdJlu$q_peg7q z^#b+P5G7ze;wwYzU;_s)FJ12lJ*G~1?l$ze&pH>S==j*VTSK*+{PnUzB4MlMmrlRP znt@}jnkINLLrH5b*kNv|IRhy{ODv+e>n#jD(;#hgioj22AI#%>l^F8{PWx`H7y@a8 z7iUWF}o9sKg9#ljb#?W=RH zg6FdZ1uYuPNpsLAqDYG&km1Kt>D=6sccaj-n|?TMo@~`ILp<44Gq+E=$a7|3&e&|P zHesud(Q2@QM0ne1KMRTe+_{+@iIII=7Imn8dZXv@=NuKz`{13xGTSaSK5EY6BtqX( z>HIDu!gy|BeW&LMg{5CVC9|v|t(TnP{}~?YbL&Niy+eyO@cQ+(3s}I#?hYop7(Z7_ zx;uv;8j?`De7jnCVV8qD(}gbn@uNL^$q=pT^z6vEa{kxRy7?=co8^Xe`eixJ&$Po_ z9?`pjS({qb-tW7j0+LL!MC1$i6bf$|4d$H93k`9j!ip3*GCw!`h!gcpO_wn!))hBk z^BB=SXb5;tx|gUrbk?4o?h-(n6PaE^SB^y3~@3y7VKMu=@r_CIo?zbK1Gm zYHbGB-2D+{saHOQ@~21r=SR4TR52h82r8E2g|=}*kU;9tx0%Gdo7uI;C`3)Ccmdqz zww(2g*YDZSi36^lzx)_M3JQ3+pK4z4Qpj=RZ7AH|!)fyg>W;U-=?79oz^Vp?gfg)3 zl&`r1ksa`YABS0<`uQoVYStK3>z4ef4qP`fHvL70{{`e(^#;bOHJ2-AP?my2l!|a` zVhVYXsyX!nbYv+oaqx&%$t~)-fuGEx$_zRVW0K(xhHd8e1cmhjrf9NU4;vUCF58^C zSC68L5T(Ycnr`K-hM%|t%lSyJkcNY&&KtHMt!M-N%P|MQBkD8aT32)1*Ctuo;l#jD z&W|oh{u=?$*!*9c<+&_z_`+=ZeyN)p-+ki_kG23KT(#rnP;~S717DqD^k8ei-1KSH zeCycF%%u`^`xWi$D;)pkjgf^Ji8?_h(1~xK?WY42f{`VC&=TYBoohrSAzCX-A^RDY zfC|ePHUd_I=xY0oL3(8COZ*!1PhKqvVX*Z|=DYBn%CWNUBNT0Yd3MlXE8NINM)I``&H773&1F zIIQ|gGAEp0?y|5AkQr_VrG7OOPXRhet6O2%SCPN^Doo$q>xel_vfGYhJ(M3ac@ z5^l;$UsX7;*s>h(_zPp#4jP$M*}pJ=rU3C>@ixqMVfLTxWj_v`u2ykGj| z+k)f=S~-dzST6cxdDd@V(f;NOYWb8iRO(7jI;b%D@a^nNs;7ld2QK)RVdhkLF@8Hle=_fzP} zQ6_iKFee1HEdJR)CV?@w>4v)=p84=Zs8F^aIM@HKtSq|b1#_DKX#PK{zB(?-u6Z95C6$y`>FzESknW{RI+yNRQ2_w~0qF*5rCA!3 zlrG5yR=T@$e}~8Sectbnf7ILc)B@ri^3}`ir5S&Q9GS_fB2d` zOIs*6#Er5XpGR%r=K7I``KmgtM*&K`bw%he~MU2C5rGv83*hu42ZCzUy8VPTG> z6D~D-*uzyqgs!8doY(srS4=j#Wc0yX7US4Zz)i4t9>6CQ6le5PH?OGvdshen$B+y2 zlP({R62pOEw{Lbt2kRA@ph44U_&f9E7nu)M(&#%oNC_8p%*Gi}z_0;A0f4zZOYQ+| zuBK&o=4aPTuB|mWY%P@vu8P?z41l@c)4PcUh>4(WukS)fQqn1J>4WZ8D*Z{k!SaWnV?QUJ+N+79g0 z>L=7L5rlQZZcfk;`uS>>4M%|+8edt{t>%G9`zPd6u+PV1aJ|`|(KG-iwX(BnTXR&S zz!;gFeaV#ioHVRhcsVfVMr$C)72B{h1B^baC_6@)()UUIj1u6!f#Nb}DMyiTCAOOu zh)R9|((aQ6E*YU1(1?i$-iCeb0GtJZ%TpWUKf38K(WK%Ez(+ppJ;WZL>ih|4;YXeU z-5zh9Yb&?QK=AsFN^ca#j$RPK6+sR3)|G4*Htpa`^AE0e$bLq9srHp&y_`0jMh|Z0 z(@~L@=+?X4UwqYGj}zE9JM%GhA|YgAug%lKQq;I_LRiSIE6(ln^M{|&oQ%S=hgL7d zHkz1Au2i13(Y<}W@btxtft@?=SG#?Y^vK@sZ~5M{E39h_h3`5S&SdBt!OhzLToL?e zey!Xyc&D{(fgZVg^H4bofK?hauXx-YG+qY&{R|Za0?w%zb3ijRn~U9p z8gX&Nj0B<6YR|p0p{7U~N0!nCH6;@*g244c8~D*79tblI(CnPrK)?E94sKxsrNe3{ zmPE4-r~WOTzJNkIkrAU2aseJ}GBShl@$X~eJR)raIL&SdjGrd}2XQ%U@H6<=bsRd4c9SfNAKoZbysosU8}d{dqhK)o*lgCW1N>#*(kR z4-^y)qUQQEJQiRgnO}_Sk};HZG<_oYnNJ&ok7KHdN(_Z~gIFyL`&x}L%GGnFOJwyn zYi4r;PJn%{%GZ9BEGE+)va1C_&rmbW`omYxG!^a>7}%F>Bzv!WJR?!&4ILf_SIgyS zkFSS&O8+sAp}^_wfERD4)=9mqk2$J2V4aev*ik~zG5BRxQT;8;M285Rt*&%^hnp;a zIXSasQ@-X>_pbb|ARm}YSujh+d*p)+^-lyKQtjm|Os}4~AMKc!ySXXuyV1owOYO=i z#NZv}{qXJ?M5D2U&<+R;0R|o1^Zuk^rxD;#!MT|XZ*-S~v>F2TnLzV|bcDy@f+duG zzQJQ%z_O@5A?>4@=SH}21V|1tOFYP`czIu(`ECPD*(cSfK8xW=Zb0XPg`P6I%Yn-V z-8p*+%fW2dLT~@TELUdcbAl`f1Pb`-~*<7h>rvrv>;ag0LW< zNq}f9%`9~8Ufhvvc?>_XGqv_g1kJ{?Fdd)_!aunz4uw1}#xm6*T60YTOt{XCb{<8R zp1TC(Nq5{DFOvT{&&^G~*hf`vETUhL4sEUUA=m%A=05U;qFdhr&P$Qka3~;KcMewB z+O1Ew0myxVyEM#Gq(AY%vTR(jp#G#uGrK5-s^J9<`OhWq#Pca{pmubs@79P=9HEKn zi!0(*S28@FHC@t*?0nz3@DmQ@n%oR3dMqyM+G@grQ&5LDgG~rx`y-4XfD$S%?aeCj z5Se(*lUyWnf`$?pw6)nxJ-=$pvF zJ72te7DMj@uUeR_kN>096k68sNsQA883PmRWg__1d_uXsW6K zED_$jY{yD6&$6-~OnF04dL%+eIId>3K-p;Nr=pd88=E*DP?WWa>9I<<=#=;rKP1S}*9eOass!{%W0& zVvrPm%C+J7J+5w`5s28LOCNA>HKSxt#%^9Al*&|LD6OfH$yBK^Z8`iy~pT-9l+c8|@%IAzI zC`7nyw+J3@&w^u|zNB%VG1t=a7cqv%43b9?ko5w|5V~>ghrK-X%IP$JP7Vs?BM;iCSq$CKnDuFUem7n>u%&?0+Ec{L!pfS3q?PT1 zL$M6#iNd1T2^K-ej~WXR$cBNQfUB89d6|uHpI4)G<>YYz7RYvi z=1>BlU_*-n=M5$?bAh3Gj>90J*n1tVXmhpL#r5tS-?oSA1So3RXIBE-Rtyyo{ z;Y}N}5MbD|zpQ9@7pkL>UHdLyiK?(QJZHt8M0j-WrBh9h?1U0w3Mu?{T$Dr^lqVin z%H;>tzO!&7EUT75nTf#!LDhF5S;Sa!ch1VbB_X{tA+gr{=pzDT_;zf79|b4|`)#b% z7ySqXQIK)Q#{K0x4J+?|J_VFx5Vf)jNa+Vs=D$-rs58ZmrEV?{@)&xpnHvf?eguTk zB+?{MFg)|3p7R2tR)8e}HDspXO?SM+Lm1%ila5F3QmURy?aG70zvW!i@$&}K=%N&+ zPs(P)t#wv|BA^JMsw7uh2|8g_F0Z@zih*XEI_@V%b>wyg)SPopJ~ggKT*#~I6EHYn zV>{29ss7x90a7yhUoOCY&HyZGU4}OtTM;5v2;f;Vu^?PZd6B3;mcdBCc~6`DE(-3# zuBd>$#e7e!ZCHC@xw=miQw5DsR{A66{|T%?Xi8{xV+Kqpm={K(*qF)mS^qe>2$4e| zkn#dsd_`=f?0oJNg|__MnW+y|ay|bYKES~y_dj{?n$B;0 zQA|o>@8SyZ;}m)TgKs)T;SGW>7g}CgBLn)F1XyL?^WwYKWaG57#=b9Z?0HViR)p70 z>7oI;5*XZIR<3N6)oiWXR?fjI*5;e~T3v#=9^L(MSf>mPUfcWzy(jYvKLb(W3v|!D zGh!Kp;*w{+X>(B<`i*>&HCze+-@Q2AY@KtQE=xKbdF>VHE@y|^)kkmt3CTD|mbyT+MS-``(_s};qbRFZ7M_`T0P@9jU&qS4PAiExBe(XyQ-Y>3{!l`xU z4Zj<1<>Dw|gLleRdW)L4b*)6oC0Hd@>{q7)i4gd5>$`9CXzi-+7v5%i@|rYnOX46% zm4dQ&KA2vbQQ&HnAqlhS3$ya`(~ogYj&81heAZ~Eh22$1DW07iBf#=Y`$aGPl=3js z2O_f=fFa36KHaO$EN-a#gxs+NE)zBMn9Y!~VZ%>Sl|WZdcXe`DLQkFf z95CYo8XayfJ~?S0^i+z}&6%p;$upg-vM22(PBX{v1D;Yqw?s~QT_9Q-nbtTWl(^Fu zCKO~At3tKmmt|4{U9`?2#313r_PPZGN;%dBZmf0k4By zJ>T^u<>9fZ4xm^7+*QZGDRTFqRYg`U1|2o0d38iUE<2ME;m20INqG@12xbG z=GK}Sdx+as?Fa-rvQq-=LO;bFa_?;~(DW)OC}>~U6LIR=%e9W~GZ*xjBOebcnRBWa zbp7)b%KF{PqXs7(BlLDs5b1+IcDAh^yH7KXP(r#;)(%jXS6DJ&;h5y8oy-Ipu&CAf zr}iSR(M-+njW73|8hSspltwQczi^Cbh2G} zknKD~SRmRMO~#43Sco&ZJ~mb3ijv=Y!A?7LL;%0ncChLd`!iQmpbt-YxqmP&t#t(> zqmEfdK$N^-V?o-_XozQyKxW;gz?Fv8HrmqHRj$#sRzkZMZr+?nSa&PQ*cqPW+>O(bbP0AmE$qR+ zH=CDl#U@^?f?v4Y@=J;{Y%SP@(m|rAsI|g}IAGk6`ZSRJkKZ<0M9_UmdPzge&tOK3 zq}<1#JO%>J#wu*Z5$$lP9bs9YYyzpw#;VlqVtX*_#?AyFUG3O2xFG-VcZwQ^2n*^I2g7LIrtK32HEzVoPEnlL3P*J}fj8qfV&a zb1SA~sJ<%ryzai8U7@{xHdU-i0TA%CRVw%zvfpZkNnAk90^h;T<6AF>Mk%jXZ3ZZ+ zRS5!v>b%drs{ud@1Uu&57JxOkJrxW^w9RuC8`jHZY6HU#?3+n;IGZk2{iiWn%i$RX z{A-X0z5c#?ncD%;^SNEWs)wIt+Pn^a>D|;XJVZHlg`vvL=cIm(h==ziPG+{HWmO44 z(5T|AI<#M#<1T4>Z7Ojm#Oz(>oGqY=MeDC5f(&lg+fO@AiYc~kgNFEDXZ?7>Dl3JG z{GNBJ_2hpKBO^hX3RuzFItE_TnIAh@V!9mndl})-t(;>o#g@E8QdTw_vl!E>A&EvS(v7rm4|1!WdUFQAQx{O`r>D@QKrUa89WHKZ^D zcQrp=WtieOm9c1PgRYTC^r_Qw(s8H-@2X2l#Z! ziR4~)>bj}P9c7=41EM>L$H(@h@2&${2Z$q*%a<{ZmqKV#dGR?acU+EyKWaH-9~OPI{<1-u#g~z9^7f{SQfaM%bra{VU{Y`lRUrsJ zSBvmFd!iU(eYm+VowRDy;2JVLM}2DO`B++lI$!{X!%Fb{Y8;vEdL?A>yv)L9bS(oI zNgAm1PB(ACkL+6KTscIXQ=`hFB3YCel!#BIxE(|>!!Ust?9cxs z1{p0NnBB`8@j4K!YPb>7?hMa>8>Y8_WI5nwHp{BeO#7NkUM-hvtR$CHMQDAlH4iUe zndKW|ANTECOIuu};Fyt>fzr~_7fh)w@U06a!{%gwXV~zBS|G?k`4+b_w6T7i6Re9#IJ_@sw^k@>WUAR=c)&J!i}zb*;N5K023Y8IEhaD zY*Kkgcr5Z=VIfF2z4;uL5*r6fEm!PGH^?|xV?YqN+@%+9@G_XSMyW7Jay)t(tMoWr zicuspo&P@&Ca5o0LDysExSDQn@7e#wS6+#{0&%HlNdWNQ=ejut#63Pc3Vf2NKPsv- zDf6{>~RS*9|5j82(XVa?vhZ} z_Lt%BaDw;cn^~HB1)5atKf~_&`r}Y|rcEW0-uwbc74sniU-9=nh+HuJ!!Ck zN_k;`v*dhu%K5spBker2tUbE_Xo#`tiXXW&7_c%~XN}3)*H@z-JW+0q2^fQ58ksR^ zje-58KZrUUpbP@FE>Rqj*UqAoQkr1b<@{w36BjaMd||HrJ^NrqPH;}E4X=mi#nwAkY0oH91CuRa)6)2Q7-RlTY6B&iHvL&OJ z%I2LuEjiPAOAQS|sMgJH(N>3=J{F0vaE0Nh42lq*lAez#i2P#3Rh8>AeVzS;n>%4h zgCG)JTH>C26`84b((vh%j&2MBH;kdj4Qy0t-8N!TI?u9gzPS5_oRM0UUui$%&r3z-z^tgPGyrQHY5HwbbugCtjaNfy#l|o3?U!ApmnNI&PI}+8M zzPlZV3i(zLb@1WiggyB~OvLTh$_KUj`a*|#5Mm=^BkRZU-12RDUxh0Zy+_}0?wHs9 zkk;|n`warGPy=_)ohCPhg`qgFnQ zXGJoRW!;(6cP}j1T6eud%N~Bi2+YdbkKqj5>8qY!zfx>)e`uG}u!)Yre~tcD%rv%m znpP-QmAt=kqVOI(P>fsR9D(c@J3?==n6+eMj}muESxiR>HYxk#fdF!?Wz;@78BkUV zE=Vw4ah}KxnRj3KR=k|&`BjAEH9wZg-V<@}tIjq&CwJVGA*h;8hsE-@CtB1Mu!|j(44cg?MGE#%aC71O7;l075 zAR}|dMPi0XE8|^(F3QI|P&k{roaA;=1pWQkJRA7Ro{K`DZFXokDJMYwdZbbh&aD^& z5$Xft0WeNSpH12T%BrEE0WhsM2o6<)3>uQiDKw;*fR+ z#e5#D_XUa8uB|^ha_cLS>!yUx;m}SvRAHnA&dQ@GF~Sqt{(MjJUFOEPfY&)ee6gYb zdeNE0neX@4T7pjJG`ZGzk)3PXo6q%0axHr_L4)Q-V-_-^dfi>6%>*Vs0FY&F>c|#g z1QY;_CJ4oib6s(+eKIiw$Y9!I9rRce6JQuxe~P#dGUOT#tthSh0n}!zh%sqUO&XS* zgeV9k^WdCZF<9dWJ@Q}^X}Q6(+oKDnry)&VXAd}l6%9n!$_3a`Kf>=+lk}5 zQt0NZfXkumn(E^}pmqms#wLkiFz1d#Q>zCbgW#Ujkjg%hnH+-@86kh@GE?U_p+Wth zyoyCh_$sAfEKv^aVS%;&mO*|1TCT+nKw#=lBy3cC{>@U0GgtYub4^zv>9d|6Yb8HM z7GG^WD1Wr?Vxqq!nNQR=_>cf^GoiT`Q@zv6{Tyq1QDE`~p%RR>uoXKfJW)?7ovfvn z`;(#74++t5!}s|mNnf@)jFVj2TVCH2mR4EW3=yGg&>)%5JSZ{CLN~z)-3uEWzE80(0rJ~oG z<~dhzzwc(l5Y;`QKr~IxE0l1^|E7+7(`Too)P!5$N^wz-G?>qAF z&23Zt;4Z~SaFm9%J7+bIgdn%*HupYvnd|85n%Gz*E#xVI$p_^Y8qvN>5y3$-7{}v4La`uy~{T?R<|y)Cwe7h)liRgFxEdLKq8>;2%{R! zaS486>|pj(3&$rPpRp;vGRaRMIM4C{nC+y(V?1r2`|{3szucF1p+I zcIz+hc%2ujy!M)P)lfS`o6nlSaiYaMx}ns-vaH@M5$}kSlr!$8YsA11@8Elrgw?wC zM8Z^Yu^kJZrMZ%$`=pombno2vNtHUDpw3V9!W+*^6zA<-v`Nt}yIXjN@Z*K80MhBR z)p$>X8cDVxrimq#C``#8zBxBhp4^WSgWO`?pFGA3wSI5yVxzMnZZIxT{$~LZ@V&B- zls7j5nq-ErBiD{6796vZjCH*tn&bQ!)^mS^3Du0vz?Y9Rn3BQ7AFNRZg_IC~Nk?rN zmks}e@sg7KoEZ;3`Eg4Gap725nIZK&-(Q>o!@W#~k#fPCt*34AE@*6V@Q46(qi)Mb ztNLjybEYmWM&Ru@b7L3O&S-IjQiCBoraUG9BV_23n^r~@xf1^w0s7>@JSg_9Y@5x= zMtEwSx0vupVp7C>l0d>>x4xZQkQovh8oCb}kss;tK@7QZgxJh~da`RBe!UBOAkp`z zP(;ANcsKqX5~X1L718TD3k0A2$<&2=0R$xDAEuIYU;TUpd?z6-k?tx$mUyQE^gsCI zg;Lql!|FfHzz5G|FF+?6q!u6p0+_5BFKOe-K_;1yRtdJMx`70stLpJVU#n{~caEkuG#rBXRTS!y~Hw z`2+UShVqtCTP-RNhIvX2slxmRfuMXejOV=)^0AE7qj+^TNbyN_&5{ zpJ)k}_B_1eXUft`WYMGxkL{Zk?4o+1>IjEtNfnl|;+tCBXHM;y{ZmyU_1sEBBR}9N zJkzxJ+ZX&jhr@!PR|2GDs-l#=uB6PQ?G1{ftB9aw*R1>R1=crIrztnp9-CS}WR7hy zq<;q4^9Eg=Oz*~og5S^!J9o&udQV7^D!2Ua-r3;@UDW`h0+VlkxJc`Z=fTN_8L<5) z&8YXNxTHFa-zuxi@Sa&+|A}Lg>ya^J2CHZvRoWGDBBcf=P7(9g7n6t1f|^+eZJ4q( zPR%TWA`LSq=GP0%NSZH^dnL1HRQb-U`SA7)){@=Ee)h8Y?{l$}{AZT&D6FMBT|fCS z#BKc(QRQn|zpTWXPG{5ia~4oUqo9GX!hCrVfLyZq8a$wMm4K{0N7-5R!umV9%^1VO z20#-)mf^{B0*p*1Fj_PsusslAUsSmC zP!+(uk)19s?a3$U@wwJuo^7B>fUlVJ&7|>fm*FLT@6(&kgg`eApejJ!3Hl1vTejK2 zwkljI_%HTqMC~?aI^tnx@&I%-Ht~*z9azG;C)!SvoHSMJXRA|`&{2#0sO01rys?8( z{DD8=Mqh!^BKLL8rD&rZ!N6WwOD@2sccZ^I8&O#J;ngz`*#O|IR`v_XIpI*igtfA< zdo=>#nq(;&8r}cejIA#Y^w)$1Er2FFNWL1>KRi7AeSoc*YKBAG(2&mP7t)RPmg2~R z(>tK+`3DRkX9)vLG_Ked9z}qP1G#ncfQRzJt}#%w3G+*rK^g>=fYF{d%(|Uau#oj| zF~+)Lw2RdGUU$$m9Ca$F5&+51=?ZGm1F+5)x(5lHuC8`KF}PJcVD>ESZg6qrkbiQs z(Kig2GN%3f*1u5))M@<=zFTCM?M8kZPQlN{o)O+uZ~sZRC;`hjw%&n8EbgC??}rg3 z2>06Z&DGNh(dyKJ6`=Pfn;L^dT@C1?6h6z$x@eKvh{yK;_=!?ZuT1-sHp}s&=gc7D zuT3Tfk5Rs0i#KKBcN@4^3yMe^a?o=-Gc>ONA|bt)Eb(7(=rZv#RZR(^N|;~VW8i`$ z=x6tOci(#VNlPUQ$bWXcnu7}`L7OZDdNy5kVG-Vc^I2E+Q-#&gd#lBkwmU*tj`kB?LK#Ew}Cj2-AS~4Sg z3}bgSXx`vH^ZTdQ;6N9QEW%Zq7;#GtDd@Veu@nW;50FWN>~ssd1$2L4T%@c>l(x$! zK0cr^+Us(9i%q+T3KPG=+4NtID2W%Bx3h~LOa*O)=TT3clDl4mbbDxT2(jtr0a|Gd zKEJc}4@e0Hw!+|Jv7w(|c;=iWY~b zeK0L+|Ay`@?(RE*G*uziSbbe~8pO20=z6MScIvL)I)!%k?2@ufJr6}5k4i7Tj&3$b zR4dTPoEMVV3IEXcquT0`Ag|l^`;GhUG|JVPN!vZ3DKb$6{Z$znDOV3lWeWy zcXy|X;~57Jy;AlEz2@q|mHDp9%1W6l=}U<`>!g3q@J}4PqEbJo-gF*|=_c!`j3Q9J zC;OT4V#5h-F;W^DH{D`n)17AIz~UjnxU@7FcS)w(C;M-C(mb(lyHWG^(4P*3{6kAf zdp;Db&8q&-XGDAfX;0svnV}pw*`8!KLP(X{ry>g$yKFgDQ#I@%P|-U!S;5mrmk{Q< zHxE0YNl5`MDlbdC`*1HUHGdBptl5DY>n9#IZ}k z71~eVci{TaETKksLab3PRXa@i(Lvr5Xyi}pI7bpG7AfkLhtc~%1#;|aj^`Xa#7X9# z4>g?35X6avThG>*iS-^3;PFUHPjY!gG2NIx>aj|Vu8j$XUeJGQ&sv`kD) zH&~SA@un%5q6Od;`+{kzjZ2}jeq}V=n*EQSHsA&bxcyX1)67L_fV!m;r{~h}0*?H@ zyYxy#GJ2K$zZKnsy$7J$QqfaCxM??kq*sC&iGw?d;;Cv?FM;jt!H=S9V)7H) zbFA)a;EIh(Rb=nSnZY8{Oh;PoiNVfMOWFe~z&pJxis}lK*fS=GWMRBvvCz8*PHFYW z67Jztxl-e*zxM}7fHPM++fFH*7uF0qeQfX6yiYf4d@^B7fH163lwy0G@tI}|o11ve z>|{c(x-ESV61}T+=M5t%i36?1np9}NvlOb5y(KVWg~Vo3zQrg!Q>d%E>2eNg<24M)9s>xss7|IQ!SS?mR+DVpARBI>+ET!n0YfjUu+ON6U8S$fvwmvpVviJvg%E?Sj9sR;u^6|*@9v!Bbo*2mBsPoKCy8Uy+x_DFR`KVObd>^JnaXnKx2*2I zppC{(pP%?N(T}QS(N8>Bj~Hmcs->XL%W=>oE$MuD1*b-9VlCa13Wr6vb^H;2qXAE* zCpNRKjwAL2c6L&ki@RtU!ukww#i6-pTiEK2u7Ru-mV3lK_~^^jsh>tq_S}*2vZqB4 zmly2P#9@d%)%Pze(Nj(>H>%SmpHc#7fEIWcrL0liKjQ)BJR((eRAr%x*cT^at<%%w z^qZF2))%~J4SO$}CWY_1ibU76b%IpEZhN-vx^dvq!(fu+Co8){)PUWQ*>m;s-wh&z zfbPsjkNgb>f_T5@2C&@w0!Ty_xqQtA}-K1cp}Co zz9#=J{`7|nL$Z(MA#-ysyMc?7^Fa|y5Mn~~oUV~O&z?+ue4ZBGn`-*ii9Q~YwiF&< zWQy8Vb|kq6f+M6)Qwi!Hd**mCP_&2CCdhbBX5KR`XcNP2m(=_tvq(HcOw6rfYqHS( z+JC@d&whuv=Jzo+iXnK+u{NcIaH!q+Bx^0!pBdrFxZK$-e(%vt&Bn@Ft+mU?OUKK67bu`dLMs( zC|qwx@ZZS(XugZ?|7%P=cqRr1NBr3ynYjNS_kG+1eOA6=v*ccqha#ad7^CvB%gu?q z;+sb<);%j{MG`3LO#KwtWe5LSvXGJ_JD$o+P3p5^zT<-u+$$IVi3<`1#NvhniV9LP ztD8ghrnWo~5TiMH=qY-%taZQ$3HPX8ya9b!>Zl5Sr?*&VHSXm}!{`a2jd}&(Da{Ay zf{ozh@cLq^Cmv>k@I2gKzg6D}TyjFsLu7V&m7ydJC9l@Rf4wEF{l(^5`R@OvvU%Rs)YQr^ zDE68*22~?|Cx_xE{cVt?ZL5wkMde8TW})wCPG1$*s*lVTO>ZwDKJ5tH*$p{+W&_2= z$t!8dHXkf=jAEy_8YhRsBF3wmI$VgGq%;mmL!l*Wt*_^P=W5BG+pg+1NN#i=AvA|z z$gx^(h=rDwQB(Ka7V7OOhQvt3PBULQ2eT@U^*wiVasR`WoQ=@HwhS8<+PNyEQJU7f@%* z8?aq^*sq>o!`pwBB+@-;I71@o5pa-DE*_lKJFxtFG&rHl%ZEh@-z~fKe-8|>Z}Y^n z%Vy_J!MhM2@j2M^(wl~?hry~DZr3b^BN=97UpCVn;zzKV@Wn*Dtd zygIa`X3zFjmEyEFjss(GPCh~Etj`mQy)ZVa*_YoA$QE0L(X50nF8B*iOOC)@BnQnX z_6@CL)O+zWiJGB^|Hh7+FZ~~%Xj9K;Qj_8#^0|4h|6S|1Oj|Y#HY)qZ7h}DgmNbqe zw#?J0B}P+T45djYTB zIa-iJrq!D^KZIecSLuaZ*yhXk4s!c=_ie-#a_S&jk2+HC9y~m!kH}InwD{9m?;kUl zn_BrTVz>7weYjl6S^mN$N@=;3LOV3HIUx&#Jn`0pvgfk%r8Nzb22cu63*t6z;cD$g zg2?sj6b9lBvg8ysijO<}<$rI*Gt`d&=@k0>33<>7!y+PdScWab6X?Yse``j&r1WiHXCb(PH8$KufW(mT#y8>k+=$n`` zThW{3+ zU%$eOOfwi6@ckO&;R6d<3ME35!{NuAbGInuuOPLP98X!r!9`OXaw2-ZrEfi>Y+w>( z84Od9@ZGo2tM9<&)~Jt_hoTFVUxiJCzPi|d#FqWGxHhqHvSn!2=w@pWy|N&UJINoL z3VC>9lk3ghS?x<2ueuo6gKRY?s-3Ng0byKP(I!HR{gQUBci#Y^^UZFdvmO@nDev8f zo_0Am+E8;9!K-lr3=brVc&1&R7^G1vN5M6p&Zf6vXM;tj$bPuWI<>Xd|J+ez666}% zy1KqMW*_|znSY)UKU`{Zx^WGJ;QxB<1E(+<@2Eyy1 z@Fim$tSbuOXPU@P+>>i+a3Jo15D#S-YW}m&sZ$^8nGyGuUZ&g|vrvboW;d7ST-@Yr z7iZZWCI4r(@Dw&kb=gIA`$Ti{|MX@a>@EJ?ss9r_M7V$#H2I&R%sPMjkR$i4J2v1I zkjc;-hP(T+=ee_{Z!Rft49>`2ligU~I7rJs*DbR6NY7>nHNF_uYTsi`&s;n#)gS6r zIk0z+pz6@;{`De@ptQ8pA-hx4Mm!tuET-F@(S1*gjJo1`z3HU(D z4{L()%1oX6?705PtS**1p+p8o_y=pqr1^0_&(nrxF{rZYYCi9Z-kOLoZ?EM`mUQZM zE9aep^lgtNsmHj{@y33!l$)GPO0t6pE4_A~7f76#)c&+2A7a;2=2pe1{`;poji+mN zK!=}ecI1lJG49((FVSdZZhMlho)m@BVq6{WoE_e|ZRH9}+i_7kQqS&2-*B)=joTCR zTRdWCruwx0{glmo%6--ut~)%A%mbst^b9Snz-O#B@T2YhLQ&bc{%>RvSL@8^zq8c& z8>!I#`T3?yL6Pdc(8u2p5kQ-@iu=#QQn_;%!S*SWZtTT|h}&py^Ik1AMCYM&E(Uy+ zi;a70`y35Oin9w|G#XBwaW)QJy{!xKIm9gSe@W$euwyPrC>um6f5m@wbpcam-#JfE zvXfcY@3h})I-N?XYRP%HCDU9Sj7&-!-sv7pJ1EJ|J<>=)1tyPd%U{ykmdhL=PC*&sBuZ$hnZW~^%8;=iiz`3WIvrE@n{w=3A! zqfCur1?wA&wyzhwceh$etv+s;AaEMX7pMCbV_MFZ#vTsY_6?Np$Fk_A9C9KhunUM?oWP@|z4YhrhZT zDXhgCovTCpQ&lq5QYwrPhihAk=#U4$ZFkP%fAhtq#rLIn`AS!dCCvT73=sW-yhuGvA)scO>u|+ZI<}ohiGW|LXCYhq`3UH@<_z`liJche2Ou5 zY!X*v)`V`JW;`ofh0D)9$$h4BD__dNgEK z`V!f2GO}(vmH#TkFeI~r)M`~t`C_Y^*Z%XIkWDY{`Y$Mzio*d>)hA0r24dG|aP^Yy zQ^D}Ds`U}}%QE-e$ll3j==tGT?n%L;{E_8r{Lt{D{+`up`Say#&dj z;}LIS7w?B}}C|bm{&UoezoU(@& z)$F}^;%0YnXDaHtK+N^fq4HwBXkRNdX+PLp2#%#yH`t`!{zCgC^_+gjpE2i6ZN^Wl zye8NR`-XJAc;*iBtcQE#!e}Jh!B>M7-;e3MRcNG2%gB4tMX2dnLE5pwlz^ig_yROt zyb6T3-GnHRd5(-F5m5()$)u?HsqBwD}(nvKEu|CQr7ehMH%^?k@#J^z$!O4z&)toCxg$` z)pb3bAGs@Z-yTg0_Fscg(MU-g_G!mp&`wm#7pYx^2kd`&l_RU6aASx3RpR3uJWsZU ztB+xF>|2)!coLRJnc1+SMp5=S_-#a{dGrq1&)(HNLKH;R zCBToGGUG!0b(GBQl@dvdBi91(2iAUc?O2WcVAN5PDmG@|iyIP7###08xDM@io6ang z!IVOoM{n(@OZx<$pIJu zsCN7nkcf+-8yjyGzY5(Jytu==j84=LyauVg2_sk|LK-|J_`yBIvm>HN~a{#%G+cIfr5%_Q{zp~i}51))ph$Gxh&i|E8k8+COj zy_li6>B*vxe>fTh%5h(K*a7D$Sj3!ZEBg`tWa>P*f)*85VWc_#%TlXh5p@B(L?3Us z8bYTUvP?To*W|hLcg=4{e@gzJw@pss%sw#SF|#HfRwH7K96dCCW%i_St;lzty|s(Opii7tP#RX$E?vtmTUGgd_ALZUp%XGlTx%AaVegNHzJKIIO<1 z%hT=jIU3YMWt`8i^6qGf^D-fCYmsm)TIH^QYxsPBiY)gMqU9>fC5UnUXKgHpw8#O<1d1Ro4efILqg6?c!&gM9wHpt1#n&ti9AVk~9-`+gfpanwE)bW6L zHIq2K*g@M*T89f_qiYA|gu8#2W2<3gG`8`e<|P5JwVNMJ9iLA(0eaj-2!1>E9ZOzT zG<$xQc=;;a-1gkPry$?n#$WJS_kNav(AX8XP-2aA&<4{;xrTJLSiWzD;kZqAa)hYC zdh?j6BL&HL4c^aKi~#Q(J-7|eaN$;?1B339MA2t>q9~b@{h6yiw^^H|f>a|C$aI zrN{4}vk#9HJN<=0_xCIP&~^3td~b{>^ctiR67MA>Y@pUhLifR!CHhSE%ZuU`+FRaC z^DLvN`49U)^E+DlFzpvegKmD?s<^KuXG7KKDshpoeT!H5aKjRLChd2+ie#Y5ALpjJ zlrZ?X1(_t)jtDNJF^$qp4Mno{6s$&sl`!ci=~wwJoO^dukVe8}z9;A9ozh46YJvl9 zYC}70YR1u&zTuw@Lwj=tk{%U!^T5WFnwMcl8$^E}qoMtvPL&W1B?|_?c$ypU~0$!z* zW!?7g0Ci;S+LQ}i5M*mBroy8MR5wv$vE+-r71iAE*QpMlQL!Y=tKa$lYfC6;*!clU z_QtUNeJ?r**%X0cXSfyj4mqSXAk#xsLj8ttlfsd=;YX(rzMh+X>prZJ z7dut&m>1YasX*HJK=oK!%xv$9V^1Qn=F^A8dGD>SZHc5{-~L})Ujh&1_WwWCRW~=e z6)9VhC4?wsuTb`V-wSoKXWvJ+D6(XatTFaMWM6M829Z5GS;oHa%gpbb8Pxax`aiE; zrDvWw=W{;G`}6*Mp5uAkE7Em6E4)IBy5j$SFpjP}Iz0S6(aExJ-tkn;4MW`S#!qZ) zac~q?7on-xF60sK)UzWnuRI@e+90;%1Mknyu2FlP{<6;P%I=w=1+7|Ti}Do1xW4sC zvZ1K%l&<)yXVo3P4Nr4ThDnz`d^}q#Dl}9jXJhFpt#@3}!l)(qaU-s0;+xyly3(X2 zHg1|)FjsWy3UzRi9B+8=#|HjAyHj%G#_C&TMS>Po&s78`R`r-Dk&;_wnx(!;R;6m& z-`^Rv7tiC!Doe0Y9m=%rd#njs22bTjNA4;3P>)fET5W6mS^Q5v7t5%>AKu5dK)?3Q zsVD3mDSrRFY#9HS31dqa;lZHcaR&_N&z+KC8+MOcVA2CiuR!vtw{^!?zCAZXx-qsw zE#!Q}F~`tTf~iVsA*rsx8GpaZybvJk%TSl6eu~fheU(AZg9d(1gI*8(?4DBpl1xwY z-A{06;N&V&)?eG}(H;k$h@7fn^7hO^= z;r!UP6dBO{H=;j%MD1~B33PxRN9#VEMhna(!(BJY;yTZ(tZv)|S#*0l->|MmVbOEp z3jV(t;LpaZKB`rr<2iqG23ZXGXm#{eNKy3`&Ai(YM-4`zK_F`^`#9uyMtSw_-5^!> zFGJ%?yvoKIJm+w%eCk6<@3~X_l#@Lar92gAu%6a*jocT%IjLGFG#AgQ=IM7dgZR{qv~;#M>?3W8 ze>+U=Ysqnafv2a+o3@el$@WvS`@*ZU&xSfT<~LL5MV4YM+r{mXYNLTCBLXI*f_7gp zWt7yf1f;ho2^CAF&ZuGDcD!*k44Ne=<}+`a~!Jo!@Zp4vC38iHUmD zU-&h}ckivs<((%k$m9oxZll$1upZC$ZDggEZ<=5)vh0+;nV4bQk&HE>lxf2*3}tVz z-fwbL>gaS9t58|k!8qW)hz0KhX67ZZ#drVb+Ztt~sPJ_P1kct6jb+_ojPI-$lOnQ6VrJWeinYW1n~mdT(KJ&>49-L9J>6C*Q47 zH_7Zd9QT-y!m1myDHdl@Z4lKsB<8-&RGH76qE+lEeInG_=8`UxCcMxgnXa;wL?8F0*R#=L zd*IE#)^YOPtQSL#9{9wuD8xKpDJmS(`td}yvX7;atp1HD4dum94{K#FffR3*v_zFO zl>)6CT8)6v)SC=ykshS%llL52)I*;i>;LJvxeHx?Jl&)S>$ zb|B+~w&VbIt>Qcn(+y=h#rOr^yQqrZuWp5|!zuEQaTr9Tnu>{+vfg$u2aks$u3;DZ zck0YlA->G{ei^`lHI_*nKRA{%emQA1<1Q!O?=~Zaf75rh`Yt>5IpC{|)&=0tGIgZ; z7nxJO@+1Rpo#j@`CvCwm`4@h?$iCIsb5$Rqk>xL%=Po4celEM1}I#9*8b?iNjuyD3wur{OerK zvX&3h1u?AKX7!z4pWWDAi^9EjGLmIeW}EId+`bX`l6tMT=>8hovpT6g&fU>;=J|F_ zUkke`ZTEsGUT|;k8D59==T3)6w3_q$=h#AgT@=n?5QiHO-)-g#z9aEKo16~sOD}{A zlqx}cF%d1NC%CKsd^GQK(PTCDsV;~8wc7z zPOJ3o1ES)p>9Glw0}fVObD{j?v28VxC)TEm?mG@eQ=N|;MivfESg(C{!Z^^)&5CB0 zH{-Q^cMMO80GBd|PMCf;<0M+Wp|#dfL_YN_Y)BFUwig3`z3##VpTNKvFLI`9kO(cc#T=#qRoU z+m^Ctd4Ax#v4Tbz0nzjQS$}L&yqVfI#juw8no8%;3TCE13^&cXwvpN9UT^ir=1~k1 zQ=j!P{H9p|+hkW(^AinBLt{MKG7axz#XsLFx4w<9RNAATXPcIZ$%J-d~Fj@NucGNXG2srhH9?Lfvv}LO*&$gucsJa zuK!?^e03Z2dM>pUKBrOw99a*YFq5^!f;AVrKeF{Vf*YNNohoWY1)>7o{#iE2P0l7I zCDpbVbU*EELZX~)B`mAc*{23_I$8bwn9ja_wDgm^8?pEgF%6^3J?*vRpA=$$ z5f=n=uh@0A7fD1IORg!Z*yZjyic-%hBTeptR#F)#fLmoB4D!Fb-(sOP#N*kx>j=!- zu(+kMKtcJ`f4Q{iRJTS=M$?Y7V@{IX(7=X8!%fGTq_Clm_*JDBV=ZNNCA*?0+y9Jm{Y9;~ z8+d07TfrTjA+EJQbUQ7TrbaMVNQFj2nfewpT8ib;{-vRCOkMqNNz1g}uva{QvLl5> zbasd#@R}FjtB6(c{sINnM#p0JwN9N9l&f;IF>vS{LO+V_NgaKzT1V{5OJ3UdgXudBgZ5&^c53^7M!Aw8hIL)eB$o{& zR7-pbDXt7U(tq6$aTIawk-=WT>a&Y(lI$HRq~z!tj}@I@)+@EpmO?XG(vtOx9sVD#Bys-iRo=~Y zPMK+YP7249%Q*JVfq#TLKip?6pI7DiyH(QQ^;d~Nq5P@6vgD1lUS0=XtX@$@n&Zo= z>K&@F&F8&QdsDL~Plt|C`}!uwfrews1SWPleJc-=7k!0H+~JFnVm?gcN602!Ikp~Avak*fuy z{-k*28t>k*m4Mc4~g`CbS(hVv>ix7cavj>9LK?BmZ9omNEUVhmP z^|sB;l5Q0c!+EcKeUAqQ2D;K61GO|8sEwslG-!O?JA`_;YaJ)7Zk#dy-e<5;&m%9> zma#4hTJ2qqvZJF(_X1zWP~<6PuvKqb7#}H5nb=L-PBxehcEa!lNEKH$fx8@beA?Yy zHzpTY{dG)fV1^nc3(FWC~BoS8q=^vECicZCLkUM$EON6}jrHL7D*3U@6(0?~j z6Yoe}_7m)BK0e>k_uoz@wlDorxl-V|x9mM-)_-Lp0=@Yo6*F7C7F=G$%2-`ZXnWUu zYfhM%>zs^ne)u=w}F+?vo)Yi|w-Gmb?6sj#VD*he?}BF5jE zMP9w)xF$6UU}Sn69h^>k5^$nNjq|Uco>DVw%mo*Z{~(Q8d2MYWNa@qyTFM(v-eKT8 z$DwhpT9WIDcy{P|bbP(Fl`1y8kpT;Q?KI@|NW;%_%*|EJ1%WDbhpD%`) zY<3uv*GD9&+(`XslchVCtvlPnPOoao`c^@9ewKkAPOD=jYdjzP_*8o3n8TEgHg6!wc_|5RY`%`|ArvU2A2$ z(PjoVZ01v@Bz4!#!0q_!rX@MMiaJ_~A;H1=-*Zt_mu1R2`q6UV^lqNF*6fqiEK|HV z#Gf5q$Xx3%oTtjY1qNsw>1f4+5k zJoFZv3k4lQj-ZUHTU>n~Z(dAKD45@hv})kDRGu-dp08TWpBKenk!i<&eJP~tz+xNq zwdwrYb}{=;`Kx1!RZ$qujBm~L5e$um;};^EN#@^JZFU;C-9O{(pxD*8QHpku7kxHR zHa3(as>Y2;`x30v9QA#wMiiV$z4usoC)H5B9@C;%tQ!~*ke-q8q;tc4xaLUV$B+8X z|7i~FFFm_{Luq8Pk(`iM$N<|89d4p-dOy;Otn|oKcm6J zt!O?u`;DD$A(VsdlHX*S^Bj0-c=Zb|nNqNV>0~=H3C}n>p)#9pt2v&T+|?T^+YNQX-_NV@{0&-D)WKa@0)r@h6L}wH=^``G1u%@x$q}3(|5*5h zokF#S3-eh1$z>-;*FNPWuA6&W?IAQpj(iDfA!b^pJJ0hKESjxE(S035-%*uOs=d6n z=FL`1%jMMhLJ=!gKpO+pc|Xl0wq8_!E_$_EFIF@t$iiH1%BoO{D>K>d&Yj2R zhUe9asAm}lqL79`4=`!V|JHRzBn9C4D``s9_No;8g=%|sMBWEAkX*DoU!hc3roVpa z;>9JQ29dsEn{Mz(@#xuLzTCQ@X~!3tjyLL3%SB3#%4iyfQMTS4dg8u|mJ>T|vGxIU z5{$R9zYK9_Zn@5)>08R0{LEzkMZJxU?U-s$s|@J%tX zoI&cCi4*F=xrVnF&8xA;tm0>>yq)=@j#mT?XV7@I7Jm4k;{3U9wQb2+>#E9H<^)yx z2PgCw0gHrZ;1A-un4?weNIBd6NkO?^c~Auf*KcbJUw+W^Sl6 zEn8_^S>SPCS@bd>omC5q>zez5)chW;ZQH2Aks}~+NnL8q9G%iJ9IMv)PunZUm#Izs zox-B#8BK9-HE#CZd^o4s`j1AXy&-2rHx?~CTP}B{%i1T_%Te9yT6>&cUc$#RzK3(6 z9C8ZldYQ#7a-piQXe(2-aB6yca$Z=-R3y{4z3n2hgl&&<2lmZ3 zcjrq^%X>-r=Bx?o8ITW^N{Eg!udS|TH{fucCl<;_c6Q%UwKVTqtqmO?Tk}TgG>Qj5 z>s-#T@w_wem&fjjzKxkLbA|S*%n0MPrR`%(@dd{?7(&Hz=4(O2=K|lAXnEOC)r{~u z8CwnyWY4Ns?hOQ@>w_-0yK6>q8>5e&1Mk^2A=13d+(WD5QWp{07YlKFYhP&ky-YlB z_ml~F7G{`8EhDr~e{DiWN2qdIuex(~6}zP=Cq;yKvsduppc^yqxaQT9f=WBC-}D7R?qyOhc46+GGC zkH1RA#8X{TwaB~H&)+MSUn5a(OJVu;Z)!lEzE$+Vd_%5{MCx>`X5lU0uixHO^{Mw0X>Q{C>MJWYd3cR2Dx?t(B66;w#;tqQnTb$Mj0Vhs+C(O!4>BVK8S&;0jU03U7i`u_|(s`f7!FH=XP1vzhRS0 z^{`{^xu+w?CN7*=&%@4Z+K}em5M#88w6T)Q(brJdZR_P=8}>EB zKY#HH?LGs3Xt&f*S5fh`U?0ABvv^YU+Z*O;notIbqK148!?s?^)!p=ptkfj?3nKw0M{v&_Q9y9d4pCd0@k)aAKVP1oMN8GioZDv#s zuV1miT16=jKnon+g^Xbs7rGRVZXUl*icZk(RcS{Iwt^ke;Z=tyKgBEw!`W;u#>7 zNIe>*B%&-+#BOh0?Gejpz0!1&bOp3P*zf7&FxB!oa@brU>3;>B479UALooT#y>Svn zu@b&4fiHM-Q4=ZA@K-s#xOkB#Q{23AJ02pH_D}H5L@JOc2F!p`Wy>`&zIeTjxFR5Y zwjfY#D2o}58R!vE$8iNld*<_bcG4!$sQ<8vVcQmtxp{nCU&V{OT*2H{$h5xW1y7=k zy=_sp5syE+xhg~Q9WR0G<7slEj}mAVsM7bWrOy=W+$lCJQt5iZlh>p+ZKGckSRbxL zX(CH$GQx49Qy5KJaz-JhHbz;IGWiyEJyDM}f#%Iv13!D4LVU%r+HHp7J4cEY%}ivk zOrQkoa9yrii`BEcpyfmMpT+>z$W-2wWq$4?bB*qKnM)f&pF%s#6#JK{!vUDt+%VJAmC*rE?9}oK|WQ>$eACB-2+G#h| z(Q1>si2ad$t(`RM0}B2fmJ{A{6U&F3khq&{KGREik8#!z8{Q{+Cy z^;+Ew625nRj+Abx*$p&MTHMzl4P>Y7L8T9*OMi)&lb7~oYYb?}e{aW^p^6JX>eIel z9>k<2X7oC{?A0lxG7fV`ieN#^~Kdh6&j_np`{kht)GhVT7SWNJ?7Oj1tiga0W1a8l0* zz&NHdN$`HlyJqzI8d4JIa{jv>DOJ0`n(N6w1lVb(-i!#C_5|rRJ}7;yFEyN>vHP?q z0yv@B1u>GldMIBqUUp`wZN+*=x}K#JuBcsf)3~4MAjRGevz5}ULFd8>xD6iHJuq+2 zy_(76m5|+Jk?$7WKjEXhv$Zg8p`@+dG=pelifrWE)Giys<=8noX2oN5yQVRe79_b= z+2V!k1^JPSYoxhLdnAZd2oHO!?EoHl7p=V3SGxPXS&cbfvr-|319dmI&S$M~l(`o_ z%mDkn{^fgADJnh^cn<;XxU(!v!5q7?^U)~Oadnb3J4pAZMusUTQi1!+=Y=XxnN0jA zI(pV4c~{$61=?~NCSI!dtiJIG9I!*X$%LxJgbHq-(}^-v-P>AdjGc_=-$+f;D%z`% z#eB0vzlj;bRrL;S`raSMVWbL*At3p)X`>u;!=D>8p@AbA%aM9l9PY4jHB zB|Td)-^SvvnV7pY&qY{?=e7;9U`W~4w;yZ`?nS1GttOb&SxE(nW_5)bMe*?Q+87j9 zsYL{ebGX;;jNf$P_{WF&8^xl*{h0a&w7uEA-j3a1HP;6Ou-G>*pR#M3|fY zf)XkmW2$L}bPN{HK~e1KwMD5@4ih`~=pF}Jf8EToV1YM~7x z1>Np^okE85*lAkdWau_xEe#6z`KqaPh4*F4HSP53^Y-~lRnFDS9PW}6-=|25KeTak zD6=)h*4L*~oNvZ8cQdtz3W`+vI*v$1mlm6$j6zgsjcg4}7&(ku{sLn(Jn3g5c{jFw zG?e3F#J>T%-m>oE%mQsr?aWA-{NqZ}Hu!H%*oRL7{Hl7gIQ21WKI)rW;!y*Rx!Llv z&#owGDY%M;VXj8YPcM$tX60Acz9gRkKeACE0S^n6hW((GqD?oW0e>MV!gkuMYW8*|7Zt30DlbM>8K-S#E=D zb=lIR*?7srM26xV2`7VcAmj*E ztn!ovR|0qqR_3|3({w^9Y4L8;F@3YWg>rcQ!9*m!ncZjqUUuF?`P}_X(UED%pVi!~ zNZ4toPFZeW-QbRt<4qm_2GBm+ChYcHV%M7k;@uzJ1j0Iaxd2f(j+uI;yPEOqyPT z2d?b-XyRB-0LF{N5T6_WwJg#>XwLD4;Awi1^fnwTY7Zbj3BtOkHI;>KO^C3|BAX%0 zbxkJwG}t48$O}?|v!{E>ubs$z7x7@4%=_I~aJ}C^#`55h=2r7i=)lupQ*FbvO!F-z z+<-i0=naqC9Xq;<5g=6>fCpEr@Yc&OHXtvEmrb>PC4|>{8<1!M%?Sc zrvtlbn=QHY&-|%!Pa3 zg4*Vu)hPf$C5uv(WeMXb!u|LBgyYZ8e#|yD&I82{b%=UVjyvo3LN%jshnnX6*I)aX z5Ylb4FZL*Pb~4#;AnG`5O+EExMM9*rfAqG9tTg$f$%tQ1bmQ6I0$3wK*gRA?Jk5q1 zvGH&l2;aRC9ndzl>aS0~_dQ9X013=7oS#cZ+mdF)Ju7k&ABt{ZveqP$-G6b<7T3LhdfjSXWzg=R^eT^G0@x;JOG!Slm($ zuLu#xxQ#9s=@ftW%?*O1anBC}f@+vB4Jj12mRHL-H`7$vKw_j5^Kj|uuCfcot2XT4 zUQFlole`-(|8?eq_K|}wjGJbeJBfipfgQHB0IAvF= zi-=+?GLFc>!8zp_E+y!7+B35`DWsS1KP@rhyMapGk{EG-VR4Ea^ug|tBLKeaQ}M*5 zB=R$zJ&97CS&@w?3?i^#ZLTP_19L|bHkxYB072A8K5#b#v6`8wf+S3@Q(3rnd{kC( zt=iBJzf^bW@iZXN;J6*=S2rq~22(%j(g6x4b`flrZRVt<3LG7b!Yl)9-2IsXp9T0U za~Q_VXv5AG|Jm|!cVmeVye#iLr5H{MI%~=l@E5EYXO_VDQ+69v`;-~der@=_ z=RzKvi}^XQ0t1D?8bgTm)ricw?y;^Luy2%YU#bt@LDWR>d+nppa>kr_<)Q2zv23{4 zI(`|rm*khaatz9I$_H+=h!o83z`a#KACCTq`dB{D2cjMBN+Jkp8YB6$jM2so`-U7Fl12!R;Jt)slr zP5uX)>JT}R@+@n!1ubC9Fh~9BzMmpeS+|{?oWQx7Q{@(0X*|bjbTxYMDWt)kDo!G7 z9AT<^RO`yi)xHiwXcv*HYzul37h6o9*ZlLf#xfh?^y&$Xx#B#nNKX@j%jhGK)ek?s zwJVJ!w8Cx4dMq_}*5?3ZcxU}sf{xe*vYVTcUfgx91?OjeeH>Lv{*|{CO5OaC!}aZ? zw649Q>YdyXvTVdO+n7I?B=Pbih&W~&d>vkdfpfu?s87(12eFbtk=v8&d>AUj?3y+p zRU=c|aCoz#;j*_g162>#-3#=%UF=n#3$WS_T;>5A%`PKkB=4w8$9{e`ZS2gf;WGO= zG!?IKJV@kQbr{VXX(o}L1%Oznnb<_)T;7G;^ugdx!LOJ!J_6h}S9hehAdG~m$6y1E z6SG+a4^Hu@*p0P4TSvN3;G6S_VW3}z)=4Deu1DEe3k9Ag3S%0sm_`{~7d75C1rQ}1 z;4PC(cN`(B?(H~RyG9X}nr`PO`LHMFs^7HP>|kXdA@gYqmOC$Ky1SQqEk3{GLZDsU zOMTUQecNqORbv3Yw2NnRdIcXCbH>&@TWc&2qt3)K1-URL9V`F2z5Q1s@|xFDRS7*n zFxN}sPk+7u#DEP10yC%rrmJo1@)u}`a}Ua~q#3<7dyn6)gP7b^s?U|SzV1Zag?|zx zFCk&!h;NT7LBDjS?VCKm(d(U9P2qDtDsMfL_{kJB-tSfF;*^g$sx@+zUwW=s&ZmBP zVV)zjD3Gq3j?5%9#mIBKrit@J%Ftdo(}H3VanhOwy&Mji_uDG_i4vT(h}2?L1FCG$ zYt$NDO?PK?GmQxnQD%e;-hUqMb-8?`;Nx}V6 zL|*f_o#2;;JOtU{L;|L0BcIyd#S;4KsM`CH+o>~cN_3G0qQlF@&eRj=OOk(=m{a- z<=aTun4RqzHDnuDHwtPO!qRKpLZq4AP8vx-fe#K2Q|7e&|0X(tv@VO|^M&EXmsnk$ z00|bt;t#^^o-Xo17a}?!YzyEB%Ev(H_4f6F`-A{7W&kfYybms~;RP~b^n5#TZU!TW=8CV!_a&k4Gl z(P9i)6xyf3U2jZzGa%_a1}tIIW0jkl3Y}q&P!maWCZuj69W&>V?KKlC;{$!fk$G) zK~Jbg;=s({w715m@%{O2MVDM+yF+g8v#7*gct;a#E+Dct!#ct+h})EMOlJum?OjJ) z&Gya?KQ{Rm)J9#hA7o*dqNdM11vznG5Mh;nnF3zolXz?QMldQ(jr7vjy!vMA^L? zLorNRFJ3Sm8jS7TH(tUj=|;cl5--x9TQ-KeeR@{?7`(3I0_^u8vgyKMYVOKaXGfXx zP95+=^$=Lxv5z~RQa^bxDj27RojCO`t;w*2>7P7H49e$(-8Fgqw4!e6#B2z@qA4vD z7hg#$OqAlX0{JThLC%g?9L@{g^duZ_2p|JOlISzu>>yquWKrPP4~u%1wyrU?DUfv<@; zl#V4}OhHfP*CZ7CCWl|Utx71J4t-PP9_Er(^8U?8!L1o!*8f}Jop{s%; z(dob^6B}Snlz5!z#B+x@MGDjiiaEm7=_=v7A1)jyS>xJo^@jGHDF=W4cxPw6%Jg;k}! zH)$`-;rf|DikNO4W+bfx~cF~gx+8kE443)iiIQa8Dmzv<`C6sQRuAR9A~#ysG(Xi zeyN2CitT1{x^$sR zfsV+>Vn*5jc$YA84DuH-Tkc!;*2ZWiVW~)g`~iRro_I&w7Y~ zhtgL*2FoFZvw30!@5^Rv5K75G1{BjWwi8NXf-VGavm#t33ugA-yNdd}Tr5dPT~2NwMlRw!=x_i(OXdSH77X!S86I%*%14A(dU%s2r-lW<_GYH zgx~xj;qNVbGPwNGLw^8vIEo6tMITIzv;Gg^svvv^Z)gh=7FR>sscRCCg#t|uI|!9d z!+dR<#ub8OLv2uKDgs9-0q64W7Ir~pPcmU?>qb8i&FOV}tc7o15$Oj)-#!6mi&NxL zP+MSwi`6m+6OiK}ZX+3y)^`ZFk*8YN_3G~(;B-38J;aflU*P)xh2s4Q zouzB~Eci4JJfIr};p&xTtmgi#nnbX`DyFF&TGU*~?f(L%8}1pgodinFUMTN2s~9D0mE4U9iqUgK)7uR@QafdE^gzm~8M-`)yxY@$Z1 zFZE!M4Z%fcgLfALF%XQOh)WMOR18rus75}JtETonli?w-OcjlkdWBTD*$AMu2n|k`QrG;1}N2PtY*_q5of~BgFXp8{&$&!&LplL%%2F?AziB zh~MG+cFi!#FG7_#D~&1HK(|47lR=3VMN#3e{`>%Z0a2p_Oe_l3iL@6>FxfXrvY8GX zYgf5hP*oPD0g%X91x0jUdo9Zn7cj*bZ7;i^P5 zG|*>6CW&tlOwtYB0t`dhIg{ucq+_u@U`dD?>n)=f?hwGLvJSJt;IFI@$AOY;7Nn=A zC+4zEWguD0zGN&=GG@DGz#L3sQU}$bUd5W2S6{kAS^&q}2LfTv#A{6R z$bbPL;u8)Lam#W7ip)Oyp5V?3zV1~Ig2#I;tMKcsARa)z0KR8?6ZBt0|7us~7%?Qi zcIvt-0aCyW7!xtb^9-Qovo6CSCOyQ;!3=pv8uLGkv_Qk>oh1gY9_#XBh{!eMgMheu+g29n@Md3fQEs+oBxH5|zIJs9zUh0E>Oy zbP%2W*l%EvXU~W%f=j6Qv7hg+n4@95Ktt-YF#~b{cn^VxI?c~dpcUcao%O3$Fir;Pwm!iC=8fF8L&^qh3N#5L z5d6j^jf$)vfv6!6TFzV5cP3ltp>4Fz0e)dAM=T-vCswd6A*zSW9~MK)j|HHgyo2)= znH(~B{)wq6BJUVBm&DBm!c`Rhz6xrP6hT$Wp9&m`0RS!Vo4Muj+ezZ?Fg}33N_8zd zbYaD*Z_vE8#Q-sN7_BPXa-YPQ8_t+@NJ+qAg|%c|g9s}hWJFO2KJMP_p@Uw)LU6rb z8Y3$c`9uWbimsaqElJ`8$-n@wUcoF41!Bk21_uWdvna=v<;N|!#}|C@bE04eU4l4n z^9qP_3OsJ3+8sFEFlm+79t6(rT%*yM?%YZ&Fa%FE9_KE(yLAiSXH)HH2*WlT6r*1F zJ?A9x@^Q%N;9+YYb${zgj1V`pS62-mavf%i3YlNwuX|`{vc|)@Z@AfS7ZR9?=dfPU zI}8R(Z8nf3VEiG5LBYzS5cWM`fLPir%0u8n1KE zOv&BROZZnqUOVU&YA{M-8brYtU`{UJ(V!>`)V0{Bv%BsA+d1&0qXdDVv%t#ex!C_`MU`k^qv;L2qxED)k9qOdh!1(hUl2P7rCfd`49seo6^qut`$$ zn+VP0v7<{%#J<2VXj5=))d~Xv!0;|-2n$DtpB2QqxVTIbVruhQc-xAN%kUi3d*{c4 zLapT40f0I<`~9IR8%MbJhX>m_V#M_!Wh!9@mZ>TF2I@fIuAhOpS6~7q_Vsq9WZB~5 z;{nr9fLQ~?7$cG7BU->|0=e-PwksVolARJI;fH{v-w9s)cDR}j-7Aa_Y3rKhz|GM2 zhko4utZ`u_)*j28M+ea&Q`Z8v>TFGj#RcNb(qob93TpEEC^ZWqx_kE-s4sz^bROod zdy!^SqCg#0AuxpRL;pfJFfPCBgOX~of@Ja|N7q795@a@*8h10Gx?nE~MrC=JsvFMg zw0;!O0Ej)Ucc9}0VBaOuK1kJ{;3HzngkamM4TQm#br5Vn@~=T*Ylg;Re>3Y39~k7; zkfG=s93n@*G@6f*5nx9J7`iIr7t$E7fKnsAI`2fkFSNi(XwD)V;Q4@d4%48*LGP`$ zR)SF8ZbL%~z`FQH)gdqpzm#QbA=r9R2x_LQrVg?<0YY=C2sR}y zz)l~qv3U5QEe%JOeMCaUS0PSYPc%kxAM}vF61&7T+~dDnQ=4E-Avi8j8`ohG11~!a z$r5+K(OQh^j}gUeKlDp5<}W_AtIpN{-mnYCc?|agfHHDvaq&AL`}U(@!2XkX3945O zK$N#9v7`c&y!75%(2s_xa=v+dBOmBuKZjfY66Q7ZKo){3V3>l$uvHtkDgL*@y$jt( SzY^|v%Sb6o=G-;@_x}KX7dqJh literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png index 8d8512f04292297428ed073139f2772cea8af17b..4ca0627274ba6f0d82531e0e6bd6024426a2dc96 100644 GIT binary patch literal 100402 zcmeEv2SAfq*0!PuiU^L1qbOoQ6a@kaRe=D~NkAY}DWL~Qf`kwf42TW8s9>k4AiYVG z4q`(^lqxl1L%Iq9A(a2VA(YXX`DXV2W_Rb?b$2y+%Pr@ed(QKmb8q&9FX z5y<}FUw=h;dwIlm@JZd<+snnm#nAu<`qh?$D@eiRp;rua%}|D7vYOzt7tYfK{G;RI z1s79-b>3-BCnm7cbDAv;S0Q2)F`g*3MMUz+v)o zK+4c`+dH?dF6Oll0apKqkr$wxf z50UcA$6SeCocVE{@doDei`JnFray=px@v)Q_I00nR#8@AYAn!oT^F32`*hDT@=8;8 z@Yv~xIWr--W1WeVsrP@-)|4ct<>^Btg7)SpbMEcwhw%QIE?$thr{&1$2bkiYe|JV2 zJ~NBy|ED>iU`WS)STFLl;Z51FFLm06fjHP!j>EGxpaGVQFAm7v5bNmTWlSXDe5V$W zBhlBFhzG0K3%a3!b@FucA(9EsnnW)mWc$u8u2`}c5Z6o#>RvcEXzBS9y}?y1$$QE! zTyg%8Q_)~|s6KraER?A$P*Yf6EbuNFWW;OEI+6aCg>mlXte%CmCp>+1H$Ov|(6HPX$*~&a(txJl4XWWQ3RVbHrn2 zuj43WD_MV2i)-@p-d1z2v_V_9p;?X20DvahLYwhi*Ly^~` z>CsRYR#X(YXRN72bJq1DS(_mgK|9_~+U&8oVJ-FonV?BnOAU&Zr3q2b1EJ`IH}`PX z)F4`0coDF=;JycY&Ty=S2@DJ74P+r>=%M8gP$4|Ouy!p#>=MNmeP<&9sS}_WUjIFwoatGJ1~|38nL|?dLb;@`HZ=fSiH8Q8PKDEIJyQJ{mu&f z*;>_6BDq*N`#It?D2}pTWM^GqB_3c!0nHhis)N;qBBRap+)$0GM~jTw z1Flio&-kOv+<-)_e*8|ef+P*zRi~kGkml6=L3^@5LvAR|scY=jOLLlfZe|sufOhwS zXSMu|Oc5|NPMr$+m19549@h^RJv~cJC4#XB#m^epmmwVZBpL#WC~yrB|9r7H0virM zK8@pmfm3ziMB`s^@$5^#A7^HxjgAWdKfXRx;MX}V!WCp;QgE=)AYadk@RD*cd4!a# z+|)(NY{-;BC@M&CF1yc(m~t>qpuut?wcAWTP_us|nt^9H!SMIz0)f!)VkQTl{9d49 zM;kUAh2%*n&29C5+MWsQIiM-d6{3+q^vwgV{_Fg`!7`^;{P_@_#K?# zp-w?Tu@&zG;*qttwWYJBBOJsf$ir!>!;Cc5sgTcP$5~H*cNYtDswMCx#vcBj))v+@ z@b7e7=EQex1#7$)$#IW2*-=)`%LtB!IpLLjtj&lXC=Vwp@RTw$*Gy%6v6d!YPI!NB zM++~Qk%tz=2o8h%(iHxH{FIJ4-U;|BfSuTw1;fD(ma<+Rp#8aVm+E2$!vQZ!HPX~` zb0R=UwXdvc;2;e3Iu7f$TpOIsKmURQs#N7i#Cj_`oF@&NOz>FvlD-zliAp^z( zH?p9BsAWYnWJfK4OaAznz@KtBj8 znikn;j}r-{3H9ql1LLHkaTI{bFjVk)c06WK6#dQdkgyhVUI0%~0k-l7?Xu;H@_=;A z###Q*bt6p#4GrwUWserH2fbgxT2s1(@VK?9h8*-hz)-)|7Lc!&ETlUWuore8zb>b_ z;{v*3<2-1LRFoz{cFGQ*v1kFku>|M3WdqN+oy5L!`xmUV*2qVI>5#rU#Ur-ip4 z)&e09qKS+ne(x-^G@WLa`hOtuz&KG#f0l(>$ap*Jm{UO?AR6tJ2TV)B)rGn+4#h*NwFMfcr>idqtvuk15n#qt7bxaX5eO(I zVRg*Ct!3R|;6CKbA&Jaz(y3JoxZ!Mk_%&V%I4hf%>Q1p=h{ZdaX@TAVAJ_w!teG_t zvJi)YNBXTW>V z=(XISC`3ccf@}Z|A!`H}rXgU7z>7oQfqr4Y(*Y*RzUC}z2;N0|fM}oz176cgZmNC2 zCNfK@k9aHUoU?M+P`8 z)n9s9FiKB$j$kULfGmlwCnu)N#1qixuaACiJo!ZoVB-MDQ$wuLbJ|l=p}6oHURnq3 z?F6zCAUd%l9lJFhG-PFRQ19${u~E)m>vthIt3%0Tz{v_)m_CQp7=H?zKw9dwK7v~>x z*R$!{f0WzLq3nQuvZ?)CZB1YEaq$8u!|#{5^Iucn?^E)r^ulbC!I+2x#hjT8140oL zeSVQ%0JaC8P9scrMi+<)GhwfuE<{m0hRKWx;~>lmmN3*`x?C*lpQY7#W#-#6a5 zt8%(6y#Mz;K_2m=@ZdAT`=1krf3O$D-|;+ut`qj^os!8Png2i0HE?pb|8)(Vy6$vz z`xiz$*soakY%H2yQUCiP4P|Fqph1xbq)l&@%F}Qa|Jd z=2Q{?y6}aNk^in^IT)N{8`Hi1E$o>yi$7@3oNRsE+0q)JDDWC_9U3_q0-@tbp6Mo=$Q@R1%5UdqWGRPbIe=M5; zAQs4V{YWbiQc3``K(J-nQvdhi9YRJ{R!Ux87NNxXGu7c7toP$6{ub+nBe~yOFaIsv z{K@Tt|1I47Rx>@}V-Vg(sa8u72R;2(NbgpRq*h-t^b)#7Ds8<-q=oX+Jd`$7f9qpa72f z&57-@F!`CX+1!c;LQ(2px*=nFUChz;4?3L_*k}FF|Gs;gO_|K@$$(J6RGl0O`v2h@ zG-TyD1bo)kBo-$Vb3#Ncm8WP(frCJ=1A|)6|tvB z{Nq-gU(wMVQT@4I{(Vd3GJmdC{*U98IcNl-pa8JtoUFwEgh=MV(qE}xLR5_1*!O9R z{}^{71JHxqj}%P->{_0Z!C&Z6*nP`RWA0hEA}1#`{RXs(Xb(6XK%8@6ci;*qqDrEXUO^5DbE+B*B~o^cPi z!QJ}D8{e^{f(BYToE7)KeXv+Y5IJxD!e9SOG#a^xi`=%6SM=aKu3!BtMhY1nnZMlP zHy;oc1r03x)pyzN#Hb%cs_^UXJM!@qxwb;xmRhuM>H1mnEks5N_dj$jB z`i&8=2MP+gNvZkzjG#$+B7BvEnQorXhw4O3l1b5!p|n4<&Vu=5^EvmiZ(lsBWAsX! zUn@VoES+YaVvVbf-|MCpt7z7Doep*stH^XLwcCMgOwg z(XU$*dc|7;HW~|jz>$d4jfwit=VHF8^yi*qNw}Z97clLE#xc?*V|Ux=!?wMzGc?5v zF4a1nQ@JCLZ}RUS7#pbSt`Lu^4cl&NmS$J9Ww>Nwv^yfQO-NrrWVfYlfgkGY0H4%7 zWXa?N3+LICPfkj%%EcrPch>0C+(D5hBH?c6ILxW+<9VZ9NkwS^AHpqe$W`7@GTjjP z?dGGi>$|fqP&;EUqYEhd-S6Q&+!l~lJU(PoG(Oav&+03P zV4W6Gv6gQ*xoU^+*th-R5}2n{RL6@5a$jBtt>bR-fU6v#MNwt+)9ulZ*NI^=PTGw; zJZVKk*Cr-d#B3s?t#eJ#3#E>DV3cP`!Cc%XDp6IcEJKxmA>aB?l>k30a!Eum^G2Fk z!iC%rT6EF3A>;m6w?h^!{W+S_M%5A6{kar3a9PsE{JH|MJ}PJ;!K?8u4oq|{!acP3 z+grXyC9Bwy>^|yfXB;NQTCTsl71=uGRZ@P8zh;!#9WHJp^0>b5yqJMd2Q5gY_VP}v zTg7yiaz{Fmp}Ib z0(W5rjN#XeZz`aqt+>`4C8U3OhsBG&-@_upm4m6zbA&_7D2w0d6nE4wL$sY zv9E+^LVGUr86~MdCFNX1+|f_w8Fq#KUsf()e*N&Q`%T$l^v^`h=e~4-^*x#=#3TJR zs#J#eC3ZaLo{dQ&^FfSSJo}yZh;Au=Eqwu&B9Vm5>B1)Is!om#XbQ!5R9p-*8ASW zOI zC$dD_4pEzpZbE<6Hr)9y zx05bO`_RvLfdD=fWIOE-IeNdo-np+OPjB={b5-wQ?xedpiGJNX2<2SNan|sz6w3o4 z^q;ZAinKxZ3;KgwQP&hDF)eLhwx=*O@OFc` zZECixqU@ruU}eXe`ySFhf+*CoDK8d>M#1I_aThI;nj_oZ0!64El;7j+G7JWPN6 zW>?EVS3_D9zW*ny;bw!Q-c zJHPw*^36Al8}7FnFYKxhd|;hyS(lx??u$aAc}n8GJRj-;GNY|80k3QvP3X1Qxsnnh z>|ZdyxW9|=jmgXh~1(YT>_qnv+KibAqYF*-goe>BxlW3C8 zd;e4aVJ-Y*{T(rCG(q5aw%_hzr?2lT&|-xu`*MONC*ruf>bo8%*7TCMt8A<5b75sO zmO9Krwipy}CV2F|qcbl5Ao3*_SXklZ^+_$1d+I4Fq61ByY5YIO+mw0=oEzj1t*O>* zl_-!L%r2Fe#H+NN>@Wshe0*qKVVNX6tRA0w!saGnye6e2?+lQZ&@n=|YQe4=z6y8q8;uti zs7*0xl^COk1lTQDwAA|$>;0;({-WVXQ%PcXh5+&BS?is&J%}7H5%%Gk(dzt#CMyBN zIHx-LggP&_Ki(?yj%!t9FW$(p7uhray3nDvfc_%A)NG!;eNEXrJ|SBP7u13R8?__B{nf2F zrg4;7Q1L+fqoBpLm9wcj-B`BY{ml7}tCfyox!@7!^6l$b;Axdp>?dBOr|0|f=TN_eW zugXrdTzwZ|VRZMf zvhp{$S~maeneld6w*sMk5X`sN&fJCA(RA0vpksH?IMV_GM!U|nGDMU;1dJ*pcI6Jx zSue{+A2%P~n{ue_{(fPC0GTzfv=8VQ-N6Dee{ZaQc$VYCB^}tfq3gWB(G{eE=w+Sf z6Fbme$*<7z#`Z8XT7kz?&KavR3$sP>5M(92m6)UPLqh2XTMqf~>G$5e$n0)t2wuQ* zV@Oy?sv!KKpHmVt_vr@!RF%|nLu{oDd&>Ef!g5Ku!)H_qYgJcflr;0m#;Y8tQ$3K* zZ06Z2Z?dE|rRZ!?{b-&Iv!p03*{Agd^ZCoxo%~I~)ZVS)t5?xJZ+MkChjb%MR7Ph}gADAUkVb+kK)Zh-HJj z`U~Hg#oNT@pUGO(<=2~oZ@w{-($qRZNU=}W&-ZLdy~}eUfAhNF{7RRbdCaxB4h=)N zx>2Dan=~TdYqoIuh;G=T$0@ma7~GFM_$M1>X)!so`x;e(5(9ec1ppik%GYMiBKJ;!&SHi9rH zutrj0R$$+emK#N=%=*PG$))Y(A>jZ;r}sx8Th&I+ zZ`SbzTx*-=v87nG)m!&WzbnX#1}`g0r_NEY=vyv;@yy}xiAp#7&| z+b>EL4Vq+oHlT$Lvd(6`=oEO&UyF|f$kwXAn3d|+^ZMomF@vs*$0DZJ)!1zD_T*Y8Jb^?-p2NiF)6|>lEKyQ2?CIHs5z|j#p#hu%u;rG{}2M+prD`sK(bN zS#*Pcje+~9%_n;neR(7tC*$|&rFwaYK*MVL12=65d17z-)rEe~{T#OnhM3%92g&3V z5RzB?9Q3U{1R~6}xkUSp;H&aG3v;4dxjuE)#3ccGgg%H59yzf>+$;{go<8#7vPXUL z)tv`&1Yh500ynCN&EYQV)9t=7Vcd!=BDCfM+Icy1sI`F7U8%sR1(E!QVB>vf;m7AT zP=;JsI6xQ)`JG$GnGN=9;jX7IN!zEoMN%Iv&c}nKNb`cd()ZqQiHFKx2Q4X;4FNUP zCYXw^+HSH3_&Cg?(`zCEAleGX9@2+pNM()-~mi+G?Q+Sr%Jm<&fPkZx$bDsFIT zXIpn~vRCU+M}Ns=YUT^&9j=Umo$IDEOUKE;uUM+7*Poj~YoW$mL6hUTrWIb{ABiR7 zIh1~LbwXJ(Ccv_dAJ>ZCYsHN5T|JeDxx2IKcn&X)%;3i^wiN7Bm!ca%!>;32xMB+NG$ z05TFqes4;HyV{Bh25ugse``MrCTd=nh#>`*m!@K8vFsjbY5NR4KRqLzgUEc|dy=S~ zW7+9Vhul16-Y$CL^6V11>EyR%d>>L!C$q&X00_AdRRr=%=<7e{E>Vru8oge_IM#xs zzkP5bF8g9ebkK_%N@!*_cbhr?1R%`Mtn0&eSV&b!N_yuQH(HljTCO)dn%})Q&&MTh z34>x;SAcnM6ro&ql_4=G`B`L_UvkZ*hm_hhdq$oV_1S8MXY$iFiKqA!*AbA}QY=~S zP#)-6D)GMe@cbk*N(dbv{>eOI5}0Q|2~l#t_UWJ7Z`_O!n*(}$fG0hl>E=4)H0LjT zq3ck2O|GjZ?i_?~vv@{^89^6Y9$P0^GINAQ8T%iv9|c*Li~C5gv{qO2t#G#tB6}Wn z+?+xhEr^2XT>-|Qwak<02!i>;Q`wOj*;d*4m{xHj(Gm0B9MzW-qjV8auLjFWDgzt- z8F-z+MNEiCYM)svmb45?b6(izSysUPxi~nVY17XrDOr(aQ#E{B=iFB68R9t#Uu|zo z@>jKy^tL`IE!T(LAoaSjDN0N~>?MUkr)c-Do|DZC4FnVHbgPJ%6EJ!64jz3EWd>?| z9*iEh*&*mD<0z?@e4%mF4`K-PP5JFKTkUxq-g6x-rAZo7lh{~1!(h!+pi88qacH2 zqH+UUc$TfxHI435-B}}13)be)7QS4hDj?&^te(t>eja$7+I$7$$xpY>Ipa|WLXN%? z(zkhd;HJjW_e0z4GaQfZ{5HH^=$0CIxXrEugc1wj90mb7>jeKp`QSmOGz+K>zN8ia z!tOy;qlA!rW@2tgVg9NvU}NUbE=d{%lqN~up)tGAJFWwSI`RpN~vLJX$)7E4Bm5KTtde+KC=p*n(_SxRMiMKhYmFNfO!QfxRbe$dmXaM}(ag zCKP_rMn$Q%;?_8oOT-WhdgZOI;04Nd_ZJS_(D&xcsF8K^m`aSY?hRO_c_&%s%5O72 zkAK&j%P_yV6?H>MUg%0exhf*w_~xOSC67ej;5#98EJ;O5K;HFJ^ib@uFVJF*YFN5Rk9l6-vSyG`YQFkS^|YMvv(*79n2yWaO&@iN z6S0L6Mk&_Wj-PCwn#`07zO4d?ijnE!HaqkE+dh{Is6Da1x>DM%CBZo-y5UfBvQ=gx zsHUL%A#AT4?EC7LR>aW8?b(VMg2m_v<Hb2PcZp&ReQ!qnWpDNRMwR_ zd`vcp)j!!K)MoPyU)L(1i@9kdHxAMz&h$F^0=I6xz#5bS4pa@$Mm|X|+cMqG)#!{t zut`M7V^zC+GFR(PS(m5pTauhBE}$7CRzdb%t8|CpfsMgu9IT69uT7E8w|YG$bftM; z&LX~iaiho{upTxDU9fpcbgkdqRv+Ptd@;zt@miCx+eE5 z?=t<UR!9OOqkXLqk61!uU~lGPUQGi3jJ6~O z52s_xZ`chC%@4+0w27s`g7aI0fYH<5o)CAg>*Em+@olQw4N~YYL;ze93pf~0ZMMw! zO{k$gn#l5IX!!HhoLag4?E!xWfqmHm!pYevYc6u`nbVlo>#OI45M{8YZ@*h-Iky_a zEBavAh9efJj29b)p3$RMl@65sj z&Zk$~k2~Wmz+h@Rx)5LWJ@j6Fs+}X&qK`{DKD|q+^L1+{X7wlE zz8QIzHA|&9GeiOoOK$sV>YWG2OPvCqc4ZW~FdbjW(PSE~{cI)oY?f3_xlz$Tp!jzk zI~x~6ibt;Fvm}r9R4P23$m$wgtL0`AEAqIbvi>_6-!g@)tLi9bD#C>BDNR9BO7y~& ziGttHc4AI}MV=4ySuxd!hInY9a%;p1 z3FgbIB)9JyHUUY24*FEMMy}+GF^lMvx-7xmrmA@9*e|sqcp0FR{nTWyC6IN9+ASQz z#1*h^>#NwIuhD0FXMcKd2&uu{Me2C|$}_F-+S|OH-zHd=iqiGRp(aC-T)~Mowu=&L zSA60xGoSX?9GlxD6>1zz^S~|#|1YXjdjUjy9}TMsekpgDKQ+^DOAz}aG5moQ*Cd|4 zKPAvrZm{eQZT;%+h9G*dG-$=Nu}%72{$3tVQ1+(JPhqF(k5!62?8wTq(%B8TYAd{h@bpee0mZrPY)b-KXnj_mf6 zKLe)wAP?CWS8X2ACksrXTFT_a?)}TkhrY7}LFAhfUcvau)hc$UAQ1`DxtxS_CATgt zNp;1<$e<1dtxsbc8gEi*q)I@RSEFnlsFNoT$gY{=Xtsh{Jd5qvMT-|EQ$~;3y5)#> z$D+eWuQq;xoP?+$S5d%l{S74&$k8UlDxV~;ft{#=kHJtr}dPGzXsPHgd_FqI{OwSn4C+x?Fye33$m6ExY+UK8Axc|1eo^dpf%r4) z>6I4z8bU^`nNAk3}n3{OY`AjUd5SA@8Nkk9xSCd@6czsP7F-ZcWc;*?SARNK-QTMjX07zR$)^u@kd>{^>^ z>>=MaIU$m~^9=sl(0KD0E@D?NEjn0^J%S_J4)-@DbSh2`6MV7} z6J;--SK6`-y&6=-R9f}&*b`=(8!{9avHGF?N^BpnbaCPM;acb9Np6K={cA6G9+Q6n zafjdsLZBAhGvGEnV>t-mnsv&zr!QhVftS361BYuBk{1vNp3h zahXz;z}@Ba==7^&{KB8sz9pl;G@cju^aYeOSE!SR8AI-ipPw z<>YnG4}-bJU>vF zLP0mTUk+6Mgi_(NDi-7o2il8w&XZ<~{5|(p$?(2_XOqf(MH;j;m-h`7OV|&iS9mAY zrZ7+Ky6ak*c$h~(*&d{GY+1woMqiZ^Yp9!NSHcl%pw-&@Eo{pc_2KH54)5a^jAxLJ zB2It|7|(;}KvYPF`3wnWZE`%?2z5Ma7T?8$fYH#l`3Ou+bLBUOtG-p&CmQ@HTAkzO zuk!rN*|p&4u*BN&4C9Cw!i#3t&pKc`)4RrkpYR&mZIxRp7_Sh&jjkIlaug%G^eWknE@|wz*V?h1@TZnu3G8`l80ro9cUgX8bh(KPyFz zC(j)$WM@!CPjah{>LmixDe0EQNd(hYMu{3gesoNo;SVoUAS70?t!cXLIJZ)yc>tYq8~w>FsOzwEFTP)G3K z@^lF%zp%Xf^D8o)B+b5AX&pogLQchD|91AcPcJ@DtdT#yYVuTZ%Avu=%`!RLFF}ZI zOU^+|LP2=f3CXg)*^~G667&<9fl_p7rh^@{Ybcr$F+i83@#@I{_M;ahW1-9ao=cSD*Q-pIn19Dc0i+pVu3pRHcaa#=C04dhM$CLUMgGN4sIFZj(u z*W^ncJiN7@wp&m@bIZb$mLo-5xYjr2Hmr^ciga#*IK0trW|$O6IeJTrCw?rr>!`JU zxBpA4no{+{wb9t}cx!vwPFJvZmqvNJr%3UD|Apoc&!X(1EZ^0;E;UYT`)1cls5V$D z2#x(5b6@g&-{!it?LqAdm%?4MPL-X>a9${=yE1rVm0FsDU64wJU%+5b!dBGvtxMEP z>033T`?!*A3e1PvpMrEw;Z{&Gt9zed8Vaa~6Q zY)9rR689=ef%%R3N095S7W;I0v6mba)Q=~FHRwEkbv=6xhH+&!=*s~hAoo-^6YKz{ zE^HA7E8MX3P>rx>tv8pMaJ?}7els!Y?JA2Kjr=v87^n*L@p)tlsL?$eJ<#7+V8I&h zt@#o(iHciusG#!g!&A)uFYjKQ(!V4TdqAevbgYF`g#il$+7=ovVGHs}bv_f3O^QD6 zk6%N0#6$&-Rs`Upis@v=_;B2i$(*!A=rXW8I}bjQWZU8`Glv(-3EI_>nR@25@}t!~ zLwoc6FM$wpVkhkF!_~~M262(|U*!e`wSs!_^37LesdrT;K5edyQd4vE)ID-Sy7>K1 z~W)YI%eCSh^*B zp(j6HkY^gupOx7~jjmrYa5AquMi>mR&cJ}AyyXsmf%d%M_*G!L`;kQR)MS7#ls$J^ zq~5p_IJSRJJqvh;L}HZcsLROL-ej{@Bd^i`ugDR*WD}DDwKXK8Nnn@9Gc`y48Qd8r}%*( z^?AXcezLsld}8fLR=>Yf?KVu3ol4KCo|=N(t;GZAlLOXbeJ^$e#&mBOs5OMXlKicJpl4 zV+joh)=zvm+Fp*y(_d8*kVq}(hjv5{3>0+L)xfJ%g;%lMmQPzYayQ^~j|V#MDget9 z33gcU)gkR%WQ2Bue(^XeQU3YlwbUJA^k$j-`sW@XB(!r!u0iO6W$3r=u3J^=QMIvX zu!ZADr3(O99s{4t?>aCj`)Hl99&LAHQ%fdjA3&0`wIS2zgFY%kR;#9D!Ws|<^e{{3 z?J=;>Fum6aCPkx6Oz{C~i9xzIeJI(gi;)(ULu5q0&$lZI=nmFCV{)MPRsFC9Z_EP1^^9Mqb5-1;ePA8#MppQ{|%uo%BNbr zGr|hXDwKEb?r(}cB_w4jc!8z!43$z{h;PoBzvG3#I>qR=B3gw+KmBpM0>dyPEng)p z`^y3Wf9dg_Q_^OMW(n?%vfVSm^{ol;`cmh@Q5z2)-2C#LDX#Rg$Z4XoZo_3&Zqo2| z!0>k46E|%6@a*FVtGK+{fE24|5W}Dt=$zH-=(yBnFQu~A;ORwXt;*T)9YtRv5VYXI zZoi7+Vpz#wP=j7d+IiVXa+kG&Xl{UH|5g<_%(c;rS;OhR)V-aJ1uN3)Xdt#mK63X)9o&6{GAhPhEN-J;lDHZI^w;1u;2Vk0m&yv2BZ|Kkfl< zquL3?H92BxYHL1s%Uw)_fUvSzy%FOWJ^o93*!KK4hxjfOzTo<%Z?Ug^yzSnXcMBE` zop}G;ZW?q18-vIdqJN3C=^*kw_aXk;b0U`$clR&8hPQMGFkgi0R;_BdymIJBS|dE5 zm>_SrHuvQKg|E1m8Pq#`0Dp7Tb2v)Y8wj z-b(BcaayfgDegZJ2;AtfaLmbvF>*nA1p>5U;?2=-JVupkPFGwXhz;3Ft9N{NL?6Yqj6 zzd;C1&^0(|2c~*rJaSTP4Z=UYOTk_6>nclcRtY$b0t$*nBuwGkC03Jud?ZboWC{Ay z_ZKIlKEi`lLcxlDI^QPdh@(m;-6*LrN|m1PY6x~jr-1rgO7LNx9bhwGU>uzpZZUX2 z-L%97lkI^yvqqsWt9wV-jyMpa8b&5wuC{v#Dq@jsHtm7a?r0vDDsb6_>w&8Yg!ECe zZ+ok9^*fo2Jl`O(Du(3qBJ91mw+9SYB)q~@SJ}ioTSN^EYybqHK5_{;VBVdh_k_^I zPU%(3BO9I)kOW4W$v#?1c-+&1XOAyn4mIEFSc0prkaz(0*)w;=-leMy)b89&A383+ zGN^+m;frOJO0oOq*0&`(Nh_q9M^kq*OtXpYSwIQJV)VN$12@ZzY*o6W(sey(U)5SN zZ)~PF=;hzK5~p0)C5UUS5J}sSZ}5SS+s$!Q>{iH=y%MGSk)Yn%!^K+XfG9C|pSZ(j0M(t>&kilV?t<*|6 zOrra6U+aru+HmJ>7Tvn^!Ntu1v*|bpvRb1Lk-<70!YFKPbfN_s@23@F?Yga_oK#b>~@!C5^M$<@J1=k zA9GJq`ChcP3&*q56g{<7kx?5}lp8u_B}X@lx&$1`uuufQ$!;I# zmRyO9kW|&zF(-y|1(r4hvPuK_${4RR=mj42@i#%#RK8rBU}I4wpf{?XL5yz8v`7nO z<_lC@557KwY-F|pPIEZq(FK5+&v2D3>I&++tUo+-q**@s=yA+Nivr{PfuB0>Il$Lsj-p=bo5+uTp@}1dxkiD7X>@UwvDA(N^TqZO z{RumgqYAR4Gcugg!-flE((JPKCawcSGXGwj?NX=$d3;l_H&0jE>2(S1(uHqU{XEu_ z3C{W0>F((%yDcEE!YoTW+WBs);qj3nDcr-m9%Q~cixle*^a_K`I!~=jzX>1a;jg~( z>UP8ix5{f6gG&(y7Co<64RUIjsO}kNGzh4x(FPrepT62A=oL)}NFS1_ZwRQ1itB$O za!D!UXxR4KS=h_I%}>J8NcLAvz-IRz;folPhP4|j_r0UmjjBe9bZ_VG5^}H!UGHwm z7{)Icx8MK%-rzUqPGjr!(wFzX#3^{$Vqeo9YjU(ic;5lGlq7Gp8?xxklMkvJJ<7f{DteM|iIm)2+3 zfbj)$-(M4N(?6IPzQeP>t?2BxqpR)WjqadK7Y!@itsYso(=gY#b$$KU2i8$rs&(xW z2$BTX=hr@5c7TpPHpiWt0EncPS(ivn6E`-Bp$G(UO5DNjpnP-gn5hFl@cwIqBct@k zO9op4Xf_G;T5%uqzGzh)R>ylmDCCkae?4%G*0>2;XA&l|izsYVcPTRO*?>cpp22QL zrqGrlL6aoa4WDD3)r+BnOFbR>tP2=J`!A=ndfp#4Zp{X#U=-GFM(wt`Nx;;Z+tTki zF|fG$wMM(bmAbcd%Mr?l(lgFIE(eE3gcObHmF1elHpDKvz1v>R+LqQC`Nr_TuxwnB z*|^5!u8hx)N&9Xw`jB@!w<-a(0I6Y3kWqm!@$FJ(uX}fl(nD<~K z#b|oM6ul1Tu(LNt<)|Y$E_&OIa|5gmggh%9ohGpf4hmJ*l66=w+;%gJwi|C4%dTZQ zRaG&(c4jBjJkAJxvpIDwvucSKZOpzxgkX)Zs1EEb#$#FpHh|M*o;(8;ljv4fLP9l3 z+~#qie{OBxu{Va1BTWNHbK#*kdjsYr>{@&Ft7XU2O_hXx>hVMs!#eG+B3}Xo^sc@@ z=dZS(?-}bPNgm@5P)t&JA2utmKsu|dckzlFt(PS*`cWgh=fR8gMDR7*@H<8nf=!J3 zUex%f%^#lZ|JvT#sbaOXrT@`2xonpKSGU*%mFO(YvrD6W&BO>#VFlc+NF%l0){Vim zrR(GkIF;bwdr+D@>76sE9f36I=yk@#$qt*#tHXOX-mKqTSRPU>%+Py0!5n+eU%P>Y zTq~pVGzvAEbGxG~LO!Q=Ad9~-OUJ`K#%>2PBnW|xWbIdo@ zuv!tb(ZC%>a{h4@)k%?)$e|o`MoAnvcqC|-ljhdy^3|ZGnJOaTf%zzRETEV%V4hIb zyS-$&eE)f=o*nB|B~$`$Bfd!)%_9~ucLCp9^20s>-tWmo5(K8#7VQX#$(9MvCljF zB_=(?&gb-9Oe}dbQcPFr&ZrqK^1bN$p+aE0iAmnAD_Jq{$+u7{VXv6r3nbVroO)5^ zTebGZJE*$bZdIX{mi?cfTG)OlqBIa%Ym=!1q0d+CP(azm67crP;|BWgzMvxzy{1*f z(nd{>UTk(B5O(+qw+If35|jo8{l(`(4{)^T)#)BRr+9Rej8wC#@4w50>vP|wjvgsd zVhpV9Rw5KV?rp!+z<<$ite5KGcC+UKcZE<(Q_;?OQR7$Q>P`}~?;RZ!TGHHYUtsSs zc~d+qryt~&#Vw^9pVc@O`imHejoz({gf(-y2rJ139BQo|*=-M0&^(+X(UMq>f4x?6 zY|^u&!;>$jcYahoUn|2~4Urxdb-ALZ>EWUMNrO4q?ugpz0SW_Il!}R$9v(b5+*{O_ z6Ohq;SZ>Y8nZZvnraQ9JTUxwc^DJVJzxGreV|ta4W8y9_j;S1|ZK}T#g}EElYJNBH zQ$2_|A;b{)mXEFL2GX2na54?f05Z;S*;}=bX|0$ zEvRKDW?hf{gFq72>T>OaZ%`>o&^*|iyUVj7d2g#SxiEl5d$cqH91q>t*ln;``^iMc zd2qg2()z&HtD+mPO8OD3`(Nw=87B$1vS8ZN;l4V9e)Nq``z%1_;*4<6*WA3F4rwM@ zpzPxpSf6Pj4IQiYn`b$r4Z*{}(q;VJcdh}Dg7?%xVsu~gVbz@%<7&33;lB))3@b?O z*fjoHE@JCDXwwUFl=sLEWBV-co7d!VZ*2z;X`Kp#yS*4}+;g`8NM`7zX}~vJ%wuqP zez4;42G7n5V$iwdB|u~-!T!9pL2a9CK^g7;G4>WvRVZy6C?E(3f;7^d0-{JaNQhFR zbVzr1ZcYpLi7@Jw$?&`G45{VbIBvZFn`=WP(A>D1<}mF(vF%=CyZLE}N#$L4OWkfG z>@Bt}-Sa3x=6WX0PYU^;iWl0QM#Q|GJ45~dOtnx!qbKs4jmYEr`3kz7zFzHzT*-`{ z^-hQ=L1#P#v5^4{uFrA{2Mf$pw|hO5tK{!L)<^Y!XF+YBe(R7~hA$)Mr3`;4Rik;b z>l%HT@f0@|$<~Vjl`0u;XNgcq{O<~q5D1Ixd@GQOgEHs)_c6tC}A9<)Qp*msjXgQFN;1rUq;V#w--F|0)oE zhZbzz44MOO*r{Jit4Fi{DL6t2Li!NM`?mGCfvvcK-j0C|)>C!%%UxgNkxz@4M+0@v zIdTi_Suga_naX^l$BTR;d!>(3`VZ8I!8werS$+u$w7>+;VWp3Ia}Eilyea0$&2^8Z zN2eK2WW=@gZt{E3zE$+8_=O~&yNCOI0z6nsHPIL>b?HDN7ZNQ&Z~odqZuIeb`-`~j z<$=`mYh+M^PJH6><#L<+)S#~Y+w2^-L9&hMKcqZApHMaGzeV#0hQ!W(>0L? zDcz-^Y#I)VNWMpRzgNhR*6kln`kVR1mFjD@c+ms@;LK~q^>)O;{#o~1$=*sfnr zy5^T-Z~#Q(V#WGhE?b2{v}~nM-n-!+V|ezBh-bHvx}|X zN}x3}({0Z`idi)i)ZlXjA#k7MGXg+vD8==3&sz@ze(lX0{ok`%Wa`jLf8>Ywo2s;E zWMjL!ygv++dcg8~c6dW%tXJ`GSiz3z;O6cOHe4b#HS68R}u@aMC705qbXb(NsaCi~PFka_Uv2WL> zQ8!p=wO}~?$OKwJy`i2qv}I^1H0n*FYfNt?hx3rX@D|$-s5~(-1~ZnuB@^W)%NHN|fdg0eL9Y&cE!4@l*9Qb+*R^`%F4(k$ zE#!qu`o7DVB3+c!S(@fY#$pd}lt<8`l$*^|IsdF?`H1QOz?V-RBkI#G4Q$rw#v=v9 z;Z@p;nN2agQ=hYFz^wG=GQcXYErRbaOwllDYA?1b(?SmdR&0efN!BJ%o!@XFr@GcY zNsf}IV4Wee5f+5of*7pF46(eu<}j3>3+hTdFrY}2DQ8iC|4|U3$?#y*hoRBKwULoo zgCyiJwPMQ!txrc2?w_5LpR__S)^A8 z!Yq#<3a*Tv%O+@{^y4$K1W2_-c0Bz{8YZPu3FQ)9WPkDK-oz(%U$M9A47%eofSLBu zEii0Y1>hwL=k0`g9^=`sYRWZ8xcawCwrh?xE-OuA_xFJT&6XM|m^R6g4Lusrcl(FN z7El`7f84m~Q=5%w9Cnj`A3?gaq^7{>TdD`64gMWSNxyq6s|f^RZOSRj;d;vDKz0C; z6xHAN@J>b2+*VN(%kUXBhWH4xI-A~}?)Gp;FlpgeF!&{5b+96*uAUQ)M#{f&;X0cl zWc;lt^;iY&P}CK%_@A~@zjQ!#s>9fuN)lNq+{BTjH>mV^TT7@S4~n=TO@b1j7Y>p^ zin&S6@m9^@fQ$fF7bvJ?Oxcg zA(&_*^ZP{s9^f$%!-*|$g=V4=FrTuCRR5FiyNAg`9_(t=T6%vKAaX;`r2Q{FY z_7^cJ0CVF!v7`rpCM^Zs@9l$*(z)4{L|2~!Z6}+Ed;D9T4UcPIo=LrB%Vj0~R@yV8+swRg8b}VCU#!fNZWyIo} zpn8qnOOT)weq@ktVN6O@d(kgNz@z^>JVU9A(8O)Qg398{K=Di3%k4Se4{FjWB&!2@ z?!Q#71RGGfqC8edH;oD5jYka`a9Jdi_T$6*1|O~nA|xm_KsTGVU?Ybt=~**MHGlvT zsb6~$&(1|&p~_{BPLl|7s-U+>RANb5BggE6Qj9s1)&^|i?p~2RN`HQ}Yil6OSLe?2 z5TUn-UHlR|9H9Rw-GzW1%uTK*NOc<=O;&x4dtwqEtx$Dlyg5}fa;ovG*y{VEyYjcE z>**;D0uKi`sJsYX+}YqHTND_|Iw}ob;*lBW=X5{r>jl=B2BDy4iC}ZGYCzcqsv<|T zh^6Q_4mLSvvh8wTPt#j3_vUke8oKu#9N|Zs%?Kz5hVkr@;|-Nq$|%?)su{(wp^!RVlT6Be6wl#=#_CnhnJK zkyhUUz|hK8pD2$5;0Du+ia!m7fEf>nII_&MU-z6}`fu0gG8WW68ZYm0{%K@^&-7P% z;>HcLCyv;&KMD<}%`M%({|)>zNH(V9{BFnLDj3Z(0pqtm8g7?|MFrbsz_Tn$75UKZ zH1tX_$ITb5y4rd%EU!(aF$kYkST(%tDe@OxjLIB@RWLJxGCJQD^#oWozUxUFl?L}Z zhsX@6=;4|VG+#)x;#@}$UoTovg1Kas64TfXk$bm)DPwTKE5HN9=v5v>;qq}lF?-#wJYB`I#j9RDt%#*#XscNVA_9!_x|)}G$DMx>60?2Gnxet`nL=g9IiJ|fi%fC3jY8m(0PQUmw&BZi;%-q zc3Y#4&Ex7K#y05i=>#GkrKVHcwlDn=%-Gt9CX0(>PO$IQ_VvLDmQ3qexw61Nq`G$q zG?<)+=z|-_W;O`nh$PCIZ}oZ+6ewMicoru1g@K%tDZssmXWKo(=}Q)9(Cl?8^oYfi-M~UEA8MMq~NKD5EYtF!wv-st0 zRKFE-Tow)B+3Rz<)pOh{$XZv%exUTt=br}<7 zW^=CiugREifU>^RF+cY~L0xoBN-yrI>CtCjP+gGR2nqSW*{%T_shIU;!>*)Wy;fO|vN4hD{q5Hj&S2VJrgS!tw zdm}vV$>s5k-S(7&39t&&D8S93J@=i%sQlIFb9(-((Wf#~xz4#vrQGm6)pL(eHU?#; zLktDSJxjkyZ3xXIW)5gE-7wfHqvejD?exOccI=Z6wptQryzA$E7=icAFdA#xWu_7`o>22v|fh@Y9l>RFA+sAGtUPQb39*sEUFG)PXTB>FefKU zysMFFUbhBX3R3wmc3P-jt=dlyUv-Sb{DrF6%m`?vVWEHHtRiJK&ZWsm0pq`9lP&^6 zAYRNRVHn6`tRnYCrnn~qVDhea<902BIXviBB{SLY|ESkhIfnJ8IbItmSH39ez_OdF z5j^cqA1l3$_;n%IvFYkg(d^cjA*hvj2cIYG*1htbfWtoTXmbKD_0>Z&Dg@(c$Fy<2 zqZkH-?0aAI9&-F6NnziBBq6(9m_mI4KN|>TN4gDgMq+!TuE=FW_Z?s-M98+_A3VP{ z9cSx_=aAW7?im134-4j@rYjMRdeQ2c#zVR5ORDBzwpbnh?mu4(wgFr{N>`YlVi3Y@C+ELkE=U#y$ffM*Dt$ zw*)BMCRQLpuS3ukMG4(*J!8w_=086*^uIR`I@!^00s^Yi#<9(eh3hj~PIk4gj<1EW zik<%Vr13B~zj1dUN;sTZb+!*cIAmLC%MNkQBVk$p9fkio2U!AOvbjNhX6Sc8c2IQJ z$cXv2JfPCwBm;agg zA`6QFtN1%@Z4iKOlOTe06K8mUzwz~zT*l0%?IrX|{9SFmk$EIC%O&vt4a_@!v62v( z6z%Gc+%+Q~o5ELD=?5F{p8WR{|K)3KNM2&P2vCD>MKT`1uaWa3nE%0MxC!b!1=Tv4BKnmclUsBKCuskFNxAW@V!Lh(qMbWhr z{X`XO-BaBEE&&?iLCq6A^zrALTNHgp)`8W31u}B=%NZM>$i+>v^xOIV=Srf0`qNo0 zRbss1ksUa$jSkn@K~LP>7^Wk zDfP=-^t2FXuR6w2=HKG~>k|e*?%c&pfA&U`>BCzKP;YYm@TjUujwVzm+$qgluzj#J~R#3<3(F;{>+E^@hC^;P>pK z>;VZK_$e33!Cc?(nW^6&%7JPS^H!XjQx!i5D-0~%_q-*&iT z5?_;BpX*%{Z6qSjr7@pZt0`{_F?u1D28hZ{!_Q z9WNTVezNW&MZNd&re*(MQizn!0K||1w8BFFy0ug=XS)9kYzjE);n1+Y{byMJ*GV7` zq3v$SaYi@iqo9(l4n3GayZ%tPP952cm)geqKgWkzYvVK6sAXolr$-hx4f}?=p zTf}-qZ*Bww1GH3?F0ov{EZm}xWV-i0!|iY}nt;tRrQCdq;QeVVn>8FXWyKF*ZpnH6 zVG?`K)5F%~Ieoi-osUUuOcy*l=^pd0AFSQ{)(t3N-Qcszzt=uZhjBj#C~ z6DRRcBQD1I7q5`j19h`-?m9+%qfAe)`acO=^5kuhM>68GX92etF|L$}a*K~|S?qKoeVk~_^Qh(3mj-CVY16!Vp_zAU~oHAflpy?g&703qW4 zLIefF)o@t|4(s^?L;Xuk`ayPr&yA?+W<*1<^o|;@ph|Ji^_u%C^D87bfJb@XOsS!s z-F$LIT?)W!v+0gLjAT~lRyk}gFAzl@RR1OkFvK9YZm$5JU1I?;{>jUVt*I9M-k;Zd zbH~5L8-J$RO3s>3CLRTve$~)J*W0FM5((qeW4UHfy@wMER}u}!;72AB zM(slXS>c}U+m9u>7IYEHuP3f;>chjLs9uauvaHwjy_}#q=2>uHdE(UY!A8;(UcwW8 z(!Y^V$Fm`y=*-FV-j4I@#rt)~4cBi*dK1M2KvduI?M+L>xg8$jG);C_wZufSMxFCq zgyfT}N@T2W>5^Cu%Ixiua8!c-`q2>g^r{|V;=-bV#Uz7ep_Da6wd@W^xf&sxy<6sW z)+cZslu8rXahHI-HT}zn#Oiyg73M~KT@IV$-nohef@sg~qM(R4I##}1uvT2okdrV5q+1iTO-@aQj`t`K6xt@j-y^MafA8zuKP>xGv8x^RK-?w>Aq8 zhdr1GlgRw@$hK6nt`BxbaJta0iIA|nGTBlHgoG-sPfM0W#%uF5YF_6En6v}%%D42I z?m5I^Us9t4%Qwb$PmA6lp`wXLjqQSuZo6``4WxQ-Va?bV$hQhnp3^ zBENn-yD(BxwydR^J;4QoAEIX|KR9QzafB{AVN%|43%Tv22q_i2Rz=AJz>{L@Lu21e zgFx2RDQ3ROp5Pzu?sUo@;UArxL$fs!iQHvOG-gRQ+tYlL4IY~D9_zzQyiR+q8)f}x zKMrzUwl9BG%+~sh9*On%?3~i5L{}n;jsD`Xe(4GW8yhz0AB0Zc2PKO=OiTbUqupn7 zh`K$-^>yC>0F`W^x%vXN0J9Q|;+vFk7PJ33Mh)~B=8Wx*H}^(&7Pb6OF97@orK~Zp z<&W@16Eu(85#4W+Ul1CIKYg02eY&UOVSWFS{|cWpMj>~?kVa@=I8P(E@9fy4O)S3L zOs-IaFM?5%U+Abu{Q%Yj=J_bGUMV3u) zt^zjtL9$Q7KxP=jda>7x-TU_8+T6kFz_`sOk8NXEsz_oa!)5qy`v3Eb5}BY-qUu}d z6-YFGMvfpsCn~4NCOt!?%Mg=ou)N}({-i$9>CjVcN2ib-W?mcpKqF|b#iwmY@uRM! zE30*SIH#z@wbhmDrj+~94>^FHib}+bPf?;u;6cjcqrvAgzcv)@3zY%9F2w@T0Bm}V zD%1IQ$R}@(OgF8RvogA(oE`};iT#&1%_V_+sxlM4y^&AMqFBLLAl!&xnVNWf!G6cp+pgro?z2`kdoADFrD-ZJv$mQ z1;&I({OaPRfAXjpi+c4t{TFfgxvd!l&f_DRX~t#7&n^OErgKDm6+iW(fau!4=V<`8 z&=C<=-fJ61$NPKs)t!PYV;#;rc1@ zfB&iG3xi-cqKqOYe8UGRUV^8RjaU0oOxx%1bOu*po$q`WP=(Y#WxE`%yg|K8bHDsn zrdshXQ~Sty^}}?jl}^6%#KSl?vjD4w4#wT(XJU(uL%?{oBCW=+4v^OkF$Dwo7p;p* zt9CFgAMXpsm+DVJOyK%_#G_j8xUlu6_doV`OAN?&O+Nkt^$m9xg$gdRK=@w6A5L9*KHFl+ z78eywaUCmhJlRQYH`r6uOm)9JJ1Q=*DnEE$cpqCgfp`Rxz#eBeVN~pdO2meg$nC%$ z-v|6Tx%_813pN6UN)P~=B`51JF=R0NpQWdvOIPG`?%ynJK`DF4ID7mU_jAbP5Z?P& zd&Yg@y$aIx5ZnxdQV@mQzr7DOvuBJr!fG^>q2 zPlY1D5hmE*CvFqLye{q_yZCGu-A-om{$izU3Gp*8McT)QdEdI?G0gOX#8TrT%j~!@ zY7wQX(H>b}Zmh6K%tv=uGWKl4P8|6@SwbFLu-cTGxKNq64$-W6w;|BwLbFBGy}2-Y zU7vSN957Q~F}0n`wNl0*PsvI$%Z1s5=s%a{#^Ks_H8n{zaO#u%k^zXJD1OgF8=ebVi@^=?bV7Sq`Rs*>3__NcrP2)!?c45Q7K^J9nuy>sR0{hIU)SX%Cbhl z4t*G%c}s%OU*>7{2@q759{I;|n3i|pD7515EL7}1$Ld_H5qjWp8soS8JybyW-5&h3 z=BkdllTlnTvcP``0!eLVN?Gb`l&MqHoXB1#uH5cKjcGT2WypojGE|qPH)~;hjTJtv-5UnP4pcu*&cz@79s4^|Huit!G5kQ`&^NRO4 z)LcBxImS9Qr67)d(*+Y&5pQroI}zcF7DEwXt3!)U{f>VZd@}7{cFK|xc&1Z^#rO=! zm2j{|!P?Sn*XZb0w?oy)TOB(Dh4`jd)XtiTA&9bkttBZWm1z%zKh-p(n2-A`YP85# za#tmm*cHFxe2werKR0535tw%wO(v&w@FuTVT-R7Yjd+Ft-MGGhmq@iLrdOv6Z?Q`l z(Oj@`3gNKw-m*{f>nRP`)gaBWFy4Z$6W+hHre`1~aQ8l$YKfy__ia?Yb@X6s zA8t78Jg_c19j4*vUsgY>%Oxtee$#~)nJYN4B|(OCg)|Jn6mxgJz&7B`JFBF1CUrZ8 z2j+@?;rwGVJmI^6_u1Sno4_nwri;traaGrrw?LYF=9nX3Fw$I)o1 z!H`slo^IOd?YpX06$wx2rzfmH zSB%$OQIIh0r=ejorlbtthf!cTRcvDWt-aJ@foq|tLEJ6|hek#=wB(|Rw0w?{iM&Fz z1RS{I?!@A8ks*W`bwiX>EJU$^-KaVdVNR ze&n;>mSlcfc%A5wyCC-9`;>ZW6qE8A`U+9Xu=?W9; z!ZD66NWCBV=_f+NAHilMSy>r;0gV@M%ui?elT5s-ggB#<`>IccQk~&4QwnI!5Kjo| z@$vUk^|JcXDvFNpScnVOvBOxDd%JNSc|ASw3U|M{V8WX4#B5I zoXAc*{5P>4t{d@7dPZ(9_T6O9@2d62beq=aFrc-*b-Om!mw!bU;NsFAGesNXHy~iA z65J5>^+PII<5=EWYj|r=fR`RGitUFw+C;KuUZMg+K>_K^UU9@ag{iOqF3{oZYBNQdT}O?L z;U`S>ahcW&-E}VQQtf;seAL+RRJ$#N`h1v#<3KhvAV4@>Q$B(J(KwVy7I7BkBsT9E zepDWX(PW33=wT(FoIFv`mePn`vhzM*4h9k91CuFx#zN_iVuPuLee&qq$hbS>!I?q3hXCHPLrYqTQ}PGx9C0ZN&pVp@v8xmYfH`?-IBE4nojYOz9$G~oT*?2`?Wg&A5I zzFgvqjN;RL)Mpe+sp-#(jKv1}(8Su234_pjO$px_aOsq9NxD8kbutNo^zBQSP3MPB ziy0oref84r!qYP}8f`(|xo!y2oRycjHK%gv-I#h*{}rndVoI!(l}%BO%TTAv>Xr z@%>1jnb&ZtIn5tb-7sCUac_Hq-6$CyQox){gT0^P7wL*cTp; z9Pd8yd z(lbQC(7(vg4kg3xJgaRV**zZvrGPG_0LHu!`@L{^S%*D1I_rkit2cuahCmB8q++uV zr-2NiJ1|r(rtJ;|+by)6yxP?Ah5UxYt#v*bR&Gi!MKg~A3sK?=KS!b<*u}rM{uq4^ zSjI_jbH8qtwrYifuDML2Kg$ck4Fm32Mk9x%#TX6bQSxDoi*dgnnuv`s6$iDbvFC5x z-nL{nG?k=GYq`;zX3GdoB@I=);w{CueHr$88L=){|Sd7If|LK!$ig9@Bc^*{QP6DVn-15v6MTc5J;-415;SugiG+i7d`qi!r3Zrowt@=CU< z<^l{{P~$0IJdFjL?SooCNJaUVWlx0WI_`5$IpIMfD?hzTlQO|W8=(~xnmQbz!-J7%8g} z&WvZS^E%0Y&F=`S>)_Q1$U+M$9j%zsV;s!j=IcB6bd6p+`21NZW9v)&u(vfjRGdkYA}M>pWBh{5?*Tnyt9Y0LT5)>e|~ixV9} z@Y(Z6^_bUdG~(YJgMpllt%WO%a8_%U_61&xd2n2qUs{nayecl-h0N>;gz10N-t?zy zNUwCV)kY;PJYyBz`IN7?@V*jt8ba0OE*?%E7<4MY#d%+1@whqplt}x`!-%ns(!IE1qpI?k7iMTq7+c>UL7AWPP7M0saId-^D&R(w>JjN(D&hnv>wD-Wi zlSH7y5!>!ms-?QXy%;-=xH?^sed*3}a!=YJ(a^P^`}^t6p_IOz=6G_8lvnZb%+=h? zn`^)OV%LklcH-W1Q#v~#u??Fp?UUTK2Np(sF$LwP9-+vm96uz_`>x!=ipm~u+&aIE zoAL0q!t4Lc11C2=vX3{zbV+i_+1(qtoJ5A{u!CK(i|Vk0TCsc3=5TsR|1qd0L10vb z4B7QN3T#|a61pj}9y(9&&uAUw!gd}22c6G^FE$tpIic~^^S1ll9Zz}trm)M_n&(!T3p}FhwIYYHS?zS>UI(t&xMAc*7xs$v)alJWf_m~ z^Cl>_;>56t&%1av^tERe*5DaUOo?e@&e#$W@~#HjePE>31tEwl!=wzBL)1cOan1)(az0*H1RB z0H7J!T(P^I4)=+9?3z=W-uC#A5D)|~L^9k5*oKzmUn5xxFY75e@u#ZopYS{USdpVT z4!nv_cYf#XO)itf8@BE9p506(fzJhZFYzrrufM0?My7BL*LOaZAdfrr5x~gEJQHZD zN*9;UzZ-Y&QnzHSZwpIRY)ro>47P|LU6k@-%Qzyz6ONV&GV%w`#Z*0*rz6WRkuPD9h0^9)q`h1i6bcf zp^&78cBxwIqe_qKdi@6Q2%J)xe()pB0`rsj!UiAL`#xoasNf+$!3CeY!8RUaptrt6 zkMpH0DZeWxc*|h-&f1$6AEBfLGFS_m9aK5ax4vd9D}>{lwcrROK*9;_5YL?agdDEgh_ZX$Jde6BP{YafH1;$5;`$odcIKBi#f>jDvJ+0y}Kzs~Jcv@O1;TNC|8=%4GjBf^gT2lwWgad&3h!Y#?G?3c`SX|nmpo7~2 zswh+hPYktO-FL#sSH2ae?K&7Btqp$~xC<$MHWg`4qO%JRm$iEj(Fzao`8#_qi6JZ> zzg3D)ft7%Bf19+VXTUefDtNGOO$XZoN$a0)dnqn|66d#URGJ(}5t)_QRa@&Xn9J4p zh|%k;-vQ#lD=ypMym-g!Is5^5U{<^BYh)*J%2L`1XmM*9W!2H%$OceEBK5p>ovC?s z&PQzJPVad^S~h6NWJKk~>E-csOYe;Pz*4%zd$wdPi=B|qqp1M$GJe@c|QoQS2gyFMA@kJBN)C?k=$Az$#0=0^)M}UyZ9kV?XFFj z$l<`;9!zZF%1K5B6BzYC=r4#i#|U`vi^_5k zQ)FIOT9T&=&-BOe7@)O>5*oOUPrmSFiswjkDAcIl#8U+aYASj*g=PQH#*!9pc?YS+ z3Q^VamZ~LI^i&a^%d7MbC2Vik<-aNyG8DjOe|Y_&iZjBKmYDO505g@m1SA{c95o1x zh`t82OEhL6m&PJK;4qVp&ogdHannyE>O`M|<6){wEKk@^!>e^uXPV9s7 zXT6q5r+u>d>VP)|@>8=}K<`NCJvDue5t?S!j{E)Y(V|aN#Xy#-`UrT0HpQVYsXa_I z0SyiLJ6gySVvwRn)(pZ=VTER)-!z>DJ)DhL*M|q>( zYIpi0y#_T$Hu{-ej?%x51l*~qm#@Q}ID;CkcpGJjI;_>KVqO^FhqnmLh|#c#;nsRT z??r;}OEx}1DosRu0Loh|YpA7il-bFgR&c?D>}=L2cKiBzUiPM=p)D0POnR-g-Qz# zqBYs9KRL)SlJO#l2bDx=4K247|94zvN)3+pT0UVJ2YzYRizZXkswH&jE8HtV?m=O( z7oxz?*C+;a74Y*^-^}@oRy-Gt1nl6(qk;#XyVCHwonZseLLb*?R`X_fHluzj{>*v1 zp3RAh?}wMiyP(;lt+F0Gk+?FQhB%$4K@7m00;A1L@FdHsOU0@{vAM;JXCeh@^@+(4 z)K2EV&LHKph6nFuG+zM*cy}S!;Jz}RA3w(SV*qt8=l1=(gio4VB|k)Dm}EYSp%qcD!hxNfpv)0&rNC9=fpUCN-AQzvPAMsT;w3qmywky6@vc+)SUZ zW=uf|-1fU+_fL1?#PfU~hmW3jkcP3K9m4Z(Oeof2y+q$!z9pcHF^FdmH=ctrNF4+o zEN$PKswwjmtxe!EiQ2o+xi$ljE@1)VBkpkn{NXcw{`tPirIF>iWtJV3Xh8 zy97|tuX}uaeHXw>675{zaU~lCeB^S<=jj5~t-9mr)3z+WK0fnjWhSFF7NqG8SHLx? zn^%PD?w(*5hwYE@Z2^9Me&3QvINW(b)hcdwwC8@<+5z~sG>e(~hk$fWOYn9rHWYa> zv5yeISX!V}%%^ZNP5i@%k^2nyxti_018~SSiHwo6r~5_*Xq$G`=q=M{O*lU=RgLRn zYSkTGJ!Ct%w1<13)Sz%Ya{uciEA^I7$0h6f1s1v&6M0D-Gq*k&nC>(-^sFh@Ow8yz z%wX9guU!h9DqNyjhWWlS83AG8Jt-6Y@iOy;BZ?m_)zp^fADkWI1Om}oF}H+Os_;b* zxI5n+NQ8rQM9QYlSRdGo>u3eK?KP=^FDb%Ik6w9^5t1C#DmH5;^vjQA=J0Gj5ugLhd&LN+HBzNJRv z5SWYESK|c13FE46a;vY2?JRDMkiN?k;q5!5}a55SImv*xCq8$+7wIvIp-fn{?~P`wheyJ z<|_MiAP#w|W=(u?l+bL_Ks3bAk2O_GN-1_{Z7mv{bMUeKcwi1Q3d9NAXVoU8*BHU> ziyLS-SQ$$5#V9=(A~`!bQA9oHJMXy&smd6Te{uZegRXL3{mmhIZ6*n>kXgqqKD3^q#fUT$B(cVD(x zd)bV`sxz#?X{|-j$FRCNqiRMnDz?*Jo~HpDh!)s1Buc1?xsNNvM?nDxMv@y3Eb5!U zTaiJA;j}U#ZBo%6B`}t!4>D5ByUY)3xvGl(cSGKKIoEz4vrDb1MJ#2c$4lr2$`;QXs31UV7eP098+s^Ls-uBJ?HzGiZ0%^T zX-s^rl@^za^D4_WSf4&( z)~xaZ-HX~SXNQ$e`}(NZ^e;18gSP8Ms`iXsPAB#(BD|`ZB6uy(pvq-%=$c*N(D zz=Q3E)l{dLr;rsUxA12}{GR6=!s@h3Rns?+T}Ehb9sxaRuDe^^I5cys9o$H*pGW)< z%N?jG+$jBJ1pbyCwbQo2M1DJ~^Rx6OV06!|Rs zBtx8dUIe@CiNJ7HD4D0!;q6j)A1L0=SGm-vVK{4KU7&Ue%z3R!5r-1wRn6bE_!ZET zJS7zG%ItMtER>5tod{iLS6E10V0hl&tGd3HuQxuoKIRVbpi*w0)zOaAnOd$G9xLA$ z?{AL2BG8JdX?++=rm0wDioZ0*pnwu;cL_zd$INXto7Iozro}TqR#yCK7SdQB8V{Sd-b6I(2N7ifhTutnHM1?*jUe3k;7qM1! zWwmoN7Vjia?+a7K`NWa#Qw4}ox#0q*Sean>+a!3 z#NOP-$9Fe&7dklY*04o&8?33XJa{r+#IA)Me#Gd4FInyk0aNF#{&YtD>75@qSnlA` zc}~K@TJ<^{!QWZy)qq_-$udkscW}TSysNuq@BR{NIN3ld3q21{BRr`#Ai*N|^BC=~ zqcB2`BFyZ3a}@mlkE298vo0>Y?dm$8wTk7HUQDp=5qcpZ=7DI>-JsN@<2^ zeb1`8X7r`lk`}-C#Z#(M)Ebk!dDiWOFZmMhkXC)ANlrSe7|Z-&m+(V=8`iE{)j|>K z^Kt$!qqC!|o%uYqpwc3RoI8e4jD~bMn$CEmB~0B@{sz*(w~n!WiTu1WB^t|+Y&Gw= z8a$Ov{(fg=N!hE~gvs;N5WJTQNl78=PUOK$gXB5}nT~Fh^2(F5ilyA+7v|4u6YK!7_iLmB zwcF2UjGUS)wqf`_VWjrL!`-@tfr;tm=?Rm-w_Yi8u#(`@QI(dmWhM3XorEAVQ)iyYGB`x*MH)dNWGPM>6n?~O=9D;`yDa}--6Q0veywi{o;!A~h;zM@CgSa?` zd>!>~u+off&1jofi5O|a`)g5_LHfmYj4b3j_cXfRv^pdMF9IDZURnDT(Ii+Fl`WH9SaEJz<{F7>540 zltLJ*b*B)WSP?8%<^!dF7quiBiC|x6+h|r&!+Kl<$np+7IcnW$Lc(q*!~QnJk_ZYd zRAGY2i;Zl6qJy}NzCeN{#+JGkVfs(^mm3~wej3P#=FSDhs~lYl1UqUaqX_s~uSV1a z5%h~3se(Yc+xhR+@ic9Jb_Cv3Jd2?6C=#C1`8Cr483oC9XNsWX2nK`JWsv#C$9&x zdVHWO=Lco_o}7H07~093+W~2?kJcB%-2sgi?yXc{o-mA-EV9JIk|N~nJddY=pZ_Gy z@qBY23qA9BtgyW_G?^ngyBY=08`OBr8Ct;ki7i(_A_y?#yhQ#Wdhnm5=M8UEP(8%W zdWdwrhU-F|-hvt-h+Ho?63j*X-t!S0X(3$wr1{vzk4(V^g0GVUmTZuE5aWYJM)tWd zjWt+USoWSpst#zyOev{U3~u_l7M%3Lm35m|k*qG(i~=pRVVj1A|27QU9lY^_T zujh00I6I39)iib^Swr+*Eu`}g|e~^Xb#TQurf3|0z^$jYO+z<24x{m_)qa6X@J6*(Wc4SUV)JOPYMaUdMr6lF z5IUIPV!U-rb>%o6Irv+$g0XG{KO3ZPl6;_X^%k?tEHXve*Mt1Z9I3o6S=|0LZ_wS{ zcnjIJ{B}&ykhS&#;jK#(C$0H{_u-((5JC9PRzv|n@HGSYi&9O{3?B&I^&z;$-mO{Z z{N!2GgH-~5M@ek#!8+a4SQ_M&=d;{NDXd3tShnbP6G$XW84f8VGFthA|LQD<>Y-@b zZ|EI6IK3;F%jODiiG;s`bnt8{{Ovr1c8lVK$x5+CgEBrgr{yf_`AUWK4ieD0*#Ww8 z%X}5{lpy*&adnTDJKs}+&_P4^&KmcvEFR1q3OI2~JfYFxhrBPt?eKmy6YbFCVOFv| z`{x4gy@hefwh^f$f*e*BlsSLbQ4=-$;h9WQumU~59DMIoNI7=cG<)E!5x9jsq%|Ev z*jpe@a7cjbKZB*V8C{D1`~cH%s`^P3v-&5#2Hh{1rN%=6rD~o)c<_|qeFWi1o@?Fd zouwpt88zpuAn2z1|FHFzQB{6l7pNdA-Q6W6Ez;fH-Klg*hjh23bhk9pol=4v5RmRh zl+L@)uipQ?2Z#jWNsups{c~+q^!48^|{VpA4Z{D4=*QY^J%GIstV!fJ{XQI)bBw@98KVe6gQy#jN`ezum<^^(Rp>GQKB~Enx)MzXEqd9UCrt&#zsJ>7kW5cH z_1*iD%bWc(FmiPjh}^k-Z#V#M76z7U^?Q+Av)d6NXsL>woK#leR?6UH0`pvfsjwO) z(9}z3^YeV9QHZ3L`AF`x-VZtkLb|$yIv*drV{XB;>#!<=Hil(Z4hJOg7GIRtf#g3R z7*l!vW(x^>P#Ig^GQ2(e|FQ|jzgU?yOt}0fpJzrL;57)pp=0+;WB+pyx=r!W!KnSTug(-o|HTbK#}j(m0T)1k4<$nXBmraS5m&~G2#y)lNPUS)z) zZ~Wj%QbwL5d47r;KbH9KR~2>#xrnQjV%Ro(bT5JHjToSF)~At5cy4tlsjkv(CE zh;~l>3w$dH<;Q$MWhNt+I2SRS)VX;N6<04uM^??xxgVJtdIy+|N$xE}$gOO1j%V9vcH80@0lT+^y_=5sOsE{)YBaM1Ve>U0-6>YNMH zfCw6thTw3VO!P0GWr<06R-t0}O?@}&zb_I6K5>~p;5MUvV2sAOQC#a2h3a#0nLCz zo+z}XKpJ5nVCDs$8!jWPagciNfn|}9()@onWcM2MZX>2gSr9YkS2TO_P`iWKwvF3u zGZ#8Cj3CrjwP6mHkBib6jENNee!9AUmOv$C{UT5?gA)aul}hk0+p0-GNeptfDg!Rt zIo6GDZba+PP@!x=9=8=pd%K^*-eQFQz8VkxbfIt!cg>1X{nH)e-T&nT{!pFC&nFRT z5Oi*TR(LHj$j(QMP$8bo)H!_izfleSf)fSvZy1x zJITHv{KH)A2x_B@*?;sPHE5vn22u9k?X=!T$Zq_Cp$|_`_HddGDCVOu9bJ-J!!%2B z_}o!}sZZ}rMeMz0M@O3}-~n}$+oJ)pyZY0itMLci&MVN5WdNg|P7Q-u6VXk57p8RD zr11XeQv*)2GS=0lwQR zXErZK@FNA@+k!$dyYKk_J@KEFt@ges*XuwQg^8BLSo)JM1~w}m#cC;oE81tpR1E+Y z=G1~Aut#mLhd=}IWRV;mQ!qHC&5jpaCXmBA=|Of4s-@;90n1lNE31`aRHtH;M~>fp zJjV0fpquyaOuXA0+!U9~jXwn5&wMrnVd<8O__0Upa&b5QudPYlAiES)F>R3?7!Eg4eSZmuQcXSNs|SEui$ng+(hM0?oVzntOo%8UFN|wzsb@ ztJPBVC1?tI#T1&tq-U-1hj;=ii@LVyhL`UCiNMisSUKbxW=a>BbcH1%J@z_k%SHN0UD{@t8jinNp(Em zpP|#KqlSfrHN65y5DsuED;Agq5|H7O;th~8#oL5|BY|I%7c?XW^143-+pivhanPb+ zKqM^elu9=5sWa~)Gs=JI+P^A})_0YyGjarl1E}hfvedHzT)bchI;y~)epbEw1u7`( zdoY?l-M{0*z1J2JJ}z!?#2&C*o6#M|4|e4tZWIZ6p8j}qen4c#<9NS`4Etp0M zDC&08v7i-KGYpJ(1*D^pcd5qt84_-PrB1yvaA?|!qSx4_{5TqKeJ1F8vkDBPOVvtZ zFXr?dIzoV6gD}L!lhOTn5#1?E%n0o7^DPAj5VYF}(Y-Rr15RNZ2qHM`5y+@bazX#a z^0EX_D!6}cI-W1LKmU&Bd5W_~m7 z?dUdVFYSyAKSv?&?R_|1AHa92;WfCfOLGNVfoE|q8BUs<2B?_f%T)aWrNi>~LZ6HY zJB2M2vVoua@4pi&@X^~@{ibM*CNKI}$Xoz}bQpE(mbeu7ZuXMhvka~*K zc&;RLuYTQ|u30v;6+N@(grR!b-Uh!v6h|hNKq)cVXrtu=+}E67Wiq+hMpBrfgdVP_ zCR(yN*E%kjgBm<}0Y>(F=bOVD0h9R-Z+Aw+c6@M=&TcPv`Vtwmx`==~KX?Ol#KyCk zNoKGS*fML^fIiEnrfc4J^6f5rAKikg4cgqan;r9Bi{>g}!Dcz)3sG*5&j!QF#`Iqy zi3~sM3Qk`?|8G$Zq0K{hES>uh@NPP>b(XQV< zl=HC)i*x*@0Tr{&6T9nu)B%#jhvWu=-D4pjbQ6m2-Fi!AhxI7LJ?v@?X)5QuE9JqvB zO5FhB_5KkD{pzheRsU36jz0|@`6d<@5{ag#~H-)3ax5N;3#>um1?Bi zWN*Oq36XP_AlY06#U}0&G7%^8chb;49%yb7 z)+Sqh(cr^|7p9);@be4G+S(dOpl=#eGsEJ6T;uFyWyS8Cs8poZ%KeIz$ z?*^G6aAA*%$`p#QGEgz;N%3Yf{d?H>b3tz_l!{8T*p+oguQiq;QoMYQ1&T0LG7iw2 zzG?!;2yQD+*Va7-xo@jb;SUHjSv(_#^&+zRmY#i=qFp<7`?y@@8Q`WDJ5b&AfLL~+ zkj483l+2-^VV@XS1W(_|@Z~Ku+H3@&39_~|75WYX`{r8TTQ|68&#Zn(kLCbpZDCzZ z32||9hvjz5nQ|P#+r!t?aw+l|W}x4ufsugMrPR$1^f!{v%mAgscdrkrpsQaJ&2_It z(4-d*4Ddl~vR@KSVbp181|yXaT29UIF?0IqTcop{W6r4XGMrHZ)Gg(XLr-_7sKCXp zYZE~kU5KcwJ3Ty3Ila6A(u)D$1<+`?^muooE?m53e+nUALs8w<556EzUTp>hL6bBOolF$I{bu3OZ+sGOLC0@N+Ux`v>! z_{Z;$_cSeXX!j}wl53xvmLu2P?{CiWL3Rly+&#a}p!AlSEd{2-x*_)G$w)=R#DV<$RL*-xv~qe0Qvx@MMD)7SRPKYkT$!8e2bEO8waiEi~Xf zG6^S^+^3q%TQRMn+BE*aX5D0jk2?P6%#=ch)l^u?2ftpi{_g^G7 z$AJy%g+ae%(D17%e!mBOEX5+w&DKc%P3FWNL#RUYb2&nvii*ktEv@*S&+SnYMPLi^ z`@kEJ995m)<6<-#b$u94qQ~NNSdIpBH*G|{fQv&+;7!2O7aXTRV{?{1$KsSJ=&OtM zyXZUt{x<=;`J|7`$q87!e4YBYx~QtjCDt{F|7ro4dMk++uYuKyjnf18Z5Q;vs@and zqXa_p2g=Iu6CgVYXpqKm(hUCaRZe^f+_F~dpEqwo8LmLQ0^IN23Pc5YOzqllkJ}c; z!+;gZU~@pN=>X!{;XKxg&z~5#77^uC;>|=l%v5BZ3gD)1SxaE={0VX2bsr)kEgkMg zwF-izzs_Pbo>~SI7#^Zi>W-qInowTjG3ly%FD|mumPQ%WvgCLEN^RuzIxBVSuB?m* zKMKu21LyPf-OcrNp68$Kh0a!BJ~=BWdy%tg{;R`m2o+MPqt@0#!G&mka(_0hw2&RY zBOaXEL2fi%qV!`{(;hvEK?BjD^O|P!Z8-dX9cP^swNQ(sxJL^CU2kXQJK+0ld;4NQ z2bE%y$Zw4((>46_oaEe%1cK&&=tdkgx7tY6&Vh4Z#SN^{E34Q4B?ezk{>0k*jzJ+1 zia=&ckvlS=JKq#Na(w7+!4TFJ+8Nk1%?6isfyP;+@k^YN@=$QIXqHsu+vOPOJ#)pN zmQYT&&xCp4-*63!Ao~x`ZGK}=(IzN^F{e~pR=XZo=E%VGSdyPy%L3c^y6u$UIC{z&q$U-Vwj}L$2Y7$M`hVZ4{Lub|I3v?@1Tb^Y zgQRDKWL#3_4y`5WZ&V!ZC3>4|*38~pJl%57A_g^aS1Y|d>u}#P)i=mx-*EyG`&!^^ zaUf<=^y_s#BO;x0Ax-cds%x*r7^(nSUy1;sq$3K=TZ&Q_ih^f3;wY@sFYj-2J;3b? z2`{8fA!MjFL)up*U}lOcw2OlOQ`|>RoPoGsyODaZC0D*^;V_~AYlTDAM_x)4>^E&w zWNoM$5A@zv8k5hb&cPMJwlFCD&B=<1YG(F(ujE4v5X;I|G^8HLhlSs(;xKbjZw>|* zQ3#9`S%X0BV?#xX5m+HFjq0LNNbmR1)%_&x+Az;r7%E97>7KQHv#>P4A8 zUadhWh*u?vVFkE8*24;b2U&yjRw+BxMkzDgGbJv3n=&@z7{&%jzTG#66YwiHpMPEL z33{Vq;8p#8S1y%vc`U;VpHoRrT$E*idco<7YH6t9-l;cGKxU`fTk@Bd)|eo?;ZRcRjFJ^ z%h{9ENCS){3FJ4?bAg5MU*pJxX3MJv!oX^u;ouDcj1f#<`?Inp6}>AMmIiDtH;1`qpHVvi=6wCDI2?Sqjo@yxL(uVONIDs;D-o66g5y!Pc5Vf3Tlm9L(T^1JERsfa4TPauV4?`N)p1?~% zONbz>pr;`zK9Q?i)j$-Ntx#m>iGsvL)FD?vhu-|q$zVp!0s zh}k_~O8V8KwrL?t7Ja|2_1s~D>~RxdJ?{)s67tY%tGbW>tUHRmr^R$Xp%B)ffzi_{ z3k>`zQfi;MS`AS8HV|>zhJ%!@6SL{;9g9(Cd+k5nf z=|?mrQe4Y(mRiZh_o9sZd*|n-`NQwi7Q7P7;uUO1i&jJ^{Ox3of4q9P^14a6e!ie3nRF&awP}?ukF>&a3ai4OYA;|PU@3`8E7%;3zU~_5ZeE^En&q_^sygL0lR;iS* z9mL`cc1p-%sA@Pwr#O%zQG*-bC^VZFTC!+PU)P|j)Z4k!wFkwQXNMTw-6izch>J3J~vOe%~FtK?O(;sfFTo zgf?jU1U187)ewIy^yJo4^~Ed?&boT)p2TMpS*ac2JaRt?1Mme@IOIUDO|#WyClX>^ z$J1^+X@WieNBeEh=}sa`zPl%Giq)a{FlEG~_w6xwlP#p*h8(%)JP6OqS_eHWAk3q_ z`R}<_qP@{_HYTcB(Cm_sn#kHi(tSTjMci3Anj0EN)5*FZ4)zUUaMw1|)N$P54E!k> z{8Faj-|+H{i0?j&VEl(URVStw5$UL6XtrWqhjW3g4e<#N^T3hBuPCgQSXrmV*`gqg z;V7i=w_f>ZQFZg)6);w7eCoOJs+7p9bjZG%GO#KWgIr@r)su-yOtVt^bfhO0Gm03M zalLv?S<^dJHQ3rpiAvz-X!5Ha=fKvrRow^$(`bQ0Uqt|g#-ROVC>>RJwztB<^$Pj^ z2Z|)Jz!iPz&$bMGhYx6X5d_>Nj5U|>MD@y||I63?LWZ6pW+blTluz^=N!Lbvwm_l{( zZYhYlJ;|ChwM1IgBN{y~$s}?WABCLG&Yo_LB@qw#MSF_*EaoHOb008vJ~opJruksL zzrhnty@3%9jZDw|AgH7ExlZ?{dNd%hIIu3SaRk71jhsy2U^rzFxGv)AY6wo4Weugc zZ!L0Y5|KwiL;KNx`SGRP`edHipy%VmEz4&7)SsPiHusA~InBsoXs&v?os0lE_&(Bq z=2c6PeCa${PMl58^$g^>p@37cdWU1X)H*ZgV1VkDj9*yYMqFv-1z)mfD*eU_OqFJH zJJcS}*<*#@|Cn)xucea5?E9xEWFn00LwK25iSE)wXy;)sbR5cpJ`cQx$EcS^^@DSc z%%hKv)E*kk{fNaJ_(}A6?li@{Fd!)R>mgRaDGq~}n7BaH7tE-M4|=OrrC&xu^Q!Nc z%nQxZwtXYIRYuZ02Dddt(pN~o#Wn}j+w;Z*|F3bVSqRWV$6cYV7LM5NDu@&wo||dB zKO$CxK9>dyUsb#p9R+~L4Q4n~=`GC*Rld%c@J<=exF+`-2k|w3m#ciKmnSj{NUzW7 z&sB+Ico&B#16c5gdxwmU#g$u#uZ$9ZIBmFb7qi@A8R%j6?XN!8?0l=Zx~Uh2lw}fK zI~PtJW_EdzdG3D`DL$ijynMjYH_|{TQ|o+-4N<9K0W?4?29=~GlMw)S;P#4`0(StN z%dzGGrlqGdy$@_vuN@6Y`o1jDZ&Rk3`cxh;C~JLTjr)#bkG4FHTDFnDm;#Si{2o7( zgtuBwQ9?ki1rW5*vpM_4W;V@g!x%6lp&M7kpkI%NSbbqOT>4dSC$S*I%pN83XiOj| z)vaGNkBHvEBokaqF$!@a(Mj3 zURjl>a_Uo2z~7W>d>rj5Q$2Oq%T)y5^;d%7$#;7xdsa{_DB1?^rR|-7@KEb;| zE*dcbbpC8~`6K*C{{f%P(2iI8PJgcuA)=jA!PxyRRG|V!UH=!)_n&9RN(-aG0ttSZ z{FWmUEEh00>1>^@ISPxVGh%Gh>mMUOqBXWbJKw=bxH6T5|Df-U{X>k5(y!`lce)dH z*~XBt>zFrYB1nts?(2KT^hx6L6-Hy^LfKoMIp0mnWzP!M6x1=~;h07|oPEmDQFIY) z-IVZd21+MD|NS~{JFymMk}ys+QB+PHl29fQ@M_Rp%A!#qJc|DgAc6vq)AjUbhQNAc zt5=kP6%DWnk>_C6kR|1p@bUu5nBJ??jm9spRJWLLHoqY5o9dyyNX8fM?(n&;qd|_6 zX5m7V*ZUMs$6PD3@_ujYcxR_X!yXt3VySA7{fH+9r&&Q`48Rs5XX_1u%`kR~ob`jf z2^ip9YhTTrI@eTO;gC5$?SeX#w4y%1uuJLyf#N;;CLElSPwBETZApA6gbDg zMl=Ziz?n)?_gcEKtKk!9%UXFe4N8e=REcCFHh|XtU^tS{FUckSG4VcT=jkb*D0(?Z znv4et8CA~Th|u3Q2dmitj%wR!-6L$=Hw>vw{1mXh8~ViHec@}6Wsv~(?gvbrF5dKq zg{UL%Z>HxBv(_Y2t<&%z{%N_p!-u+$gvJo}5xyuqrACkPCw^eydcB#5U^Cm!PwSt% znA-hZU+U?hMs_!1lGtl;Kixne7Wf+i^oK(R4}Q<0{c;lfwubPBO92OF2pilp*FREF zP?i@Ez`)SNwF(h(OIR<-A#TjGe5Ecm@0kK5L2&{Cw3*#tV0WVuxAaz*&we*+;f=mv z0y)k(U?;44Nu~nj(663Iu_5gw4>`lns31;#uJ|8km%p_Hta7WEqy^6|%vg?hC8f*1 z7x99AQ|WG3cI`2NnSI(w#$PVLH+O ztTZ+I>U$XIdOg-9BG}7exj!w683Sx$JZNGS5X)x?fm2+gC^x3HUoR77nJPY6wJVgs z{F{sa2MZMdi|iif`u)v_k<(KHCu}_Qs*II#>A0-Y@(dxUqNgTCSXkKKt#k?8xOQ#b z3yfgF-|fQUR)q-)uZ6CxPaJ>KCnpSDg;pgb3P~4dG&MFqm_K*j0tm%%XM)6hBuVCA z{9ypk$TBR}*#kEqf;;BnN-DL`KA-t6LH&PKV5QCJgKn zD2IX_P}Cef%U!A`f1g0Mp`y;^=OX^EbY}G*lZ;(L1^jFiVnq{v#e@AHtG0r&c~s84 z16*0))YPUm*3Gg{`?Sgcl10+`BUz4HRH10w{uCC{`g|6wyxik}sF5UK0|F1o6+p2p z)!79zrbT^}{?@tQ%2q=4PvPW<1NMM{#Y>l1GYn=M(;K7alKLG>_X1`7AeBk_&cDQw zyfE(pu>J~D9s0{reOXS}_%T_tW2(P+ks!6%M{Np~UXVZqMH6u8rb3z<<@WU0qO#Hn z%0QPjPD=vb_HQXBH*~posspMp?qY6ry;E}>Wwg4AC*J0Aw^DRlJ?ud-@&C`W45Q*w z@(zjSSy%lu1SrX9L;$x7qM*AT9=n?}b5P76Q8)a%Wf*bm&0ojQ-!HWT?I`BIX!Xtx zpVrm5vE!d!YU){2O&Z`E-sX6Oa?ZwC{*8b{OFpeq1-65LrW|fKn!DYxu>G{ubM)Q> zkWw|GS$xpoUP90p=5{uVI<`WVqVNg4^FWDkxl{=Ik4(9N9y=@!B_2PcGr+S@7o8*h zf~J{DgLQ{@A^5wQf4!0obon+6pv!01WF#(5-RfHlL;EevbU^E*TgU*hX*?uA4`69o ze8J%JSn!p-8XSEemelAYIIgg-CsStjTkA`pobC=LJQ~^%5XSr(I$pZE&GB>G7(`h_ zMH$!_ipwIx@8F9T1{i$;h1hd!I&E~&P9b^TEnKLOF>7+MG>-mPmpk8jM=Wi6ydciI z!{(7wH8mL_|@9Q7QrJ)QSaq>$=hE z-AFXV+;fz9w!}_i&U0;1(g~VxKR7&do+O0Z(f1Rdh-7` zv@g@?mx@hAyi3Bgh8p|8!0he&tS-#Zkb}p-@VyXN_FSVK*-{O*>Yx4Jgg5?2Ci8rCePPa20 zTHSI{V?mc!Pyp}rA_{*Gzdoe@%ZFRXFrPB>#sJGTV-wtXS=At~c9>A<>rRMY$91oUA32Uv6WwZQ(k|Q*R~1>xXgX!_>ui0>r;CjZ+h*Bh1`++ zaylalhN{>4Ta?uqv!7~=Zi*^jKhZ4U^DWB6gC04xCGSA+xWWnc38nc@?-S1%x6s#F z&+I41FNe-&{-tQHk~98OtZ-H1eu58E3_9?Go}&%wx$b*ph1(;VLWUExn~ei5l);PF zI!;mkFc^jtr)lj@Qz>u+{06?}jqe?s;O@d3n3Sa*RZy1HYgUVUJuw-KJPQkV{3PE> zj<=m#INHDQIbe8=?E6D-V5=`*E}${4_A9E}WtCI+U9Q>T_nw>n)n)qJqyy-{<5@DE zgANDQfj3s;7g*t<*pyTS=olCw@4iv}+SGv~74nRgTKo2k{Eq%uz$38jl8oxip4)!O zGx#76&FOsGms)W%N`L-4xkIcAUHmHn#GUgYqU+ar;%ki3Dbyig}MD?9pcDJ6b!(qF&G@rrm z0%?}+vlBpgRGy>DrE}0Pdu*Vb?a#&$9E@;tNC-C+z)+;ze&n=xF`pl~3 zEG;bww&~TL-=iEJ!y>iS)+9deEY5!-i4QTD(@9x+FZ3JcTQ<+-@(GDs*h(f(6F_S6 z(X0gp1%YzoMJOssBzQn%rRlqO@4z@c2@FUX|BIt;e$#$<&_GKGCN7q0eoh}2EpGej z?0vSIkTwL=n7_{U)J}DQu!hZi7(IzmNAZq)2( zLLobS;Ou>S@p;&Jxy}L!s7Ro)Yd}*H0&CM;Pbkj|rb(i?mVvqt2D2SRM>Ob-%L85g zKof=7>VCpJ7pf_C52_H;Ds|M*55-d7oVUj!fPN`A1rmm zpnl?jRGs+6`EZer|4$usT*#4ak7uiV_XK?9Ak|&Op9Ddh^0H+(d&@v|x*mdqgicca zCp6t~(Nw=~&TSx|_npOP|FYO}G8ZN^2A|?VaOe44VlH#_WqI-|HZKU>-OagN+IoLX z)HxAnIA-0KMQ!Cc(TanR5=tsxqHLX|(nJc}L2|wYiqA7K!d z{s-8lhgYruM&A?&6GfktaN(CzNv_CLYWnTQJ7!QyAW}%L0Ne6*$)N;zg$(=IGBqjq zU25WLy{5m!VgQH1%Oienn zTyEz97z+)n@6|7n@Md+q3LvS6DoJ<6-UB#bU4@i4`&bYR*8WBDy-+3ykmr#PFOc#5 z0n4!gWB{UP#aEf3x@;tvY`A@JIEQaQ1>#F>?om7h*3`plKI^hv z^uM>qU)kd;N8oB{X*u=v#OEs7%J7%40qKp-Sd{oZ*iajw5(<0=Nab3yAylW0)!q;! z?XC|3rbDqzgXJ&rMi7AuO>;Akux~=H5|`et{RxO#9F?WH_dS_AZES(9GWWH)_L$6W zZ($Qe{GXi<=T7*t!_XMZz@BkwkYv`Hr{-N~;8aC6+rJ4~4`77>KddPEBpB^$yHqFP z8L}S~N5IFas-yCKDKF@S$eX2mqmJITCWj#ShXmecx;Y*Ji+Bzzpx*d|IS`2>7J>OP zejeT=b7XOH9Ii!$IF}K0TCxS!MA^5cTw`}Dj}Nr{7MRO2{4aYx zi93x@ULsydiWAHyH7de70s#Y#6W`mhv|R4GU4^F!a-GU6V8O9Ox!x?O2f{gxRQg>W zXQ6Kc7b1H0ahW+Fl`LULYo!;~*>^pd9RPxukgP!|qL@i1u;-9JDlFwoATb(s>YG=p zE!BXO4GJBI%BMQODo2BQFkdtTk8mrAf*Z6Ceq46zBdiS z=_O;nyoUDu{&mwbV>A?5gb_DDxL_3jkww=jkBAn?DX?vK--fg!FgU$;ch~aBaAr>X z!|_gJDU*W-7b~0)4nzv!L4ScctUS3X+(RFddhgfpXKa6_TGmS85A;z7#~gWxv5a9c zXdEAx1=Jz;M~Xd&I1Ir!6`B&<_8w1_HP66U*Lu`^! z^~Pov`=wmz8KQ+y#n0}5ry=2TTfBe>4Fgev0Fzo*33S(G%_CcemQt3O)iN%$r&+R% zaNibb0y64WxA5zl72+V1B)YDN&(2p(g|6e%6!JMO{P=iy?!Ryc1gIBW)9&&mOXsmO zz5AAp^T9cX`tExsL}8-1_&0NZ=(Z9uo#KM7%)eRys?3p@QX+&UYLBp&rPJfjTXlpf zIhNq#i7al_Jc&jMxu{DMS95?MyeDBc!k!=BngU_J$9H@n#6EIz97A_w)pdAJCI~8M z2a_6UvXHj#P|W^+mwp`%bpwZRoiTgOra$Nt8*FM28b3G%>f^8Bf$r}h=9;84VA#YUql|eD`c8K!+TwTFz6&Eg~ z(agqqQ_Z6wd>8L@VsnGZ^NB@)nkKJB$@`~uZ^s#|1Jpjnt~U13sb#Q#DP!hIcF2>| z`PyJb7x6u5jVaYT@6d_CK=d;Zy5vJ-En}=>6NMS0ekOfZ)H&FvLE2X@$Qa2gC9-(u zu+*x-k16qHrYyly!1K3xf`OtaU&N3zl}J{CMag3!Ii8Mo|uqr`MkoHx~vOJRH{Snf_x(V7PUS|%Wyizb;cV^wz zc^BIYmnPhgkaT&5tu&}spl=JpTNTJNf?tvMN zd54MS;XzLotHm0^J)RHl$M8*sUq9*?gmNa6b3*8JPC=KP$HgH*m3}AV$mVm0hIu+W zUhC5FOtz=>@5WUPJ015h*FnVNexbYOMcPkjx79)?7eCALh&A&d`C7nM5$#QRr)pRi! zIF18|YwCT!Fo-l<$&iD&Q-*a(qJNcrU2dmw4{U?oPtIYRo@cHML!zdylbtC}b2v4U zSMH>L6%lUtJUfrSL1r#ZM6)QFj$OqTTat_=rXTqn3^q8C(9$V#1lvq?2_`RaJWaAv z%JBP+5)1SW;bY$EL`#R{gFt72*M}&h{39}|eNcTUi+u{^joQSs_YaDaFGZFvtAy&b za$-1Lf19j@6K?k#PicQ)M-!VQJYNWR^{!gm>&ceRW(<&+cYZgBVJx!5t#}CC<45St zp_jXH2XnDIntWx^;c>qmagA`mh^}yxMzgH|HgK1C!`UylM-a}G(_>`_yhG(5O|IV+ z4?`x6K0la!wwL%2>hQBFi>^rSP22dAv~UR~&F$q8)(pIDQ41b3BfZp;xmUB!t>`kkHK59J?JabaUQmNj$o3(a*0;Yt5i@gpx{- zQ6y{M6(c8}9kPd##VLlOpse+$V9dK*N6`IP|J0y^%|<$~Ra1Wx+0~R(*NzRWd*X+( zKF2RyBEE~g1*KXPFW8G@OckSP2I^czvhd0H-=o>k%!-)~ansbAycQQ<)5`k0&*8;`+}(H+OjTWbiqd z|6u|q#pI6!E|&84nm<)SQm4~WwB&*;G}uKg``&2Jw2!~R$Ayebut#&NXE?mbrWd_Y zdexlsJh91%cbJY22+b#M^`my3$YJwl`=&ZBB;0}G;eVO&D#ZqxO za1Toi@{&~BQ!`A5raQM_zDL+sM-36=UvBrrD(nJdkHde{Q6&4Y(THWSPts!v6lOe4 zx>o#jV}h`6F`5$6)O6|a1|oA3n3E5@K5&bC7U<>3WsaS^Nf;@C}J+oJQ`oR~*Fbgh!0Olhu z!nb%oKAL>dv*}c___{Ik!|Y31hGcl(dYpRXIpO&539->yC)-={ZcqwVzW(+Rfi)l= zfw<=tawrSxnnsc^HrkZydTSK=+-otf^^Zj0Mwai+go6}mvRh0iPH+nU0f!setYctbGpA5exY8Y{S0FD-966x>gA3B zEZ82srmn|9Kkp0p_veIfSe?F8BYhiYU#iWmqS%px@3w015m|a(0CSaR;;<019V6BE zR<1~=lyL}9QYe@*Taqtjoi~RmmZL%Wm!E`__rs$0<9=b2!-}DKX`%-MmsdL-5H5>u zo}HgdfSfk@hjeCfjG&Bh@y*&cCd4X8dBFt&Fp6fhsEpu65oyLHp(? zsG*brKMZv@I8cwXN>EmcBTT3vNy!!TxpD-OSox&!yx%;|R3FsMGSewUvN%0nzHJCV zn5j<9U@TR$yKp}#^hMfLJODeXpQeQU>F4Ij4douN~Tb30x3R43DsNqEniP&80tdm^8m+bwe`*B|KC zBkr$sK8lawPkpGkCR-qscqwu}`hzSSD}#&&?b}J_8?wH@);HCtaWM$2Fo07C5vC}Q z>tT{}c{eM_@A}e2TL0S%+WNt5V`#v!1SIr@ML9P>5L?>JBx=~}bra^B9LQQ-_6vhc zDm@r1Ic%ePd=lVB!Kr;v(QR?D4 zO6m*M>!c7Qyugv{Qlf}v00MqM1kfgi;Z4u&w z+%twHmDV6mf#(i}g=Hy?X9lO;uk`^W&^;yvKTCb6dUOg(W5fUf;A9|b%mpHMKUwYh z8K_u7N)?Bu@5%~MEP~Yx{?x#^F5m|Vc8BBC7J5Jv@{GEVbfCO42@2#zfKW#cMd2w` zq8&*p5*(=$Wo08myU&_ML}IcLbEAKOzAy@-PM>v}7Zy=AJs~$l{2n#UGQuDUK^b=d z!>vqx`ZGojm0w@zv#z_KOi3`?h?#m_9xsK|C?1H}mQHy}6CI3*@-89gj``l$yF|f> z_?}O^N^3i2lrDX^+9Ud2EFavuRbOEA6H^*psWm|5^R)FLKk-@IHr1$Jp7;aD`Z>y@ z!O&SUt<&D%`@5@aBm&i!k{b*ylO?WB{gDI)pE@gssLj8{BPV)k3IBO8Y<4=q$tK$m zF^||-oBH!4+Q1RpJ9c?+I`w2Njhxf@ozp;kmu#LnOc|N=AmTm{Ye;T0yk;v6dclua zEYVeV>v(j5MC}$GmD2dz^lZh#Y4^|nSf4a+AXCP_D@AQ$@^THJ7xk_0{{V<#lr1#gnkFNUH~>7J}M#yA+(LwOna zf;;F{%O7A$;A*F8RGFi1ONiOEvSEIhBRJaodavQNhqii=z8Nu>SfTfJ+TO>afZ$CW zg_ilgqIj?SM`+OMjK`)R)?vj@WHdl;vO@Fi!I zhcvZm*0E}K4h-|6^YavMS{7w~joCGxfDSS7Sw4&KL`Nl^129tz*GUFa{FYfHOEx+h zpG_2gk@{DnvO+I|-CJ3mZEDGBeyboAhGf&qT;{lh-~~`kMtU~4wIKzh9P_FT@+=YO zW?<$uf~H)5>ngQko+Xqbv}vH*Ks=`Qnhs-5?xCPa+mD^rjb~Mixk^|8<^JjKEjgz@ zlyWJIxxCvhYX0`}%2WZ(putqMvP3G!(&xs{Hw0BPn#ArzFDpxbPw~5_6vc^<`^xkf6v{x&NR&{gf!XC0H~7H-p-*ilDWe5rOxE&|1> z6i#te=F-tWrP};d$NWA)Fh{b8kADP}PQL{|#((Fbus?brnkta#%2^zfGM>u}TBm`} z@)qMuR-NdHhjZ1H`dxIg$ycei7mgPE>^%JSCOn7?OT|^DP9zmy++*wI)LD|r!D8wv zykM+Ias*j_2W^}2%#GJDdKBouPM2GDTenVJWX`YqNdxPagA&$inEG}R$gy%+^c=vT zrvY3R7K`*ksrXXnlOw$EcYN;q)ST8ulC5K3r%RHZ`^`a>JNu0gYiB1+i8~K#LPog6 znfc4CG(RmyR=*48ObZ*h3!y#f0L^9M#3_n)v`>%{o>1j_3rF*=L`@k9X+KNq2($Ol z?~xOSV9mMWhnWE9(RmL}b?k8RyhNH+{n*3w#S8jtQJt;5SMpMg-*r~sbeNzsE)5;^ zoF$jkm?>hZpARz{j%r&yCl&M#gE^9WjzKI_bHe9JW}P$USjZW zuna{U+3cAsArZnATfS7#ir-Q^Z%YFopT*S9XFjDnpATX$KqjJpclfxCrO!{(TQB|m z&|p%2Zrg!7tVoa9)HcqUPJ{I`dzVgyQo%vmQW{S#dn-o*X-Q!QN|LKm{_WN{iNs*r zB13~-KnLxeqp1cF_SZz&H2TCG@r%B9Ck4OA>;b&*N$MhWuwLBtOA1%(rF|5PUX9Ps zmzg?0P@lbj?i)Rs_CCp1lop^#dm~DHZD>Xz1&o!cR*mvJlio5&64JC(0=|w84wvCz z30ZL=*Vq;S)Ir41jv5lx?uv<1v4rHIy`eCL56G&UlOv~(q(Z=?Djpw;qXosW|24d} zuCgBh9Y?&q7_h)FL3GVs*@-jAF&l3yGs(EY-xfDrFmzOY z*O55SOZ@(9D?my$6+C@M8mvlHCA^$J5hCqhIBy5DDzz&A9(ZxJ+CjG>I=`coyD~nD zJH;VoO;M=!3C~`>dl7C|EK;_Fn~yK*(5Xe`hzX?KEA&)`RTTEe4?NjUaDng2!rYR+ z&hKH5^#*$VI(@vup{pAh8WRf4t4A}vJsd36WQcM^l2Oj7-N$Z?SqgetVEyn#g+5|! z>*r_mz}E=hAnY316m^w39+%j?^?8zJ@q@7auUH8^>sr?M; z5scq>=K0>kUb&Y(tVhH~7+E5JFLdmUAu$LHUh>`KEO*hjNXk9V{)tjDE3I?roS1_; z$6kP8oic8{C^KeAgArd3i4hpKo!^5{AngyDz7zWEhUymc8H8W#7hP=ni1En}UmZ6z z*!5-viPl`0pZdv3s_BRC#0d!EOt2}qkfAuDu$NJIui`l!<|!|Vr}M|td9co2Hi0tC z*x&jaC(}*CVA_7=dqOfhRoS9wlsA|V8SN5DQ{ISuXAr7{T6586H?c;)rXsdKdN3pG zo@E)`Ki*b*2xye6&$+Mqua5?L!Qu9%qxy!Oi1a%fWm($G#T|r%aarUi z#w&i>1Ha2lc#wokK;!{)C_u{ZLB6lJGmbbW5FqN&sA z+b9WNm-1T$3yn;yA*r)nR8uhp1{=(j+~tOqx0MS{66RJrW1Gb5uqu04EyM_*d=|Q& z3h)cO`W{*`!&fc2zo}^Y8lwM6ADt^U=}4n}&s60#e|z9f&Wy9!R&#C~)yLdp9cqCK zrX=hBQKshHW%m)mS_*o*PT5Zv>YSn0{c0D!6(V{V9|1_^;o9&y!zjY@;K9bcj2DXn z;dT>yBMyTu?UhB^OC!nGd2Jc6rr2v*X=W2=}!Vh5K8)D5QPrJ6dK=(yy2USVbnLLy=YT4v$~k z=zh4hsDOW4p8n;IqxALpmN1#1ubAj%t)xY1eJ<(je9_Xupm|w_0AE%yC@bBfMiRh| ztf7NhsBz)Fvn}szZF#~=g`0^%B+?aTp6HVw#6`h{=N;PzHzw2lG4Q6LOpVRqSf33H z+T2*b8;GJLP>L#Ej(-h0S?B8PGH{o~%hEy+v6br}Vn5T)!DL>`W%-4SC_+2=bUGEv z)7MZKbCV@lni*lM=h^#4j|T!FD$hcd0`Fx<4(m#+xQ__hPXi{wuFJ|&#DeZR3wd3% zWd_+4<>JOx&j#&4svXi``qI&i_ZRjW$XH$}XqX!ZO*vN=_q3RUaYb_|2>aCBYS)Qe zv^UQqoK_(QwNCHEWjlkp#O{wbnue8~TIoEoeEMc6>f70zmrV-bTup^tSL@%oJbdQl zvs0HPN+GPLrw8BiHiJwvrFFi3+Nu=*dB^$hPeA&UmfZcy2P^*udGVP5#W<4>-2cPX zRfk2{HGNSK5tS5Bx*H^3Mlkdzc8lvB0hQZGjxrv_ol zr3Hf3q&HX1XLtF-M-N<7(f{qaJlEj?8fK`1Z2rvq{nMon6IJ69%)a*Py^qIBbu{_E z$u%o)6I!z5p=Vy>`CbMZT$VuDU^keH`0j^kpRNm{;v-{kw#{WJ5-R$$A>-sV!FVze zweNi5Kn1jM`Ca=*J5)MDUep)8s!_^L0x^J@Y_`EOnXWjmw$)U$d6||+9sAiDF)sa{ z zkR+mU=JV=J;G^C~kDD8ntJ3&d#2TppH-nF>MAk!@^`|>O<(r4!OD3_jZ!<@I>?n*? zeHz50$GYgm->9@`EG~S%@xA|->=Icg0gkue-M1$~FM*$XMJuKx6Z=C1>*AGg9E|m4 zI``*giW}B(V&^tgt01w)G3V&|ZQZ!j!&bil%;(8kO#+T!$ii!!7UZzboMrv@Gvy{K z8*d@&`X<;vc`eQ+tc9L>{M1%PC%JuRLMQVHJcTHdm?)4q2{!t{@C5hpB`3FkGWJ*s z_E_Uj{-?mA@F-Dav7FsA&Bf!uyuU*(>P>i?*EA4oXUUhF@tfF_WvJ5CTce@-?}qK~ z^b#ntm;ZPl*AuGX?x|ebCwrhWY@6mj);k3GHMEO1GU%huPHh5o?iF4EBDQP?17N&<|nf@NjP)NCPIl89aC=#Yd1$}3pA6G`H`$?3a zJPtGebwMr~({ycBnIDUVDLwwoB~{ps%x64R4M$%*<@VH8`Q16J1^iVIbCQ9lb;=UnH*V z{Q)5|3F^{qL64RJto{3%!htAU3=~sUy*<5AS7|E&9wZu1q4yL^)xLJ*mPS~iT$ z7!a+0UzYW^pmP_9PK$Ar&GV)C1m}PG2{=0c+Cs5YPzo=1{jXLvW{cCH_oJEnyL6RYn3w=0yQt+ z>CzIq)i9A|o!3%|!@7nHh&V2=zt}eTZMTB7EtlBOXUS-xl&u z-<>S!7^akX;G|jkP9>aJl&qvD_Pqd&aow;Q>M6JH?{jzewt)eKn*{l0R2`~8<*Cze z5z2>DGAu70aL3fdnCM%PF$^8H%IzJX7v{NRhTQ$iQCqrKE+=@0-X|D?wDh6$x2gxN zOyH0BzRzHQFlmZKFhy$6uYP7K>JGB<--MdF6h>8))=IofnnxNQj^-$+Ws>@x4wZ#A zuaLK+l2F`ptTTd$&rs~^?iVg|#UlL%0wnfejJNR-$XV$g2go=3Uyy{IuC7odsg7pf z*QNFp`hy6uioIo;58AAiJS1z&(#hWXPZIg?_~=!iQPExGGnD^c=kZ);j6qQ%t{?3z z`CXLeBOtFgw&y@FUW_nV!U43UKk=P+q2!!ow1?q&Sx#c1KS~6pLl3iOzK5V9CG7G0 zmq0IKT|SOg?e1c;r<$&O0^=u8%UJ=Sis=e-tW*)#?~Rk?ubEGG7e$MHEPJJ(Ij)X; z>>*s$)(+St|Df)F`YPD=vGIyHV4-0HDuaAV`ze5XNO^n)p6FY~V<|qzD-O9TUBC9o zk0WJo#j`#rGJy1=@VR;q>Bo;_1~PHcX{qJEvN1o(*nO$bnb`*aEq=_ms|UzLAnL&i z-sHCb8D?}Z@rSWgK=>@z1{vT9cu}<5SZB{+y`xTh32u`gSsN0KN5l>W{Rvm3dR+C56=}*_eK5-`hT24<;hmPZKo0jdbQI;M>fk zdr=a72vFbIYtMRUj&=Ig=eY3mfil0y?%t8#OyPrsn^m9^29Bskzfdq%+B-h)c7ac`8(XMI2!m`_V>%eeK1w$^&a$mU+o6;)7f@3J45t47K(Lv zJK!w{7z9uO1@$n-b1;^X8E)wwMJ9|dIPora6AI9c4ClapFrR~37SlQS8W{LyfWOM0 zc0b#py+Zfu8Vu?1F)&!Nhu?BTxMKw~hBygs$g~KGc)_>0w3Dc-_A9a%pO;^xe6O)h zK5Iz1j^}NmL3pXr29A%P!{@nTpJ%K=#1JGuY|2j; zWZ-RPk$c~+aHBpO@(^M%1 z>$FC7TLZoq5K+@aK&ti658GTxD-2HPhCiP*dG6TFETWtQ$)=sHiCWj4F39g2#Cu-f zZ}MDFZbF2|Uw6IOd=yhc%MfYgd~4&;xSTepEX2b$%U?=vC^+ySdNv)!b5vj_u-a(jW9Z>8h!8R3}3&#*mo`1`v%Hh@*h1s z4gpY==_pqrIcIuvD6MolcZV#Q)?4Bn498-CtL4Z{)vUFASbotV0)R3d;D#Tn4iRwq zPe-%Mkx_>T7=8I{zw&3rZ@O1s(=XZeKyM&u=+`e}*QtJ07DddfSOz-3b<3hi1$kaU z0Xh&L!C~CV0B6=LQQreft+5AGMRgB!nyKyqOrypgm?QIGtQpMA?eK07#tB7$={t|X z5QNbxjw6E_n-n8*o>%o>=%8RY*kkB$#%Pt>yYq*{JPdG&K$)qVHQVmykE>E0-iL%=lu7Qd2KcJ?x4$guSU=J^~slE4O_DjBzc0~&`@u0Jz@3Z#d^m= zBgj-~8m{+TwRLC{xH=~kDCB-<6M)seops)u&bS11G@YXa(S{xhZ>KSrwIR3izNuR# z38fFa*$lY+%@RsEx(%AoDZH3B#c3c%hMV&E^M>= zzGZz(tmm$%wN5sYGsI-I7<%t8ryeUwC1wu1daHZsmOI>6hWT(!6s< z%k=8SsV)m;U5NK<)6&v%1NZcc(%iX*zzs(|)6&9nsL(icim@Qdw)+4o12Jd_UO;pj zH#KRzZGz?W>Z_TyWS62vJUws&LO7>%c2r0>3SCs0Da_yV`n<&OX2Q=6(NI2*lBX(W z>Roc7IR|MPo@3sef-Y*#Fr!rnZVk?bUY)|R^qF$GnDX|pU}s0nYZFjW)tSD+y(oii zSl{{xG*+)U`b>Q$t#NX$51w)1T~M!*TP><){Y96qW&v@flf4MgjZ}_fbqvUwTfr_Z zthN6nw#i!VO^!OFkS9~h(0skKv~>JNI^CNh8JtEh)?$Oh@@E^A?2>Om%#xIGe+Ld9 zWw!_8!|0ZI==kKF6%JKjuSTTG*nj-I$8O?I(H?7AQolzx!Jcs#yT4=brkq}hr6Xql zc+7^;;XL=4y^hVRm*%r*lXf@jGwcuYOfV%_jszlMKT6$J%0wyqgwRRPsytVbu0y3| zM&*Wk@N>!nNxTZuL<#Pfi6%Q{e*q|Pj5g|PRE5#%_$-C z=^M~5>kr#dfJtJ_fL>dsJzkqUw$xi42fKy!_wGcq>hLVH&#ik^m=Ce-IZ);=J$Udk zl7t_>VNZV1!rXWUF;!~N%V7x}O1pmOWw+j&ec9&}8Y@_HDlQI#Umi)^ygCD-T2 zMgu5k*0CO3x6HzK;^EG~h&4y% z*spuxzVCD;FW}po>^s?g#j>xPV2!=-++MGPdN@{o&V&P`#tY8ptWZ9NpY(caZfIw( zy-xe#JoHDJ=%DTdLZ4f6M#*4gPG@`^npXcE(ezGR?E=2H8Kss$D|j|n@MXd4^PZnM z#hZ!ACR^y$YCA0qqVhf-b}8A^q(It)D8sy7EUk8Qgq(Q6pPA$W9M5}AC5ZQ0BmAPw zQ+R&UFHQ7O+Sr`n_|zO$$^^m}u6gIrAMxEO4mBm3U`tO@yeWpuVipcO-*~f*=Eoe^ zw-1q{D{k+n5by3om9|S&>bWO9n=h}75wh`3Aq`Y{kcLB);DkrPWQ2Osax1h=2qN76 z2N+g?sQeO662DR@eTSpd-^uuJoAA<@JjH$a5F;-TRTKG9F(t}$w4s%ZArJUSofx-T z;ql-@jKe@wcjTun8N~MjZTN`l#ou<@Y)J)W5Yq+P{2;2QGzM=wBQuC!2HG$@sYfwI ze)=VY*dWj*{Ym|@SvL~fx9;f(@ZG)8esF&sJ`})T9z*wL>Pz2oaW#4YUnihIC!}IUvq)XLhkXY*5Bdd9@Bp*|tBS zj^|$!bABzAzovlV!yb~b4AVMCdzSY$E1RZewTSym)@NZI^O~gPwT$?8)SF-*r=_=W z1ki$4A^cOuxBW&J6u1izf zyyBa}L^x0^-OXPo#@rc=aKOopg~PZOE+<*?e{6F7%M&NnayRK6ll=9BV1^37V1*~9Ly zKG_%_dI;t5HsRotA2_!~v4deQA)beXi>?xCV+3F1o4--l16iV*k{?Xg~_Upf(KDV-8mXhS!ws^hEW@>u>%0taV z3!L@|K>4$RbC!#BCF2<`r6_L3t#8rfiZXs$QshIC$lpgvrU3{^1vX}-Pz?VtkOEl# z)rk)9!Jwmr`ViIN0~zGQBU?uUh!~HJ+ijM-lbKf3U($f$!;f4W46`jI0hTR75?$)~ zZyu{TxT8J6;}sGCD^`jCNgVAbr!1lE452hH_;O#J0yPiJBk@Bf!VHZ;lSEA!+WPi0 z-+KTSDzzPHp*MMhf+AxvQ{;lApIa*Dl#NYh3u)g*YqPw*nQ){yE_-j zKhGKBqO3;BX|H#Ags=qPTnZ!CN{U=7ZfXyXPMj4b%DkRQh9D)1(O05?`9EnGC%|Y& zL0yMbPP}JgNOnH|BLgunmhN~h;V;~eNogKjDb_PB1BD^RTvBJtJ4h<~sSbXZ-2s@1Z4_*E@`CD)Uhj(`AD7NCQzhhjZs85% z8H%S2-34zdu|KlDd)w2xWiJC|xz^{bZ- z!3EJ>K&w3Hlu0a>#AG9ZT$~3cCnpo=N#=hAEN;yl`8Ux zW+oQNVX%Ajt$qS&lwga0qz`T)h5Z#pFSbi4yEv*-)ijw8xr!Otj&FH78ErxYx-}Xy zk2qDLjR!jOj5_xP9a=?&-7Ptx;O3!PLYBOC{bnPy-pr+(_w)qZvG}CLQBSZ)uo#Du@fEDvuUB|JF0Tm425#uUiabceC+wFF; zeDptc35Hgw>PK3qWBwBROBP7f2fx*}uRafPmmWA0>#C>X0+P>PE}=EAL^37ou~xTq zIu}a*^sAp>dx+KFi=ic_Y&%x}Jd#wH>D@TMO=ot6kA%OfX3>tDHtvd$060$WUFHH* zGA=jnFYG#Wfytu-578T&BuGH(fR6&k&R{T_d3zwH5$wyy)JXZNm+^}RWc1)CtL1=b z=;&#u65>5WX2f#1R;mBUiHd(K{f)n9^LBIdO7?MuRVKusWB2&ID9*c>8PKeS)Bii< zA?}a3^o4)gu(11MxafJ@T`i<4G$NjYrtZf_!hP{=d;Io)2-6UyR4#O~2H9kh_6&o1 z2aJciQ=0lGA`bT$RkN@Wn-9(my8~D61}+Cm4*Ajq=i_x7e`>cQ^gq?Z9hQ}G{;{=H z%k@{po`nE1>6VSm=?uq^61%;=-t$L+U(p`kUHlY$SWcmoZQ8t?aC!Z7uVME5q3_#9 zHc|sz*^k)poJUch20M=j=x(;!RtX2c&+l*lD+Fit{BDsC#j)zHK< zdv5|%*iEl9O!wW%`FtY1VcD1ZCr9F^TdHSR1mhCet7XVkw z;aGP1t4^ft8|pC;OU&FZgkvZfY`YH9?y#0H4TWI%McK4|9k3o1PMhtZFeOr7cr*9t83g^{Y z3Yq<7DiRI;2t!L%nZEIPp(YrjtQrvBuU&2kjU-J{v7M}B9Q-E2x}xTEUH+IkTG-ub z;JRY6l_m?cP}U6hHboCb|NKhs;p10J@HegU|k*qMgckdoH3B#&KOO12hgV5TBRnXA;OVq_o6muu(TLDSjUp3qN z0{CpEea&v*y|fm;S?jU;Sicb-t_f*g+8h!yQAoJ=M2(-)@fcNRJ?U17>`GF$=p%5A zG9}n3IxT*Nzoh@MF8vCvqkh*zX`(9mFVKWME|p((^z>lpRNF`b1oVLLa~#|Ltr4we zt3=#n&T&Syd9s~+biy%=7w@XZw$EVD^Nb3nWY3O**8mk2{VNL1Q9)7dQSaaNJINz$ z0XuAyUG&Flx2Kh;2Uc#W2(JLhEKD=(rrrmqXKJ16_U=@XvXQQGYP{h%u&AV!^`$@F z>>rgNM3Kkb;XVK(W4@b5k@eyu?-T)@tQ3m6)}I5%vkmgpaL3FCQXgLY3K$3&*;%nV zI>zP2TkCgtYN(a1-<>O$Eq8cwf_EYdhAqSA8VCVuS#6^W7$4T>Siygp`JEd$YX$x0 zsI(U2&Ln27hE0NIFNDSMQQ)KQ&pbGCgfbyFGbu4Y2XHJ@X}EQ)9<`%}gF-;P%Gc?T zzu)j@yJHj#4_kewf4u!fBz1&K`{Uh_QP=~9u!0PlwXkxk#&ybKD}5lp`bhPgWLD~}*Gr>KF?qSIni!1BNLsAz{sNJ~nhmuJoPiUkM zUdhJrNWP$v$M4!&or%Ht`V!dE*bik~|0Ow8VXbSju|Evq0231VjlXQBua8RN>U0}# zXR;)s!5P8?16OW5u-_P*pixU{H|y=p{Y>|h*tE#JFO@VB11}V!Qk*hr-S|}ZWy0p$ zS7!BZ7;;y^jOZX?1a#4s;re|0Q?X9l3y3L4v+yv6ek#kEY)H@^pTSNIk4c9fcRa ze>=R$0x#^%{_n41{=l<>av2Gdf&VfZUnqV!^x%dQ3u-v5@9cz1NJnaY*BL<%*><#? z__aB7{gSfaqlnv{7MN=)5&N+}iC@j+ZHqTTKlXAGKaPhYTR~E%((1|1kGz{l@yjv9 z@eA5bZdJ8EaT}5CC0$XZcpD(AXuP&HGRbXP5fOmqSdpi^!l*jCW2Hu8qPR)CLh>9QwQ=G(NLJC|OI(?c+7 zu8r9nK|#a-t@8|e)SV{UGIJ#4bwk8u-j6-AQ_WBW5LQ%fCj_i7<~2#H`!P>Gu8F(@<)w)nYH{1&OlT*lJ|*Q8@@53t42(;94F-h~#ULq4o75L4EQo*_&e#0X;oEKD$1N>&dzV7?dLZWG_-t(To_>Hla(qtDn?a}Xi7AltGHA(aLGMANr3zaU5Mu7|G*k+4AQjjr9$Bw$M{_;Bxx?f% z`)D>i?oHv-nc2kQ_Y=@-IK;6r#7FeRP-3Xk zEBVkwmbD2*l71%wo0K{2cl67ixre}WgR!bWc2TGYaztEY>&u= znR*wdEdkb4L-Wff==lUkMjjAU1l3Xr=aRGyQjgNHcO27n{mL-K9?)%w3Opf6f3s7` zVc9C3UlazJ=k5NYKkL%X;l*O2lt!dIMvE&-Jl5<1y-G%|Z`Y@^lZ4F!G#Fg(q1o|K z+b6v=qE@#7r)JO;>~iF?^)HqA>LZMMINSIH20c^DNfmOnW6^6S0mFJK?vo$~Y&_kl z^ffcFrg6I*rUavPv=3zxIcaysi{C%C3V-qvpat9Cm<@hL1Laii4eVvS!voScHI@OO z%EHt&?dBw)5C@Eq5{?t-r3W1Jy$ALO#_JK6qJO}i-$`O>=FXlM&>j;Pp+I$gOv?KM zF-|QhgY~{C|7BRR{O#IJJ8`Cj%kCt$GVHks>(T`;oaZx=*5^>wtFJm(i_4&?Oe!E9 z3XtHn=`Wk{FRATSv*fq$6-*7X-bWrv@3Y`y{c}F~g{`P z4iOUj+1-(fAPI?Q*0_fcbfmp^qR{#&X1uG#d^zn_!|%LKc#`8TwqUijsA)eqW~a>x z@&6IE$H=ABbZl`RJUdTuquFCEFqc3~eqleeyWX)6*YhBw$xAMb$x}2EG_4{WTn~*K zq-iA9Bu|lR6Y@CMxAG_`8G$ctyJxc~YORKo^WN>nmkan+ryDKoiJN5?5%m(o8tTW! zLZ@*7jyoDPG(r^r@=$=0{*p`33&>@~M`K#dWMtVo63ozCf*i~*@9mLj+)MVF*GD}A zlTZwQ-duqg?uketPq0D^Cv9W3l{j){y<3Wf9ZTNa4ekl*AL-V30U|aE%%fdR3cGPV zYAX)omu=p}WF zmUOv3rtYm=WU{Kn*lhI8W~r8mi&!u^gfGf9j5Ece+?ieLO78lX8`rij9BUG=O zOUj*m+eNzg(lxV1)V#GJ;AE}c@J5%Ife?D8od~)A5yEw3GReQ{BC%_WZzKB0Lo1zI zz>8FMzi}Zwlt3iXe># zqN-1JjV>m|-yL^)T|rSHks>}MLzNY+yy0GkppF1z#r(7sOm3x~rLv`Mz6<5@=p;df zk_4|Em-m6p@1ayS4%PbhAhp}8Ja3;D+;MjXc$$TwTdAV|HuZ*gP#?Lu8-sjqt=E3i z!~VcrLnah(0=k*Vk7c-$$oAgL2M$uHaKQeLD}PA`Z11OG@|HEBFIFdyt4YTSsnnj* z4`|ZYepRG8+k=xyVN4|0H2+Ex<}KUZ@>ITh?3g(qE_+$B5kn9kmiwGRD7G7R*@6D8 z`T7OUT$>t?6x$PH%Ne4lTp`dJ@*N(r3DYWMXu%C-vA_!{=Kym?B|66yWs<2fz=<2V1ome zQ6oQuXO1*?T1Z1y_+Fo!jf1w%5!*N zTB+7U^mHspsWUzzgF|^H^;exlBhc`MSL$Ya4F^6Xi8REDg`=p+sG$8x1 z%lmg8%G#UA_zlD|Te#g(R{{j!wa)emaG=%y&4|CcHJvrFF@kj{GR*U^tZ=1e6L zFuwP5lPBV_WRfi|f;XX-boNRtaXT(UG2-Pqs~U6i+3D5kIy&5W1*Mw2Im(zYE%2!z zI6S16GbWDFyvP|>?EcotD8qA6C0MFbGew3&oi*@=y1}Y{$iTPuVyy{#dj0ACDQx)! z>)wM0t~=_uxpEp)}-?!;lfU zd*&?Q*CO1SXh&*o`#j#g=4vo2OlLd${7nDVUYdbgoXki;6UHSI=cF@9a}Xx4{!{$K z2^hT`k?5f~HC-vXvDAA8nfY?8%-p<*86Xtk4@>1At|?ROr*ko|FXPf`2*0F|!K zcp-ZSb-KzWADHlaw=Ksvig%XOKfziPyS_GGt46zy>6%@f{D3@E09d$dArtBUr5N|Cq>q5P0fo&xwph8qa08uOOro#&N2CRlNfg#|<8RH1twnt>+-JpZBie za9FT7a!UxT8_8C&DI1}mpuA|JH?@N9dV zQY}yD%R1(i+G`w~1kU*FergxZI;x$DHYv%fvsh{g<=8RSkTTM zgTOY1Et{HTwd>`L3x_0~yPpdOj-Z)CqZ<^hbios4qV&QWyjt}92~}ED2xS+n$xD3* z)7j*`(n?Zlz(MbbK&>0t(-{?!bOdP=5${XnG_wDpy$CsRX0q&&(EY!h2bpudqN5A) zmgolfn-z8c+ztk$KF7|%BW_)hvW-6@kJ~xOvWaHCC$eWdMr=bG6@*V{X_44)l zH1+a;@^0G&Z*x1I21Z!G8Znm?cYEYxJ(I~o;t5Ryo>4B{R})GM?IEOhi0L)(i7RJc zgGjpMOEP`m{}N?|Os-Z}CJ7;De0=qJ{)ebRU}===_X&>dD=f7+ekhboq8HoN^DyI{$7BTAOh2f>NEAJQEPNNZ@ekaBnwfTo8^{YLqzgUxS zAoYHEGga|{sWR`&^LF@mNqe#HsAVzJ96X-`Go6GdvLQm}pgWze@%uH%-VNs=5MsRO zc~wO*4`FW-^`)fL^4{Dv7uS=oCqX8F|4k~=KRg7ct%Oqd(ZFB!GXb&1B*JVeF&;e* zTiJA6Wu^l5HR&6jF+oZj2=!m?X~Tq&I<9cdfq!~G7dgZMTk-=_g&}4zqWiy{uQ9BIT{IgT-)U*% z55?+^aj5Ut-*F~G3l?FiLSZ&7nA$0mXGDxK9eyx-<13Kr(ugKqAObpy~y` z-VY;neuZlc)^{nX4Ik$r5g+)=YkA(CC>77vKtzwEKRHr0Cd+&5A!>3o^k4)DmIb`z zEEDZmw%de`PbhHLWWUy2fdb(GJBL#A|4P#|G81O)XzB{?VFaJN2RR6V1Cd8!>uiGU zy$(fbnDa?D89m^-tA#hFoQA&_XD8XQEO6^~iaUUfjAl_GA<qdZv&Jf0qWz+@9Uk>L|Hft?@vvCP zsXUS&H16Rs_}Ja87@*SPA*J>x%B>j)aMSZu9IpRWeL4ytH-q%I|LT=iAkeG4aaX|u zVb`dy9N(8muLFZOmeMhxW}nWN`>P14s$PBhR6}|Y zkx7^q3a?fy^eeJpO`G4hzj$bgsL%MG%PN@&W zTT+r*u?%xw%*cG~?^mqQ70(S0fk=LuNLYm&!2=u3XGI6!&vya8_Rm&F{vW>t=|Ct= z$}Xamg4{ntmD^5ic`g40tKIM8WurcN6HcItPMnAX<;3bYYsy6={3S&il9^j_a5MZUV7OM*EHf(NbL6*-KSk_+T*rUJd`fxK z9%%pol`N92gJ@^4T(XRl+BQF)kY*aV<;b|-zrr=9$B4+&SNKIA_ zY)mRW?ulZtc}3$pP5Pi5SOCHAT_5u6At6THSEenN7YgCu*e8??_$nXBttsGGocxgK zV#(7%<#Gn?|NjvtWZZCt@gcDOD$x$vp9eky?Oi~i{&8=9{VQ)xRalhl6b561gX=el zhU*dYox^pxl6ivwBL+?{oQClGP_wODq}(^^7kRAbPhShh=j}YklH)dJZFJn?EHig`^qa*$f^% zM{W_$TcvgVygkh42BmZ{Jm_JLAkEOBY%l$vz4)u#UlV|^Y^?W;{H3TB8!0V_M2`mz z4u0D?vhmSe#<&WD@!cgEif3~c55}Da3IZS4L?Yvlq?RK$kL%+*iWo-A;~#X|EvOgp1G(DKD^M8bQFA&LkWR>f4v4~Nf`PqqB z-LHIZ?dvXfkzW;U8aNFg4O2w)S`jIstg}XV3#cBFds-tOE%YQ5pv{O=VUQYTyJi5V zQ)X!$r;?xaxdh|?7|P5I1oJcOx}6d<&!KO0IMqs}M&ln$xjs{CQTH>9>^U18&&}RA zR1ma|T1Dc!{NqZtGCyYb6U}Bs0~vkXcrx8K?R_2dflE@k$^1Y5Ay4&+1 zVhv3d1PH)0;ZKhr{N>L-8uHaA1?j332~%_bDAEtUKYQc6LJ3c$2x*xR9(`*RWt7C~ z`(}EAlUU>uHS(LcpA$9KefyO1C(m-;;|y%b`2GpI>LY|?U(u@wbLxQ8ecR>%F$b#J zPP#3q<2L1z5q1q6Kv0yNtyA@bU-7h@4fxf+W<|#e{Hvz_p=cF()D>br|0nYsj18m} zHZjM}Fyh8_`;IRvu(<8z^}$c5-@FWdDm3|zTI!d+rn}P#D=z-Qie)lFK>kYCN&Ke9 zpz!9MHgz)HN$jWduMYSPQNq}WY%u@voR%~B#zahR^OEmbOU{TyV&e)GffY!sDd4O` z9JD?q1szVEua`OgE4lWES%#=Uks^HB+5U>R;a#K!#{2n?f4aSK^D}!nMl}0LE1ZmK zX_dE@cRsK22VyblgMCP;tiet?EGMn?%O~dmi;-bYhE(2w98Zn?dOT+`Sz=dJ3u2~^ zc-jh0Pm1!Zb_K%)f+aRngEIgkNt?MF2Ab{u- z52-5h)9!DLKI5(D?zKMskar+7kruVF7U;#_+wgVnPYzTU0eey@gi zAnfYkJfZo2y2Xl=WdhCk&GtXKB?XQXVXw8DpafF=3FYHsIWoa|6$O-_a;Bj1iuG8P zpk^wrHz{7S4t7Xd0Bcg~&)gyhftQQ6!UhfcYjgja(%3r)?!H0`@3&~02`7|;Gh_6R zcCnAHXLi|#9hO9n>>&hK!#NsGnUP_~iok7O(XRb}iFT(2Th&w|^auPxXJ~;u;jD;y zqkT8Z-FG>?`E=>MDwoJnDM2})k*N_if7nDH|CTbwc}7M_;pLg0G-Nfcr|YHYK%r@e z4-Xo5G9Fs$kJH-(wr4n=ul7_P0R6O>HPHH*Zze4KSZp9pU~7k%<%>%wMUku49#DAJ zz$8JV{~xe7f<5D9SBeDPu}F6n2;#7k=p&I6B5=r5g^SjDir;AShtX|D4$bqv6M2`W zdYuhYG+T=TEi;m5+lB1L2Z4n~k1_=arJC%XJWq@wsocM3OVV_xe&f75&IAfCF-V`O z+k|2DC%UjS&Fta?7Y~Be_?JUo$zb04JMSG$#OL2=ZXovOU8D70r=TAid>Ne74w1cQ z66BBliHagj?OyO3Wwvz15P?VO;m@+aeCor`~)d>?98BJ`~ZA%?k6fJ+CvKO4X`ybuL=` zjoTLZC~{-@Q>LrdwNArE`; z-!5~bMgEmgL^dwPy2YEU%A2GJux6i1{A=6Ft zBG(N6Xc2jl{Lfe%UJ_R}HtPE~s$daR@)XLS{(N=0*E6qX;YXO8h(4cqC*QLKx) zulFtBm7jzMM9pWv^4aWsW$_Tbxn8iAU%j?v>u$b@aZV%AY_`^aeR8@nfS#7-)$hMi zySq#H`sVVq6c2uW4Kv?1K>XxdwcZ>maIu@L#B^h2() zjdt*MK2Lboe3gHu1m0Lu>Vb&4?8PGM$tgX*IW1i*r?I(QkeHd) zX?79sPj*z-@7qGSqV2$JZKVFCsX)BlB*oGfn8V3lAa_m}h>|sUTkE5K9k5GuF zl=)_itr9y*3YRCC^X;j7p?F-!)oI3#Uc4^%^P1He#(&_klql1%&RnOOm-_3xj;pKV z$qBvWY@*&a2mSWdoKtld8u?|~ba@kNvdv(4S=mbB{z#d#LDX2TbJQbJPCj>6%X*up zGSd}J>Wz@XBfd7DY9x+0E5SF$Gb>OMa(3eRfU{NkTZ0NWC$J8M8 z6JJ3rUB5CiF9vG33X&IRz?~mapZyL_ zsRj*1YnfE1^#`8YPS)~y0YR=+q;z&e*=o-W)VvAizQFTd_>8uPB~;G_eYKgX=|;Le z{gt#~c6IdqMT`1rgt<}_yT=-P>cz)xp>tXb7*=Tnl!J%fH9(0Nmtrj_euNLeP#mkj)PzO1r1pxu6j1__jTy|u# zpB8a@-=7(~(Q|AZ*4_heEA*Wl8WH;^%pyEyC+F3du$8JKXwXzAgrHQ|s5UJ!z;&XJ zzAM{Sh*ICPmm|h&F(yPjnXlV?&G7BN{s}2G+yy>jO)7%6^FWZcY*BpO(n2BI(}c-2Rh?t+o!Y6rXTJpu zFghrrc+gI@qTDgs8KG_%G8KJ$JuTCcLnd6XA|?>9TQ~{nj||_wKd1IVci{DQ8He7G zhvivhEevkH5>$g=Ox3G7;a5{g6JlC`1@a$F+45y1ai(4@w6&d{D5c>d&W|)TVSA99 zy^zbj8bY(x=5wXZPX1gnwKJ|AH$Y#>T&~N1F`ET2d+k6+5YT_E2DCP9cHX|K(y_f> zfwk;r#`v%w-%(&xFvn&+ zQ&P%+``)XKb8zVUBtO|DjH%JpSzP>h>g(WJrDZpQ^4x?BMe^8`2@#j!*3i@u;;v4I zrd!X^Zp{1B#yze2OTGvnow%nB{yOXE;~`ZYy5wkEX(CJ`g47#2Wswu8+hwO*7+n3N zj=6nSvfJUmz3+bBVc~t&CX<#QD2afb%k?r$3Ew`mI~%k7FFA+?eD+PU&IfYP{aP$N zmD!s%)_G5%tFyAB_qpK8$a-=Gwee_}*w_?v-Q9;zvALp1|F6Ak|A#vL;x!bxZ0?lY z*Cktvlxs5OmV}{PzOF^(POMzUrDof9OSx3U<~FMugGDYwsiALfyV9swGbj`Z;~Fz! z4Bzun%=``C*ZRqPJkN8^d7txspYwcPUgU0>WSKG9#=YtdXUtU_tKzUMT9#5jgyX!0&*Hn!@6xJ!;>CuM&BidFQU)Sy*1 zE|@~iH9Sxs|FTDtl|EvL!v?qoC~@>{C&*jBzg(>sz&os}i0QCdvFPaQtlv?l*r)rDRyhio`k@lJ+75XQ(g}> zyF)^Y{OdRKD5vDc45||OjxZ%^Itmd&*i%f!!oo*is>${exUY z6RVzayLD)8z%!lQQv`qDe|5Q??$tFn9`z7S4s|a)&ndR#AAuM1)0^n(;K#*n{9P;? zBWmoMS#9^)+SWFb@rMdc%$L8-yk(Y-kO*j#Ep$EwIo-Hk zn#`M%JvNxms_mwFYUC`&wZfW6dsbWKlqpt~Jh-1cIzPWC9&|{ZJwv)LUGKI0-aE44 z3nN#$J;mOO(N<7hxJn1%ZFszcYhoRh1Vt;?#_}UlHxD8`eUtb)badhdt*27GJNT{S zi@Yf#y>l0$ZX8#o;&D7aOT!LO(wCnzci*;j-uHB1%9{Roxz5=4V{dLx&fGaUNz>(J zy6+6W?V`-9ux2LJ9K~3XKq@q=fH z0fp>ReGi#2)gs}9ZC$c;Y$^MV&WX>10h968gd`4Ac^*vVjIPon-FH!p$jG*Qm$1}k z8~v6r1vl~Qc{JDXQma&jn_DK;DMp$j$7OF%2HQ6*edvAHD?0EbBp{wK(pvC`=t za`mM>SuG`dU!4}=&vHM3E_#V~F_icE+=q8Zp^ zxJnH?V$7QTJRdptw3)u>hD}AxL8zfwY=JTuO^0^lMXB%Z zDeh%XB-^^X4;B4m>@!=L96n$cG?Z%7?ea9qS8abQaJPyTO^R${dQP$~P6l73=-T~m ztW-w+Tx}3O@+c{PKwDp+OP27D)G-dG!5|%#7rL-eNtlyh)4}*&8PEGKb+%82{`PxQ zp(8sqwWXx;75NT*e)0B)gs@y`zXqR(y^XTIH_&9ArQnQ>8st3&rLJ}Q#NKO=p(_$1 zMCr=CN!UbO0?b67lRdE$spT{=LHPlZ2G43Wy^x@nTa$OamKbUkx*plT)b4BPXZ1YC zDC|gk?rAG*>VON1A%E@ddJX^>v<_5U^ThRH#M49I=^{4Jf;SMxH>#%JE-o$@3i5aT z6nbe482L&YqWd*~bVY2`0SZRtrtCUlz-tWx8;|+vJ z-_BI@17j3nZ4>ys(-Mx+F0H|Q8`dLuxC}QVF;{67D}%F(K#7m^B1usqv^B4ioNx|I z{KG)jj>nq`h+;PK!}Sr#2;K^;q?(6vN&t<|0$+TX7EXw>`QU842}v16f`%THp_{Vq z9uPhUkTKMMHV^CkW#E{`>fR&Uz6#G@!d!+WkV0y&Cnmw(kK!W4%<@8KbG$R`D2-_0 zD!#NTxN(2lnw1CZgjGP_vz*;EaPnZqMC|bz|GvVA^8sJ3_eeXzUVJ<_`bzbdX{Yi*>J#7P@L-zda<2 z;jXb6wW@Xg%K(qD8(&N9v|RF4F6eIw-hkg=miMTBSmv@DQ%+~@MnGc#Xyy4{Md@g7 zC`OhWZI06(xRbyufKcYtiF9*Cb%@+H*3H(!);xzH2xTA|l7g2pwp9poct(AH)HHSRj*?@9&m6R{5*Q3-H;o(?+Q0oC{|F77OdXy9St zC0hqETn@l#_}}b18_`1+z=Z56ECMi50RmvpAA7*Nm_h(W``&DjOt zqYPnM_~~c;y&DwbE@VZFDV)AEmT_#`JPBMVzhaWlvCO3fX#6Euh|;sL=8X`8GUE+% z<0PC*3()vP2!PS~Lx$LB5V+ti7!NLXg z&*mH_cm-6ogTKr?`dnNh;B)< z6gF_gAM$r~C_cf5ycbSev6C^_%Z0(ql(!n0hM>FDXJ^%m! literal 81586 zcmeEv2S8I<+BTwCK*few0d*V{1VR$JbOBLH1VR8INC^-K1PGyoW>myp2N98G1L=r> zlz?Rrm8Q}=iqeY;p_l*M6hIwkXZHVQySuB&x%Zy(*5`T8x!KbwJ*^eoo47eRI96!y z-)F$V!Bxq@!MSqjV$hP7eo-F$vw&ovrN)t5wxx@M1HH{d!^Fec+YV2_aqL8>Ge7Nw z!yJetkDZ8pJK=CES66Xcyp_GXl`~1)1?K^pz;$P$E#3}~vt`}`hry9zFljNEj1f#` zCqh+H7W{=kiX)_8X3YDo>~Suv4t0qXJb_@f6Rs&G4g+27GLe+riBJQdbnq@@Z}6|T zthA*xayR&->gr0sVQ|(5@nBp{DTItTLK=GH;C>@rotYEzZNrp4n_?qov0%f|F#nSQFiCaqi3}FctVt zgvL&oD!3K;FG8IqTJXii3QU{v z5?IS)-Qxa8i3mO3J zb}R4`W((Anm4_7wF3cIhHA$ZKJK<{H&OpZMsQr3yGaogiHO8B4Lvck~YZ1s+6d2xW zzX8lVT-W!kwWPDNO{^g+j#04IZ5do$}#Wr(YD8FNs_Exbmg?29bmTmRi$-& zmHkg}j3R~t>nT47Ke+pAI$%NWP3Y_-Ny0AxWsqF;!=CWHFovTG13729P-xLr$*E+$Zp;aw8 z5)NbQX^mI&vW64Lw)=sVI0BCXn$tH_1>U7g)-%$!*EK|X>Ecx(E&FKi(;(~a18qKx zd%Sgx?14m0zyD4#g(MB0Ri)_RAqoN-^$b%&BY>kpv7VLS#iU@;NO8Cnv(alV zWlADtWyD#{4)Zdm6pWQy%>=M|SX(t?^si~?8)`w6ddAJjua6i7n z#uh-EYDCaG-UE`S)IUm-NJ+%^nncP-Oa7K7;nFOP%~vD*pQ=XWe>UFu9h~8)>ZJ?i zR%aWKkIY=nOl;My5g;!?5l&qdrmwE*1I0{6o^|qez+sGiOh7C_IeI&pVazDtUv^$* z<#$aPGiL(HdY>!V8ZJf9N9e(9oaNljjEIi9jy66ZQcBLY8A^IsnHUgkoV{JGF$9>t zqlTA00tUq;CjNlpl$Nox4Tx0$J25Z|nuQ%q-~>m||NOk`gENBRK@|1TSJ$?;ae>xg z3i6&kUR%q7V1=Cy*%<%V0-P<{?>-+7$T+gv~;~0 zx!e#*0XZLJ0DDQ$4%WoDM~d+oZV$4FgCodJNYL)317$0K8Fd{^NqUAzNiZLTKE?}V zEmMjPBWnR%^2g@{o>P^w-ggM}cZjTSWB`o=ve>-&I37aiFs?g+3}#CN`azmfG|2k< zY)HE5(6}}fFi#&nycfV^Xdm!-Zazj(7X9ITNLCmr0>D!~09$#3ei?Grb%b=xz**i< zyS_S-q6h2&w@(AugZ6J=Ev9ZEJZ@&FCIvkYFw}4L1>~y%hjgb4?1eGLZ_8=^ynwD4 zI1iemkFGir&a?w)E*d~DjBC(5XRm#SK$tjG3wVe#8d$3K{3oGaDWF$|hvJN&ULoYB z4IxXY*V$`7=#_;9AkKhd)D##jatQfTtB4?ZNO)jH{;=1}P1) ziKMmjp*d!0$Yz!Y{y^q|v9i>GITnhMbhXto_5ovnY;;H(FfAE7BQL|{(zMrK4^M<}`* zJ3?#+WDQ2d*WYJP0#O+OzB6V9WdZ$t4sehG;JVJb;2v!%*+3lzqNb@7vwy%Q)fri6 z{=HT}3g58b@3Spig3PSWnAg`?9m*5{mCR$?teD7{Hz0b~C5?C0l`uW|qb2SAY;VvSDhNbLjVg&#y|Ej?EoP?Z4L ziIM3Ty=mz|Rwf0F&R7=%<$QxA@DP&t7h!r*FiD6Xz>#oCNf~LR%(szV1}P;jhlI`k z`7Qc~5J$qE@g>w$kt=m%B*zg4Wnx!9^g#bm(AT!=1!`pxHjUlYXdm>vwK zsi_8WL*^AW(*x8Np$3Yr?mi}<*V!+o&=&sGP=@E%we#On-|tg$W_e+*$bcf^!Cua6g#jrGV*!O(P$46U zV3!ft!;y$&cN-k*(LYu+_#5K_d!K_Yzc;jpmAgI8pT!u#6=!#_BR?C(ULKQ{=&dzmu%BkTVMh6Yyc_J5&)wXe(0ZvVuL2m1}{p36mS zkNUq)c?cOe3kc22ckpjh?Z0+tK*&M9{lmEW=e+iZ0SFKQM!V5+}pq|Dc`P5UfZfybXhm&BLE_&GYv1 zzUFmyV1t!)JV_FwXJ4~9+1ZwPHm<1&gGsA{EB`eHEh!Bb|E@MLZx`{eOJ7Jy>2C&> zf+1M8!5;PB!k$^H_=EP$sz%saksN0E+Ye3n@2xiAyzw54B850yP8ygq^xc$ErvMn4 z`E{;N0j|xKDWDrsICnfaH}K8Dgzq>WQ#YVf;47?RkgL^ySTzGcEKuwEo>m~m-!w)fv(QM9_ZV*xMvPTNr5Ai^Fb6`iVdpf`ujUk)PEdgLP{cK z#O35zh;SCIK-F?NR`K#L#7qcqWEF;lgCnZUKYwHz{}!N$g+c$I=ghI=uQqMwnt#YR zexEcWfE)bRP-BEN>#Xst5z9!j%7}lZ1%EfHEcBM!e6I0tVX!REn`f|AoxSB=0CcGv3w~dQ<5) z&wGDe82a|){XCloC1kdRL$5debtmzW2x%#BK7$>n*m-=;)Bp-#ncuwJ4u?t4Zkx^D z@j%Lo|5FcSu>E45w!hQqyu>~ihyL%w(_G19?o0-R0+{>cP}2V|KcE4ZW)bi?Ta$)~ zv!l*m7}?<8*89NTHh{V;D`yYye)K`(bYg99dbm+#E~zaXT+&0>>imX|=85Xh zjq50?JM{v|}k7`=a6w)n3JCz1d?uz#Ck z&aowBz^P@X4F1B1!WbLQ#@utGOG$~#{2KxqC>{Wz!RFz2BH%v`RxaQN6=1e_0Mi+~ z4Z7#Qil!mt0OMkpE$7rcZ-ab3lz~Z#vrxlVNJd7Sg%{Zd`44?z8vgzMG?`>&4gE$9 zjKp{?`d^EEGr}IL6aa-t==+b4X#BM-9U%wR6Q$XR7WUoQb~#z(Ec5=#68<%LI;81u z{G8b^&#C{n_xiuR*Z;jV$9$!G_658Dy)?&sY5G6=r8y)LRKj53=j(p((wv-(l(?+S zY&Q6}+IxkwVCg)F_g(1!KPl1vkMgh)*KfhSKk_=skJ-5t0vrkZwyq{8BLl3GsZ92e ze?bw2F*fX5$^+iJ0|5D(jorVylJXBch7A9HN7b5aX9xC{;4nMzqmdBramRbIfHFAP z2!5jyW)1z0ofY(pO8<3C2#JJ)9Vu22VKX5q*uNzHWth=F4yt?E}di96}u6x4(?MvAs=8Zt{JsoBq7{khMhgtz&0y)#g5M+!Osg z?#+fYP1VO=o+qa*IKwFo^Gy47{kl}q4Y`NRQ=gjM*4({)SG4A8g$0?MS_8O z=Ql_`&G8z*dTc1QxqV*x!R?Dm^)57e^*!vB@@+>sIF|}Rf2~^$raJufRCg_;w@eRb z4Zl4oQMb|lrd7CeW*EJrKur9r-n@Du4Trp=llla9;c!=-@2)yctLwjTv1Gk6k7q*Pn?Uo z-zCYeWe=pnL4B|Y^gGB^;MJ#TIoR>X)|J!IsiTo>g(7#OK27;lLTD>E-pud6gWz8r^~`4z%a=BpW&6-5Dq;VmDM@8%Ca z*req5D8l>w>EX%2^25c~#B_OAy5w~IJkg&!&|7J!Po_MVNc(k7b%qnB$fpX85zAJ- zs671$*sxF8mTQMy-3%}2Wo;4O;bx|{u9U93k z_YH-^rJSx!jTFpe;6g2`?aFTAk1yfP6pr$H`%piA2-6ceSgzdS+3eHN*g;dV2rwH! zV=QnL_jJ>%lMX9nZnC+5_nLc|M5X!^y~Z+&NBq&_x?p1d*mGk`e{zFU3XRbEm|8X< zH>b3xK#jp!?{(&dj#q0wanh%T8_IpGI;l$p94rII?luAE8va})s6flQDA&Hhz9f}8 z{>yH|Ugepwi->AUPm+BomV$TDTex_6YF0C)7|2CQ_(-$w0Id%ggQps4Djr37wnE0^ zY2#*>M^BU{dJ(?kU9rxg7M^a;U*{pCurx|tu|xr3iJ)KVplML)lN~L4*Xa!8PxM#c z*5chP=Y9uK27IVvx za{3FueLrPaOt#bBQdNo8%7gndRt7!q7Myvl&db*%OnXcQVkZmixfw9trN=Ro5;#@7 zESKJ@CgDTJ9xx+_O{-Wunfy7N@V>WrA@APTo#Q}?_nb4TjPFJEU}5=V?coXwas`e! zSmY?X#asu-=cFH z5jQzZ&>y+&$mc-#yRi4m{#ZxTCzG#4Q_R;W11XPBw+YU;9y90q(43P|4eX|6Sty@L zPrCfNc;Ap#{k@-07%C>I^DZ}P3LI(j3g1JHyJex8DKdpl@~_9oer%6>jNLXd(h@je z^nhP}xXxa%f;?nUv(>Y9n^!$BnSn*6WHLEhh4$KPXj@=(vNAEPaD7>GJUp=LZfMzg z-!i!l*^mzpUaK!mvZxxRpkhK_QHm4>^4j)#d>(i1)y2^(BhG$PShu`W_UEi)NSKWQVDxLap4Z;z+`bz|Q<@ z)#ao7aT5!z1`Og=jOnQ&S8B{jr7t+?($4j=3&s%Td(&TtpjD@VTgxp-eM&;hCu~0) zQsQ`jP5TS}xP(_0RsBzfg}EQ2S0{T)aF0&~i3dukInLq?Yt zjCUv83+ANkdbgGP6yG{gLQT%#)^2L@8Lyys&Ciw(>_xi}vp-%t&q-HvdSic#niF6a z4RW9!{gIm604kS%>cmlzx3u7;)7f3rV*=|sF zEM^ju9K3x~Pp!>Ga{S2g8Y5huNDW^mX>Q3U)(W9`JAO4~n-|D&zlecY9lzID>e0-n zV`g+N%*54QB9&F)zUQT?cgYRZV0}yRr1#(!6XTEW*KeCdC%^K_u=%_)=&7UAmqt># zRQKBCfu1MF;uFzT$@%Z)*Tn@+^kwOZuAhksUcIR;HY&i;=yWs9*DLn!nHmM9mPtNG z(GwU!&!Ew1b%`TrW%t0KoGkq(8J(mjDi(dtm4g-&$-&Fy^E@TG!vagCYCed^u18?Z z-GT-y7FhbzL)PB&4OVmY*9+#4>)Cc(KzfvySRkJFNzIUVofz+FeS%6r7E?G|Y~za52{Se;>Vs4Bzk!aDiP zmH^+wZiRd#YED6x?|lt^p315KjhIJX-qbAq)`_C&_h%(;iulm>pe4#HW6DK77?*p^ z#Hd(wbnZ-=-k}qnEO+19T=At~!00=TYq7(~2nDaQ48PBu^j5Q>Ct$KEUGGkbJVVn{ z_!B98*iD-@xl0^H7kFD(Du+d%8P=6)LXKD;O0sk|12%zOmEgH|+NLt@klxNbthnzR z4SumTaS2ry<16Udei8?&Ow3XO;78}6pU_Q!CS--n)aH<0G+}`R3iC0Q5;DOn5m&_n z2RX9n7Bz=K|UYtG>-B0^qq}YMpCb;+5M0v~e zIVZdeg8aeFZj0vuKV6V}$r&T4xa0%4trfBQULw_e8)iC`XWa5VTl`1rVuA&7_K%Kt z-o7Z`r)ri-sJo*wbz-faE0#09mHhbVf^70GohHA*(uhwc5??A;lcSTXWwt7KdT_Qa zTl+JTqS_HPJtSQ8qGxx?*uK?qPUZtvC+nZb6`t{mYkBmvt9?=Tri19=`kLDph=L_+aWJ*CXkxGMx!Z_4t_ z<~smZxz=40-GxELhw2HqK3*_9HPWKcC$mo6H>7Zr314Ttxl2`i$e=&1(SY`xKEa6I zLlOm(SHjh=Uz3m@OD|UAi9i8krsyz9QSI?I}Bj%7v5`Rp*<-}%U-n)nRjmiOei1Y5g zaXpA5&c$c#4 zR!fiSx%S)qr@KEUP)4K2dZ?!__)&A}dpgs*JCeHtn=tX_HPfOcn2#WDq+o|>rAye> zPfY|V%%0p~Dl=;-DjztTa>(g#Zfhx6Ws8JVm1#({7`>o??0Yx`OWRbcs_Gb}>i@W7VD)g1f$tjLrQ`jU+qn%ADmdX`8+O!=PR4i%? z9FnnZ+@2YF=pNBtObU^!mm!tU8T{Rf$<6KYMqEM@0=JJAoew6U7Q?PC_bCa?`R)YQPjrZcgQi+bd*JLX;=ZD{Xy1Z;voR((s<8PYhzT(#iq4X*8`eM=2${n|HM}Bw%5{waxmoep;)hL^Mva+^{EpUj-Z{V;W-f#nqQSmT5 zk?WhmXTJ);7kte$Awlf@j&$F%63^+}4gl9+?`h%4RN8QT!o8ZOALa!33W!vq{A~JM z3n&*X1Jl!0Y1=U;mDAuh{l;ssZSxlW7G&Vad_|lF`!<#JAm*h%>Pg%lALiiv2*eiJQCK(Eved|;HE?Dk%EGe_ z$B2*+Nm!KDlav(+@wMs%Oo};d0uYfpz!M1&J;|uSHUOGwpOEDgJtoN040|B8h_Tj4Tf=4q;eM{A30qE*651gWVmMf0b_SU64N06)24E5v+ z^<>|j&=dqIK6!<}-rD|xnSgL5{~SaXNaK}y@?AeEOn!Ps>c9eC=~-=RU)TBOcAtLW zxZ!O{&w9M@W)M%N0HZ9cX$hS1KMeX$3Y?i9E>fO;Gd|R1lalx4%;3?Ovj3w!E;;PeqF71H0iM)s8(eHW>;^huZRP=6&X~{P3240zYcq{ES+zW zuU4(odNn$eg0`20wUtZ(V)(GZCAU;*delaEpYip?Hc%UJtG-Jg>U{GoU?jH%$i&|+ zt0f?pHdvLXbkc z&Orqhg$0@Ic{9@!4FI`z?_K`dKGJ`fvMK!_K&#i%BLl&jwWzjVoRjr#DiBfGeOu$ZW1x%>b~sn$1z$;gw|PwB zN(mKXh0B3cJ(ksX4~905#jnDA@&yxUxE~vNV3hQqYh^Bmz}Y2i>?jXucz!?RUp~g5!VXlNUWY^WmyKp^y)=M-){< zS!b7UYX(@|L-4=7GMNG*%LSDh@0+xMazIi{%#-_On9<||9w}RkK~yJP)s;^38Elv0 zuB2Bi;BKcMwFWS%{JbwzW8qa8GF%X!TJt8&M$4YKu9J6*EX=EaXQ;V#N2G7^AWEHA zIj=2zdh`rV zBKkOpKhN%6lLD0qtJ~Z7WJQgPMK=UheKd;m6#$;?8UJZ2IKCNu8LAz~)nJ11IR_N_ zA3ehtzgJ!<+se_AcchqqMlSvVMkBjjq!_Bvjh*J$I(~lv`bE!^qasx_^+4mDIq`#0 zpw`e>Q?JV>)C0&p(?)O0l4 z;zG{EXVEyucmqd|D*_;RzN`+^xOCdqDO6foB%wS`(ClJ9gGxcjK>Vj+K}Y(nY6-{B zx2h30!sDyZWI+P)mWVt0s;?OS2H+9?=f}$@c+pQG+*-;-FB0%gYy!ocd)=R)V(0lX z^rvKwX2H0GmT?V!iw}$Xy2qvgaF7~5S5TD8N$v|5nK>Rz$yFY%wJF;`c@#~nN&%cI z6$1C#BRqn093&26B_H=}T*kI|P>X!QweAX33eYQFO<#=>U6rxn(7`omcmmN2@Pvs~ z8LK}FI;P#q+|5no*&2V+cykzJ$a?@%IB0|p>Qm0+CZKTxpdzR@!OvAWF6tfUe@3JN zeLtBacQ=)ybP*6O($JMR5RuJnru1l5ynePk!|^jGIjEVtiOy+6TW37=uIh>wtrq<* zpov@~MZw2&lIi-PPM=V?e31_l`J>jcYSY;rk%)|!Z}eB}`Y?}K#wCOGkf*Zc=VfQy zvRyCG(FvD~{d1>+pOVo=!OJS?*18$KVW0|HAxx`1R3^o9zKyFp=bp&xsbEY@GI#G* zuf{j{!CTjM6^c{_FW+eGKR&d3Q(QvE+3_2`efYdHQ!r|dOspSYH-*|6g29IIRMM|< zI#%3@woG!E33}VNggc@}VZikD%Z550ql7=M|MWIQc+| zPT8eEv`}2Untzo4Fdpf~^##>6nmYhrRd(Dxt2MoZt=W44i0aai^7~WVdfp z=zCbv3o>wq`bxPwZ?Y4TbK*nJHoesa!E4eyUY}!@j^+H?G-;K=lKFq>+CfFsQtA zlz-R6aXfAEi$vhq*}*l3g5F_a7Kz&rEB?x>ID~3&&T8rnvyXH$d)|o(8Uhn^=1!-t zDZyPceSUut=G4~q8+VyWXk$@sBqb=p+QJ!SbUCT5Okv<*e^ai47-8LY-(Z1F1W<+3 z6Wu_2Y)Bfcj^Qw`YHf~*{G4;GJ{fse%|b%Es@QL?@ELgw^$ z2i01Iv6RYyoBH-;L>#c=qH()GmDmRNVzG$k2H^;gD{J>>In|Wm1+SzOo>m+6A8D!) z2%K~iPDFEM*I$YwJ{nK8^nMpqT@V2Ot3PGXgX1;A^ue)9Czk^`G{N5RtyXk+6LiEsI;{9MFGh8nUw|y<@j2=OF_LR zSmxGBUtKy+xtB*zbt&HW7Rs#Z!={0=68WhYwkpU=V9>7p%0q9_bZyM*Y^t|4Q-DNuX;c!JKImjWCjLXwwX+-DiRNVuewk zl2^ZZ>{JQZju=RM2iUwcO~t5LzS+BNMJ)YX0QynNDy-G`Ca1)Ad-uNP!O&AxlboL} z>c(!~h;AxAJFnWa5m^1p+9h^#$r9p99~M6SEe*|@j)#%n7pzZJXYdwWjz0}S?UMzqGb@p zs67eW$~FM@qwKM%wty)MlPs_E&8}fCp)x+HJcX8&xlLyY+pE5&hpSYC!Z>3V(uD;A z8&8_UWy2DV{CGa6*PB=s^7Xyb64V~ra!^;?BYL`ZA+JdkqFh8upk;Pp?AgtZcw{v- z#4IZlgAGi&hXWQ&nYg|eny`u-Ct3Mn+OmTIhsv~M`DgEEFH;0?SM0X^Cz;#0LMy3h z>7ME0eUaze49w@W%)Xlwiim5N!mK>?c(6&(>$oZ5GdTjqi zD8dY131P6%JLauZydz{|S<>fhqx-RbDW(Eni&X^<*xc1@i4tzcRH>SrSaQyYMto(q z>bGk?WeJ#j04eztQww#BJ5|y51>X$g!ZSwm9u&P__?_NgBLVQcm;HG+Q{UEWJBKZN zCmQ$8lC$L%W&KI&&(R}P$>6e*_`GkZb# zP|1t0>qZ$;8doNjcI!)3q-^<4tVdN=FW@A*@Iq3h4lQd`dXhNu;!{sI+Fm-*cXUv0 z-i|TL1mTctzI3*K1Nu^V#r4!U)^|Cuh{=;je7^17Nb{%)4SwO=F-S9))=}LPDri22 zcO!qL2NdVP&an3O4J)UdHVn@EY)w8RH{Vp0W*B?NS0A*5xUG760bM1K30To z)l{0381>>K9C9lmC(g0>3dM!-mFb=`saW^cO*U@6#aJIk1NWv0sAgbKwK@s&;!`A3FIn*1CeaM zZ=hf5nZAlWl+b4|)ajP(KQlrD3MCW|IzDD}pEL+*1(C<3`>;X`l@uH_jvA#|*2WZBgAwJugQsm&w5Ch?}VWOxP zggt66_b>5!m<`P_=j&>B2b~{!`=-kha-7jEKoq_g)7-%#b5zp0hgNQtuLXwzHkX39 z5Kr7VHwOa=Fo$t5J1TPy+~`=*{R5`<(yoH(1~Iu$zbu$|6f?1P?U&#I;3`9lt-<2yOG-w`^vaDJ;o_1GqKw{{D3XoT}Ow|ja4EIYKgRq0<2Vsc+j;MK!8`zDL;jRo` zvH99W4u7KIT`WDxX3nDGLEtu|(e|tay4-*NXo0+<<)!9Im8KcFK&ZO|#GkGOad2w$ zpR`8g82?;HeZci8&WVF)c= ziNIRcY(vGVDXzY1!%9Ywd4#PJLY4n2oxUG>PJLozEpKaJr#>F;R66st#1PcW*F7vc+|27r403dC65qZi$NneQL;UTn_nD zCitA;b+l*pd=2DCyo~kV!GP3B^DTY_Bvr*}Q*=RUO3JnMv1ZR6zBvAI^Y}EAE$jh~ zsw9G0r@50Pp=D4_z@ltEwp&9Byu0Y0ev}K?-XfpusY|yPH<4Hu2kaHtU>Au_r$eQr z1G+(ObHZBX0MJI+3P!}6zp6@}(Px9eDP*7I1fX4$Z(~xhnZxx?4S>tOTh!HDa}t;w zW%GJwqGts2`Q;mG9GKJX^>%)c-r);U4m9x;KQlkoJp?;&^Ee~gL4Up80tD6G`Pr1Q z3|kO0g?$6BZv|ISYL6}NV!03U^%%v58oZwXOJhA%$|r;(CJRL|VAp<#pu3Np41;3G zwneY*8^p>hF4`44d-qc0VPI8tCzdlFzhnZ&`_*N|TF7voa-U$_p7?VIBQG$XK>{Vv zvX3!>pNdd6kn+o>&2}fj*eBL4HN2}wrtH_zW0)NyMma$GOkcJUvO^W2G$_I~ZTcCy z{g)l6!~+rCL+(Gx%>leAD24 zkcjX_v#ubd2WBptk-Z)=0hK(^&1VWp3K~?6>WA(&iq%?L_Igf8K0x}}k_;uk6$Rm| znTErGuq4O4*S=r+$P@O>Dpla#gnTX?<{IX0Cd8dQS^zDZG{WKul z?yT!v+mEUYFEYBDT#)0@b%j=#Zq1qsF#UKa&-(LRXFmO-%@k7*5X#>tr`tgS69vLE zt;1KJ2D7#+y@9)}b>6+Y8D@2?t9(n>DhF^9FT<&&*;J>aETZqIOVislnDHzexT6Am zlq>wj8ip*mA?I}h`rzhD-Yj3a?CrAGhL5tjuH89m5tB3hcK-RRuL^&wGQh$rpPmC{ zU`g&c?x`07iq?7CLl4|~tSuZx7@tS{qUFJ4tK2%`83J+x<1vr^2`yfLzBAI(ATtnh zb6BXa-n1hpXM^39#Dj5WEedaqXh~5@*QH4Jq>#vUjf3xYXc;6$CN^BIV@p{RkR!x{ zH+vui_~H(j%+Fa78apmYQ+MQgS^i`~H#=%eGw^w)7vbKZ=>6hSC4CbnH91NLmD*1) z9$BC0dlaSU9GI0Zz|un;7cfq<+MVr;U@#BO?>~1`By|d1dt-x`@_HBj`i10~^Kq^g zyqHPaAYc5&`ziV*Q?K^1V-a-^Sf9OBsOb)14|AIkLVTQ0BD=Wt(LoV~)#5?Y$b;0J zKf~s99?89%QkL>R~|Dz|M@c zK!}jcmfA17P;+uF?1f8wd^Ub ziUP9st2PJq(Fc1{n}yQvr)zUjE03jxG+tK_U zY+9m9ne1-nvFA(X=czuJC1<3d(lu)e#&8%+p7nS-*&8~FTG?F}+3@X8hW{x7>6 z&QE7bsamF3E4HXS5g|t$l%QYvFn7*semp&~YL|?V#K`0-!xtZRFX|3!^jv>lC5dOK zr=iB@^Bpgpn|tM|cYf@7)2FM_x8F!oP~%iT`dJTEE#{J(@hLlOiEnFkbgoH8_6SO7 z^uZyE<^#xVkVyX$y`FH#$@28jpwks9WMF@rOPdHaM zitjh8#@kdoQ|a6XrLa$Oqi$FX-7%e7moAYnwr zzFvGJ1XpToQKq9hI5}n)?BeXHKk(k`=@jw$R{0V|OHgMtO|NSSFP(amsKJxouu`Un zMpJmcb!`bn%zIgLa!=U#D3?r}Z~DuqFn_rkMXi|eQ#<&v>07QgV5Jp?UA)BQuQ_yW z>b~@hCs68e0F};TSQ-#`T%r8#;jpBFGj(^$O9Dn;CRW5JTfmOi$S&$G99WVM@Z{-r zpO$pH4eRrs>^fAiJOg#nQ^Lb@{8DhQM&!fumB%@^#v{vX@_#NlekEEzCd#-r)iAd4 z%d*O=p29FemZR^#4Z_DJuMnwiM~{l4T%xBdeeHakS_6jrv39}EZPQq*{^XiRd>vU{ zG75f&)3cPN8~joyrlw?MHv6AD9Ft#M;bb3xkX}@xP(wF{; z)G(1JaN{-UkR2QoG` z^T^Vg+fFw{!-b9G?&@A&vOXYI&DS7l2@D5!o!!m3vZH}e~wW{PoNuG*xbnttJ8fv4y*a-13^DWtI_YUX-fkbX`<;P5(`(du_x-Q!aU z_TkRy_a^8Afk>x@@+ovxt)*r4s9#`oz{`S?GXGzvrqzpbRP((&w%86oA*2gLl%5>f z<%b}+rzsFi$GWbrFFRa=Da<=Y8UPjo{!cEYA9Oq&uuyv5n;6`vY*|;@n_^LnI8+>l z(9Df0h!3yBTkv0)syXDsHMvRjy2XR2x`P!Z0ls%9{3BuqX>D-|r6k#-_IHQp5lrs)h*BJHwfu|a!q_JzH(V*LUw}rW){kO zunU03LJRxSrM4Q;jVe&2oM^MN3(s=e6Z@)5xLL|~z!2eY zoOE!L64LOZ`&Rue1*yW>;1KQh$qCU-7t>2yO0ZGy0{RLQiq3Sc$9m1D`~GACz8h> z4NQ2A=nMA}Jg2tx4?Mf!QShv{4AWG;*XxFpdFP`pjr6vDw}ONNqvVD?dkv==tBz?F z^=`9szJ}k+O{G|2@&Wxg&38%x#k-hx=w!o_qbA{(?n>`8D-ghXD}H%46eoecs}~(v zTM!bqft9!K7y;CGcXKgRb66&3dE(x%cz2KD=Yq3qx^ZESTosOP>0P9f;rwkgKFz{| z;4rQ23=E}Bn?R-83xkj<{h}`|5**Dunk1B48j{H8d^I$O*=B5?k=(|2rm)vFPh3TEAgha4VE@q zuCOHZ4bWv8Qk~lnODo5;7Jw>3v`QnDk}B{2{sY%c_&Tb^Co@y-3dOQk^&o>j@&TIn zFDi=1HivAR&8^!(RBi+nyGvN=pnz0v=WZ|m@|(7q6N`CjavC!F&#IFBlxhhdahnz5 zv~r%-hQ@|XIo&!umDJX&SR&rk;-A*xpOR~7$g_ra!lZW!W!d*J9p0 zYIfMdak%{$e+-56l0Qx`Ah)iGN2HRzrmU~pWxUyc@VM!eZC1pqMv$Et-K4bT z17&m}IpeXM)5V~g%~Qm5m#myXB{%-`o|WR|zZP6`i@nkJ0Q)Xu*W^s`F>ZS6-UHBC zp*0Xgyre>vT}YQrs5o9DQq}(x^{`>u?k?Qjsqx{`^O)WzoK#9-?Z%~S9us#81XGO- z8v(~!v)h$S3mbRqdGxW|uBf+jIsjzczVTfD95R@Te_xMaqX;;w&2wFBaky?oU#8ic z;=KyXVH2(w>eh&r2INuRWlv}B8RH~J+`qQRvGi73gJ4O0WLufGVtv7*$|*{|ivNoW zyD0(Bg20A%c3OR@pK`b-t8UqSE<8gllqk5-_3>VJY5zcIKQZCGq8|tXj!On#Sgya| z55PgFn8Q|5pQ@ekfLY|ryZX5jwpB6w7rVLcG`qDXCDYFw3_Gt_<$pRJdoO-R?T+al zpML%2qc!jO!C9^Vhu-gKtcKxv(ptf=@_v|AjWQ(~Y%{?@U&W-^HT3 zm1RbSfGo{wotX$8pxk+9-yHTtPq$Arb_O_~_3S^W7V3=itlyP>7>k@3!;JW1qXS+o zv{Nq%OL~x4#}i1lY`ouAK`hD4Eg`gH?3TFThabPOYnU$W&EWDcry1|ir`c!Dl-kWq z)J@$i&^#IoSv?98DaSIkNJ>feN6pQ`4`}5$fdrY|u`)Im`7Pck#!2;Jp#--X@Evm7o~d zvpDODWiVDLK2z$8;m(N);V|di>RSo(bJ0y|j`F$l54aAdHXU5=8@q(~=!j^jwZw6{ z^5|0I^tExq!$cgTi~?cv-4HDAdj4R~qE#kB(U&GFmy|??cW2tyC0%V8^sDtwSJi(c z><@cQh>-3dsB--9%Dyx*vU72le0@^uu;q*sCY^5VR&dYp)7eO5uFbK!*p?iLXT2i| z>FSx%hA6*j8yDF|C*Q1sNA)?oMvXfsYTaB!H=$oA-0+`RX%{MZBojRm)L^^|RkLx% zuei56%`TT-T3|ztCU{+D~(~kzh)yY0Rs?Tl?G`Uiy&`oDP?Z_kxZtn!19KUX+ z^u3Ei@)=jfqn$LG=?rasX4vkUeKn}Sana|G&;z7E>I zI%$twNGdN9oHaLa=bUAn;ULNpD$Sv=7bm$OFuH$0)$(95*bcedWSzWJC{;x$`I3Uk zHpP4S`A3Q`x4T>@z~t87=rpTR!uovV^ZoEHxDR^8jF>-NU!Uph)G&~GoUHIk<*@}y@(`6^g+fWx>*KXLvj?%jf0om4p=|R;#IJDm!mSh(L zLOrzS;V^Q0pw7NQombK5%Xa%n^0lp`-n5)SY&-Z21aJ;&Mq6Lm>%BdHAULG_>hwB)cqy~_F3hnK_9+b`qIac^!rx9Lis zCa8UVPIpxp5UlOP<%~^06nO!KU55GvY!_hjO>6ag3t9rC@o#_X7(yGH7ET9L=w`mW z7v8Qk-MQmpZJ7Pd%M*i7mIxB~v3_o~?~0W!s?Z2kdxa5lLCiL6{a7x9f;%yhh@sPp(J+x zIx>qOJ^*zK6ZNmJhHMVhpO;pO?tCe`RA?2%R*ZbO89*+WIo1~IStv4x9k-)U`0dr>qV<(sVNIx|&P15Uv@wM7QzSH9MrRs!$c zc8v>QqBpCmOWX0(E1vHLuJGhAQ0qw8CDLVxGTB*as4Mc@NqpGot8Vh@c-ct>bGIrsj>w(!^R8GKdEX8T&$KGz!=?9h!mNq;pEYj}D2|V|LFdr z-wdcgOIv6z2sy>PahOI?y>avycxN_QVPKEX<-s!LmJ6NDv=2U|a#R(X9K~-v+mqrh z0CkWXvqczc+5#r%wu`g^M1@q)9;76a0;B(sbMgWwD`IP)v}I(<}V8vs#*j2Y!yI*%2yoaq{Vhmf&P{>^OLKNyFPWs7ZYkNU~)SYLO zp(U}eKI5z{wPwXu$MJ(&pg`+9`r`6s^VsUe^d;R(JbLVo2QPn_d&2t31gO2$Cz__; zEbkiJ6g+okVxIH>mj6miAUI)`Ccvr{K%vkoqNn=?tnIDf=Ox|TeSFQN>um!;?*LF< zJ*yOFP+qKgt|WPoG3k5Yn~cVJP)bq>;d-ywom|8|3&35OQSvC6FY#oQtdDz0$W^zo zROrO1uuZ{rF1AGqfo=N!g^Z4dfThQJ5luI8?p}XN^uzjhmz#1AtE(Ts?eq4futK1Q z+oFZ^T?y}QUk_Yovsm{`hSToqO+OQM2^MbJFuR@q;ug^8danp6Xp_kl2)F!|Ub@~Q zgPl;m7`}Twgkv~(WayC0U_)`1NmYJ}cDzr6T!Zx#&uy?@Zo*j1knPDqQz`<+k zFGyN0T6HRI#o5&3v{LlWt!P2|o7hhel|s0@Jjv)Tu_a!XCE0Z9pvyI=6${2oO+VK4XA!v1AoU#Kx;&U$x& zb0suCgc73?kAh1084nCgz>@tq-4=J}Bo@$5sWt6NsGQ>aoa6b+f&c?ze6;HQVVNhd zrjLvQI#(HChh^#Rk}>eqhy8nc80S`DJ5U|sAjE812Pomi+ygYrD5Y%v7)Re*ej6R% zW-4#E5Pbjb$ddN4GGUZ{y*OgF7LyBBR_}G44(%P8g7XFCU;5KM7daXW^{ZH*p77gh zZggL=(9gmWU4LAH_Ryi>>W!w?Tx)qVecpr~q+jN(@QPHSRSztmJqw=kGsqiG3eWu* zel_>L_WpAabN8Dny-k=}v;0g@O1D$S(L;{}s?Hv2YqrgHOmZAtv-d*+eZBmUY0#(f zD&J0+--j0(dcvrSzL;$GNgi8}P855*IC`K&`gRX++V&=#^U^y|=|t0Xx4@#3nhX1= zDebEYS1&&|RfBreAJkolt=?FeCn9;TTH2|-L^H`b&+XapeO}{-{PA`v&lg@lut9QG z(WnGSB{`%LMg?K+S0<>xE*m{w2~e`?BFpPt=<}i`7q{0Me@b)`DJg%tO&uM^pZ<$> zYPnwwf9T@C2STGy-|o5oKofEWMzC`Ms(Mt&T!o4s7~-=jX(xzT*N+xN`NRliSo8BN zH;U6Z&7Y`+PJ;Gu&I>5YXFSQ7w8g|19?Tzx75+c=-oh&ib&DI85u_v)kZvgj5ov*; zQ@T@-P`U=BLrSCt0SS@LLApZ_P>@i%k!I*_c%R{@=id9i|G>A_w-$@T8Su%y_p|$F zs84p52Z8M8Ui3WuE3BV>yyhq1di{#J-2tih*HsnX^t+86;6`9J(1oX&?=ifqTf)3N z{L8Le^))|BpH}r$U*Al*!uClp3EBANIWy~WQtjRDEQ8a7n#Qf;#l>!e)qU3eSHo-| zANTS_kjZBcwc*c8e`F>KDlyPum*7{s`ZsPCW#adgJhFPc@nyM=RYy#@9_x1{ralp& z7j^BPe@*}!Y+7f;YzP@zG1Wy~iP5s`Cawr1i$q`{_QpF?cC>I{??C(YFxa&~Y z<#F84nv@^fq!{{BWZ(eUw}Y`8b~R!?kk^KkuJBNh?Lnwa9!2l5_cfd#Ten7sv(p)0(Ajo*IjLfP)%vv^SK8O47TSU*Ctyh!&1?p0CQglm%`nx7b> z8l_?GcWiq8s*kM5C6Y=@U40;v57xt z%U|?Tv6P)!9@EvxB%rI+D0d;LvEJi5GK}~iJx~0;V9ggu;f_BOEP0bZ^QDw9cUAa~ zkY(&K+fJKIK|I!!!cCA4@y{RuAZCb%+4kb<|F~Jfnli{c$_b#&x4vq{6>hREvmYVnXUW!35ZEF$%p8g!%9+oYUe;wEx?ugODw%_*~w;v|>o4 zo^a&Ch3|!~PhRStJ4zl^w*6ljjPV6%l2lFnT34~x5TFPPDcZon`UtRYTb>g9Vk8wX zhLoSm{zszZzp*@U45XlZt+&s-OdYk9Htnf_&C>xjy>%$x&-*hK2P%^8@AJ3%8>|YE znITBB{8uI*7hn$FIy9hWo1hf;R_?AA>aZBTICz&mbtE7#JZNUOUHG@Hi40PG@aGNA zyNaQ!Ljg@dLT>&InEu@jSj>{}KlEP({zdI!{NTS)_kaHCN?{Be(Z9+vOv3_Kr~zGy z`F*8V_lo?Mi9Cpu)6V>>Wj{tfoxl|TM_ybB4dl1nC@@DL4e5<5De@5vg*kaA`|sWU zUKR8|vs$kCIRe$P>&NV0De-qSW;$dZ%GI8tkP^vxlcV6@9DskOrjY`_xKmPd`%0(~ zAuSHy9>zcF?C(Rym&pO^5;%<0xZ3+mu&xR0|J@*sGA$SiOZ4H*tD(eze7aT3sqh~q zvsa_}jUluA8-$+yQ)#>aG?4g=wwnKYGznj5%J`KEL^BB{T$wV`{F`+2=ODtsFE~w{ zSgr__6&X22Ns<4np#2^*3Yml8yuns*^>A*1E!L3y@4-XU#K2HQ{-$@Xh6(^2z~uZa z;VNz64`(4Ktw0vSczCpjU7b)TP*OOg-#Gp6aY567lTM)OD#Qz|MGESMroR;XXKKGY z;1|!nEUI2DQv;~m#Snq`e-jpd-%kp1?-N>@S41!aWTF$t@7@2qE)XdO)(h&l2UkO3 zBK;1_?GNt%FL_xi0V+Q@2qV49;)$jI)N>6ufU$f`#%RiLi@Hdo|L={^WPs^OCttn` z2eX-i+({uWy>7Ap-ERm;juf&qZokTH`F|CkT&;@*S(p05y!7_f5hH`%6U4u-=r5Q2 z|3vhcd;dQ|M1UV6h?oAC=l&~)*BMw|IUYVb$ONf>ZyNl>3D~S7q&w@1CGu&&P-xEV zum7d%tDm3(NCv7YF1(Vj%|LoA8UByh1bQ$Q;0!H{7~`v<2w9b{`<(zg%6czXCELiN zJNX3;4i09UsqO++IjA-{4)L}bZft;UOpM|#4;4)q^Ih4f{~kRJEuc=!QH<;>;fWs& z^}i0|kZH1A?h7IA{Um!^xf-r);N#}!LAdlS`42d37 z`R~6~6y~qPDEv1I_Dbq=0s%!f{vaEfzDJ{+4Q+wIG_pWW2a}y130fgA>Krw?bn*=~ zlgKZx2O$-jnjhbUCar$;1I@92i0LJ>GLyQ}#sw$We{p;>c!zt=uMRxQ)(;f~pw%PS zeq==Ru8Zj72Cn3f9Y(x<%apUxsGb1#fLh@kd>i(9kliQ@voilD;r!2SLC1i2>95Qv zyedjaD}nk$_Cdyt-R(?P2})r{2Cs51!rW6kh5c^4gB~rV{YM&$yODJNwHBIiaG)`H*= z#zKK!{8W3Q#>pb*VZ&JPu)jo;fKPXFVpWw##Zuzlsz<}d;H9BQLF+Vj)5zIEqsK73 zM(rpsFmsb<_dnl1zd}Hm7U#H6&%sWiV`zluU)-20HroQlgA}M5J;BYz8 zgKYc%JUV>M_TOA$4CuO5&f&_`f!biH^DA!-R~6?$Mg{LGrc%^phdxEHVd zi};2#qJHiZ8Xd7NZAwy_SLi*!fDk__|g z3(q+HA-jLLUl+;!wPl4@dPFl(u1Ok|^&G)cm&~hSV#!#Jx|^EX7QYU#)fPBNghu*a z-PmNl{qB@n3M6r0yW(5@=X2_(3smFcHiKt9S2O%V%fAC+?_cH+A5u9KB1;8?r}xW6 z4Y}(f^DgV-Bt?t3O&_;YS2izGivyn|gkE~$k?*VrPe((Aro0v{|9g?h{LD|P$^R4w zBtb}T4h))qnXY@>`M|(<8~Aj1YI$4KZHE`T=Nlh$YdgRzV)HNX1QrTZ@q`mXR#6m+ zHqdtety)J)w|tO6ZioYeUr9s!572f%^2~ay%QhQQsI8}kdl$F|p&SP-D!qJ1x3E8> zQv%m<1Nre)na*GNiH}S~+-uiILDFm5dk87^z$+BjSdE^~R+N23NjOvwGvC)yu2#I# zSjrkJkIh#Fwm0mw`cL@yA6ebU0QPpbWSjQt)qYR#RXL5y0_F}}A9)IRQ-`1B_EqtS zLXiR52J?%&7K#6)KAKjf_Aur74j6qHreZYWe(p_;UMUw-Qv_znA)X;tt#-09;*LC; zjq;500J%07-e zNzroagD<)!j!43)M+Jsq5%cbLVeUWGKWKCPTrhkPYn{3MVnsH0v2P|T0e&My6m zr`hUR_s%^X+ghSB1JFNnXC32)jMq1=77UrK#iPmA4cS>et1G;Xd5o1|STcArl|=6G zbH0ndCgO&HdyBeWSx0!ywn(l>hqvXhK+I~<&>@wc@jyY(h>`2~kT9jAHp6gUmT1@L zDvm%(qTX1JIBrF8oz2o2e|50R6i0<=mp(ymrmu*)*2u=W4sFAshuD!^DA!*FIZ7Ci z$=*5(n;6Xxh+zT(uf3s|<;d{p+^uGs$z4=|eH)^KInagaoK*M1%BAVYJKKc!U!e`i zFmg9Pg`_0`I6SvV>=AulHIL|@95I7feu-gp0-O7JkRF0KZbV-IZVPy z#tF+N@_l>)VKsB=h_iQ2jb(8`O;5Xo_TN>!KS|_Ti(G|UPH)sCdb!Oj9&~kfX&_Y5 zI&@5iDDN+V7p*27dV=O9Rj;sV@C&XPdlXLSBh%!sR+n1~xNfk@7n4R= z4`TQL-mKqrnBUoOt)Wu0)w+x(stwR2&%Hp%FUtv~t}w4&O_5Vut7DCe#`UIqO|f3? zE5-+t8%Ywv4WHOS=*A9>1WLmR30QwUigov@XbJhCt1AFa-X!*B0Ms27qr1N>zVORE zHb3`d8|{`G9V*j4@(n!QLnpiYAKBFkO&$+iqgBLO6$AZG->Tuu)cA@#*E&rwtTgY` z`o8mrGyL{|^^{}5p@Ru|LaglTUDs_dTugjlJ&89l2Jfyim~JPDkcSU`76&{(2cL(> zVlFS358G4i_99Ttk~?Z23% zelT5+Y-BtPNGK;ti_-=k>hoj5HX(c-zKGeesf3G9XE}pf z<#_G;y&g3%*Sat768Jlgr;-8jEuCN787*(A1u=z6w3}f_n$uV-e=U3NQU?8f?=r}G z2{GQF7qor1QFN;w0k`@9kOAZ7b@wq;IQS;k>cuCsl6~Sw0}pGPnr7?^d@3_wq^DUa zcDL5VJlf7n2S?p1Q+7{rrM*q5aeeq)y{8=5AGZ`<(z+l}Q#fe|_X?Ia7~Dw8EP{M7R{66|4(=c#5rO=(Ifymk%K z>m_;Jx-}Y8`|Mi7!;LmCdv#_VVdUdgbLjC6k;Y#2$IE9cdT{g0y36DAQ~0h=?eWXg z+Hsfg4L!SL*|!`<^WN}z;UEL8np4%Svl5b|_1YKR7xcle>7yQ@6#F;i6fKm8Zl9Dg z*`$8|Tf8cR4C9Wu#O|9aHe>&IF&$G=Wbv664V*e*epr8trb#@f>1YmoYKcnEd#|8p zsd4(n^`zs-XS)$UE=Kfh5*==(YGj&4CB<8h=Y{Pn3s+VAq%sgFy#L!*#c=XqY5ot>{{nYvE$Af3V8p*}?Ip?tT8a5j$2iU0RdlE0URt}nQhC}{q=EsnL z)qibfs2Na=*jB$iM~VYYcA^Z^v@m3h>*59mIfd3mXSlR}(dBt%i`OkOFO|==tV8kc zHo6(b1xhuLL*_`NbWz!WfR4FHUVs5!_$>_(Fu5HzaA0o|WSyT5Eg#V>S+fS(E9@-Z5MXv#!hCiu(A|#Ynwz zpI(t>Zv*eVuQ|7n!|xQ$AkC$qYaCqnufI|It9UfDTY(lnyV1ZZJVJX}^89R3pEK!7 zq8wgH6#bW97^hQ>yM~&qin6^IllSIo3&vaxcuJ`&wb?3P1i)lH(}WKw%h;3J7uy3t z=#mtIHMCEtrctzd_#f4($Kdp9xbQ=Co~Au{s9XCbtY_ij{iryoS4HFD2zY~G2kyV0 zp6K<{S_6(sMsu%~u;Rvfgi??3yZ2D9lxN-9lP&K+qJI$Dz>Vyjq8A3%3pd$5Isdr{ z-~jUgL1awja6@i)_Ap;FMrAv$J)_ESc<77PvkDt#z6+P!aP^%kq%lWX3weRPegj3s5IBaX)s#rwiy{Iz> z$q!nbT=@fzI3v&)2e`!V}o6=@IWrv#qh}+a)X>#l9!M^8RDTYqWirOuf2+^ zIHZN*$&G`*VYlwjeBy8wcyySB6O{bCsBV4s%qRi{~ zlY4AM(YipZY@_uHG;i#WcZuCSj!2tKIB`ez<#w`c4Zw6Ujif4>0K#_-q;N+hBFI8VhdI+k5 zf^Jw8VZ9(4l7fA4E6N>G&T}XR6-RsVu1DfKGu)w*w+3$xpyN_J2W^CO12RFa9*_0N zCpi^PTnINyn(ySfRcd(IXb;)mQpthj6L^m5+iV<#EC$j)4~*p#Ak>Fk!jA9CJuL){ zbPn!{NKuRsaonCB)O2agAknR9s`Xif(rEhKL_>W3#M8;TKU1M7aBSLdq$B80`?3V# zJbKi6I3pfuc?0no)H+k=srHUhcDr{G(OC1Ynpurq8~5dTurT#F`A=Ai8`vU-WqKW7 z3Ru!EUm`3y%mie5N#55Py{So&=C(tH8<0atL61_!Oc0SRQO`p!&Pt-~ye5*zo1{Da zwM9^l^oZ^B)h~|<&{!9g8@~r-!HCI@`WSZno8$fZgNoz{nbYCl|5(+mpt9Xi_DQ>3 zgYSiSZdF5cBK7uui^Kl6fsb-d`QO!il5*_)z;qRE4w`xBr+x*qy0i|&tb@Bk%FG&B z)DuZhH;*mR5P|vq4L*02vr-#ULd8R zhQvtoqTUxW-F91ZOYx^7rIvb)401dYO>4eGGkDysZ}xyG()!*{6l zov?iiC3&Jc-R4}Pn<6y{S%Qfb|M*FwC;{cIt#Py2`1@XDNYU1|?3Ghqyt}WSnq%Xt zqeSn=dIK?tAyaYi^lMS)HnaHtj66R#da~1kBMI;x21@NNe5719zvHL<5n+r^a<&}s^hY?*$FRr&fK{~pTs_CDi8n`+3&2rg1 z%%A5)dKkS)URDpFMVP>5)LJIfs;0PUUqF!WQ56bbKO1cHDw-4mA!h|9C|=O=l$aby zEnY&SE<`nwLWC1};uFHss478eJhcXb+x7I}uUL#Dwh^oC97c^I;jPQdw!b!SCa5SD zx-a-mfc0+FJK+^W4SW>$Hd~w<`5MSAf2NwtGSt?Qo%IxI%-C>%TjdwYe%z{wS(R_m zHr5@VFPP$RrbgB><@pX1WCtoZ;hYVwtP^1CW8A!Jpch)9>*f@X%bNC*m3khp zR&p+Tz#MaRrA3_UmyO$PX0p|Z9!6I z8a!crW*598kHX+QPdi*+t&|P46@yx5hoIfywcVv&*G3-DW=bDf=Iu0ad=C;wv=zK+ ziJc+BbllgJGc+Etr=hfSmy`GRBZswEIRp>QgBa%;% z8}CkFc6)Z%&h@of#cK<7}Eq zJ(&_AWj;QhAJ`grTe)+kCU1M20;v`0Y;j*XBGF;fV&>aq^G!G^{Se-bm4& zsBko#l^$J+S9O9!ehwE38zYy=7fX`VE|t%X@9R~T6TgX*smN%;dFYBJRIQvaRRf35 zjGeC=I;#$x_hUa{c!9@#8*1pW&z)FjF>AP$ayZfLvn&+`@5}B|6qNRi3v6XmzFbV} zIaqk%(c#kliA2|PkwS074|C`Q!PM%_u;+$l?JVLX!DfGuXh9$*CBGIXd=R)a$070B z*g&>6fNFxRez9#@=pY&Lf7gyV zFz3*7e)xz8vF)F;Zdq|Bm#Kku@|1IAf%^G_bHk3){+z7!A=wFcaMYtQg*OnO>-}>? zLz?Qxf)-5;I%$Uh%mI>`4S#5Z?&sPTFO43L4i1q^LbNB69ebC{`3L3N^6_FMxWd+X z=CImDnKZ*6dYR@o=)s~3V(@c43KVod!F{G}Tu1sQnhtp^ctILw2FXPk5_{ym(_KGz zr@a<0kl2^3=G03E3iO{=_uk44cFG^n*;6i#HI?ef%YqtQZf}h)NHc777&PeRXp6{# zo4G_zF{Q2b)iMoUfj;gYV1xcMHsytC+EgsI#uit8f?dtau89zl%Of>3>EbhG_wC7Q zl2p5$=345L{gt_TkgzxV99`YA1zGI+^VkavdB`p6S6em40E9&oda?UrO69=OVNwMt z@K(-ZpBqE=`_#JyqM;2so*#u3K~%8m7l%$xAXV$o&s@J- zlOy#G@)JeEVql@2!x=c0m2^KDzDCmKiHD9BC@B7a->~bg`$n^9O5=l;w8}~*Z{ke` zmq9M+aa{mZi0ZHq9T6x7^O`Ks)@p`-I=C!xrP@-t?Q{E*h1i`5^w;pGdGg8ktC8%r zwg_fcR>qQyr*9!A(PkAA;e!ovF`DPq-lELHQP)h>6rf|}dCJcCzb ztvA#22^Qj8jQr**b8eE6hzK@9(|B@K$tjyPUrm{}DV`;_uJulXvNCV)d;eOu_S*xK z#$krcxpf_6LO(ukuy2N~c5nI%Trh8qf0iFi)uE}_Oik=FOcNKP)tA-CPD{OA8NiXA zW*7u&xrB_P>S>-~9MLYeVZHTtZ?`TAxGN@l^@ob+q6SJg&0~#DU<48^FI7|t2EoK- zCeC2?L@;m9?SXEt?6eKsXIO|0han*qW!DdGQv1smqF(E<#*N?Pl?I}z8fC#2d`6LL zy(6ToJl#W@E-=yA|G}e&@@TD13su2(9Sm=uoo1WLg$COVL+(Anzt$re{Lm`^QmqQoHb^*yG-wU%$gmKLM#BHBiYk#a z02YG4Cb`G#3e6H^YcZU-dySSd@z_g=@AEp`W?x!#k~ll8Ktgo#EG9cC4gMOcZNz1k zz+?-nkF-5$Y6&0?_IDSnj)5zP3cYZ~G?4k{P=24DNsxQX*O*%0XbxFp`4c*Ufwxi} z*rLsL{sL2b9x3O!u2MyHMo;+07{}o0X|@;pQlgWO!7*)<>g`tUA8r?qm9#gwPSfMt zX@4iIUXK{Jfn6h*{3dQ;1AA}Eh=q{#m*4F|-hHz((ST^Xe3g6FFoZZB(BcZH5eR_E8nW2H8vvh@!qGf#sy+m>3A`_exn51bwOvDk7$OL z!M-0*VND?`_&*Co%9LmF9rBfxT|-UxT)=D=VN`dHXK|OD`D2|Y+i_wva^Ql>6dP?D zA2V@Xt?K!)5bXq~rPsln@r)^GuqPdC#tma!*o>fs-h;N=12!3Qd9%&^it(;X-ST-jRqSx>y!3kjjj5`Z>u02msMq<)zG|_d z5dEtMKbEtfBxPzA>E3;Bo+Qkm%-ST&mAJ6-)iE>Twk*@Pcb%ybuTtJ#!wew!`r+O~ zV^QaOlGi16YVni0PyuWU&GGTEs=7LZo0}W^Vb4Z7!B$dQPaGWz;TE+YM29x8v}MpQ zJW5k_Yg2@nkOt-V*Vc8EasOKC8(o}HPzDHNsibvf>~{2{_Ax8%W#NR)HTe1z7pu6 zqLUPQm1_``;Qu^1jJLjERyk^clwYbkmNVp}45`uV8 zF;hT}mhN6c@m=XvElQHt-|@aMKt)r?8Ei1C*TYKu)8+5lRN%Lu92iHQB$9y=zpXhIbddz0Hx971&qknA=jc9RM{dKUU~ zODw)trUYhM6JbtT1ocj>*rQ;Chk!g_;wjrKReul7@`Fq|M$9_n@gH zW=hNhYd$qMlb4sz(kU}n>3AC-&-7KzVmsm*8fjx= zmuV4xWq{beM)0LQl17*l3iSNlFU=DSFyh<5*$0vnCwE@Rj6`>;GEg2%r6fh7{!D>> zW}^!%mio{ZLNAFGA$O>g-F8%DVpERNpS7{Bs;YeWPQ-)BPl0wOC^teW3Laya=pVNG zmmp>6!F~2WFY$joKsZWM^RSm2_3_IA?t!%s)bHRJZBt9asb*{X#d*0_RI5b$^@#ve zj+B}aVvqsa={9}$;|14A8?zyg;-8zw4+Pt>#hJckucxp??lf(Oi5rCq3JpYsI1Pg= z#~pH3;VY`VSIQ5`)X&)^=WBPENpD?xjxbrzRcTS4Hu-nbM~r_duG{DfH>bV zw`0IZh45WsEYT#ghIw;JzFUv^!!QzHRVf~=!>Eo6lq}KV@URjY0nCXjrXiK`^{-vR z&X?51SOC~wnh+0LTX<}2Y;MWQD;Xxh{h+m`dW*mp=l`1MHYB@OES=>pv*7DphTkmj z11^0d5;nt3hi|W@!13;t+Yz%XEv6|eSY9gpo`hp{e?=4={T6$!6)zYMW4$_v9d;NW z;a_|DeUu&()$f`x3@g5tCF7<(;-yGrF_NW!e?5HG7m zF;9O{Df?$+C}aVg{Zh~tB}#uV$qME!KK=B4A#@4I0Y>bFvL;7eWy6Ug7Ginaw&_5M zWJGrxb-&qv`{gW{*6^B(5`uV zN_NXPH$|jIVT8&--P3OzQ`F!P)4Gi$oAdGI%@m|$X%QgALR{#RM1-O~e0?q5$X+?` zwf}CEJv$-xZ?OjmC;>>SNd|+;lm{qP>4tZ9W43;7K?t`<{4lXA-yrz!Kf_+l!$9cD za2(fLU*PxupqAH%gjkon+xie44aZ{)zkN(tbzSp;7`StSLhD#mnP#zO(>-hju7XSw zx8EWH5RI=2*g^QL+1zXV=A>2ghiuXEG5PYGLM+zxA*g4P*Th^mgy@Ej;-9y;KlB$E zyYDH9+S0)O{KJOxkI}^wwk=?aN~`>Y@Hh7M^srZ1wD?pSDv3^taBzSf>R?9%pgv5z zMuD);Phz&uZO!Wu`}a1o!ENvY(!HzD91a>Md{%s^^AZK~DBjm4Pft4JPJ+F$5P_&r zOcZ<^FHO+k%@lqo?fW^l0EhG97ya3x5yE_rqOVJk9?$m16QjX=;MmfVkVKj00S_N= zMGjT=ihr(%18nfTg36CFoLq(DyZX(wgV`@!anP3(@{f$YT0Em$v@+E0IAqF9i3$q* zY#rCrNXTR8>c*x!3BbJ7iMfpAlyo;bf49flK#=>7ki-(uOJR7MZ>J(9=CCh4jb9r6 zgX0x-Z#r(~x{$v-Vh6T&7$oRX0e)$&>-v@+mZ@DEEePatHbKa|DjrG8c3DKw>qkD- zW6y*ltwL{v%)`DtawiDfdwq*36ca^=f(mTQmgz60#QEkelQbUo4p6qbMgPO@z9Ps; zIs{PNZ)Xc{$Z`txjfcL)!}8N+hvnRX+V?(n6`)u-@m0oHvE^@L$rY>+O|c2~uPu8# zN(R;phu% zIQN9X|7*C}aIUt!>Jc43)Q4|oM;YWo|A`%5rca!+@&WJD)FthT5`L$hx&N8`k> z?NWR&k9H>H8`Syx?#eXF0t!jV{8njw>jCBdLor?1&rO%w;P()*<^Xx2SCcCtZlZ?n zhK8vY;oV%HTa8Kl)x4hX53}|qpXG20kx?x_1lI5MP#1jYu z{v(KD-2m4>N`wu{4`)yhn7R=Kz>#FUy&K7{2b`y;(2#(a-Z(dF#;sEn4u~maK^Xl-Dz;K;|ndo03;zBsiul_iW!y zBz;}^&Oc6u#tD<}mnxD5i5tty)uTQ(S`M-*9imVoQfDK_`2X;%DD6|kCfa*j|I$}{ zN`F=tj9eXG83}>$0Cp7$kWy@@s<1qZPl5)!!D+%KUogIX`{rOKO9vAZo#fi%6a#9d`N zat5tM{)ph*%f!g}%T0;h&#%yf^|ybZ!Uj4%=GlJ|H$D6*`Js`+cU~IYfSXHw43OHSkPt6F zf*io5{WCsATlT8b4yByG&k5rZID9`tZ`Zqav(J)-qWf)Tdjv{J2xSBzHHV?Go~a|B zs=}WXdXo(Y2~t3+$Z_rYe$mEcq>1dkF@fch5D~Eu7!1G4m|RUhd}KJ484PB9;andD zW)+2G3r}`7kyGe1@JRkXM--rR3pKylY#(^yWvUh_r1V}U+S&0L>)I<+8JbB9s6ueA zZ58U56u3jR8z0Mw%zO&&EGb zulD@-EzY2|K(9z;XNwD(d$cd5o$+))p3D{tHxYH>Zd8c85Ol-2;ii2AfSJ;zF-&3~ z5|>%utFRg85ggR+Fovwq<#HG`>LXzw`2j5A0>GdNkv9fi-J`GL@rjCrLuT8eHQpx>7TrR6b%3=3;VfUJziO^8 zY79{9gmfJ1+1XK~8oo$=!2&WY8*>DfhyFbUUeZd0`_cMK2tj*UX9d0R#A~V-*nKIs zCxHYF=gtHJw4P$j!T@T+44@M@_yMuVl-sn^$>s>K>pHi7wPtx7ZiKD^SRuBm3CA~} zRjl-RD&Of^S(aQJ>qE27+j)9b@IAyJ+g%^v1j&$&eCK_B5@`EKSvm4l)v>~##R=B{ z0cWQdr2j{)^9utihY)@I;HhjPasRQ@$SLwaNQjISyE&veS)TXz9*{vs$9( z0H8DuwCU^w4g6V=@TBh{X!{aII*Y4GCrSP~h{fRuq2Hz&^e)iUQ@<6g{+Li`*dFXR z9(W^--DN9FV}SX^DGz-h#nwPkqDdi{PeoE7;r3t!ePd=O1H#r{k7~~NxAl><#vT1N zUS`hsy4S(l=+5b8lYCn!kwzRqLy-jl!;D&nZf0Xx2qYq}<0S9{fb620EtZ{t8P?b8TUg7 zzc)+KwN~ZKfm}&KIXKA`;3qzGT2$~GuL6|xv(d|=24DcrM~UOAcy+($md6!bd%(Yx z>@*MR?k7I_d7}mJdC)RH-KopSa>)Po#PF#Ccd=Js4S z&I9NPb)88g&+Wjq%5mFJYC3CYZ?{6UQvfWW@faK4(VbtUSC!xD10uf6NF;@|`rRIc zNPy+n2^u0~PAqzC)Z}!^H!Y{XktnX?7N_JLu60?jZN>l8$UF7&SxpCMU$+W> z!#D99cOL-DLMymH3&djpRA3eX07K71xnica`d2J%B6;hYn%XUmJr6273?+tuZ?;5!gDF^Bu46P|Vf4p1%_m(mp6 zxFbNQl3yJv8vGT9Zv}u_*%qElP4P%fNrjW;72{`Ae0}rFcC=IyGsj+N&R+j<@S1JN zhf4q=9{V7S{9XvT-;vvVv@{l~Q>={t320W4;n+l*Zs@*}6%!Z7Slo0`>k06;dcpQ2^CP610aE%ski_uTz;#mNV9LYJ?|C>m#Z&*|su%rI zLR5JYgabd=$AWY5F0>0Gg->MmBf0%X;C8}mKm_Jb1EKc~;K=133<8j~g&28ul~X*Y zpI&qQ902M|otMu(hhcNm_FP9nMH`O4Vv4{wfN#lKO$rgEw0b4v zfBcIqWUHDK!J1z=^0+!0;3MAe=+BudYZ`HZq`me@E(+VE`-Yqm2 zD|g$Fm9yvBdIjISWoX1PB^>kmQw(iODn@Wrewwaf1>9eks>Hpv@$zjn7in!7Wy(7P zQA&RXR1Lo7U$cW~AV^V2>)E0b1~I;+Xjxb%yi6D=z7~{=<##fqXQwgCKGB5F`$O2V zSA|Bn)$DAqUnzK&pAHitO$m#2r%JCF)WIR)3D6B0e@=pC@(@)OV|a*DG$2TvLhQKj zqqv4a$OL})uh^i3{AWrJ*f9#pU7qd+{>cU4wN=Np`t<6h;M3-7uxHoM-4KqTm3M&~ z!sVBt2tZU^0N9$EpoiO&8)1|bzifxoy)z}-Kc@jytK#>?75V^ZuCoM}S0KRXey(_V za37un85+c;BZ4x{g9^eQs-Zm0ek>EsF%#log2(XoBW^U=?0yWRd}qz+2cHYKxUL9( zUsAa@#P?%gQCqztN2{GNhuE^FQ6Vy#i!K0y-d6xh!-h`j9OZsffwr`1e@JiP;97e) zEcEuV|Em2hbPqX_Fzh)1_IWt(dmT5VoWb)uK8jlKTa)Uu)0V#U5}n^F(^q>S&bd7O zCKFP>@zxA&b0ONo2TiGw&b$@_z{Jw})))@>b-&(ov*c&sS-lgOT)B9;K1wvuDvj+x zx_$2mE0{OHkk3V{*v-)vA?#D4ol^GUFD$J5K1eq4LFxV7{Te*s}4za)&>WiQxv8%aUK ztNqs9YL~Xqo$Xin-Lw&UhtPYXlyiFZFCF+bt3@5xD~4HBC`VWCZ4mm3Q!2u4nFW-` z`1@Rz{C=d7{sRMWp6f9t4Y{Za)MB9#r28#6G7wVe({bYHlunAARH6c)E9~WV0aqQ> zhH8%BWEns!i?~HF@auu}4L*uG{Me%7!(aXk0rOz};x+Ie!4V#!jeMwfu>f#Mi@)O+ z!w~73yM0LXi?Q-N$8zyzT#^BTa};#`i2?lSBD8a{mzAM;_(rr;tqWlB{20zX0B%srK7>Br+|s3w^8$++ltlpC2kvzD5VO2NZxA={5RK!MX*p|o=vus zwT|)7t@a$!y(h#C=!Fp;UMO&MraFIjp!^Il(SZjNg_G+gMQ>TPd~>EBIy>x+>(+lN zhigdhX)xic1mjFlLPSs1HwS$*U_U!EZFN-9S(%5Z=PpkwEMC$%A}r{tEZ*#~bxE7Q zR!G}R!in)f6sbC&CdN1^ThS-^%qH=#6`m(b z+z4rSt^UdI(P3d0n2>@M$+h%HG180qo zNa9%?y);6m#Cg{{h631?|F}`0x=6c&xNE*w^u4E=RSIW@;aSZE1ra8L!p!Ce31M>j zQk#OWih@j@HP1-qFYl?UPnIk`toitpTSU(GLV|^z?A~a&rGW5Y%%PmdX@OzgSDDiY zJico<8w2nMkGgE+r6p1v6sJ%V%br)de1es`rF{vu9yv<`rK4s|OCy%!=p1 zCj`6zXcEHN!#SUsoif~IjRTP$T_cyU7gBv>oYAU(YBbqcdJ2!zJnD~OE;bW8ZC>B5D*u7Y>4L1jw>3tO3`B_ z5%d^XSb`LuuS=}Q%4J_SohT1U9FhcBe(9$vJ8!;@x0jLz$Ah2(Wrw-(Dh;zN>avv*e%Jb@S8xexJ7Jfl2SJPedL0?FlC( ze^5bYeB=vzfQSIWBxpZeGxsS<$aI3=uG3isYdL=TikoD=gUk@ zF~9JNV}jYo^?GV{x!l$|HDi1fDrMGR#ilj7SAjIy@G}?%-wUExSa~O~;EGIiThL(6 znRvC53^&t_okb0K9qTF*PJn^Mw%q`9$Q@wK1R%Ts>-mdIfy~dMor!3sh;*)jb&1Bu z7e{mc%(qtepI`6spePS*<#JGaI#&L|v6Cf7CX!0X6nG6j*25^)LOE%MDbcNT@qU%J z1dyL+zEzA-$&kvs0QD${1oDUNPxuC+lOi!vusQ0LHvm{-LXzTA>8oyElIo^E8k>{3s*B+>bX9-fU?)E+I$oGRFXWJQ&c#yFvh z%xC|5HW;Z$vz#!3NijKhER-R)wJqX03&AF2o6HtQ@ig=(4rmg}HLWo317O1Ej0J4r zh`NrJnjxSAOdmW|BLoo4c}7i*G|%dkJ_zps+~BTezw2!gX}H_O!LR5lZ_wQj@S+gL zauoCPIJR2wWBU!gR_H6!-9?h4gm-4y=Lth5a*n3#yu5GXY80pWiy( zeL7HKrS-WR-84T5f4~8{Oy#lmF?pVkk0|2uIXX;=aNsk#&SuE?XPh9A8=V(IHXuoX zC*e>Y855EQpED(U^gL~>?TBW64m!@Fmd&i_jyH1)a)-oB6fG#d+#h5O%t8FUdT`uVM1IN#0Y!fr)Z;+$M|EOj8<3W8RrMYPKPQZSRn zh6pHm4X*x>94b%1Kqr0cJ9%^e{-t#s`Q``uw}wYDjnmaSx@$Um>|}kCJpv9QiTtiv z^9HB&XBSJvZabB?7M8{Jf=y$}hw&JfiWHghRK~yN7 ziEr?iPOxd@XC{x6=-c}>Yfu+I#YOs%Lc?|HT#7oagY9oRQ1v)q95UZUg_UEwKE`#C zY+Am~OG6hY<1c{lyPqI_B;6y#M@vu5OKAVRfc-TFqWT7}@Qgjj{rf~1tJMUrn5nDJ z3AlhZyqTK~zz*$T%&fLw2H*yI{Oh!EHRZ^v-Lvibm9pd`SskB3E@|LqzKQ{QBjcdO zY;ze7H6S7YQWoCc6{c(c2wrMFWGIXNPJ=bWWo@bFdU{g2g_Q@t@Ii_I3Q)K@g;thx zFu;Fp%1{U~=zUv_9JsE3P)Oi>cFK=}8rO(AaWsEVa({1o-azfe>_q*chu{}hPFfFaeAi4)NG&FR8iDKrg zBL~;n@08+$jBmz8C>va6iN$e^7-D;tBBqj}7x5<+Ktl-R`2>jyCQTB)o%$pzzp8Yo z*(t4w?S7Xx2r;DJf^Klg85$ZQ62QyZ(}#Zlb{L0XdFjmAGP>r;(*z2!81SSrVMfFs z`(JyAh<+VOaX>2`lzWGCeuwKu}#(Sg*|)UXD-04wDiPszCe$R^_26UAoS zjFbCy#ILIVXaqgu7k)DGtX`yB_u4>!VyAJu0W7tcCrLcAnwsxA&6@zK;^4=Odx?_G z;maiWbD~*^6?S~&zn?UjI3Om~G0jKz(MrXz%mNF_W~EsS+PZsWnt4#F`*(MDHM~5- zgw5gw&|u?h=lapXZ%^D{s?_9Y`vat#(W@~L2tP>?jpIG-Mf^A7^nioJ|`Z8w*^K=NAv0iSaL1CM|5?6V5aZc?4j5X z)A_M}>tkA~--ku4!~NYuuekwI^JPMnGkrxk zILS(XK{UXUUniM#{#)<#y+nrZrr%fd&~X^7Brvo&55Id)84Zvk3pbp-96H%ySP0DG zS4JGqU5$u-!~96b@lOY!ym^2am9`c6)w}{C-721?=sCTXS(k z6~E+qwka2;@7uh99z^INYx^h8%s}75|I#m-^e215E2nEg%E~@*D)O zA`h6=ZZdgsM5r)~Rs4~E<9ZL10NH&vG~yQING6N^^pH#FT2i>0f(N8zV#VE27D*5} z>le%hyBYIFysu2$$KYw_ern29y`kJ-ZD;b=d@dio)q&&To1Dz}JiG7qG;eizlolKz z9tP+?B9$$2m^`!k-ma15wAMTvPpX|ZQ!Wi?DCrm6wuSEz<5k7Z8$THb&HGP4T=YeQ zX9;>FZ%kmR*xj$gsl72KwM+8NC{a*-h|9!EZFHtS;`YEC+;5r{D)ZsN96bw#5gmO` zZ?ykz-Kk9oMPw^DN5Px1-5^l%QtFz|^@XnB)V*G7n9`>*HNYQ{7|=)5ye@@={W|{Q z*C3~T#;uu~m`tb^Ki?&)D)%;<1xH2jM&b82u)pNeVW4D`Mz{;bHXn$%?U<7C*{3}Q zDCCYqIu>RO!2lHQ+uCT^!vEpxEugAgoA+TU0g+9EbO|VVKZlEIlYVLNpQ| z?ni=4apf;g_tGLAc{m>n?mErdsw1S6F|J=WNmn-Q?CKTim93V*dnft?ugOPfFe7#> zbbuR0JVfFc49n0H?v`3M1LA5aap&2^eql+}dn}Ti{sey2bxbksw5M+64qwpoK?W^- z>?Aq@Qbag%T~_D+=>LKpZ4^}?rcc3NDQ(ylm^6zwxGD=|522e$fqbL5m6w;-+~eox zhZo+E&NFQz#Jg3VapFDkkUjUz#w50tx~vMsY|2Oqh*Eq60RUJr=ohl{N^Tin-M?SM z@Ee!ct~K_%PsaDxQYB3h9ps?}GK=v>7rAHn`Rk7!dNQXpJxs&cgu*ZQ#^0&~=2w@z z$F(#k1-!k5o;iK=8Z(xDy39R)9MI;Mu$!zs~(9 z?@j^4&-_yOCBovV)SyZ_#tc`9-fQA8xQy;|E7g>rW5LGUa1|*XY+`0fVMqX*kM20j zZ-w9GgzSB$_ZUR5kxomWvlE*p`9$$C?)b^RswdW@r9oGdo#++0f)`5s;04#mYYpru zvIwxuyB~@T;`zI)N`eiuY^u24U;B%Kc8--;q2?)5(#`i9Q^6TMa;3J7%&7zLr-Dr`~7C$ONw>-2jc^Dy% zN|STa*U!eAsYnzSty4{d0sj?59MznOm?H%k~w$v5P*yD!R z_6tNH-Fa%6D z!wk;?3Q=y_9Tkxt<{Adh*`83|xktV69P#zAtsc%!3VH;r1|KU7==jyoJD=y)m&~ux zbbX?Ctbcj3v-*J?3ZNeThnlt^?><~^ra%SP~aw&bIM54gs<_ z42h$6gM2vyiIHd7D{>YIFVKO;=FXF0grh6FT_31!n{VTi%pkC!}higL* zm^Jg#6EYK){Hv)wwmC_8p~<@O;2-5CN({yXU>if9DR2ZmXcH%>PFQBv78&BwOSW3` zOO}n7PL#xj+35s{7=@a(*I0Ea3ku%bZ&d;9%A>9t5n6AdoS0BHDk2a9M*VHgS~4dl zYLG9rB<%S1(5F=(!`O9PGs2k$AoH6l#zVeHt8}9NE3(xU?&A2P+&CC;Ej8gsiNF%> ze5LbLM}H;&A#3-`^k&5!rp-ey17U}#{2d>VlO97#$L*ge*2`VujAJ)ou9UE-%_~doieX^&rQm*M& z7h9$BZS5%?U{prBHBdIutNph^M?(_7z_sZ4TUD+XAgR)u>aqK{(c@I>+Q_k=yL?dO zvJ0KsGhK2Ifq|~4`LN?=tGSOQ3tWG22rjZuUqe&7?Pf}gLBL!GLYrC9E7|de>bww< zt9^+?a1-}75T!RojCB@2$av9*NKn0Itk1!y&30$%Xw_zS4efp%zm`!|$rAW)+x-{qK!v!hI2dG7_I1A3D6a&0JS2P}< z3LH-FpjDkDh5g`t;F#GFik2oYq;ux{fbItEQX-zl^NpW>eM-vWOUfPTv`0o*O{XR= z4eK8*3WqlFs(Fs4cD2YVY^&4t@iPq_zM6BJsK1`3~{Gewi?a~s)rsdwXe>M1|lT_ z5X_;7+O7qO%XUs^bG$eSf81nGNn-Vt^b}E26OGAC{4d$ zWaGlh9tPmi44djbjG#hz>YW1iG2p<=$7`8?4j8O2e2m1k_t;@5R;uzgQf}P94IxL> z-D`BoBQHf8v9PCy+F__u2T|~ld4FdZ$ut5a-=o-tb!`$Bu9aJ&t4ofJY!JFLm!tk* zu@lwn1%O$hq<$OhXlp`+m{mI+Rll~VQ@1?FX{HxgilR2Fz+K#VyfOS;5Q<`xe1%E` zPXlPBhK9IZw=$iI{Uj68W*sQq`p7Gzwu`D7(T zS6T3KFB!DlJw!+6YsGtE!iHN<>)J^$YF~lGi$(KnS=yJ~?vj4)uJQ#~HPl;x!#xhu zW}0yg)B>1RPVGVt1~kk#^t)r%f!y1vDyv?Qr->f|@>&IGU2>nSgHeay0w3>4n<)%1 zWoTf?-q%MQee!lihqgtd6A5gHpizcq#&0`Yn~aKcX@+%D{V6i;_(2dVg#dZ+yY;Qi zUC>Pb2{AJoERBuL;reP@dZKn;x>Qzx>u^t$2J{?P*I5YM{L)doV98gt_*0sle@Rbu zLB8YjXWZw|!{A2!$8fiRuLK2GB5IKGl9@3&QO3TPa#2Ri#H2aw-=~3v1ns%JLp^_}v6t0quamHGG0jcs**d3}PPVrzbG)^k$^=|= z^#vvUAZtx(UP%#mffyQUAu<~;GG1sASKR@}SDHeK0VlpnL{8%PDdbn1Uvl8HZ%8o! zDl20|!0rW40LtjL6vVU=Cb+A5J|B5c(oV9#!k&C`6L$!)cnD}K88)u7nu-PRo=)U4 zQZ;tmTl>5>fZQ_5jq4ftl8QY~2L41}Rfe*5MD%=xVC+Lx2nD}-dvP1V=t1uTJb}mu z^vzUw0%fQ$z8(8BCaB$4U}SpS!s`~z(I33XSC_(OiAsll3^p`bsr?>ARs67=B>9Rm zO4{f2MRd+;1g84Dvp+O@8`3^}<9 zpIL-2cG*@<6gw*UUFlO#6duSh7Q4ot>S;cKf%qi?GEAT8R}ve^O0c?HUey zo{T>l*%}oM91#H)@Z|{7Q)qvlD>vbq;L^z1(0vlXS>K&`02Z zjcWVX$5JPscCmtwmt!xsz7<8H!Zh?NB`EuFgpY>u6q37uE}qH_p&tJT?~C;gsEH)@ z7O$XZ6J9qKB!mD+LlkB5l&p!xbV>- z9NWc#{na$DHFyj<_Jc2P(|0~ZKsfoMgHt@6Ql5tk8xxJ2@Q)R5t;WB#QYxZHgAr)b zS0kj^EW5 zV$tb><2Q$5t9DM8hIv^`iSor#OnMj}Azurx&6H+IGw`}J+A}3TdX_D#2B1(XAIb8f zFL(xMh^D5`Wy;_@W@n!RsKF~AU>^t-8vN^1DVD7N%6(p_mG4F`&-h!U22{fdI}gv6 z!wVnLP&g-b8Op9nA-gmm)9B59pcEILs>16$I8~ub3&oqf$nENIkz&>)%=c2|l9*fk zr1^fscH)*9+i@@E1vQ^R*qITQOh=3&ef|J_qKF$drZ%7&ta~Hk7cL}GDlIZA;YTIt zZZ!_O4;QGAIM9w|2b`km*d&)1Ul_!4hB*l~ptfFQbw`_YtoUNRb12NC+KIlWB`$0z z8Ip2vUIjsey=BRiI&$htQGD>_A1;7o_sACfw($PKtTA zNr6i*Y~m~dI7`$VkN|1Glf8%33^v5}7vaP*-qImBzPs@scpr};t5IfyteLzgER)8; zbg0Gea|zAWvo1u=}_{djXBq(gf!=5nUD5mjvIN;HN%Oom&Uv~ zA%7Kt!Z8SbXA(zBP%69IMp;fcuUWgpmjxCDYh=9|XzX{0pdtm#oGR32h$+j2?D#FJx4k7d& zlqGL+QI8vT>lNCEXrizBo(#sow#K{94whq$v0su*E+Z&H$iR;7m7qEcLSQSgF55rV zfEQjM3DXZhrysr>X1DSQn3CqpUBTF9h?a5CNgSJA4#e#JqiaB6ks=zURh1wt)vqhp zO#`79i;Q6TkAwU>;O;N%dxW0Mcf$5>t}hjGl~ZDd?$^{}vTy7GNBadYX2fR*Pr`g= zxJW?<`dr|ocv%BUlvgpF!hNRgN2~io@!5+9@0_+}rrS}(ue;;pyRJ1zFyF!Zo39y^ z$j4&{aHeHSM7Dg?s~je=LreyI)D6A24jo2ZJ=B}7Y@3Bw2b*sqr-SDrErD%^+xp;B z1O&?_U@7mgx^=p+GQ~}Z9ziB^-3;oMKYlkG+TSeCaLV))U3bXWD=Y_a%?nkd^D&&^UwLH?vvmPIpV6Pj7IyYUnXydB z6~kjkYoSeF0{V0+bxZ1AS9?}o337iJ34?Ob2OLKjxJ>eo&R>N$MNU(B$PlyZ(35*# zDXo5@E;rI3b2#1p8FyxeB6y9epM`}~0CupQa-=?dT!pCC4W+{-m2gypri60Cf{p;yDHPeZ>8=97;|Q(C zLzr{fb~4{#kTUXDoLrreJE2{~wH5S4lrF$)tsY09kFi^n5P)Ie3IXZX9AlTXAe322%t{#xsY6jsXJ8VPB43sZp$=l*I1QFpc;OOVMEs$)1R09H& z?6D66xcFndLeI0s0RKK1Uq1_op&?F`Ps~G>AV0{{P{r;;-np-YnXu7>WcpIW`%?s8 zjF%dfLJhYYPv`t89A^kyLNN(zJ5&TVA2N(DixP(57%AC{r`0a{lat`yaIy#9;!fhB z#B3PKp2VWZ3rHRh?fGqUMPdu7(xhgFRXto$?tIUV1wR!&PQBlFPBhuvPvrnt+sSsw zHdvi)H|kyH@MaaRe;Pd*4pATR%Ms5?}`arNS``t>~TCcpGa-izl8GrN_8RKs8G+3JLDjgK)yAYOa% z+*{s}hnLikij&4-sl6`@sNC1Q&f(K(qkNTlmM>IqFB;O!1`SQJUQDc&A9T*g{AEo6tuO$cuHo||WrVp^kqhyIuzJC!zZMTNzrF2AX2ysBI z0WH`EUme;FR-;MSBLuj6Aq?I}bvUa< z3Z+3dvk3mHO@Ue=^bHXR`MdwR?Jh@&1jGp8@VVKOD2}GNhZD(Ofd#kUa_4)pYZ@7` zx1L828a1jiZ|k32nA(T6yjv$>u@`E1+3$cbC$2a@XEmrX{)0s%iZCriv4u$oV)YfI2JaecwtRexq8I-s~qL>a7+vuN3ZK26eA{ zaMH^{nz|sJ+4W851Pi(+=3f=)DzzstktG5kvB03JP%__>;R|*_tyGvDz`%FT%~Xp= zJH~>#OJP=&3iFBax574Ex}Un8gsPZzAJGn%n8mq22rz>*dpOs1#T)rtDk#@l6pR)c zNTt>uzZ*KXE9Mnlq7u*Qy{IY05N?{lJMEd6zXogI7)W@Tto`|Kap z4O^z&giv0wgNkx*&ozK{_IPRgWbtbMnrGA=s@vDLy{3?QPH_HN6w9ILZT12Jz;*e=iLp+aJ&K2|^8Yz}`` z(-b!tL^-V>7WGJV`q|)}H~Vcuhy#JU&Lz25Qw&vqPO<40z{K^Hohv#$3FKlc`d(Mk zTQI?{o+0?o$)K7I04f}u1?s9UAL#XHk?`%_i`APIPWvJIQ4SpMs=u%^B&OVU&MSjp zqDK1yZqZl@bZV8td&9EQdSB7tdO!KXm6rfe0~dJ(LCzPhT*hCj2uqVm5_#{GME-Ux zitf%jUxo(AGv&@K|7K7#58O3c44fccl7qDdt25&6s)vsmx9&PUT`Nzg61nlIhH5|$ z^r+nRq-S2xam=|CP>gulK4*(cr?R}k{ix=i_C#k+|BJl04xbPq<;YT(M{KXV&4HP` zYnT=Yv(H~|X?>gMxtwRctS;aPz6q9;(^TCX&kySJ^7Kd^U7Np+D?p#4^We^BU@>a^ zGK2dD*7%%^H?IWxP?8yV3em;W)!l;B-faAC1TkkmovQ(b1<^(q+IJ0w4F>ovecbHY zI6wE=E5)MNMhc(i(Xtql>6T2sm^XYZgYDKDmp)hLMX$53nHX#kuSe}ABQ+`HW9zdy z@-{6&{v3_!Gt!QF&2+WNu9Fi8(b=8H0ZzA%>8I#WC?i3(`$|Um-j2wmFU4I<0YLiz;NC^9MRyD}(VP0x6aJMGW+0MOq+xdPLwa_6W%@u<(uu}a#!+8km)PS9-9HZ=*_PH{1KR6I>d!XKEwZ_yK%Z_RPZu(3n!8? zuqg2fZRyN%sK-op+wJNt=6pgg$_TOCkE8Zq-6UJ9HKI4{FK#oC3|4jv!&SpA#jj6# zaiV(9%Y$==?&8w!5to#Q z*AUy~>tK2m8H8~0N_Ea`ZUp+f3(a_@g4ik-b@+H_*wh|=Sh--{d1_a=wdXdjRj%nq ziJ3)$RD%ZNo!uO7+HOn9n&_FNW|M?%`DGqJS=*)vK;qT$)T>`M!!7@+1cHnG=37!4 z-KK1(xGJwN`r!=%CosPNdGQrczM-DD3KGp40lswKliR6Lw`)hE9db?F0Wygj+<@(= zxSC0SN?yi%{N{P&JtAjy^fz?l4^u&u73HPkD&~E=Y+LuM4+{UHEZIquy3(p=80#W> zAq{9nE4e<0YuT&B1n8+$9^ayev&6As58gBo>!{~1u@@-UAcg1m?VF+=2))DF%^b`lwS6?ZA*;01_WqSFbDaUKSNd#=li43{` zz{0eKZgWtL6DmIyU?i45Ag!MYwGre|L{0@|(5g6tPr}z@l+k2s1%)ltI2N~ygqA2( z-w^eGx0M8??q)CC?bxIoJ%$b#(GS?&Zm9%%eiy?=Vt^77rX6J&8L)PCG4xnu1Ll0m z#j6)(?LBo=Dyke0jOgAkuXoj2g-2m23xClk=j(IaMK_wnAH_@afBURBapzuVT(P=+ zb5fR9FY5#v4CA&6()1iYUR0Fv(s{o4nT2=7dTEs5Yo&6Ayk*s~oPb%j&b4heju62r z3VPF_7h6I-aR^SIOLOpc{U{|YS3~s_`fc(Fn06+rKQ2o2y)Skyf>Xn-f=#(2!bJ67 z<4|Yl7ji%z(1GK2`-urb)c{sX!glY^hZNR)SLV{LF~L=Z`xG!1K@hXB%X2Ah3SOH% zJ9p+ie{<}ZSRu5*ekfVH)Ze$@BXxxQ5@JI)qaBaxFG~}rAZ+PUuO8upe{S6uHlT@4 z6CjgK)3Fk=^*XN$pRc%hb?BSaFW|1U6OA5!P5`;LIH`Ceo?8Zwl^NPDmKqSPFNB;C zj8+kwepy}^(4;epg5{O!9%eq>^9uj?^;;;KRozSdvJlS&Ha!rFnoB{hL_Ef(X_F|? zW0zXg1p}hMA+aD8@r>X=A0E~)!l@-Ns-ewk2erg&P&x&<WDST9=x zY0&neBbHIjYr|W~sso#Dv*C2;BvMuvNKBj$ua3%?{wS|1f4Lj0Ug)kfCm?w~w=Tp^ zU3_LJRlK2pDEVYGnrPJL)-hO?D6a7R|~co zdIbFb@qQPHkjs!|cvmZfm1+0UVYW@Mdw~eVS9rTfPW|hb7=L%NtEj+rbr*ouGJ@U= z#;@%HL3kX5kD=S-p5dtthzp>_gr?#C`=_L?&27Eo%CHYw2XmEOv+jG165p}iXM*qI zvGlapR}+p(IZsvhyFb-EDmJ2F(Uhi8aK}xLNTu3pQ;YI7`g;L8B@GBi7pZ_J`T7jD zPQ~o8t0u94k=D4NP?-Co#uy}%SDAyowz*~G_n>Smdu+E|BAs(guTzKQsOk=C^QKYGca_}3 zB2Cd?Pd#Uba#z};21ohosUz5WwMwD`QoW5*zwSu#zv&`SZ&rRz>LtgqIg%MG@DsK$ zHo_2+giWX^_$Z05*dmKht_u#1OMlx%>%R1H9*^B)5ukf z1mK!N)A@x}zIItg<=&8Zn81a_CLlMkd@sMZS_ZMqPFEJ6jm6$HXA+=JVJc~mOYw>n zGspi@KdRxJ+rXNa*?=Q@t<2s8%kezhtbu>&Hw1p-G>51@nfdeRCK6>l$tWifYRWUN z~Yl)6eUSeF`PM$J6A!r=crAtHZ8dEP>CzO<#JUaDobYC+9k6yRC2_yRVxv2Jut z6OX;i%xmzIz5pS zLVhEptrzLbC$S)$dcl5%GR+<3!k8v5KD*w`m{B(xS~~(97EfL~S0L2Nc%s;ar^P$&BOF}~Ri zXe6K&;j$uY#k=?HI(_$d|DwexY~Jv4#8!PTVtS0}4sO!-B_HHPb{O!oKy!fk`xFRL zN+znSYknr*lmRgY^JJXb8{3UXIrjlhOUaw;-|D#fNN{pDCuQQuiRlQ_juWn#K~D?~e0QNV~&& zY-4P%LA(behbrW3nq5$_q)U`<^Th452cmqYV`eh}|H_Z?u04FF%_+%rdVk|E{fbr6Sfa8d^W%2T;jdUKAO? za59b&3$n(=*aGK#=JgkQ1b5920faI=+Wpyqayrl95>86szVrc)ex-6m1?T$y=j);; zgPPB3*s)01qJaNTPKt{LyVQQ1H~o6mQmLcf^ z0S#%=Vz;;-XEcN*Q-U(}f7*&DA&24l=B3W&<(TY9SqDO36`qpW44-OLd7}4RrRZW?`YHNQ83g zRpgz!P6|Xxi1As^(zP#pe8`}3;LxEfx0;k0`xtyTz`J>MP36AVUO?wzX%Zfp$`2*4 zXY+>#T!brP5V=P78-me8TfN8S9>S3+F3}mUYkXq3MMZrsw@UIXF1Ogfbz*^1t*}b;djhZmIJSCW0S*8(#m|eEmQpm?a=hOIi zs(l7Kd$qG@1A1ba<)Zyg6~HCGX2UDp(-WhMd;ZRkER|1pf6dm+Gk+ujLV2J6_9{@a z0k*?T&Ku|T@v#tbM>hk&htkXy#TzRtoi54aw?(s6wPLRI>!BVvlRDGQ>&uvjYV1eD zvw)VBr+Bozy^X8F;v-`Cfx&=(qpI!fm}36{HA%ZK1#;_Wd&=&cLmh^^cy^Y!VVIs& zK~3cL2W|eQTa4&i)^(K-)Qyl31RM5*KjLkg5edk;!(E<%icAS! z|1Y+0FKVCmM-BTg_q=+!@8YtkVdg`_eSNxj;IC10OWD)e-HCHadz*TD<2#7|xZdLO zW@Xvz@(DJ-rpVrdd+?Jgt!eH-{w-Fwt>PNZ>o8Dr8I!N!Qd@o2&uiA@w*H>V$GR1j z|7_u{&1s~p6!;I8?XbM9oO`D2&f>G)mqnz0cW{VTs}aD*LnP@YREJ4^OZ-4t&_!dCX=4Pu}Cl$ffrVG+Ik6^vh7yjoCL8h7<%;4dD;BK=TDm^o)9qFK7wtcKC&YV7># z6DL(gzbTlci0&U9>}*WZ$e4)g_`kRee{-e}F!CG+aR*t+(U31u&jscf5OJU{sx<f;g|KO$(p}FwtXS{jR0^`D5X$ z5UF=Rw>kQ^uK0InfWCzhA45qYf9mExs-1!u6R_n1zZ-fW=$jtDv&2HQVt%s(+uJdy z!-$qTE^+&-@rF?@b8a$bIWG#d)ut+KSOQLW*+7B0v)LV|yy;HRR1m^acqydv>5+H} zfD=JI1`Q@)97X$fC?JY%0g-U%{c0un{cxx+H{)Fs8O{4C+nd!NDL60_m=@yFMJ!tG z=+xSM{xk%blB1#oX#TLlnHkj)Ks(bHaM^s7QCRuL@xpPid%v(066)qg*eQg=V73xG z^>7LnR;rX;{?SJK<%yea<1W88I4GLIX6&94EuG1>2!mnFn)Ijs9+MohRvG1dX*Gra zC)4P!Az+kBn69*WF1s^2j7q82?;fBXcOlM;d8nU#p4DsqHiy79UCCSvs87WgM#Pe5 zNrLs4KXc{8G$jPfO`28eGD;Uj>}Vzt})2HGaamhZ<(#6(PC@(b_%Kp7U%-? zM>%oIotin1y&?ZlGGX0|RJ&(u?CJf9ldCEL?jQI^AAg$meE$XX00MMU#PLKjI?052 z77bSaPah?qP7u7IjC$hP-nJ92_=cNQvKc zEDz>D=m&kk$!E8hxo{T+`c#q`u%KD$ z(d_TSL$&=5>P`B znv3Wh^AG);28ju?mMyPglLBY2x6*fSrJiq0iw~tTc>6+|m$L}H9zw~ZxUWJ2C`85g zr$LqzXebR5C~ev8649=JR=jz=IJ}28U#ior<2)yqB|ghsuHvj@IR)JG!sl`Y&nKTV zFJKbm|5JPx7W7-GehGA%JTt!fKXww3A{U6G+E!XQ_3u29b6Uu%Uq9fS=E0N4+)w@@o(i2OPPuq1w!K4h?m4rjv2}<|V39={P>#zY?dX5k zMd+b1j6%YgXOpl-`AJlljjm?EP{{cQk`$)Y67;x|^EGnrY(S`%o{@7--dt4U_%Tj5 z?w3skHR)^sjgk1&dHxXiaU;Q#r^!*Cxw}?ky*q5G>o>EwJ*l1+mkQkO(tBZ>9)&w~ zYN@3Gv7Xo>7|Z>K3n13sQE96t1HWOaWO|CB#ps8qps!>4pC#1J6rUj+9h>K}8kYr@ z)FD~1v+NyKr)8O}90Z?LCX|Zp0802yW+}bFLT5{xW5=7<4dr3?V?k$9G+3uAJ%mZUu&(1Fl;4R;x?CT~=eeN^jq|6<8SC-_O)x^K~-_m#=iZu`#!&54J0 z6Cm$46Xn>7Fe|^mHsxrp7J6I*v;>5Ewe4A*+ZIea2w2D%5>Kw2LuZrle?ZyWrclO1 zU_~l9ZL9A}Y0+TKJ8!}Q5Ub6FC{(FsA!pCQ5zh8%4Lhn$X~UbsBg)j@k*l4=BOfVJ zgKbV`mpNHKe^DNjeQ)sM{WoIvx9zP&Be{O2kjXIbSV&u-Y>@daIdTUDxM>%0eN>Lm=;!?9NTXbODSJ zs#Nvg1`Y_}ab8F(4$X0N0+r2>a$CoCvx+bggHAIoqBN{B~Np5DBB`o?Bus~Jk2+f`ovp8D=c_RLavci#;IHy$${XV1)D9<{40Ac z>_~-|Kg0AUp$*;R8l0?H#P2e+al2cW?jsSU92&(yps8&vk&tkMo5|M)>1i9Vcb0H8OvGt7fnICd2+|en&^;K*?kD z>OzhkQu5{F6T2Lrd+-4}QFGGR+633DV#f;A*JQ5odzV@@$a2YELia+6^-PyA5Z&j zO6ZIuqEk1j@@pqKyEIKqbh(Qk8%#~aS9^@bLD;rrXLY+?&ySs4>HH7}t4jHI$E5r`62i(FyUF^Y zms!sACU(U}uS`yCqZw?Hp73;38R>xTfD-*-|1~01KUs(w!SxrVTLQ6_K|o5q7F9); z0T7yag7wEg(s36YF{=xnSLf3F=RFgnCV}oho>gxO6Ur%4yUTl!PBmXc46J1M9LDJD zepF#ld)pL5vgumLSciz*=T7u=uH6`;xFNVCupi~MRDJ%5lc!_GIV&9+#-{gQPDVV2 z z@sr@#s*-l7X-;Q7XGFmeRq9}BURPL94h4C%fri=l8Y{J2R-PPlhJ3B}Wt`PKkyZHM zz>YllFDcz;@w4Fk%bSv;GnNdAZy0ZfVCB07(AMez*Wb?JpH3sak#LuDMV*Uw9C#V1 z)u>S5+;q(BWlO z2@85zEVFe!FfIf1aRpZsemK^L_2it2+{21ksR(78N&li2XV*88yCzkRA2 z@aG&d^{{!SvB99)wrB%pjPHDRo|EKWyu%P_bdAOTNl(P)K_Sf33Gl5%7^%p zP3iRPiiuAfLqhp82SwiOdT^ISZvQe{gMnT&jt2ZJ|0*jO2*w>Gfl-t%UCDF^r}zvw z%f~}pMVE^%{6~G8@YlSMhm<1D-m*s@xkZmgWn&u(}PiZ!xEP@E;hls?VfBjOi>C@*q3FRAxRus zSZjY+!Y9{&Vri6u!?jK&1ND-7YkuF2QP@BSf0rFt*MF(b?^7okQ8cWRY90DVRmc!C z;*x--(zgfqKsGryAK!0#=pB&zw_7ek6BrQ{x9C*viyY~@>4Kju#McnfWpgEk^B zl%8vMGTn7*&aaHcATSyS$8fLNV*0{0_`Jpp~`XpcrL%+1$q(#helWFPqXeTMc}9FQeqU~*3aUOBF^bbdPRZ7OdG+% z^gYwt#Yi?YeFB%tfQCu(vBHcT;P;OE7}W&NEI#97&Y~-zhseAxWSS03GupN9ltvT} zY5l8fzjbOK5d;3|h72an6%L%#svN91Z;rR6X~j*vq~BllbMWrG3$NCxO2_dd3$Xjd zI)0wftoFU0Insc{w8#oiDAr!vHgMx4ir@IDe){Q~Q1zFQ!&QJc*4i2TcbVxw&dJw5 zm9g82h#C7!A*Qz1%~2YWMCE4Wm8N+AR{l@4w-fjgRKbZ59h-*2uwy;s7d6}Qa%Vr2%C{?}_+)@%eC!kC#y8w-u zKbw93*UR{=u;z#qaBqC^AE87%o(QwXp4x=-{av}P1A>2bOLo>C(m8(t3kzvA)%ZUX zhl2QWm(k_~l$DAhi-Y`;fuVb$COh>Ll^x{hx+Um(e1NT0p;&TAOY%lUiA8~|hTzic2vmwb7_)IGj~a&d%e?}Jr|m&x^^t5MM{8lPMFmiYUr z<~5YR3oi);!-u@3q)!0e%QZTtULUopu?dBJ+<@9Ptds4Q(8 z*zELdX%fDw;cdY}ev*Kuq}++*j9TJz!9U3+d}IK#fs$YFpMLItZ=oHcYyWG$a-!d# z{ajIz+4D;OK6gGwb%VY*sV-c~o36bU>uxn@&>E;_TT%n}3B!+{#D(c|r4xn@BWMOo zu=u$_4ONxBP2Q9ha$u+-?T2mCO^YtTAgL2(%-$42D{Sj>=1irpPQt3^?>GvMIhgY_horpDRU@`Hxrm=LeAg1$TeE zT$cJHH<$z%wdo=ri@Xls@@hiBB`~=aa!j6;$1V*%g}7j$-=|zdiAD)RZOR5rW}XMg zmcIS;bCb&pxX<98gXOOO9r^-d=$yskooyy!AA^@9`nvL57nkaiOdOzU@1Sb zpr^L|R;Rjv>#?iFdDHF@78mC+Zug4+YWgl3?6w4325`jxd(gOuj2jeG(;@7j3kIsb zYP0v%Gq;P-*pILbdzv8Dh=~Bbda#j)Q+OP26G%(tnL$a$bh1oX`~{5JgB#lg5wt;G zpZt@8`TOY$d|)NQ=*`~#`HY7No?LS;hY<}{io;Mv)wlVfrTB2FY&}jzw10%ei22~j zI5|phs_=8>?XS_fj+}F#IrDPhB+~z}8Kl70^xK&g{(0&mLOS&5g%zcvwE?FHf`)Bm zUijBGcr+*;{I&FbJ++5y%Wbrvso|^OL0jMLHBgnqiG(NrBXfTD5#4bmNa9AoB_lLQ z^LSv-cFhTcr!%TyrIs&i9UE8^pO(k}u(5!>yA)Tg@xDik=hAe{*k$%spl8x+`oZd2 za0h^1Uy<@*{8`3-zJu#Tz)mKUmi}H`eAy2`++e(!+C^n7jLT-NHGb2`F3e&3rqy;| zt)luJYaGC}p(PIbr{)Ls^0$a6@s`Zt?*HzVDwsb?{eChJVqE}w?q4rvC&fwG{tEWJ zVUcjc<8kc$1Je_ea`4oPaz~|dw_UKTPxb_*%gMEBMhx6107f~t)%oLp-3ebXPMrNE zM>yhT3(N@7GPZ$*B@L)ii<}tf)H@GFqj@STeYf;@!Q%fo4%WbNfRYoj{OM4QNGR9WZc^0LrxFmkMjO1YLEAN@ zTDJz&AKMK+4{dP<^g9$Yn%N4%w7!n261%ySheB-d<9%C0<3Y#_*k*0qm{Yf z1?+qFZcaqKn(m(2YrOm zGzN}T$@nDPlqV${3d>L0?PXqQSPZOjp!gHsH0G9OnjX#+^WH5HcJv{2Rb)|FU({Xy zzoFFcbNK(mAN+X#-D_Y3iQ2OsgoqUBz!{~EHR)8M+ZoWE8mjG=+HKw^6gE#o39vJurN zg;k69D>-@;;}(XC!@zj8leIzyFI&-J!m%;6<@SDk!YA9F9k3*%wB&!J^FQDB|8s8& z_!R~fP~+8cA)&BrTd1Q+8G{zd)4NDNNCsRDD)p#DOLdIal3&c1Ucv$dBHx`!>pUOx zE3BvFMLh;P%4q1CUwc@bc%hKG%h9k~UJ*olQ3~$Gy3r#D3;Z8%PqqaS095}~hW~q_ zVm-jr#Ymq3hN#8{-W~C@dxi+WdUmr zQa5iBy=yZ`aP1RmSx7SK|85pYcplS~2(16!EJMU*#nyA*pv6{3lefClJ*!AD3w^kx zSNb-6zRt$$+Y5|YccDd__~0Pmtv}i|TP%lt&P#Z&FfmE0o`=&%vXcH@^^9mnvO;1dfq6CO^WU{riQ1xEn>>z-=H2vHCLz z4}sA>5Iz#zd>?b9o=ehvrI6+GW%C&!Qyj$qY`<(zp7lqA;zBi(gA7?T@oZ#i$@>#Y zN$1LZTlS{~0ksKSck?BS_`VHHeSoogc|0Xq>6~WM62JcY(D~wFc`=cho_b@|MfxXX z`1`w<7{c6av^q}xHa7xbQ1+3Xj^P1VeY*R~QWi34UG_Cp%w$&S%97RZWCpLA8$E)` zvY40e+$cR!%%qEqw2;K7!~7&0xY6nx#HqI2@nYzGZA6>o@?8Ra?hZ5-VrgD>CzH_! zI&!Gg8y)C0WN2;}FR20*2W11L&2t(eU)Cok?l$GrI||0(nUa%o%|F<)?*DQXW9ZeIMfM=Sx2m~lBW@^QypCrRA$>t<1WpTfCq=wCc$ z4G|4WU503FHuH?sCpITLBFt0s&HisLq&>;t(QO=`ED)7L+1MhYDv1BRkb zr>~d&6NRINylXr#M;nf71i_pBd1WygD!h18Ul#Ft2~3R9fF(GGp}QMH*!5-m+0NU+ zc9VecP7{?B3(vHd61&B`b5K)-W2?8effJPG4Nt5?k|q-<4M`+%Qa_UgY4B#`P#1-J zoLr3y6gIooo>zPD`nV-bZe9mp_~hGdGE^KasE8QIBu?Ct5 zidcEyJATSwNG6L$TgOXB!}7_VFZokF%|#&nY;7ESqGTMYA`@pf*L5pnpmOcb>~0SE z=ZlU2*`y}9rjf-0u|@%jV`;Bw+^?1`hM|#@#WmwKA2w}7LIn8O*I3dT*qhGsU3hkl zh_TS%I+bd8|5*l9c|x%AKVjTp<pOl;J+u6+J?d{c#OmAI>*UveORE1K&iEXe)3Kwp|rbYE#CJS$F7trOJ zy|%Cqf^fdtYLOu`3Z5Uf}i z;0xDfoa-J|jY?md3{>Y&`j15He7xO{=WW(XL6_wMuyXm%9d-Z64|rW39=Om_67dUT zE+DhreBobu7k(x%jdynRbzQC{vWbuRrss|21dgXC8q@D`ybjPx|BX(5N~ z+aP`G=I#9$NJqzFCYA<2k2zD^H)AjQA)m)oBCbLOiQCsW=@3J3ZE%*}DV3+-^?HsWJKh_9Fz*8stknVq%bG2`XM&jj?a zcC6f-*VcW1X^!b_&R_k)7HsODJ2IR<+m%SN?IpQ%c7M;HYJ1V8E%W!*f;|>{1=ggE zY>5v%vr9`XJ=Mkv9c!9`yrPz3%f#e{pIWqe&!UJYnY;qVbFol#lH;2h7P`4NVm^0q zK2Up{nd35Z^ZB@LPwEC^G}yW!1M@#hvqD3oI`}#G4R}e*Qw)sJ+|LRP&K=*%I0rdc z+xMtEp4WIH2uQitqcy7GhujjWGuer&QT#ltL_`dJH z3CHo;e37(DeC_O>O#`N}q4)nkjcMYOk7b-PYs(9f-Ql5@9w#qL3R{noY%jl?+lj(u zlmaFNC&6{%rh3c9e=jd$os*5k(swaw!M6H!gF!PbCx2rHvN+Iw(4OtOM9s9^5_x`H zx6D%5C_NTxVy&1NO2#@xmh<9u!|7$3wVm0T0xCR_SKIC1NB#mvbA4Jb7LP`Zh7HNj zUH3Ynb>yhCgF>YK!Pw7)`5RcdiOC0s%Q+RCw$ojqFK#+SIrH|H0WvpVHovUPIy8z2 zcUSWf{znMFrP5%_-04|%QS%{~DwLwvJM2KH^}GR7-2_v&E59 z!^50V9XOjPv2J6eVWZOjYwz0sncl-VU%bvxnJ%Q1#mX&IDn)4}aw(Quskxk^(Us#! zb4mGjF2!=s3(aMERg5xAh1JkGET?2%hh#cbQk>c7Mjfi1=R0is6V4C$$)4Be^Ld`n z^L{_?=h^mp?JK2Erbnd3vgUaAzGnp2*N-JG*0;5S^6B`?e2}O_YkCr?*JLZkm~5yd zFTT)v7^yhI+YmEBDcDO%Gc9uDEWJJ2)tzUto$dJJ#G89B*|8?PXIi!$HF0JdqEn@F z%%}s?YVgA=DPU}2}5IMN^j=C0ZZ(mHTWvR0N&k5U2u zZF4Ss6KNQ5?ySxxBg={-jL55dB1_l;O2g|%!wHzAh6)`f;ep51ksL&c`xe0cTh$_C zD6qqDM~ReR}t3iMHM&w38PR? zKnzBqbwHuROQMz{z0eNtRM*%l5yJ#bJNlznW2Uuw_%gezH!?`$;9tBShC=yyb)e$W zl51QbP{ze1(&k%f8+6bSK%-aqG+#+=GQni>wk{7dErKj9_6cw$B!K^MEBK&s<~)=F z@z$O24}|kwcY%WJ+fi_qL<6rQV#!X0(lok)Df1IWW=e%UsjQX63?BHO)U(8%l|B_8 zsS=h^94f5g_2m@+@O6_mC#C~Sy||(59fOW0Hs~JgUi|rq1!klI4GJNVO19BDbZ0MGm%1JPpE~q<^dakvA!7| zD>HMAj0%YNNn1G`;$=a$eTL7y#}9dun0K9!=BfUslKresy23Klxtc4^)Y)_3}=oP7HqHP-LIE! zefm5Zd|t@o)s8%{jS8cBZF(y{O8f2xaHddG{PZcE796*ttx}wPzql~f$41bUE zSSMb7wx7&GP!}yl5cLT-Ux3WGQ$g22DAe)5$JmG%~> zMH0yg?&xIp5H}w>o(=O)cym8<$*NQk&rq3osxN}7Tf8m6g{cC|Rd@Lt%YDM!ke)RW zDBC3g_Yw)kjbI0>B9{2+$XB6ZNFO=!^??O4%bVTa0!R`AqSsMVtXZRxqSaaaz0L4_ndVn*@7za za$N%15<4?7@?7miSI@(h@}yz4^#n?_(jnwDAa%hQ@^z&{L?lClNtN9{=35*X#sB4yRsIa!YW7 zomt1C%)sjbV3DATW4d~8oqbm4;J8nfFk8;(f@eiG@SDWzYtfqKH+JPL z*l8-%JBxLT-@xlEMmZ6&f&^H-pt#IX>09c)rS2Q+{?`TD)#ltPUEY6&Zaf}r#2KBf zyXRTYyD)2|_lQZ21JIPRt8dSPvVWi#>&N`sb1pxT$|x%$u@GB*mx93ac|uFF&6ok% zPA(*(pcX!+RqM#bT*NR>1?6b_o@R~nKgKyFimM_NLr+p;1k5HhkFG>) zBzc~Ld?6*qY`k=_SbP>vcs!JwnCsFS6gEIFMKS%6HCh#vg$FOr48tt28Q?ysjm>i3 z4UI8WuR9^C$)Vo6Y#oa%fRdx_bzb znqdfOhIsE$_uf9ocYJ@}AMf$_V|2-yweGm`JkOhsM9Qp0%6HdEliuG@K6(A7<~89< zLUKaa!N;}h0-|Cf??dx130=Bz*C&Ql8UcXUSNYg@wfaJjvYa_j9ga6BQ9f z-6M;-d(`5wsXcgygXv={o3KLF4b=DhYv-X-Pyc=r5>AqPx8*cFjTSL9)mqaB&8x<1 zQao9=kI;V(zub7|;R{)wS699{%X87b98LXNb0MoDos#JS{eAV8+#9Euq93Meo)xy1 zIUMxpm%zJ95aLQZhJ6xiwsxfo2H$t+`Q*)c74#cfL4zoNUe){e@4xD1gprVv6F!Dr{;VTMjFXXYt9c#N+><9^y~5rwF&qc`JbQBc`|aUZ9VyX;mAK) z4L0L06>;_dZ|(-;ubn4j%CwqwdDw5uUJ>@r`7AAGCfI&C%vvxjacFeTWL^)!A2Kmp z%Fsv_U`49HiV{uu-U8cUp?N?`wqdg5q44IHiA`z%+v7g-n(LPZ(~*Nq=_o?H`k(9V zQ^0Czn!f*8kfROYnqk)8s_)N#P|HwI_xS}B-Tb`}uxsEluyTS$9#;|j)OLN8tdk?T6wvDqfndAr7#!*Bh4yvMkg z`-I=ta7u^_)?QU0O({}z<5EmJ8;-wx>`|xeq3@8g7hIsq58s~?`G!Mw+VZGSMsL6Fr)@IuWvNX73Wue-c&cq4rd_$X= z*2oaM_qhD34kNz}EyBj2F&+#pB(}B*JNDz4E+I!QkaBa_Dp7pmF?=A;U@ne3Ww`pl z|2v{`aa|;3ZBobB&*E@*u+DzC*us4_+G?bk1B#2+T08qIqg(WmNx*Pu zsbn(~ zPI2u83;1ZJB^+hh9&;y7*e^+-j)Ly=Q0l#~+y~J&j!ziP)7B8@E?yUpDRVG*KG)#d zDLp8&^W$XIT!K&Bnq~7_w*CB=ndARdJmlZiAdnl5dCjIQneMm0`K;Qh zZodrfy^wYs?x%qCzAg6dTT3n!;ZT8sReO?@jSWB;ABlOHGi33ySk zp^Lc@gPb6py?wIe8GYUCd7g3IIFDxLJ3Ai#4zAU+nO0AAaWw9RtU+%B-?I*}fBxJunT=-x~?9Gxv`4k2w z%i}fLNifpZFmBa0PWR<;eA|sT;EmZX$CcV~kZP*3co(jSz2eIEbV}0}b zXr;@ZRdXO1CCr>c*wq^vulCy9nt+0&IoPB;yEd06oWPm}FE+^!%+5)LUO}QQ)$P(N zmM%V4inw#)+E=7^#hOW~@*|hUyFa5$;QtH_R!qy7$&E{}Fr?v5iuTN=IG8v*7<8;& zRmgB$5Jp)-F~{wgInlALa^? zdIXlC3~a`i1p^Ekk!LrUpFY}-NspO8BcP?R%JgU`M0zu7f2EP3L-cU@@St0z9<5#Nx&7{VIcFkyC97e@&3CGL36{*eS_I--Kd#jTnnT?(~vu?dd zsRJ$v{J-!B)v=q)5E^y2bMgwXbrh|1*pDA!s_x@vB9g|k2GyQLYyP7ZE@nR8UvkGK zR`FlD^hLb+a2Yyu?NH{1;+z9E7KeKmsv@dD*odEC?z?4|iSu|pUgMLoikKL!NjNgb z+!-U%T3MLw5`IPf(?a<`!CK{#Hm#04W?8pXy8lvSa)+I_W01dbx@$X6~F$c7MS)@?AFhy4K9LccWv|Can?t9j*_@(p{sWjtpkF+xs=iH*ZVD zU1w8^`fCj;oK0hv7nVr2^mt>sWt=Brb3^^hH+f=b*-^Vt`GV)S#i6ZzhBwUrx+V4P z+aQcw2+k!(#?fhJJ^Zo*OJi`~!1lY!c;co)?z}#YkQu`@#@ISxkJQL$@)!;ViTIK9 zQ7M&|LN>ikG<568wNG?{ZnxUR#yuNpUT;h(a|HCCYU91FHJ``uRBX&S@TBn5f%B@e z+3Os-OpMm7`W`{Y*y2_YzzRhz+s@398hT$#3(yde{``=cR=?a4PmbNKy`|Z&&366K z)3sff>83Qtha8$4$Z{~4jvxdDRf@u!$F}Y{(AWz}f|OrUKEqFal~KZ0-638#0Xo=G zVO-``)2T0beUvs>D+P}FWWMCj*twXT`pcAe==(}#Po?52)aQSKe0H<>)|;~;ar@Kb zZze?^sIyQG^G-TDfOKZp8Y$>;%Li|Ozsq))mb>H-VQ<@%<)2OhZ;oLf&zOWULo#EM z*FLcwR%%I#&mDf$J3>aieO%3Y=YX&*$?S!AufqI{NgsPIY0ISM5c{!E;1ut==I{x) z?f^j%Y-0TD1PN&2!urQMuj5`P)Ak~gSE9_`x}ZO9$>gCF-(Tnue~438ga+Xr!y~13 z@ms|)B6bo;XN9@<#TKoWH&cVjAVj>Z8+*67!SZX`PaEvn2euDr)B4vrHELvWW9e(f z<4Q~`yv|xT^RLf;cdhl^iJM^x!0m7KX{aI+%#ybzGZMU8Du;MeoaZh-8`emF;Nrhj ztAqQ9Zo+MxOTy!lW6+s~*_u}~pk{WT+?urx$qsUo%7up5DKbQz8JqZHDAm=)=zNX9 zXY5w8s_cHBcpdJ0;gY#?>;w$n+`wWLH)Z&lxEOel|Ztp~^F95e2*qUE^>=GF`U zfEEmVo_xFeos7N$hKO}TJNv-s!Dn| zR4OmO^mgiNbAo?8=D|)w6(gfINMYE1dXNJCtd)l_wK*8?vY3##Zj?p$N@8na?BnYS z$KEe$aO;8K4G_<7q81STgU=K&7PB2O+BII!>LG~`OLxb|%VgB>re*QT;#L9Ijyeg| zpmBBQW;TzT$U;lYAiBQ&V6FWgnTHj*G!)4mg$o_z@N)xf2*+(a@X_r8NisK=PY#bG z%KbCCi_&LB)CPGa-z)Ak972ITGT z4)ZH7`6vCmbg0?9s|v^-Q-spejhPIxWjXE)*voh*cq@?6j`yFsZQWG<$&n&+iOQf| zMZ=3lkbj>_yZ@@r0+U~10Z7C#TI=}H!Ac6_avoe`0qYGrOSGl!Gf|2;^oEgzk+4FI zO2Oa*Yxo0dhuy;b;h^rLeIn54Vw`Koy|soBd|-eH#U~>&gy5guO)ihD8tvwjz-T3{ z%s*o`a;{~21A_})MvyAXY3))qVlTY2?6jLrUQ$t`^Vstd7to_5B@eyJnF4O=+wc!R zh)a@m7Ut4FUn(FIBuWuM8;5w?>!UJH2o^AZKED64s-{B%2l36-z%Oa{-9TSsRS^eq z5MjMpc0YXHv^}}K=2~u{ZbPk)fMZ`~xB8`9V^zMVO0d2-Bm03|%l6D;4iem1AM}Nf zATU{JYtQ_dyY2*brLzp6-z{BI+qy9joGUVIz^uM58Q{Ow9Sl7ixAi}QfG-Z(jitY4 zqAf?LD=@?RppVBhaZ7ZVhO|(7wB5B58~a`OeW5|jPoJr``#*M=I~D)I=a8QPPNCYi zuTT)C219q{#?Mpg%m-Z&@LXMGBdpNQukuXfF?*5`s9TF{IJ|Cc9?YdQEK+uwXt&o&2 zfkjV->1ojW!r!U?k6l5*r1!<;E;VYF@s-5sWj$zi#fkQuPJLgrdv|BSc#IWQK z|8V@8mpF4#&12$F(-K#`)}e&T6R{h(iKs`sH<&xQC9RiMr#XAMWT8ViJjF%uLDgJ( zSM>VQ&n0=y6qd{!zPDsncrN%EYKI%zSJ?!S=*S{l%!rNz11=ySp}W{=qE>jc&-}># zLDDSnoNLSDc@Q)DR(wzio5zJ)!eof8sP;wU-208zi?)tQ3Ej)`-_{Be-v68DUvdL1 z)RPd*&Ykr{=Ig?dEE&TfQ9sZA2ifZkBS+y1LMx}v&6mdPtb>ADQlw==&PXWVjn`{y z2@^k(vTy{^uc9-A|7SB22@Qg7Y!I5w0GUr_co=Y+q$PFJ>IGDR!zN7%SS?qCfbsmeAQO{-P1wIB5eiG-}lu}jx; zLhTlo>s|S0=4Chs>HB&)2;bHO|6cg3VBw<(Z;ZH;VHFI!v>%vK9Y;#8ZZz0VJueu+ z#l$Dn%H&4qROFM0gd)+7$^&`b(d}x3e6oJ^TPHKC5Vb63Uw$UvOGLO(*XWrXlI|nQXC~ z+0y4|1646pdN)e^AE5s6?d1InYO0^aM4mr|iIVSu=?E#fjrRsh^ooJ7PhkT$*M6;) zlz&5z=i5iRLfT6CSV?(!TA>^J8W@=e8m?*C&S*DX{*V(V&>QbaWk7-Zk4%sB@1@ z8m5v5I`)p$s!x52uWLC+l8{GZd#K+%XDCOEd5Q3r0nM zQt);{ZT^-sMR>CEoODgOO$6FDFXs!7nnz;k`|byil44n zOrEWshkfu!%@u0ymVdC3^tgP%FiWxkJPr4jhAqrn5uHF4R-1L|jpg^MH!$g)iM2E5 z|E%@JbP}ZZqa`u#_@`u3GV?j<+3XbqB{mwdk{V97l@{oN$ z*C3y*i1d&9Q(2#EC{~sND{c@NIo^u-ePb?9$Z7d@1?C(Z5Uimh{^cq~%5Et(HW7x& z(@2oHs2-J6c*m@TPi@fNwOu0dhQ+Hjq^>eY60c_F&DzQYThPF$ z)T?ExCHGA$G`zr;S%R3E2d6km%h%@=9_3yO$>-t6V;`5W- zYJ-)q&YxX`HywdI^0T7lhWF2F>Ay|J{~<8O@Z~6)wvh3K4&jGMOp*zlfupx^(Y$~P{mkFG_V9q< zFyED&UM$Kc;Z{gSK|8d)Ivu~Fz|4I?L>|*A!>g73K||vp!obnRzEQ+aO$YXo0m9P4 zHT{$HOKnwlNc$7CRz9-CI(|(tyCbyB^un65PT+;LWm;1%%ade=y*2%xcl^Q<&k;cn ztMn>?+$*8(rbB&qUmmft;S=Z|*|SWmuQ0c?yMfCvO4 z>p67W5|*WjebjwnhteU(|8!TdM?^Sm)<0$N-j#QHNtp)kH%wKhDlG5XX~&RhJo`W^ zCm-wRqw_U?1e)FL%4OKyC4hIt?`C@!_5(O|+Ly7zCMh4EEt-c-<-Mpi4+oIMoP7Fy zKWoaGQLuoHUy~SOXq8Tl@iOYn=jiRCOW_=DOq>;{GI^z_dE_JSp-7qSNPdHXXlVd| z*;$=Vxkc_5)gR=BDb5?I+O4&8w8PMP_n&%r1yW=evJ4i=F*a={;;n61ZCLJxbzVdV_p|i&Rd+yv=e_e8-vd+?2A_} zc-@9B%zJ{79(*RroB;w#gw8jqFa@U$_pCPlLN0WuHHpTj`Gz`M-rJ2c_ zdZ*nFkK50gU=Zdq5~`^IfixaAC-O$lwAv_V6-PR(U+y#bp(=4h@`+_IuiM}qa*S!x zj9U?W7TpVL2N7*X>#g#fR?RqnYsMPt?QoYQKXo5!_3|gBKV?0@-_KApW;T;VD+5UO z2l=VnSCYDd)cdJ3&i`uE8Qn-R;%RiXJR#pB=xES1(|7-{^#Hr))CUx4cc?`THRn4A z(sp*xdWQ-1w);7!Yp0)`jbY1|)jFajG+_NZmXY6qdE8wPxERi^PIIEXlA%kp@?F;) zWJ&(znah8m04Jjos1$TFDgL>Zu>UONhEBKJ%L>yI^%bvluob^ zfFM3ibDbG59^&Gxw~4pYD&7V&zCC8Q&hm?Co&}3~o!ct#&&^@Z5tI}@Z)ARx$26Y} z!K-F}*fSFEr8y2panhxr+bZn63kz)&9oWdYIQk2}cxRf6AHgs#EQ#!fMxG~?Bi;es zCbn>&YZMayqaYYxB-LNdhtF}e~zt`*$U0*(YH2p#JBiaF*zrM@KX!HaYpK=7qJFcNXDw2SZyT~I{ zE5GRvPG_?I9G!9idJcW#PCQppBxLdrDFjSx4;Uq(`;i_wqoOVH0?-t^Ws~GHuJyeq ztwI^}`?cQ4`{6vppPtd>fxjpJZIZwMV3&!~4R-LadQ;>LiD}v<2oY$%V{{Fn)-C**hK)|mC7D$ zA368ed>Oyq0&68te9=w5uGD)cS%t0N5t+WI-xFgzg9K<&(@43KlTxGreOnaEmA~FS z%*3hInSZW8o&=eCvSM?@4v)<#C@XUqy^I+;!}$BgDRN7wJ;s9T?%R@RA*%qepZ{%@ z9$0PH7sNLOQ7l!?v1j;u7Z}xCllwjFYh+vs!G+VF1WZ6 z*pz$RNt~u%UNMQ<_GPBBvL3nh`|EKqz@+4A=jjhXH9j8i{>O6D0Tsou?p9drhhEUguDaLnYh7%M7Ue`9VCm;kvqSh`TN0DV3&u(rx76hxRKTEZ^i<9 z>J)Vxi*hqFgZ-Y|)00>9OEUKXb>ZH2y%~D)|1<0JWZVg!ANh3)>$A0Tp40tanR|kT z*4-CyW0fesjeebbvf7jYwEJhxU>8AM#+Ce40@#cVIRJO9`1MN)S)Hn{+cbTK{hlK= z_cimcjH4wsVf3t`M=z2yhPs?G=e$YQDYX{t_wyS!7;44j(U|wYq93{TBmkmZuo=dH ztVD{KO#bsG@XqbyKrxc?r5H?foh(N?uNXjiLja16UN^IN^6S2a)7zV)PI+MI(yd-} zg>A-Og1RzUc!Xb{tGEgqn+2js$6bQmy`)$C9B{ zx&-}iS2aHoCFYcXac-n9^WAwYIU8jbYGWNt@#}}b@5lsU?{0h)J(%i8TCj%VL=w9S z!k3MnKv1u<{=P|=tnOepCmt{hqHgnQcB5td5`RsB^FKia%$c0%^?3efvHIOEB)vHac1EqF4M8+x4V|l!x$z=Vn(fojcJ)!cf1_>+R{56;Fx9uis zYoq}J>^>LoL21?%e1iB!P92KVf=2eswS;_rz2eV+g|h=ZVmZ^*ho5=0vdy7V+kT>* z=!RWZ&UIVpiQaS_DY4lcbL|`kBt+Z|L13?6`(27${_^D$aPZ>pEzbSBB*-Xg-<_Gr zj$j#zv*i>1RdCmK5$zJ|?!wV=lvN1PQ%=3e)h+r2h-b0UBC{YSKHV-J?ObaFZlDyz zxRGZNv(cHb0~FD>NsylzJ@+>T9fk@`%e>YstM-1j=9xA=|5Y2$#R1?}d6vd_RJ3;poGH{e_Ig2WhQmMQqK9twpR;t@w44`AdJ^Q8gJJ@lpNEt{Q?Wm_StL!#AoAlHV--23kQ6i4o$5x7Oda-BzQhYZ1f z4p-8v;`-^`iA(pR0^FaSH}=~IZ;uvg20ZD~hYt&5m9D<@AI5)0;m?||IVx##AK(a^ zlYtESxPd%r2ji(-2H8E6y2FDiSCwyJ+#y1CHK3h=h;j#gaHn)$(6hf|UVSVH5-r9Z zL5z+))QjUaqtQDVEKg!+DxgDuqMm`xW6VW6MS-6Cc4wk26k)qucUVi$a^o{dx{E{> zhK%v-FTXA%KiHmTup2H;6N>fSUYTk*E0ywJc!Xe_4Io6Fv=8crgCwd#+FuIjo>Uvk zYV7ylDKFr>^JG0~)nou&t{%#Apbk1TIU1w>S1Ia}?ZGV0rRVMql4B%1lh z?!6YQoqu{YyT+)-dt?6S+tOcO`5gYlHkKKPD?or?(%JtA3H@c!obQT=(mqNs?sqCl zV0X%F`*|`b9dbv_LZmHGR-I*A<354|v6eo+zI6R`)J>O<`+y7-k=~a0n&(H@9Qb&L zu4?KzYd~B5(0|3t2_o+)=Y9%vn*=#Tb4Ae@aQERnT0HKo^w4k*Q8042-7LEZ#0M?m zc$E4tTO6W}bL+VW)DqTqKzm>>dM3j_{hdFs^--X1;mD9qHTY}b=RjzhvnCcSJv2wp zT&rKIB{=e`f4rSPWbIykzjhCZVLFbegq41)G_LdiCLz`IjD$>&IQ9cnw*w}k{& zPOMPy{W`|%l=RS=l(A>jr4g(ol)3U=QWxzTDb*N20B z?ZBYYQd7yDmv5MpGrp_e+gWqyN|HnJyQI;j^X&9gxJ=h`Frwe(u90>!(Cj6X{F9;} z&UcK&?JJ6%zX;Sl%0$jtyVlo>FcWFK2!^fNGIcVOd&bd1joR~c7wQ5f1G_z7OxN~e z%=Mf>=|U77kw0GiR?NUc^{=17oQYb*s$~{&GU}(t=O^mwh}s413g;<95%lz1$+&AZ z0OPJ439)v7;z9*~^#&K8KM7a|9@4d*z*^!CGU+Ijj-ja-#!aK^d57nJd&#Ki3F_dd z6VHx<)xN+FaG&#|wSH9~uw3iO*(|LkvXciJ1<){1^i1Ore8I$-GS-oyk7NOLQJLMK z0Pn+8#XWc7=hD566AwOOd)kZ|W-oOnChUUC^jZpu2Nx=O`JdAUY zeB5h}tvCMWx9x)n7A&9$iI^8k0FM3<<5%sVE9VUqLwOdh5vv0tyMh1gEU0SLiS_L% zU_P*ObeTW zvu#GewhB4`-oN8uyvXeCL;Nx)!)(;!nZ>AL3;Z^Z*5V?nvkVBNAiXd5!vh|C58lU@ zPm~?!QWyeJhRm$Ud&Aals4#hLIqrAI^=DQu|3TQfp1?kkA7huY4y2@im2-j|5Vf_^ z>s|5#)n02?-bi?8D}7@|MLX44gvk7S;V@Ql-NT*Cpk0I%;5!`NUqK3rvh(|jr{{$f zjZ3WGyE3b&jevAv17va4?Q!BlSL7|@{&PF(i}AoHdhib^L18F<{8xJe^5-UgG%~FJ z_IfD@aK(>jT806Q%+bA3Ts(GisKg}&Nt!uf{eCjgR!f|XRGNkD%#QR z`{$RUe!FfyGvPYl(^cIr63Ao^_fVL}YwcxATN5Gr_khwN*S6Hw-S8Q$cDnuWqSHlE z;~lWZBh{6z@d-I?-FT0&_fJxwo9I@wV!8jmH$b)H{c7B@h-CO(ez!(?u_5_;+mlnN zL&)Row_`;e9vB1k{LMGbEmg~v&G|rL(n861 zo8gY9Ys)E|>$X5JQ6wIkrWCf|tjg9JT2Ncu{QOv{VBOx0_H6-&?oSElWTdV(pL0|L z>D&3-F2($#Pedsn@Wx`0x+!gqtweMw7CbPBNTRY&kH4k!uQ2iz0m6vk1Vr)6i@zGe zW=Lt71?<7RKmqyl61`3r`~7Uj8sJr%gptxLf?D#(G>FnKwQ?@E`?oK_0#0OB$xJuB zEj=Gdl`*xeGuM&+npe&Sy*5j%jsZ(aVewVvUQwPwxqkAkXJkT_f=A$`w&5U1>jLMk z;p@2Z%f6uBR`w$s7+C&K6tT>zkA;Dv%)TQ|TpMMn>?El8BrV`{rbopTB@ijOU=tPq zeu5dyP$gT;8gjdCjYMlgK&XcEo{LYv*6pAwwUb&(t;l9Wu^?Ep9;zHKAtFkpC*Wk! z9wRaUzg?{o5V=Z!dps zQUYb!heh$STND6De;@C&RH?n(CWKntZ+gRu&*sf9Y>$P+BwKBz>14L+U!CTUnXxxuoFU`WW+iM}CmofTA#w@+*XMO-fEJX8wL zsN#VZuXwFfcES;#IAzwG@f$B*lw-OKAG-pBeQph?|ssv9r*jgG$v(pg{doT%7znHYScgu&X_e6{1 z816E^;qab6U$ydy&b9W&z`t$)0`3Qp0aK2)VS(!wk)KLU^!)x(<;|$4EvQitw#zcx zlYy&!{JY=fAd`VyJ$H}Jge;}EiPsv=irUXlg};aY0P(D>fkD=u16o%%*J&FmKDAv3 z7L4==m44BqFP{WPXF4Pu#>XlrHRG;LFHp&$E^GE#H9-((wL1RKZ3he zJO~!W!1>K94wPBNVs1gDASmkx8dl7|Q*UmGZzw)ycPSj}a@6$kQikuRpoVPbaSYY~B1$Czz_2{^-jqQPc0Yb2KX-KQC~240LK& z3fxEQ4lK6TvEc^tZ@#&6t0vg*dgDu>!AHe4W8;b;?9#-Zc>o0Xv8DTC4#o_#%J=RS zVf%BM;S=+Ju$f=6VgXD}{4%j!B4>;OWS#WpklAL35Xe-3KdFwuTkApnBS}VEs}RBt zv3XpgmO0#W#r34U<~OXkCfWF^b&x#yM{5v=uSq$^J7?M$K==gj;o>O#YX%S}BqrQr zg>V|c$bARa@~h&aJG-r8UXE{cNGhXHfjyuVwDDv2tUr|>WCuBpn2UK}e|)fi9J_S% z%<6jY-5Tq~FRK5L;^sY{p_igb5Hv@K$&$3&Tue>Ze3w6+emHfVd&8tX7j&uVYWqOw zeSb6ghRk0zP^dnLnOPo!fxznO$au=t3XG(Q`Ew#t0kOm3zuk~u{j(*NC-Jye;Z41r z4`SnmR6q>ut$}v4A=r0+j9OpJNc1lj)iHK}s@(C9%Q7ZCeq^er4=;3EzdkKck`G6p z6XAs;8kt0Mr0(M-5OMw&AN6j#CBr;kRWKZ*XA82-#_<{w8)`TPU7B|=6WMo1A^4n4 zd#sr1S||V#M*OzMalWdhi_FmKoePh<=dO`48~YZ4lLCJ3-FKKxKd2C4q#_`*hsKEA zt^HrE=L;W@87n64xB;-|(bXi*8X#!i1buMxW0anw(!M&)3xJB7SMt$)4tavLW;lDZ zYe5Y(u=ub}nb-H`@@+695zpG5LpF;;nG{+vrei#qU;~PUZ03nfm+7cru?SZ6LK*Xw z$&>&@yQU5V-*t9q$Mz3oTPTfIx@MqW+^>5Od!4KOyHjV3g~!HX^lr^^?V(JByqSUe z>6^>dYru+=(^sM*v|)2%(u~zECu*$<3;s*&p{ihOb~dka-6BDrqrSoilFr=seDVfx z>;Rt{rcw+_+!+(M)r}s`55C{tz@Ys+7NOih>8;eIMQa&qEksYOh(nB}C7OL`#~O{s zuOfcjNf+~;v`r)|tD=fsrkkz2kDK;=eZSeaGL=;jz23r0%xM~j>?JV2Pfuw!r$c0$ z;4kyOo;!cHAPw|&o1oAgi9Sz|(jUEFvcaRs0hF#HuX^CZFK6YT>LtPo(9(juer1X$=aC#gS@S&6N378yT~?(+IFB3 zH=Aw_VSqlLcWq*^ifS?h2Pj~{gPoi@dHOR_%W|E^l73S=zp@(RGH4}MYlG%FKngLj zq+(z%A)@UG(mtV|F=oS;TI(&xS#tRnjt8`i8k87Aiz#XXNYQV=(#Jm5(iA#UOvIUEt|VUPWjN;{ghH z7vxR*Q>g%z!=;BR{-Jb!8>^xru+z^NkM(n;DwSNqKAU?mMEk>+_J}G46J>rWkyqw||{PnWFLK zZdZ5Q1%&m)_~{@iXYJFptwOdVvLmXF1|^q7aIK)Di~iNL1}mN-7rYLpX=&D<)d64cL-#fL2T=tM?)c(&y7+0>q zl9rCY`U0Zx4n!_$KV*_}H^kksVX#qgqf0gXyk4>SOCjC<#M&h^E*Bh8_$KD5aOxyd zmlC^x^MWePUo!FQ3-e4rFrNKUwOkj{;=Y$JJhMV~Y(M&u&0+qs`Tl;2@pLV=t0iPl z3cs~%4TbrYS{I?(yxL<%Qc@CHObA!Y?B-OeO2+lFAbB6(Hdpsq@i*~xorxmNl$(q3 zyQsz)ydJ! zdEO5WR(uke?`e2-ir03BPj#qZ&(ajqZu@B<&TBoBmlS@D|K8tq#SP#D?_JFK0ia-p zta0yJFYSC7CmZ6MHdHGN4R-cGf?vkZZpy~))|(A13>Yk?Z?Y}sqK;7*%I>WMD#zXI zzIx||&!)Z4Y#Q@o?-x3Jb+QL!fESIFXf;25c5xhyp$!*!FF?M=y2v)7pz=CQ z+BH*+Ys*kf$8(Ymt+ z&=j24_psId3zN=Jyx6!s1WHqv2w8wyJAmlvK4OzG96&*5-&eux&=ky4M(EzOEEn!v zeL<^d#BC_Mu61SOkg1Gg$A2VoLFDgfaN`6(;3`0kVaPOONmx`JwTg8p*thXxWwr5w{tPlZVpYc2Nr?DPjuP@ zZuT#x&wm*H`YnpI#d4)TJ+c#=NLN4X*K0PkqzqNZB$os@es& z1=#TS&1tLslz|%B{qe${Fd4)^9ifD$Z1)Yj`l$8>U63xaG&X+Ya2Wq+v=9G1)1ehw zezmqJo7Bo25h`0|s@wfcRxkY6UE6^}sYB9Hoyx^-47Zx>qo3amQ6Y6AKFP6lm}-;g z;V3UlvyUFZ1RSH1BpH8DRDTZpX0_VNQeuv)&CGQ zKc&Yoj^)Ok1&%&Jh*#ppmZeolALtVAqyAiLtWJO9p>f;KFV)8OAnpID1~|7st?3GJ zbR8iNRWZq6E97vn!VXf7hMf(qLRPTGaVW+Qo@IUhs9f4i+5I%C{IbesX#*&lhIe$z z3ONe$tOj!W-w)ad^l3c-(%EGgpy}hP#qn;O zak?~agw6H1i_&nwXU2 z07?+cW=7z^PwpU!^jCCwe>`1utWS_}>vZyZ)X!A*AMVB|5AxEPN2sghq4y>QM-wj# zGthSp4krg)XoCB=m&Hpg(HU&6ekz0;6g_$dDJMt`U)>3FOlOtn{Y}ZZNj8V4FR56PXCxYW!;s4y>cQL8G_v zi6+)b?4mc{jtunX>z?=iLNF?-mfSM0_;RHAR5>D~6cs<$|H?b08vRs&c|KIIv&O6p z+Ehgy;BQQbCCi~Bj`nDB` zYrGAP!@+KV2jAvC!TWlZE;}`Lc>HUNt{JbHMIJ2J=hN(e_2dNr*|FbK9(V=|rLiya zGnEG_K-J7Lr#dF_1JPJW)-OWD(RZHo2}>!!TJ%8TS_DAcx0N|n>5UHmudbg-arR)RO7)??Jzn8W+nosZ>Vc~K{GtBmRS%_47e za04#vkK2T5fkIAii*Nc?eMY@%S+7hff5#wmSwBsWR;!fFNM<>{m_cl~?Ot@GHy{)s zBF;8w48>c{g9f6Mcw#P0RmNubFhyVONJ7`}i{vZhxVMx@Z?_4#Y@^i*CjCkQ1efHY zUaNb8aqG`>4~ibG=|o{;s_@IZ{r2st0_u21r1w+LMv4V}X;d%Q({o??pNb1!d9XZ; z%Gj9ip3XFZ%b{x_HSy@)R~78_6gemXSP{Bv{5@CeUpeM>xgf_pNcWhmAoOum?hZGhp%X?P3!p z2m1`tQa4&TrRPaiDN)CJNrLDGuI_waqwertO=?#YJXpE`<&0T8;Au|sC@Nq?M;qM)h+k(2f>!8$dWyAj&U+5T~Ql_zGUjJ4#7Vh-Bomv_?%epcPrTGNa}1_#pwBIS&$^Bb4TJeEZyJw3;! z+OAkc+M|`Wagtp>o%ULHh7&zRQOeSS z8;w{yJu-x`p=HX1D8aH+Zxmwp8nU*`xuRL0>;Fc6IeCc?P4M^GHc;R9k8!A6-l*(j zo}koQ7wdUTICf5)FjD2p11kqRfWxS*KSlT^<&rejQ3*QiyFK=Z`?a31wQ|KS%S;`tOvn8;nf2U2Hs*L+ zySpAOjC_3-2C+?L{?4pWp-jYOwJl`Yox2@34E6$t1zFq1jc3=s@FmQX0m0s5+iV=f zJJxt#zBwv1^pV%vjM6S$(J-ctZGZI_95Q>Fd>(t811?G2scui1JIPN=;VAg=~k2dpOlt|wH8R*d}`e->vdVvvPbLufliRx*yDn}~SBFy5s_qzM`b*}NE z$6VtsqVFDNKH1+JKT=lb`%;*dufjG(tIFIOyCo{+oaRuuu$PH=1;hv?*;N?m;XuP~ zZ+v@4uFJe%zh9!no_6f6e{AM{Fu@aN&l60o>*ST>g^TmqH zas!xXo9bEqCHWb-h}l;T#X|m=r?6o&m8Kgif{Vi~l8lT$x_b~je;$>@m-OCXD-T#_ zm-ZfltP=eq&~X_ie*LbNS|RiwvV?{%`w1PZCu2{oq9Q|juOHkyWwaR^KeYR;kA6`C zchTVRYiU`*&*Zs_r}n%8wW^nyc&pu%u{UyN$E<@(DRKf}Rf$qG(<%|Gj&o4eQnySQ;vhNbd2cn%sj_PK_u=Jb+TTX> zEqW*ZQpx>+YYP-Ov&nevePS5>g76{O%}}qIJ7^gv1}&LUpg#;-xCSa|jozTmgZ+?$ z`Xx$SV9?Q`eZpoMT(vpf(#-p!&{VgX#tOo8qGV$0Y^ui3OVIb``(5{IsS6)1ztny_ z5^2MC=&082rRexx5W2UvpEsCj2CX}>xomYYoya8oV3TRI$El$F2QBsvPB=E9K_`qW z**^Jovig_Mb}UxUCK4bZd?z4l8)>^6rB( zrg@Gv&`@oHPSl$?n=<|%D#)bvhYa!0=0y}eHkdNk)OyabyQ*H#Ewh2CID$lVQw)M5~T-XT(Bz`KOGdx`PpxS%jx=r@k+A(y_(r zCo|6ubJz_=TV@8?0WsC%1o*?OhiONdyVoA@oHPEm$>;Yech}|mIklgT*`-<~c6r4@ zuJQkom6Kpfm_%kJE=DG#phIkpt(`+mUU_&K7tg3kn&qX@VQ*vaW}sFPT-kLrOOioaBb82Q@qz* z?={I8;+~f!8}mx)rY4DfJ;!$^Y3bzh%LU6iM`6~8dr3?AH~b1a_z;Oh*L9`Zypo*< z=kQIw+#{&QyXI9VW8!6&pnBWU{q?+IBPzi*-APT}sSg3&Z5#U9=Pv)#1dxz2fVP+Y zoh~`jntHzBW5MvU$~&3YFwxDR zN$7+Q%;eK+>Jqd&RzD`tGrHR;fam@7t#x_lz9T0*Db zHi;(~RQBDTVUzLi@3I%&ZIUt@wUV{g&b!qVuU&Z1`dnVlwOH(p2(b9#s#I2EK92kP zJDbdT+djN;?0blr=(44{!Mn<%8qViRp}gkhSJIWBj?*vo$vF0XE5oq_ADOVUSM$52 z-tJ4x+dHURl^hydiVi^34E~h)FzWOD>!y&TpzlEnljHTT&*{%S0$QMEb-#QNG&SV+ zhs=6q#(aP}*?p^yqY&dHYd$cUy3Jx2x|LcR?tZ^v%vx*l=JW-H&}GNx&~KG2QMC*B zAj-3XasZj{b*QQF_Egv{xctyP4r=W3hVfex8@hO*m zAMaD~FK=QxcA>*X_aX&Ek2B}R*gOr4HgOoH#H!6*ENJ%%+AbyLd&ij7j9fR}hIG%g&wb#00UUSan z4pBfMdscd@oBM!%@{J=uGnVk;iip+qm*tbT$*r?5h=1zTo{Kzo#Xuj^EY&hv`$i$u z#{uSESC}N0RHZkwbuAttGh1>)-(&X)cQ7~|0thNOGzKqO%tw9hBVQx@n^5H;dXO%p zXLU~=FC+QZwx!Q(qK}Eym!VDl$=g57@JVc2WKFc_)^$^^#@H)n94rHrg*vA-1t#fF zy7lGHeBBd&pY*fLy*dB$;k1GFqoA> zgtOeT&791%HaqKy_DO7!E4yf@$W~ZcQ_t#~@ss^qO*JnfH#b55t5}hXY5eN8^OV!o zi?HuqLP86k7mrzmy$gP?4tP#pg-00c(*-H*o((S=kTRrG`2>(Kqeihy-_kV8J*62l>oYURScozHXRrURU zLnZa`9YDx$7KK3Q@k3+I<9blELJYAKzK~5+*Q_ywt_@&Cvr@mcYT?(dCn{wl2l;=X z>+H-K)lc8gUF9Smvy$Q(Qc&>82&sHyZbp;LGJW`PQpmt8)${OtoO&?I%LzBUM>p$a zsQ=T9BI2Lb$V$^0?z0<{u#@?Uu*w*SwZ4YoF_kht6 zkDkZgY^~d95K+Oc%`ut%^y@+j^zp@v$Nl@;Gd!mji#~sR>@b^I0Hd`$E?f!Br)u1oKc4MmU8z!x`@Q@_NZH~M}FwcbUh&?fP zhzU9D*a?X~>uU4)%rM_DAHs@SRw;o4?D$w?1nukT%UcIS-=AJ`zOOouujd2WdMt)B zY%z#9YQS*n(u+p%8dn~SO97>ZvE|p>B!fB$L=+)D04UTx7rh=xiq8x(^K@J7t#jSU zK7KI;XxP6|Fb}KI4f-LzQiH`hd$AM4HQ6Y#xrQS-%7QIxnWq(p-|1wNTj$T#YhEjp zL`2SxF(~fN*2#U-8i4-z+&M&5TmCf%@H*Rdq(piq1&o<|>-5j!_jrF_{#q7WXtS^O zIhx%|J}F6fSyQetm_j<76ow{1_D^f&-*CrfPSuAbq%#*u23T`zl_tH@5S>)8 zfEcH0&Rh1Y8|VJ`jgf0ZFe38!@#%!U?l0v9@C_6C!-)G4fT`(OBDw88QNPpWrM{{f z*w?TOMV`uP2+8d%_xw#`0mO$Kpb=pDmXVX`$WZakO;Dn-HDDe;v=F;r3h@M%$iM6X z{8&0H?ORSYI#1KF`k+klQp8ihP9D;E^~Q`vI)u!=rWIS1n1DEeUv&%DJ+YB5Zf0P& z$b~jZlO<3?Q{Rkbb%k$md@Ay{!`>{PZQ7DbS&v!L4Bm6m4~@+Jo*V}%e3{mOEH(AX zz#fPU`fEj{J-dp3m6PnT+J>;#l+}Hy6EK*IyO(mHqaIc%$7e6GE{%SHGDLBpVrcA0acK z3VWKlb1Af%YI5vMo$iiynS&2jZ3w(rYz7(}Co7D)N)3{u7}kf64#3Z77i)k~Q*#^ry+j0`xP z)ezPW?iTp(O>+V3SCAPF9WrO3yu+%0SvPINh{dj+R@HG1A6_?J#tpEK$o5>bZLR%wNLD zIu*z#t@##c_#Aoy4sc!DOrO_tX)*c`i{YP9H^!Pkh1-Yfnh%Np;x+#jHzGm2{o0^O zq9%}y%lyRB z>o|<*1-~ogG?;RB{1#2Mq|o;dFv}a~UsU4ZMZQ>QbaxL}w+yGjq{ypQ>)g$N|kx8A)|HiJUWTy6^gU%)a4Y zucz8GOT?Ib9ngdW`p&QQp;`_a2Gv&W)_HV%X1LjcR7qQlvxV*>FlntThBV5oI9pHR zUWP9#xw@~qZjV>uet0{`h46J*b}VFbf1ATzEC*XbG)Zq2%d>TDPXN*@fEshEpllH+%bfQ(8?;O%hWa_yp3Uf1Ei2 zvbqNx4${3We*6*^W_BJTYI7zr|8cqRUV$;}s9?cv+%1uxqthZxKByGC|I`mj{_j6= zQ5gRCn#of|LTN*KJ7ebZ9Z@>X>FoP2vI$@0K8o8GrFx93)du;B00YA?Ftqr%{7#fD ztv%@1#%PgI*9hA=m2l|zN41i;(-3Sbm3lW@4==BfE5#JvhqCWTk!fJ8T++`^M{{MD zRgjmctoA;b5Oq+eVd&8doqQyz^@nJ<5}OnM7hSy(r4|dn>MR`s zF7;o3kC+h9x7YKYFQ(8@dun2JJhtiM8SF8)6km&lCB)*^F27}~cN=jITT=z?p zD_T89X+J&=XF%VPlqaH+4;4L9eVHH86(v*q`9g(ZmzdY1g1%dhH-*nG67cdBupiq@ z!(Y+Kkv31I$-_Ju;Y`Zp-ZvMjLb`!n4zQfZk?^TN-+X%T&LPfUB_8zS{J!*rN;zrWp0}c8%fM(H+}+jiKR3v*WkP@%t1%dawvvPq<&u zioOlyu*)Y%*n9|o&Y5k^G8AL2tv($d{sSo4tXM=9(F+`6Y2(`2uxM+7HL#zN^7nqW zr~L^39#m9*f_gnqPD~sMq;0{y@JaV($m59m3bN?WpdcA5Oq%VWf1aUNceuaU77Yg9 z%Rmg+aIlJ(zW{tomX22Y#>mOY$V>-QUe*a1TQSRoi9 zf}A1zCII+oil0cf`TpK$O7lF~edrT|GYbEl#I7%NlKoJvFh^mcnCpT5_Z=DNz=b9c z>(XsVT)IPNYzOn1{e8cRsp{Fv@Wo4@>riaFP85FMoRQgg9T0!!FJMF!`unRW?TBpZ zCkqNh+mStAV|CB$d4!tv=0x_(s|Ts6aZ^>bk9c{XzZwpXu~A6tMEjF!wRv8v z%;TobYz|qV7Rp1kk$K$AfK8Lfq?8N?WK_Al*UG8f$lnXR#Rewg-X!zXua#(|yi{p( zKcLjp^Y#6~&4kC`Eq5|s`Zn`9$GgLlm-h~=K1@oc-AGC}L&WJ~Qm zhc@?kl@`xsNb8Pl!^EIEP2Sw>tnuMeM{KW>gns&7o@FkUMJ>{4j7@8Abf9}Jdi$ru zCpQt+8|9fX7v$y#633Ogra{jo^fl6ANxxrviMulQ%wuGxnhZS>!tll>rl5I4S(wFv z-M3k)q7wZsra4*-Qb|fGoY4Nh6Y()Cug+tlQ0NCAYx$)}^@1;gb4gun_lZXqYQcDL zP;>IJ*B?rtG?IMbg_5tQUAs^b&{$jJjYB5t)Q!rf+sNy3(D#lkWY%??*^Ql;b~ZHJ zl`K^Yz9{&UVQGK=9WH~S0=q6ZZ~@GB9E~ef4ZQ!tnw+Z}(nosYz9$JZXKN1>0w;w< zL}+HQ9+2`fk8Ls+l~g<8+m0{Wd~vRR5sNCJkGdmiNF>>$AshFgFsAC9d!{oxi-YVN z^MkEZ@C{vl{_5N?ztoa74-05KjtoLU-`;j8$STL$fOF!HPpsKG{y4cX-u6M(e5!;! z5Gz}Kjq_(4l0v1?_wH%>ja1)q@S0CU5pB0A>lW+w7D4_4ZBTw*!AIfJ)1GlavQ=%i z9Ch%jG+dU%XDuHH@hk}C%NYz6lw$)gIq{2zZu7f^b1+`n0lA>F@t2D1>|eXPd-=D& z-o5Ls)!ZCydE&M|jbl{^_@u;KR_ZmkWo9sBS64S^HZ3P=Go52dsln^KT7cd?llL zI+faJ@9;1-#aw+K2&Iy%gfF+q`0U=oHv|LFR8%xK6dn~?((RAIH<0hLK)UJRri|k7 zppG>P-oX`JUI{lxZxi14jdfxa$dKXw$qA*(u&(jYhPj9{52G9UcJBzcPx<3E6yEfd zBi4sSWW#KXtjtAyZz-n~LIk##RbHq@-Og8w!qCme=F1rbe2Bu@Ugq|_IT7l-U@l^9 zvo%6KeV!>s_W@D2m04mzN4NED1-Xb7ej?i|ax7Z_;*Qiq&__wN@@$4tsCOi-R7Qnp zqM=0dQ*Y@9o}-n^Un;_Y&)gaOEH%d#$AtO0$iT0|!x+z^^Btng>~pY{W}Z5S^GV9P zJ2?2YwYB~A(KIqs7bm`8FJi47jy_H&*}7M0&?eD1TP3m)6IGBs%BA9#eE{s`vQ6F#{Muo)PqME-=B1+`E{%l|a=x?fpuS6Oe8)-p3 z2WQGm6{=yGl}?Cez}Uv7677btDGjH}^`~2H$)q8StO_ahyx|W#D3`|@{I313pOsO! zz#2&cmNZ>dWe85LUc8#wfX_3c1K!{RS2*en;oG+Ci4}aTz?)U$ASLklD>Ofql+3Ie>=@Y%X z_L!Y^-Ye`DMr}Xg(q@g>fdP%#c}kgmL}~@qJmw6@r-nM9r0vNI!#g_N(KI=9EJwzb zU)_zo#30lPO1@YS6= zM>u!AmUn=T-;HvqsPL11c#2VTOF5F4$J-D(JowEXeG!pmSj!^|#1D(RK!SB7DWR|b zgK*RHR+H#s7j^fV%){?@X6(h>`nrm~!-x0e!%ZXUZ_QipqlWb7<$QCV>yExhR0M_bAtJ;@B4SP?Q}r? zv`62*kE3RXD?_$69b8+AA|XQm>PSdOy#(dwU=~&yYIDQSU2MnR7%s3rTs2CWC2Qw? z1s3@&3Ep-ZzR$ra_S*Mg(dhzDl z%VMpv7`uVqO34Lcor2-V;P_*00#zdR{*T8uLn7aK9v>)(pl#!RoaXab$Zl4zyzLQ< z-9B7_guSCMdqg6S6(ts!^%$Q|ZhMKxOfa-Y8<{g`dz{KkpVGMBnC;B`yO+@+fVb8O%UQCW@>rb+uNc^4)Mlx4scv*7&n7Q~7 z20yo=LAt+We*kt;FK5G=A~#B%w`zdUT{JtjNcF_AeRX-&$>C_+9fl`I@rc_q+Y-+? znUa!nY`Fpc;}NW8Hkg#YssJOm*sMt1XV?GGOij`!e2Wyt18 z*E#g>6%@v}l9VKtV|-GwuN>rRw;>0Gsmh<%wBt}5yiTIhG)k&ja7iW6FR|RrjOTHi ztD{Inmw-v%yC_bB)?`SG8Y5C1d#ZY|$-PLo@ZI>WDd2ZE&LfNR_u0%fx*xn_)2_+_ z)Rg@Xy98lIJ9N4T5f#8MpJll|U!zR4Y%gvWeb-5XQ( z4NOvgIFX&K(QU7|na2|}X)y`nQfa+9!f_Mk>b<)-M4GCEuVcg?XSztk=*9o}i^a*x z8nTvx&XKr{`MnQ2*xuyHz&xm*_@Z2|q?jS%I|zYZ{^JWfpx8#&D*OtENvfP5AJbZ} zw$MxJ2!|dR*VxS9Mi8=By&#=Tt-BCs0NuzY&`_L88m`l4nZSNKAmcg8)nab9qmiko zJcjxsCnD5d1Ldc~Ky zbpJH0U`0Yh@3D@*(cerIm)#A(zIhofMzEr|r!V9O?V+iMd=tlps z8Guw8?`L_ivbu`L0q~`7hIf)3w71&vegt?PS0@jF@Hh}CXtcPHeF|^M{l7#bUOdmA zTH{#?=BT*IxV~y-Ar`soF2SD`9|#1AEp3FU`VYxFXn0PP?EQG-k~0vWvL%+)GC_Ps zok-2lAIh9Io)9Ob>0=qeI-PnpohG2-73zExl*RGZ6>Eo@I>Q3EGeiM*86COK0dC2= zPo60zMk(^*6BU2GBnhn60arI`2!&2g1=bUz^g-G(;a?oW4=IO6Tp~RwbRU(sPn)d^ zD(+1uKU(s)+5Bcj{1W>7{lgmWQg&WqQ~jtJp{lFr7gCLna&p5}lthxA06iSZmO|-Q zh@2so5l7vk67zijYb z@aUsPxlbEWEV?z&j06NeQO`3)jld>ef6(38f22ijz=)u3TjxedSOUjKZ`5ItVe+)Y!nVG z6k1)}IzgKK3VrKD9dAdo=~0uZCXHkx4k8b~%5wbQ#=VHWhwS5$Oi*J|Qc@kvgqJ?c`R|_tb|kOTp13P-knnhe|C|&m zfRA#40=>cg`6VGuaCevBF)sYmGK9UF&@9`f6%nB&5E;jegwo?Z^5~zf3wE!H%Esd? zR@g17q$7E+V6!U2{(ME(eSB%g>Ee}W0V0{FJ|{hJD$@rPLijoCkseB@J2^S&1SN?+VW>1Mz?I}?sk^FPaCW!*py?uY zX=Md>PfvM-3Bj@cwG4R|bg0SZZ}ug6ak^NQtMz}62G6+rbT}ytBgjNtct47}rw~XU zk-bp|9@=2v#&qMMZ%;Zx458a6faa+v*?8gPfZED#5V}bd@(0~fpIn86`)vhBt8|c1 z$vFGD5RMn?zMdtp(O6^rIsh<6dKk(P?t~-k;7}Wf_Kjgk7qfqNXl|$vDZ{@&9kqW2 z*s8xgN9g@OHbi7Jlq%TJ#ZXAayd*Gi$?<{Z2=OVWK?20wrlDtn6OM0fE^}4~dAMC@ ziXt*LX(T6-uxbDSXw0dEj=@uN0#V;_+L$ z3d(3zszUr+Zp;~wyTWG*jsCZbQSTzqRKPl_Ua#)^4%N_%2!-gNFCiN8g-{LI>=X_H z&Ed@KtOAS*1ue$U2?>Z)LcoYY0qZ^{u^&LaSvDdQ0kF!exCH*6F?}{r41TwX#8eW6 zwK$NdIcSOo8nH1*+mK73{S0iOJ$wEB-?Qq6bXP-d)Mg379ypR(AITpzxaBf`>rw?V zB#RRU_ybVfm2e2E&sBKFXq=xfs!|Fs8j#2)!1livVlyhI6=g1wJOs~VgY-7$6%g6! zwRpbdOXbbehqYe3tr7_T<&i5N;}e617psUf$E)zaU3r({EaTeAJ#y(dSSaVne@b|n zs?1|kY)1Q8O2kl0z&;u$N(sVjpvxR`-CA}ruQN>0;B@@j7(O~)Q*8GAO=|z6**`Or z3S97j0>TLr5)$>JNANo@AFLdLYfev#h>UGxz_CCCZu+WET&{R{5JrtzttU$@!BrU_ z=(4?>alt_XZ|Jc0jlelrVvz-R`YlsYV0^fTQUp@N+bRcfJ(=C_5cB^IJ1VSHWy3X# z1Xh1UneT`c4bQSvT38Br?VvV}5*2?BP5PN%NZj@gI!?|7uxWC;fZdgf53KeAAqz^SSUxw!Y%!)wZi}4uc;wFtfY{^Kb2SoM{N`@D~nQu&UyF( z7*1EZAG{(L^(O9%rV2?-C4=r#IT#+%fH~@yG{I_mKeWpE_gp|FC?xzZP zT9GK0LC)cg4^dIlq#w%oj5OS$VN!|e6_@WVG}S}5@uLp+!O>@M^AlM@L_c9BHadxDXcQ@ue2Cfng&4ZcDc>QXRoK7 zP*1ieFi5yfQTO(21V3=$;fAL970D8Xy!`=cP21TT32>iK44~T+Wsdd#P9zYir|2CA?Q%Z?S)%L zVR7!s%tpR!w*4sj=kn6F!4IRj+(+V73_5`}RhA+vLs&CA5i0 zr_Sc1&Mh#P12=TA(?dXU+6Ok8`mbkl;8ka79L{#Nw>Sun(z~uunJ2D#upINco_?px zK9w-*{ckP8!G}6vz0C)Ke>G&9tCQ z38b}~>!aNnp79dR=i6Z%S4n;01d0<`U~q%x$ed4{lT>HIR`d6wKw!_jrx%ydf7)0>!Qj7v zDosM(@$%xKtQE&`4*M9Zd1f&9he~wqQcs_)GHw(ful45wy&jy3_Jav;!^u(q7HP6xO6bge6^957++5>u5!+o_$LumxPgyf z_8a|?+O5LEEJ>WQVqO-_JEHofj?Juk7VCE&C=FZnDCq9EVsScbu_uPD-}}GA=@%gM31I?_+4Vw29-`fffnTeVw^7G#e;&=gMGF-zM@GjN z2fEkOOiUhXe^k^^(Vmri?I1FzCPc$e08Gcxqf(~x7vOdx+G(L~f$}E~Ne&CQLK>D+8!m8fe4bqc+>RCo4AbO8f$~3+;)$CUt=&3k z=im#oj^b2S_-EYz6)@+uiGL(gK(BjTt!m}J_HSjD2_-T z%pV<_f2R4Y50KPYO`s=ne1$Gjxg0449PXKYdmo$loBHN@E#b`ycbLY7+%|xRQ8{ zE>6xBXyjf>(CRdyX68&pUW_Q9?i4=HlaqOnCkMxH|aknZ^FMskr)%|aKYbby( zm0;JL@|tyF+l+L634g861v+A5Fp&jDlxv%wK~i z?XK79G9UjqtD&NU;r;R(#i|$iT>l0-<-0)Vy!f(TXG??Ab?NN`)N+TP)Chv89&g^z z0CyS7vAi(yb<0&07zDVyoI{yn(V!k#1$9!9eiPsE`d|bg=*K2}Lz0$hfPX%i{~QRe z%X+vklBXa-D+kV`l%b(vLx@&-`9)&#U`IzF3Jq2ts13?o_QIav&(F`R00*_{+1V6! z4k145J1xJ-e1qe3t##5HSeE89T!8>hX8*3LK0eGD2-NCTbN_{CYJ?roxi2)H=}y>y zFKiqw@S-HCxkB?Xrx2L`KYDi;2D#jJwFWZ9sNNj^jGgrc*9zVT6|)SuXD?ra3OMV< z=)_=>3&7uj!IR*UO*~rY8HiYV9l#Musm^G#ld5DqSEp~=Me5_W#VZvR2!7Y20}-rz z+n*f!Td+$RaP-Lm4|7-hqonqH%LuT`Htm<~P!ww-tCsii_NE@1aBy5+2e{oj-F3wK*mZX%8mAzu5CAy-HFBTjn`75;C6)BF8bOBI-~oZ|*?_a(Dx&Ygv65J0IE!@_>C+%+%g1T6A@AmHa@K9u&b z_V$B-Bki5jCds{IWbhbIkqDtx1fAuyr`EYTyd>qDVFv$q#Fn~?*t@mGAC!CaPrA)| zyfvg0ZUSlVnyVcKY8E${9fZ-v4|L{#!Dhe_Rgv}$D84&M@B$hI-YOqrJ&|TbrD=8F znS6%(L*P9VV5~g`j>5R0dP*3=R&ff&R)%s)BnQEDl9p7i3?|vOuBfGehXG8ZdO=a; z>-mbH^D}&=Cq&37q=6AA5$W`kfN6s!lZqz|0`3U8|2=Piva@BrAN{1Mh%3fa;YS>r z+8@V=|EVsthye68S-V(l+62QsA{$~}XBD-{)8LeeQRkxKwP^tng9ExMoC0>Zo-|)# zKEp?)*FIV<#|S!`=d%51_0cWXA`o#U18$n*I?8-ech&+UpyMPLbVB;R-~0 z!U!l`?_AD+dtpBIOM#Q;;(E_>+*<`)j{C4Da{BjwU!RZ7psyV2jZ%hpIicCi)jfcI zpArF$6;=PUxDOv7B}3G56MVarX3?sk+E`LDRr&ubS5w^Wp+3=)#5Fr%IT>=b@kM#l zKB_OpMcAbE;1Z^tNg066GvI`D@xnmECIQTpDgizFJ*(yrJ)PJ2euC(9!<%1>yL)ex z1D?X8^mwf&*?_MkG71*CIH;PU^dQ@dlcM5r?Q}ZfaTuS=lj!2LnXf5y6!R%Uiv1ph!ZQo&20<9N|yWJ*_+ z$Z53UzBPsn(9oVQv2@Sg1z|+dQDa5TR~R97qmY7mOD{X0v7713?NViaSWa&txIY6s zhsam`Wgme5nRV;fx@l@+qtNgemw*GLR;%~tULJFg0^AE=-@*m_azme(3CL5^!lE2V ztq=y+}AESSg`Na zl!N`j1Yl;SZlS-yxEz82h)W*Wv{ykg%m?n_d$)#F6+DzN-f2*9xj0I1yj?RkkBQ2q5F- z&LCA#&UQZXzq7V>xH@^gb@sa`n15pmdfFu#En-Q~ zkt_Jz7A@Mh3{$sTJB6vjsf+T)XNggxRF7S;6eMAP_!bf8E4By`(osVHQ)p*OF+>Zf zDwK8oxk#Vkc=(IIZ#SA(*?gx}=Q}#?#zXv1avu=}Ynrl1yLbQM$&d-cJ}af6m}#$v z^p6PbqkEg}#i$@vBZGN`Brx(VW3m4nM}QJ~9|`G;Tg+w*4Mg2BXF@!d{a%k|>|HF9 zm8))$4N1I-cV;*wTOR4#_{rej@nmY$ubn5IG*1IIi5!ACP)lchNm7-4JBlBZnTEN8 zQtuAGl-8xj>ZhZAdjcj=CV(WLm_*JKm(cD#FQ=Q9G-0k~l2e;!$@Nv@-((0-5YYcq zQqYJ}(jYkY=Qo_b*ovh(n~q+Q4-imj%JG44V^BlCS&e?uB@g~;B}OE}y(nD-Rd7^POv&4IDA#~Tvqr;^s+p=yO17}Os#}3>mfGQP zUJdir34Ta)dK5P`Ha7NFSO4aaJlwrC6nk5mj08M+h4~<9D2ppiv2%>L3zF3m5>&VH z+U2{FuQ#q!Hb3`=<_rvQ-v92|N&^9qx-)H|U2XFhW}s~=Yi@&w4tSI$D-p`z-xw<| zfuwr@+$9}Ot;T(nAAtKXEG99vek|f#a;rH+UG68_E&p^Cd%yLDlF4E%q$HwjE4X2d z1-1D%9I0=%?+8F55OB1-K|BJkLWaOz55Aa73R($Pa7Snq$m!b1V%Cad0I*uI4~U3} zsLdbpen#y8=Ts$?Q_^~U5vTnn>fIO13)s-Vkqoy&=&l5`>o-Ys@Fi~-Y!3T?gQz(y zYv-~Qp^f<3krd4`M7+*sCht|BYM5y->UJL#O(oY~Q0rhqa6MyfBgnh2?f!$*QR#|QBT8JR&qFb;W ztQfu-#hM)XB>YMz3}%UG0bnNp()``_`}qP`f9l}JN775gi`;uyOM8O@>F;xvg3{JNy1rrQln;f4g)VRxQ1a8I^8h3nxbfWw zNjND8$5;piuL4|;$a`Cm-&oUyVKG|ZB!$#de2Eu<>rS};J+Uj;yLS55wlC`b3dG;? zY75x5{S6)=mlv?Dk>ZAOf#we*wh$ooTyvgC`e;-uKv^0HxweC_&~$Z336gSiz`+? zeFgAyw^?kZ0M-K414thdXpzjj$kH8Dapq`b@o4$>vtci2T626Y)BbI1#UYS^ckGAN zqdb_)P3Y~4*Q+0rCa8v3Ov76OE*^DcLRpMYTi|b>!1Ps|yj>xk=xG%dd4&!?0Io>ue){WA{@7^2BFg zx&#`5*r6Xw)CeZ1yB!$n?W!h;$-Mj`xSc2j&vg1_{_Fn0d?29FY~MPv>dKFrxBK-? zU?EqP$$&9U_M#kv0G&Tqzd#Z|M_2DWdqejZn(h$RyK(i2Q4p~hr2-2JH2Wuo56#`~ zRYwhind&!@z+Rr}{X<*=V&u$)mZfCgSl2+qv->y=Zs*92?`9%CIZ}+|p5GfUeyOO# z^!5bc;dG#J9Qy-OR1~l&Hv$yvWNtI`?Ws@pF+R#;{0R2;_TIm*2sk*J>7Fh=d7ZJ@ zw2E7>nz1sZNKJy}-$Mw62Nodyn_|#FiV>P&uI&_lVBpe@oYq5DtEb>Ql#6-XuKY67 z1++L>l;D~PbHm%4&mKp+X!969L)1tu25uK&<5#uZ%9(YvNM{LE{+V8A^;Q z#cPrtE*xEn!i;z|LqUpvT0=jRl`n1Y6*B7;-BV5zg`&gP`e~Ur@rKfy?oD^g0Lk%4 z;d3f_`F8B-vR^Dllk|q<{wRlX+T=YH&HQ%RXw~0oXza4crR`m@{&{TBJTl%jkLO}~ zXVB_L`T{Xozhd>j2QGg-bu11Xmk)iK94Ncd>einM}uI} z^;nMaXR+v{u`>uq;;?Tx(~(R?QSsjdFFKBq-}_s>{9hXU7kdjaza`A%BCLOOzh1qN z>w(?oedxzZiI9g-$!b$3<77!5)^ zT4d)lFc6QQB5QIGLC@hxi`4JE{AUY8;xIx0w>AdZx89PQVnZ9J$yccJaEcn9ybgD=Uw9mY<^v@Cb zB0Fr^dJuD`zEx(Czc9oO|7sM@Coir6d-dwo1#qFw?>ZJRWrWMB{5ifMmSyt_UG_=& zy8CwhJ!8d6rebo_KHC|)&Bq$n*?Lp3GKUw=1f=huMdt z>RVlQL`DuOe`tO>T9Jhiy;kPFQXuPfaesYK&A)V&MgUUl6V1`v$HY6xSsfhX`X7_> zjp+E~b?7vZ38a1pB>-D+J9dEQe0T`l#WA@j&*DLtu+JrB5b1DF+HzZt0-DB}c2@># zqKV2qr-_tzwHcQ&)!=P=1a{gh>g)MieSbsfL_~G>#yi|zi%L5Rye8c3&?KN^5B!;o z&VTk&GgeUlAJE+IGl-V_=U7FX5PycEY4Q(o13jjN#)>eCQ4f}~q!d{!-rlf0*m<(XKSnHq$&Lxd2>0wIuAqBve z1m8R+O;C*3z3i`Ei-6wM$7RR+5u%-Ry;SP9oshDQI@t_S`r=Ptd|e=Qcfud>`-AJM zS3rB!;P_kUE_!Qn8gz z68uYJ;h5qv`=xY=UkNF^IG;yQKD_6C-b7DL2GTbK95+ZoTOT*b_`v6G+~Ml}a97v~ zB|eF~3&Q}4+|@|5edSUgNQ#vl5@+S%JpRBII8HRU?hpdk_=0j1&uS0YngjmzfP;k{ z=$6GyWerSa$-ApOhLmFNGTl(-laQx)Oe;WA^VUcP3EUAAJfz>4<&?mp@&5E&{UKDO zyIGeR%*nXKH@Or$!=vZd44)t+r_Vxx0d%Sx%yeSuP!0-WeA)n5`%WD#P}5GVD|lh5 z((2l5nlUm0>jC=GxueKGIEg>stv z7<3=$OQ!yZ2`5;26+uaK$70>ecyx1`PkT4nUMj?QGayQBh=2#Y%LaSJd$j(zw zcfY;DOKU!X%MFXQ->Qj*Qt|T@CwvQ-U8~Nm@w)%gB%6no77pRxix$(&){lyG7Rv(jjUzbW#Mqj!SoIYcmWpcMYVp7}V znVydnykwnk@#2^K4lsnE>S`WbMg{tM>t}OK2djYq_*LLyd>V%|!=9(Y3C7vcl%m}L zQKb9HsRMNk=z@EV(D5D?Szl?69xm~%a1kye)GdWAN8qP@zzM6szf^^N#Xph!4kBhF z?O|Y+?_rhLxA&h4O7KqzOQCiqVdyu)^H{ze?+CY8vgYG`3YWv3kbzE-LT&2=Hk0o@-cM@keKzaSX2Dmj9ymjK>5ZBd7><-mzwM zR_+GK-pH-qzr%+m3=X$`5h2~bPeXmkBYFXKKKUbl(eek?pedGa=BMT1 zoP4;9p%`;-k7By{D0gxD3zf2#&dmRWSDw2fH9 zwx7iit}K$@l?#A92lSww$)mYaQUme)oP?a(u+iE&-nN4G`ube29I)$3ZU7Hf=r8$PjmD>V@EV32 z9IIvYd7Ryd&5~K`v~IGnNLj2JaiPJUUO)MEEf^?0y8#pwLxYHI!kegH^XnlH1cc(r zw_5?aO?^t)JC0FsP02Fop~lKqKnx}Hf7%e(+K`jjWcfRk<J@D@E)X3fm z1I-kmgt%@it`~sh7?sMOTE_kRtV|bh*eJm@b`kZ9#$%*BilKc!eo#J3;gcyGO2-lN z{h7|(ot;0J!q)?2a``m?Xp5rwa~t8Z#iq%WmsLK>dLt50LGT>>Ria}bY4Z+DEEOR# zJyjaU+7Wh;4Akw6F_v%t{v8jX-Lh9F(3Xj1SU+^fTO~E4`)#z z8{(!xc!@R;z%N915!IG>f3CywH9s-N-M{qT`d+a7iG)Yee;`GK%&b2_jUr}qS=8*< zv{dKw3)jWTU6qrsz;_ubJc$|SVKAV#W;ykQUmUMR@D>6gUNX09agQ;Sn^m4&MiBQI zKJw?1F;7g|FF5B~5T7OwTaxfu-NC2ImdVlb&oE2zJvlWuzUR|BFF?-yOq&!Sn3zwI=> zIa;LI)|x_NcwJ|^IZ?gwTog=Dfq`Tavo`LEFz@HSkMT^EV2Z8RRNz%e_$JZeq>?J}fd;v-(0#!eB*#dD0Rs9gL>Pd^H>WFe$MN1tnZrnl#`}hz zL|!F0(K=t5ax>XA2r3edBd>bEyq45{&$L9v0~?6>u})j&SzS5sH%8r^uS5jS(%6F=(_whUXUYbjjgf^#ggcK0 zVz}sny*#qCDviS(2x+g9RdWvyv+MqFbko0~DUS$;jzp@CZhw14QiwpLKydni->f}L z;zh|kRY=25MNHF^o12@wkjC>(e^4uR(<=>@=Vz6#OzL&(-q5|w5$jQHelhAipntS9 zn#_}j>;tHqSAg0X11unXkV*@gAF~yS`QBo^{-)e{Hq(}^5H?_*Yqb^7IMY5>c?KfI z)Q^nhhqRoWoPeAONu(KdO2F0`A0eL88!ZrJ4p4+k-1gHVvvjBy>v7&g37mBJ3lJh! zG(5_YA?ER{sZnZvF6yuuQ^}~5(Pn?}%4K_+YyJw{$6(l9q{=uKX|)Wp&uFb8QACj} zKfVfJRXp5!nOzuRXDHHM*$Hb-r*f~qIV|GVd;KyMNxH2T3^&_HM^#f1wgp)pU~KE2 zEr^%dm6#HYBZ?u@*pZWU0}qHL{qONvl!r$=xZN8I3is_fn1Y!=oYCy&hph}fIuaHH zl{*CD%QLt@1bw{%`$0=zCRU}n7R$K)K%d{fh=gBTJZ*UNVXdl__YO(26h=*$p z-fp??&r1Y)o*n|V5Xe^k8%RFq%T zH7*F!-O^ps3P^Vd(xo(rBGTOt-Hiw$9Re!d-3=1bFm!i!{4c-v``-Wh)?&??8Cf#( zJonyn&OUqZ6Gr3PYjg_oxVQwM4VEj^^Cru>>tD`Q$i^R+9&cL2gSZ2n%f1Xzgv_5A zcelVjE&046vn316H@Z@49n5;fJQzUUTf-=R85V!oDc{glV6$*Gj3>;JY}>i{e^~@WM{;C;rHt>Zo=TU=?hvO!gVnrKI%PR$oO}5KcYHU}SMUcE&IX=f{$-mM*wNWQK zTJFNsPy96|wR%a9$Z-BUfY6_J86F&WB`<~Og}?strEPyQ zYP-NUnO^u-?+#84m1eI8f-;RCQPkvbGQWB}Lr;MkNI^y~sa79gt|`bNezg2y6G8+d8)_%qt zI1fe#e&2MOcUTB*ntZ-h9vgL0j?<~@V$B6?3_Pvzydl}e>z2)CDI%V&hcDAe4bou7 zU4aIY&qo_5J@SJGvp-H-5+81`r_|lb;clbVzcxMgVd;r$^<;B(JiE!QHe$}-vFgST z*GAp~N`?HkFsNUIR16*qkjC;(A=~g=@|TdTQS0^11nsnScQcM@FL>V#SLq8%d!lhQnw_j;6KqpU zhHS9uR!W3_W6Q=*CP0xB&!*|74<|D1I^9}o2thrAd0fbR-$|J+=eimam7EMU*v`sx zpW-sUbsczcj;yJzHQu{EL;Ywf@(+K^wB`Pl$P&JR0!`g!s5e5fql1T$<7Yl!9>{$W z@IOa4e;)tGe&>wv>GQibWL3`G$+u#P`G@lMS1q+_TMfVSJ>0i@FPt^hdZVFRLbW*w zjkMbBucs%VzNR%iAB&Sq9T1`J8Wg1o9VZC8_p2kYmxI6FH+3m>?=~xVH6Y6KBSJ?W>VB9=ZN2NZ$>HzA zA7JV<$;y z_bOb%NVywM@8lM1v`Sg01oP1O8Jb)vny+riMksDa=Qx{w%p7&*OP6~n$iZCDGMsJ# zEeL~ULqdG=B{ogXW~jma1${|*WHiMfTKnr<@^3bc$TxH-Io%z>=-t{C3A?vU`N6BI zwXO_vZimnPXA{1zr#GGxH+COLJ@2NgscaN9nI$$@vzhAbdG`^VIj~*bjD#l*jg7e* z@Lg#jI)AN#chuHh>rbtdUr@P!2^oY{;6YS^Wmo4Wss-(7L_&zPQYk$^j z)2o)tsf{S^^`F*LmoWKD!Y@rO;J+emPXzCf`o6MF^C!^@4di99!TgyFCftZH8ENQ} zJyl={)X$j)7zG-|`sE)tpC4tm&)?lpHw8zO__?!dYyWw0hW7H4l39wF@=1NKL~iMq z^iD;I46{&SqcUzeVlKCS$&0=b->Rwyf)NIk#LUDS`+Kb7IKe1Oo&p-74`TGP&@RRLt9)({?hJ3Y|rw)>c zPB=fX4_7*>T4AZeG3-vZ&4Q}Z>DBX=TMM5ioyD5ST8Gv+3?Q*SH9VE39*(J3)wQSP z4~4@1(m(#1Di)(M?WIw_EFxi5%9`EWOA@JJspADq);m4VDXL%lft%iTl8gn*!XGp& zs`2ZiV4bCF&DnBk6{FG8^v&4QSZU|tOLKo?QMakxLW=k|CS9cV|11o#o4 zcQ6))(|L}+7G^%0cFCEk04mv;mXNU9R_GSzbA#x4<;C;YxEQ3*n$rnDj>J&?zA@wW zkYw^u>6aK$!iI#{g>SPvT>fq^f%7IDQAH=@qAIOY6jh2)qXi>*U3Q>kyxk`iou8=;g)X)9MbIaEC^A8p6gF8`( z+OBn^=PNt2waozqdq9qKH?@_8;FfTVFIIW=M61S- z^{0GUUjFb&Jhzj>YbKFats`;=AEHTh>w|de?}n{3b}Htm#2aIN@F@L3FEYU*p>{#C zOr9XF>@(w;HB;zD1#PV&Y@Ossf*=&uvfzq}r5C(eY8^_;v8#&SD}i`^irl0S`Cpwh zMmW}vTIP4Zpj%C&FtK=HWsjxm#&L{BlEv-yIjPUJ_U`jY8uqyE%P)jQYF;brgR19Y z9O}RDfg1=-u6p*zw~9&pTrXdtZoi*1Lo{&@iv}RCyijwLOXkDd!C{1`@{bN>)6b_SS7GiN|NI-hK0;A26}TA-O*bL24wxqY=64RgH^Y_Fn**}x ze*OKDIK+PUf=0a2e?zMvOb{?a6}2qCk4PocAe=FB%rC(TT1DBeE;h*(-#en`v5N*2 z8~V`w3`PfHlWj|`2!b()RI4{|9B(K1gs6X9-Qt~tk?L<-QDxnI#!r7VjtZSw4oti_sFC% zNd`C)c{V#4QuJ3yz+Z#(${>mkg`M+e}`Ys|E>>1meV&a4>ZC?jgENz8tCY z3}wPXg|^Eco>}x$Av#&@1(Re0C+{b5jLK2>cQ-${Q0o}rR*;3HeCU2Dcj|jeU1IG< zmgfvj9~sex?zGa}xMT`TITA%X0Psc!6YdqF)5wtS=_V!#r1aen_;oYGJAjeEn=`cz z`FmWZ-C0Vo!-GP6yFaSg%Q2%RND2GX)mVR_zkhLL>fOg#&>x&L8ki#Z?Y1>GLH7R~ zw%F5#%VC;E^&}d{$LQ$Rqw>n>lDY-ea8s%)3@K`Rcll$@FI+&YdUPy^Wx^3Pk0Wmg z0|Y$ua?71gHM8=3TTHMUyFoygMn0(unPWkf5Y=lPb0gzv%Gd zk;xRE%<|Jm-j52wlI^(J@(AM;g~Bl?go+x;KSIy8hb#_Yok8si9az?bU3nl&e17_cs73QL=d|Za=-g z=w5&OBZuni{wInmSokY)spsR;lMV06ho8Rb*UtB8{`fb-_8L@Y!x;vR!``{DvdRL2DQESJlXglAz2)ml}W$Bd(_?$vd?ad`DQje z<+N~ncq*zYSg*0mwZmyH%b_(D-mE}{>XF&QYpW+(O8LQEn)?0^n;b%6_wmlg?PD_e zCxyjzn^VMViTT|EJLkQNKEE$6h8Y&! zW`}O4&&Zz>w(J_WBE`Pqg>v+I-uQ zj^GRzhie&9>dos1djK(e$z_v9Eovqr4$6IFyx-s!#)&60TVW9hCStug|MAKu3cznH z>#QD0{z{()QbGYl#k8)#5!7Dgg|pG0D&!^5HVom9xg5a4D?a-#5UHy?z6Gw9pr}Iy;@to)LbD5sc;qB zHN9}HB45tHNg2WZtOAE~abLN3`u#adlA;k%P!kI{GA(zY?Ar}e)4~xTo?YCh)A{OZ z1YvEdpl+q^QnR#Oq|}6?c(G&}r&ls*Pf7o3D|*LEI&n}Jblo_S0kWXyT7LuM5Jwdr zDEJt#KJ#_d`-)wbn4bmr&x-oFHH8{zeBNdT_>Kt(l=6mH=(Vya(3v&Kp5dnUWYX~k%}!SyDQE!=Nf zKX(FWxujivl4AvU4L~uyC`~Zdr)N!+b=F-WTQd^K9V9jQp@ftzo7C;Vk26?qLHAMl zBFPxpnX4VWD40hc!`k=}g-*Z?X)Ae9O;6>a(%osU$w^^(xX{DJacf2she4F0jTv(h zAIUD+Bcy4+8vvV_ZwS~l06{7gC=95x-?$v#O=;g>gF(1BG?^Kg9oH=Tr7w+;#bHnR z(342~nX@No`hWIMRa)b5f9NqP$poUHEI`k>towwZGBLR5^o@Un9Me1iI2!!@H_2uf z{5^gY(7NxBR%AoGt;o0^4+)~!^!jrI;qJYb+Aq<$?Yyk`SBQAmS`x`$z&AR1XR(zmYkoPh55*s;;7^2?581uTG3~ z@h~$6zgLQ^Objng>tdeKZ zw$GZ@F}v$-n;($toy(V8PY}B>fx`c6M>hEZC?Ys*caepLlHqMOoFN3u6ZZhT+SSjS#zWLhWwCi)g}j|T=}b6>gd&HY9qeC9@LG;_c(JN&OLMUJM@ z5y!;cnQlUTGa>;9(;xdtS$k-~@Sv1neKLN_&uXKZ$P%m zg6X_Q%{L;2J{1$|Kt<_kmKzzM3+Gi&v(eKq0{VV)EXjb0FOz~Fx=?s6f$|* zg?U6_G!tue2rJYZ`e`9I@7G|q!Y?mbXyCHNEzje0vOoZs53prwuz19!Kc`?;( zb4OXvnz^px40s+bBdWd5?Mi$gd{RJW@@-lsv^bf??9Q3N&Y%Zk@E?t`l7UeRK_dPF6j=^<$GyOcB0$1Q*9A+ z7Kr;a^*4!{~aj}003C&}J_*M+`;W`a)gNNq3liY&su8(OOymz9% z_FAguN_}*7Vq-n~v+*c}1=a)7|1q#}ebHQ5EB$cTjQ1CX3zFWnTnI1oS9XnuC&th# z5ULl-X=Z^zfb~l!D}g@#g}u%-!+pqPbzu>(Z_D#ntXxW-K&4LX?8Z1hctB>VYyUhW zgPn2kph}?1CK}|D3ZjoL8#8A+kp1bw-_*_dLfy?FBDQyafXvK01yz|RSirRW_1$z#?|RiJBq*{2Ar@3W8(Yg`7m+8aZHCG&mT&2)qpX<|l3R6w1D z0SMgTL*p+{)KvJ;oCWCN-U78`QLmM;3Rnc|wAelzk3EXXhfW?(lVYb8Uejx>G2uIk z9U=}sYkh?BoyuDb(m5+%>*lU0LJS=wxF4DQT-fh8EjoIL89fi?g=+{o0eh|Ar-mQ`>%KgE#l=8Jy@MVee-!9HildPz zT*VZn#1Jg8lcL+%eebZy%Iu^+(Di=Jefl?5I2>4k<^TG$tuFSVj`7AGAs>E-cAu@U3^4TJmsYv9)M&!F_`q zm`gCr*WGxWw%od%=oPc+H9*9rrKM3Ca^N`n<4ZIKC-nyXtiyFPbV;ws5A$=msA7T| zf)v#YWH}YAaBB@(DJn_ubO<|QDW(^w@$HV5rN6R~3T27&+iH^1__w@IX`m~jY*7TF z-n?TkN~Ets_NE9+x@xMt08|w(KZ-<3UZiXlOP;J^XG6fb65NVF8e9e z7=QISMV0PuL^EvX(R(>)xnncZaPT>X{EhX9W$%F2u87a3VT(b}>uel!OqqT@oZ|6o zm+kJ?A9N`cH!LffJ&{wXj^<@TaO(PTy;{_5*G=v+RqV#iEC}=9Ybs78-E?!PJ9(r0 zOgi@I8Fu*ZSR!qRme47N$nz}&JPj2*j)Itrx|YJas@1w&j)VM_wPWPjo}*|8(aIHf&yfGVrOFC?t%uv)^Id`l~=9h3s41y>iqZ z$a&cgw`F|@#wPnev$E;vecL{osx9-8N?e%sGsECcJ!I3|`Gq$vu2`p(rioOLu-1OV z`42bl*j_dUsyKP}r|cz{-=&LrhI^B93VmR2WXX-N+8S?ch~a#qfaHq&@c)var8c{j zn7>_>*Vc6`MGo$|Np~>;BFPAI<}TE`N3Wziu{e^1=UF2|bW179L*o1&N3R@gohp(* z0j!Sux3iNsq3OBsbDQQft+K#j)5e9HgX|9l zYEfEJV0|^TQs+PIQ9qOSJlhwmu$rCl-V;`X&OMJ&JY!1;j{H;a7JH+aXwwYCZ}UBR z(HftW<<`#Eset9jj|{|@9j=u?;Lp#`f^S_JlR;rE{OdeKYz9S6MOm<(v%ULsa zL@@R|jq}U*WLo%E*~KS+pT~M}MI|jL;K&&4rVmM-eAeaqvW&I$Y+<>o>T>TJw-^-t z?Z5kl={rR_--e`5(RFu`rysri-9Y;*b0A)G1Nsd=|pk&V+{+4nMRX; zQ+v{c1ue$%eR-?r`~>$K{#~Imt%fT{_{*qtV}+|O9&wbKw9?>n7|i9#a2{PAt&FUE zXSB8Nd_rYYF*KRyD6ZK-eAEC@A7{cHXNE1Oe_}E;V}Ng!SOiShe2oI!%Zl&;IC$JK za-Ux>q^YF97sVQh>c6y5m$MoFMF6t+Z%5x*WpS{5HBdM)1v{PYU$k>sb`%Vw6F4l< zWQ8w8Ppf-N0700Vm5V(JA%{W4$35$=Eqz+wf$yU!(d-do@D5tE>(IHc&dmiXaB6?? z_KCaDIdW4wdk2OW=i5m^x7cQcGZ_q0za9G-*5anHA{W@2T)B{NDbd3j(ebKk4oW@6 zHt?m8$(yxyI2-&kU9SJ$`r%@syJtv*=RmVi3u8eUedvVAPgaF-tGYXT`Rn+l)9nY~ zo-lL%mIvsG9CycXAfiuAC@+6o-w0d;OvjQW#E>TFi*gk`WXImexBb&#)~AD~S=0sx zB?yXP+EyJLCto_-aye19mqz0)f{}C5eGtx0dC=p@h|@BGEViaU6VV~bNR3CTr5GV< zF$HI$@s3l=V|b<{UFFNI=%vRw<>w-ky^oQl4G!Zz>Al~e^=F%H*SVY-|CdbAg6nGf z!s4Nc`~YUFHwV8L55 z6vCw+c)%SKj%kc?a>dw5p?rDQBsIANJqDrFlo@)f|E|Q|9f8S_xpm0 zV&t-VsgpM$c6a)OBs=427SdnE5J2>xi3Ha|ZpW@t8zGJnz_r;cxW0g7whS23OuD=^ z6js_up+3m2jJEI_@dUFjv?7aBCi~De<;)s;c(KUa)2P$VI^o+VKU3!X@C-$l`pw?3 z!pkFnxM}84b-w3~xI1+i`}6J}Vd{g&{=0}25uEOyLP%fPOm?0_jK_%?^LJ?;CFV;K z{~Fj`=6oj?T-!^3YBe3d(VmwK!jSC$hI;aHH9NY6^1Y%WI%q&_Cp05CQPl`RK&_Ts z3tw6sA-NR5B;>v!47BgeMGePqq-14($cjErDfrCu)3hU>!}h3ahX2YyJHz~*E>%(a z0JUZr-CXVahhYOD}%jE0Vllxt_G4Eisg_YY$Cg z#q*6LC#}H|X=`9eNIDW$i4NPyktz^!@IvEOBW3hKn565K+i8B+HsznP zr*aQr$0`?M>wH*F7xsA^lBcWmJpvHhGVeiGZH=qcMt``UW?!btNnQTznwCbP7C~Sv zd0-4%?|}-*pI>>%A!3KvQ-BK{ghd$zCV;THvJfb}ip`)X)vxOI%IM6d9TS6ke=El2JpK$q*4_?+U%b!jGek@P|H$*Q73n7-FdJzrTkH42OgAN37qn@P1QRB{ zuL||Y+O^P5M^TDKxli8m5#BT%!q+W$6l>F+++RM$sv&Q=nJhEwNfoS?X9dvF_hLVH ztq&5sADnOGuc5DQ9C(+4qFE})(~YPr-&E2N1+eMjY%DAF5pKnO?8bmbDmqmVa=Ff~ z>0y=hb6-8Heg6W!_c895+J%ZGvg;267p^()n>`bn$7{7kBbEu%w=}$-RP%hjYN~i+ z4R2wfPny80DWjN1OeX3L|7EhUv#)N&&Lw~}+6VcGkcSoU)Sjxbqg6^1`rN?8s*!KBeuwY(0bC7cyv>{2lcbk+ zS@NqD8GpHx^<2n-|DsJ_eUY81C$D{uss1X(d7!~|{7*%3&I)NUyP; zyfQ?X1FLt^wnoZF;yTr3{&T~a+2gPO_tPrdvfy`ps4Uv)gC*+dd%3++tXgfYFWX|9 z?Xy?@$KdXo_-MOyY@7!Yw7uGN_RT#JR3m}`OpJrKb#B9e{Y(1_ZwW&jSAQhTQ zG~$87hjf}#!vuphNwG{HmiSYmM5E_M-l;aIu;ce7;+1ku$FhFH=Vn%WA9SQ8gNYrJ zvHxUjcpxsk6nH~q0nf|K=_ljw|2vk%5ZY3Fni0<)%S7q&kNozlA=J9rG8hp*I9s{; z_L1z$u!FpeFB9cBZA`9(Vf8D4M23o0R}jRZ8zgv8(|&e;b9a+n_`{_hobbf2EwUf) z56JW$_cGCrFp~1h&AT6*2M5ABP5VZ_+%(zJDI<&7!+x_8NlY)hMNFm9{-F4xM391e z8SI1L^kA#S{J)otCPoSVo^b3PEH>TiBW88QpUIVIe^Di3>9zAcXvX-WNWW-zt3U+U z6PI8r1+A$6_||-t~c8J82Xy;~ND`C2Tm;$rfZMfq{5 zA)CNQ{N@Kd=7#f`FXDRr*hR?*XD^-Ri_u(+PAi;rj+ITwT2FP(E#D32YpK5cqlz%z zMegOa(G#jA6&n|M}vNkC*8!;T#P<2OMr8e4j@V+R4G3 z=|-oBtv!mM)irH{R(+R+J>)0f9EM;nj}A9QwQI2{~cm^F~hjjWLLy8yz zV81;BBhsIN@{I_C5!{E1(CrBr<6+k!y$%>EYc{E`$xivk0LS0H^CUwrRH!GF2bI*B ztocZu7E-JcoPp1d;DuJslS427lbK19_5#TQ|O1A%%YLiTzL@R;Bj+Q){bhWml- zUX|-%E0Wz#VRewfnx^UFRRupGPvGz7y(Uv$$^3rzo3Ja2bR$vg09H?AWz$H|9Zl|# zu#uA|Abr;Dey+G&U`;SrW~KmU-*koyGItVQpe4P;FEbyZaTo{I|M8Y;I`2k!yiSw2 zn8UW32a^NSqD8h@gtdzxy>-q};G;laFrvWG6oRtS{bTaEz6-gG_r2S53$oipkdxkv zs9{KpA>2wC!RnmMCyU4ddb^W{OZ$fyWxGnyv&(PK_2VLZiXgPqjH2+DNyv3pv!+_haM*N$k_ebooTzGt&hCa|jPbw0>>S2#2P?fhcoi#AKhjs-*{J;;idT*8HTvL;t) zIUA|b*24f6LfOqi;aT;ZJsO4AscLy98{U6cHcpFA3fisZ2^agc2$HeKVi!Q+3+VRQKp+iQTqEKEKac4B`w7+%yZXOv~8SZQPIVqpH4gD z?ZAr_vnyQr@A>Y0B$(r2+_%~*A18D-z~j2uiqvQ@QR3}2>074QUaUbau^UBCh+u~pS>YA1_i9FPB7zw9x4Iwd=dk~Jx`Nk zAp1*3q!7-a%fAUw3YDhHK{@=B4N`Yvq$D8HyKZE=-aQgL_95y4v#%^PTDtUF;GQth zSn?zwsRbsvEe{U=PlkxXS~$b}H#P0a_B+8prEmRrv$rf{L14 zqK~HrlDZPT0P3bVhGW1RXbx7$%!gcL0;U1Dwy5{4N%UAe?>M#d4@xo)$;bI}nBD3Ruz_ ze*aV#jxF*WV$^E^r)Rutxw`Fw!(qjq=T`0fZn8e-f5YwrtX_pGdbWOTfpxdZ0{2c${FjY3yTXQz^lFPSAZ385yi+{sW3Hu)2%dL zs>}LV_?`hDQi@7>?bSoS5~o&?%H<{SaWEwm_`y=M|GodNLZTgh_&1c|9HY3A&{4;7 zqQUJ~-h6X$1*(J@nMk!pb`89Mz>NL9e(Uqy>0>3Van%C%a4`X7*B?f+ z1QX0Tpnv%km|Q5xVmN*-1N+-UnrF3MlbG8%!3`>wC}>DJHU1)HhT$pq^_6ba;_8;e zPlMa~H`AW$2XiB;Ma_E==Z(Qi^%7llK~b-R2J54Ik#c5A2fz#}?=u>6jU7~tVwERm zVVzXaJehcFkJ4QN1Ic4)_>vt5xLVU+pYMeeT8BF}C8Q*EUaY1TEzyGXb1QdWiB7l; zsuS^eSrtbMUZ<&=vVRSMhMPr2NV(cH&D>d`+g?UEym8nxn?VKg4?Y{-Ot&hVg(zTD zhJ;|n6zmz=mrP*R_e~m1<9zGs)Rj~HrMTgiyDO4>=goYBG#dKNrD=U)@Q1n>!m;?9 zvUnGFxhQGP_Xyk(V)l5uV*yU6Tk24r(kp|#|CUHIIt$`X*M%~C(X3LJS!@w!OGMTb5UNxp=|r^`(`jVL*Qn+UacjL z{CUTtp7*um#qZJEG^M@zYZDeqhAppjCwUu+I*~Q3TceF^F6=1}ACqaPN&R4;^q{+O zTMsX>z9^U7;HB%dg5~XBeBp1_0{QqZs52zH^oBigZd7pG0~cVGtiYOKuP)5kFbFy) zIo=pLkW^awaazc?&;cbCH*sS$tS5ir1k)Ycs!N{$^GSb3_lvHB@=x_M?@Cmt71M-B zZpr@=#`(Eh7&?RHwL$&6DpYJ6ALGSOQ*fedCf0hg_{F)V<~oBY8)B|xsC$ADQBgZ3 zBN@dNEKKk;*lGxBxD)FC2>%2DS3VLjw*n3d4l^34yU8x1enot%@y?Lf;Z`FToppWD z_vz+bfqER|FAnr$VT{+O;y0M&+<#J32ASdzoWeGririv@2;|~KB>5zgoDWlon0JmX z2f<0u&>0Y@yQdVQNf7F_C37Z+?$AVPN!dn8z#Q8Pz2yx=NR1n1$NN4kKEs>jaKy z2zY4(8>b7gxt)tdU0=?-mKXC-?4gr7;FDHUO5RQ*2qw}hd{Z>nC}%1vbVK}=Fcdx7 zX%fSs?EGO6_i|XE>N$2)C|!QAY4Ok6xA+vG_4b%jw=lz_6LeOJ124|EIF2n#pRk5h zptw*Ub%dtNWi;DC66>nZ{}@hdE(~^Ot2yNVv1sJ`%nCS5)t~PH3fp2@9R}TjEzy`8 z({4q9dL+{I0!601!)lMOak{79m*Pg=82!cSGD!)QYTBHe$Rt!;kSq$qe=GTm(hA1j zWXirK-!?(nmTx)69=(P!Buy5vBvRr*q7A*&hl!sQ;2LlG%M~phU9yMo6fb7@U0?on z{qs=&dh159-(RABP6f{Dd16L~c|q7aVYjEW09&U!1Qyk?{WHWJw5pB>^cq@-kUOD8rJfI&jDSb+JVhL(87& z3(XN;7L#gdM>!Yjn7;HP%kiU)gs3YkExu3r-HtzmQIg<~-kffkdYhP<#^>bbKhBjs zaoC;Ws;3lwvmxH{oOR!nLBqgQ-LrtTTi3!g%FX#;9_E>MMD@?MveDyW+4tt4y9M_ZF=rH-Cv{}~s{&mr>_peN@1ve4T zzG9MwCK;$nf&zeyu|3e(Z#FGaCvo)adhOtL*c?9W>IVpm#8`rr4O5XlO~PCO1HQC& z&g^_9?g?dABdgn4`TDikeF;7O5?A&#vQ;mtinM8dfHPqhf#ANE_-UO zH%>kJS9wK#Zz{=#?+blJ=G4;w^yv7vad9#GZn65tUM)Uwj|M)qLin94r(@HNg9TPq z0Xscw{7XqI2dgh|0~{}^PSE`UyL$15O%qpXg;}h;kMcd|s`7|QCk?9DFxvJmhW9)B zQ6bPf&=3rcPFVe$dQ-+xyUMP(*DrR^?*R1Tc}F-6EB;8(&lm42n8t_DFXXWTPd}x5 z5dvoyg);$qxu@Wame26w_I~xut9-QK{7kS=B`@qGxJqU5=chV?WqJkyRE{~r4Q^^! zxeH0VXWPKr%l!=u`2bf|{jDsnF4M-nGc(nnIuVntrLJcp4r~x%;ru6ri;AE~W>tP7 zmIV2TaqCGaDqZLc!u^?b=`?edE>hb}Z}9vshJ~K51;KIl7y(xgQ9LXlJ~r1E0M9SQ z(1sM4axM-Q9?H7?)o~}b%<8}(^8SXm?eQ`1=|ND9e3H(2_7m%pCdXs_M{yGuH zfDG%i2y$b6LwlUpQRC(~H6UijTe4@H!lFEk6EDkFwDdMPgj6&6Cho@Ge%9Ry+wS{7|@kYg^HBUn~x1Dbta(5ge zcK@ACzCyy2YI40<{eB8Fd%4gaKdbqBDV)0Zf}f=9O5;R&=6hn&M&n3`)%NXpTZU`{ z`ER=$ofP3jAE35N_LusH%lp%ylICN%4^r0kbKZ5&Hbl!AJD~!;o2u+7kea7%lNO)t zSP)3>$mFVQ{Ay!T<*!C?R<;Laab&KXT*rYWMO&KM<}>?4{E4+(3Y2U~(40I#m?Qth zttMAZ`={TRgIhK?&n2-(1`Z3dXsc^lec2;TRfghvqBNPqh};!`;H1r%5+NA;r7nu^ zVPUw0?wRQ9)Ci{gr&YCxv~QP}^wN9p+GleW6fgelg7oNcrNJtR3ldc7PFJpCLr;+K zO%0CGV){P$+vRp$zuV5C_%j36Px7;mXxiSsn4}IY`(zW=Z-s8ZijuP9c7Cds*rc1Z zbuSfl_ITxJscMjDE(=EmF+6_GGMT)3m%53svEvsOg~&NlR5{>O3~=)5{k#}1_5t_s zRO!NOln2ap82HX3ics^&J|Xzec!#-r!YR z`E>#f4s{1O`9IAu@ewdfD)K)>%oZrtBE4EKk!G_{_f3=6_g zMHM&Ren$?0e2`~c=Hr*W}jn|tg`uwip-duRK=UZpui+0vRgtNo#A;$`k zUKX|HrF(|~c2^EF5vm^k6E4bBH3cwudT1D-1NxXtA~Y>c+(sbZlmz z3TCFFUXZ%b`1?2={0paIn|}&I@!3wWA$0eO+vlo20e4KlW8r$2BjU=g@#-PbxcWJV z72^O*5EiP!Q80cL{95;DHv^I3UG%x;aN%3}KhvJX57r`nmAY3BV`Qk?;Q&JvW%)Yb zkD65Z9}hDGEroqVE)fdr5?e5)QA7YgFn+_ ze*;nuT4Lwoe=}TlN+2_PK=8g=Bf7oXNH|VAz?En@;vQg=+_q2BWu5_43pVTpx zO*K=}w!J*YAo2cdde8mpz~ASYlO7Is$EU9ytN^@rbQfHxT47W%2c*iP1XO11Grcxr|F4g*ND3lrkak;Oc>c_h?g^h{a>N0Y zZA0cI_ZTx6c2TS*^7cG2b(bX}RfBku+lhmua>r`7gBvVsiSgqrD>HeH{XGxmBwMx} z_D;Hu1!tjND}orf(7J{9BwikRdk#vo7ikE!meWpidj0M1x*H+dEQb$guZv@vK(Zv~ zVko1Prkto>V+*&|cXfX%D>EVK2Ee`l;Qs%4)Cbk;UYwc$^dAuHdkQcg>q~MG!ssst zspj|lQ&~du`I7~ZLhMQdWzqRTPzR3NP@s?Fw*t}kb;D52%|ADRL zzJmrtB=&!w9qs|3n%4ZqIuNpc+RgOsTdYs+0)ob%quOviM5zdA$cDD5X zFA?BCvhqKq|FJmv?}z3qNOO?)Twm!vzHtjF0TP$^J#2{daE4J~V8O6y1RmoTkzEe! zT;PHWrHv2f;2o)waj)pj$X@REpH_vW30*CDq_0PnSpRYS{3G4WfrohZ>7X!@V(%Bf z76l*cHRe4YBYUSrUcSg@u`lWUH#-Y=H8-77GN9AMbrN62aPA?Mgm4zJ`SBItWC6R+ z|NUfbvEY;0?rK)bKfdP&UOD|^^%6-6CON78(M$x5qqy1M5VChzPpS?4%zsOI_YsX# zC{%Rs$JWkK*I~0_tg>UFudJZ9L&aqiC0j?%0`CuQnTApH$S*`r6+&GTX5v#X|( z63*2ej;E1VJP{q3wt(0bzUVm{_M?ZL;*R-ek!qm)&rSW`#|1!Hxk&w9^nY$V+T+H0 zfA)7_Y3>S*3H!&>lja&WHaaW)f6GhEMmjh%GxGXY`th-$1~-ldogC6y|yQn~#EbdhqH`V`$)h1)D)5gmuv%)UT=dex~-pmdtwdH32BpX}^3M&^gtV zUF{=*GuQ^K9g4I*!~g$6JzlXEYOsOG;eT6#q6NGb0{C0^v;#^$$Z(#n&m?Ovo=heS z@+z{pTz0Jvx-Q2fT~kESH4@bC1R9n)4#LF`a z2|cH|*xu!AC9A4WF2fW`XTyp92EI$b_P*REmgPZ3hlo(+gj9^ZQ}^e`gm}g%KME^)s=?i~Fx(AjAov@6C3^ z+Nx{C z!V*TtH<|!jcBOE$tj}^BOgFDbJ`bh&zJc=@HXmn zSdcc+1hfem4k|j%lx%W8a!d!xE_^pF+nW0YKfn8qqw(EO*E`vTqK;v^-*1!o+$Y-i z3R(Eyr&SN6Q#N47e`2HvOa4~EHgtEOta#<6&~iO+&;r^7N*(#*=;eG6!8CedtSC>OgzvjftCBRh??Kc^}Jrk8@A@I5o<5Ou`ZxA4ks{;`<2 zstQL8aX$W4^jvOxzm}(1LO!vyvL@~SUu|yz73JFg3p)s#ln{^(K}u;;!D**6&nSjK`CnUmdq?8@h_t^mjBztbabKlc3#wcegd zn&TMYOBR7%Ii_wcw1L+Q2qNVxiIvMU0;%NRsuPAL@LdXKP;$`}@0$}XoJH)Ml*U&| z>1#b3r?ppb0KyC=zh^bo^<*rbSb| zmJ+Us5NPZ$TTr#$2wFPbs|ndz9v(K#e^3PtzTF3=XR8tgJOq>!M}vE71tt7-dw3G5 z3!U`x?l&}1$dMH!S#waXX$vX@ZU=~lUp3!J0M>D&T_-UP&kisd$D8vmPyhh(_^23TKANWy8FHK z$D-X8F;N4IGpzeIyUCD%&ewM*F(Gf6$Y=IJ*K?I`HML}u8}3ezTSE7bfb~*!cK_%Z z<)#fe=;&UXF+S@l6JpLEJuzX=XKCkNsKD%*<_|Voxy8B-2!|t@@Z?a#2B+H*Yxwxg?c0rg~&W7 zq8kw3kcv(A(-fN+UX5Luws^0Vcmzv&PB|cCS{{*?T1!AN%72fY(OuSILs{&BPk|vs z2~>W|F*H>iNK7pzt8?@3m_Og-(C{7*^{Ux+wuufKF6IQNr(aoeY_Zv<#4D#W`S&;y zz`;BUsw`6gJZ)A0uVe01!}l)=SFoUx+GE7U#1s;z6COw&qfw{ykcB^bRZhvY_KmU zG#twVB<#>Wv~4^-`bndHbOsT`m2*T;LK0~Toe#E zQVj`J*HhorCS=>Nq}N^ysFE69wJW>v{)x+|Q(PY|GyE4&y$XZcY|ya?Xaf^D6?k-E z3Oa*>qMeWps|Yjb#F@*-X6JjdH?#$kz3=Kkl!;XKHFoxe&<7BA;qDPA8@HVFDw8|K zHbrb}>@-trKLq&V+mnkQU%1qr+)P}rTrCjWpyj*Q9HMqG9Zcbhf@5%SfZ;M1Hqe?Z zDvI{nyEYbvxMKj$Z32Qo;}k@x#i=!G)1lX?lJ2b`b{3{hIH)3kc;mWx0C20VOeaXe z%H*If4v0IATF(M7o9y_vDuCAEHj^5&BtA}a>oa6aKs!fg;tB)v`26Y-pStdJ8wrZW zKV0b?4(8EHkq1o+E}((8Lkn7~xjtyU5KbX?{Nr2XUM3|{P5Hnu(@z8PS`7j{pT~Ev z?ZiYzDge>D)ym|O0cHjZgof$Kqf8e7DhBcTN88(%lulj<)t+lZ)q!$cKyG|zTQ_gSB_oX=By~>j5D@odFd2?e4 zGe4CzzIEcFyhm~tQ1>ZUv?1^n{@%ll%Rhw}@MPk`cLb1A-m==ueVM%gwI*|Ryn}r1~>YZ)+}I`$NFdCv9iYzot7Mw$PJoH|+MMp&Y|ZeLO~o?D%q?VWrQ6 z%%jR`1Hc$>I^+Nl7SkypI=6x%4^R&lntP@8I=`cFxe5J!%()3Pmg;6qv~mO`XmK#D z3h{FCdEbHJfx#`$qY;Ft(am)0z_Sxf58Q2YTEV^blAL*YtAOr8UC+V5%3_>fzvT^3 zP4jpIIup~j+>xDKY{B8wWV_14JjEyJs^u;T+y2D+btc&?amN^8w103JS!1MuEl2{oBSmr z(a0M+({wBpSV+bnTWCZi%qkg*rZe+y(D)&7dwN~CF2Xy4m*-sv1J5wcvxDI)b(@c9 zUQ|TZe>Y+xO32VsI7^34MP%%021i(<`Y;n-={`L>>h7Sk5cdEn9r>kj#ZZzYrBEza zcLxc9zn}~b&ihqw-uhL%o8aT}2n+uf&;%~2SfXM9dagoqCS+D^uk0zvk(frx7g(fg zx`;Td+NgE7WSrm@)E)B*giI4_ZAP`_P6qhzW4W|zqvHW6vn-j|q%QD8r`*-T)bCfR z8G(n^vE(DW3P zru!gnNLAn|su`DY+F95_k8zmA5;ZFndyXRBKf01*$E#(tz=j7Dr3&E5>SSxNaGvU1 znfFh1Uk7{B3bbm<;z$X1mp$rLV@rZ|*HyDGMdhV*$zrF2ZJkxM?U4k_AqqtiW;V7gX`Cgxhp0?8(pY|s%Lq( zsW5`3vHTK;x-++{8FDX*E63egi-#6@&=G7Yv)WiudSu-4Kxc8)k!j5Iy&{1aVK$ny zsoE9Z0Mgk^cFjJ>nHmNH#eL4BLF1CUyo>KbJTk1JOS5LONQUmG9PLovM`HLypL}WP z!7KP$9{7G_CS_denX0T=^nn!fKVPm=sS@U4`vu zqmnG6WVaM|r?w)Si8e>CJFDL2hq!}C7%1zS?|SU|3yGqLT0HijZGAU?E`dr)$#+B3 z4CNQKYMEx!>KBhECAa8pt~0!F`148P$J&PSGe^2MW+f3ftMFAfb%=0!F}lpJKRE+g zUGcufRqMEVUX@y$BQb%o6%czKRQn&0k(If9-3I}fVNQ01309uE%-N8XS&_Qy0Gj?t zc1{4jeg-l#w)n>_t>*@(u~RWKzeD!o7C-M_w7iV6v`d-lz3WSv~KxgW7LZ)+ojRe zj}uygRXSp*8GVCZ3e-H3fR&Qp;1Kh@?1rc9!p>N;Hll^0hgQ;F@Hz7rl8^5`l)5Gt zwUY9(_k2AgAw#cMU=_oC9V||jog_Uc74}%y@BeCbG!gO6KnneQO>pJAi$3|rp7Zoj z(Qf;g`{t2(l}6GO4nmJ4>SJV0CRI@_jA; zM|b?4j7=6MCWjPztn$^GhZAr_1^L4zIZPpEn!7xS!ftsMdsjsom!i{1aZCOMUc9QW z1Z#uo9+`<6Z46Qsn^Ij%lu9$-K<~rW-mumfSi#+PsAa-^Vmsk`Ikq@qYmj)iasGIs zgqh@5KJ}_n*q}ecM@Js*KPgJm2x^RL73;gv4SabzsaUJCW;K%AqEmJlN-ji`B7pAC z&u42fB6)T_YJB&Qn-e3_B2`@ANNse~I5H;nQv1F)$x3ZB+(EOo2w56x!|X8L>}nn# z+OHM?d7ym0C!4K2l||bUGW@t_+;-H5s(o`?Aw5}{2KyBNi0FJL%V?q}#P>w+*xlNw z>9`;ecym(>HGvD#R}WTvU-X_ePB{FlX1zkB{^(6>kC^kqR)F*RU9nA17vIO{HBdJs z#1Ysg~;BswMpy1Z?U2Iw0{a36=_wtsa5QT5j6}!Q? z9`{!bySrrXy(D)sBroT<_jRcqE$PV%oy~RoUXL?J?vA>OYdxiB4dak(d7?!FNmxt= zg`6xnubKGLyTVjTICI3B$ejM6iOO}~Sa;S|pX)WT zkMzswNHS@reZJh_v6Vu(M=kj)EK)lJZt&&kDt|kH}rHOOiLn-N4ta|55YA(r&{LJ>IKTYV$$SNh##^I%J0>44b-z%s&uJ z^;$YcJFi^}>wIed*&2tbUtUst6}Qzrp)^@O6q?MP&nbRonA;0IJl)^EYnna0PHHC| zRQc5kWgNeiYY^+?g?<<7Q95WHJNYyaIbOL~{Y6E93NaJQTfkEmiz!VH;OnO*Y|7aV z*S6lty%;8KiPblTRF}z?E5r}xE~KK$$+_jcKAtxQ(6Me^_&8A^^U`?wlcK(z+Z4`@ zcjGd`t5_6L(eVzBQYpO*$cggYmJ3=Wd-;St2$Z}Wg*q({h*@0$F)PB`YKA`xYnR4r zWU*-;#(s}~&Lc?cct!8%WMjy9`qphV?;YfDuswGdclZFQqX^dLc&t~ImCEAYc1Q*KHfS9p@sl#3)1gv4)%)LQUT^2;F zzN1fAk#!Y=GZf;i{73s^E}Gb`HwYJN7_Vf7N43z2h9{5|TPY3?Nd|UjvxL{2*R`|k z-XLG50V_12kACK)F@|@Q*fntB2{k`%T1-w}jw60p!#FNQ(_1vA8rrgOcWkols@_IQ zj4XWO{)iy5fhnE`EN<(ae>U!qr}+g$KzDbw&dOm*za z>B0iudpO=@b;0Cq7|NAFPoxH&;g+}z=8e2JJ&T4$>kMam8-e2|mb1F|LHN6|KAW1N z!n3m$YawtLP}FUG=7aC5^RT=3l8&ekppc&<@Mk(hfHEDnsLy*|P*siRo&wkqPJQH@k&t4uj=lj`erCG@C@SS3;Vc1hY* zvWUpo#@An|DSE$KHMM?eopv#J_lb&1F7?9O3}-ugUQJ4>>C4HW#IzWK-yWt48$`I< z!$e8>N=F3k7A(|sv;`1__AnNhGXiN3W7kn*3mEVoFnO<|%Sf0IE+tO*MU3#Zx(n`m za#FRu3bF64?LFnrE7|aWP6GjH25pd_Y8BHoi0ufV64Ui<_%Rk5$04HszDnf#2M;{| zCkWX`FgvKAA^(L+eLU`jH8%_|M7wD*jcxojP`zCjoGtdG9zcFb1X#6bHkP^IJN@6k z*JSqVQbaA&{CuR<8dzneMaW873b)=2Wk%7j z(DeG)!)uBUth2H+kUt2bC)NeRq|y(M0e0LJ2+=)^ipFeZh*QR`)yXj6IxuWJaHjvk z^b=7UEd;-#@X~^lFV9VIebs;H5oi@kn(9t3mKts-8co_1@#9*818YHmOpkkj9ijvR zGScQibl=}7{-DpRA?;?S_rhQR$`4`1Tj3$Y(&E2tS7mb#n@Q9yRwqM&{dDdGAR9+7 z4vY|pgnAT>GxT=er&qed35_Ke|0>nw|!`drAdtgj=uinVyBQ*tLaX72J(S_R4>^Bw9m8GTscC(pJrY_cg^(_ zWFSL{DTHUNd}%($i}_v@VS$rlBND5Of~4S3n*a9gonbx-iOVLe{Es04Zmc&C#rh1L zEFGwCi;u^4RC@SoIVpkqT$c=;u0Q@Ovy+sJoeW+K{p-Q^ zdHQvSmG!rFcrN@HVaF`JwqPQ$Eo5m=MdZjVTnUm8EqBIFI4#)pCU^ z3KNm9KFFxBpCGgyVIkK5kw@lDJQFj`)N8S@Pwx{uct|DG%DOKONP5Y6t|j^;ZMBbZ z%PP2n2pQtk5ylCfRtb1NDO{J_hogN>FvEamK&FjR;@ACczj=0j%0QNKYzPFJ8MbaU z@A0%H`9XgKv-?oN1Hp&I@Bfoz1ZD7|sTw4?C(_pz;7v-w0B`SvjGjJGtgQ}9*0$;5 z4r}^ot1y$S9k@AZH!R?S$;!T2f9#FOaDtID3)Sqt_89@oKh02-hhs*`;WBPKPE0nL zyNFIF7!%#;(MHVBbpng^M$tgdGut&)t@X*kBPYbM6HEryfsk~Di9_%wbGLRRg!|oJ z%cETcqv+{g?`7J>FIq+|mv=O_%`EXLWaTr_*@76m2VB4NX|15JBbgBw73>I?o*GM| zE-zZVPgfGjHW~7{lPh4hUG~Qt-AX?VF)j+8`OBGF#x+$u)7adS2;?i;uG*T3jt@Bg z)A%v=x~}TUii)tnN=)-co&3nl4SkFDVZAKupVVpBNM2{f4xP@#s(#VN+(_T9_FoSLJq~QhmK$cC&x_9w<4)YD#x!|v|o0ncjNE-j}_j5 zVl2S$rnoDGHHvLO1quf~^%vl>ML!B2NTUmXelZdEZq>mo)^rqm8;TBnr@f|+Pa(dL zbx!4}bGsW$5068>W*exoNN*=LX~!Jw@0&ac&6@_BTuw{OF7u1Wz|to@rubz@(~oW!!oE0xW6(i2VL4*;em-QyXCflf82rmO`z1+M{+R zVS#Rrmaa(H629Q;=6bQ``fl?A{xfQksP^M~i_NKKeKeK_hajqt>1B@|ngk zJgF8BR=g&HV4HE?hh%ELS4Co3TD%0KB=yai{M_FQ~)v6c0kT^R|c|NFJn3K+OZhlhr~4c)TH!O0PbnDf`7Lk0`dP7+35O9Kl8r`AX6&`&nDz zh4tl{9$3;TAb8(&I8PFwfm-Fw@Bf%YE=KdozII^BKqOL2>M8wu`qmqNsaTUBQ-(~m zt%}J#heSIr2t@^vK}-!|nY`10xilPcKz6yIhv41Uod;DxQe*Aej(o}EkSfc2CgYcx33|-N!6E70xhiBHDSlVwy zW`|4dlt|n8I{=sDin*=}{5FCbWMw>E+vuX3dy`^U??erey>Bd*G>fMmIPq{X&ToHph`&M2n%I5gMk(oJ+q!nTFr4Ldm|HeU z@nfKZLRvC@f=`urZZPm{HBi~}9bt-6;+5WUTRX{^lVu(J6ca!~E z!yC}AMot%$h>@4G9;?fK{)VzhfsEXtGi{jJHW7sG^({XMBZ*Bw7%xN{p)?8J30atM zqb7qE3C|uC9L=??_U^u$&84Mf-B8y7#hwE1U&BEF*rSOJXK#wL%7}}nJoaSoe3~cF zX@CO*Gy-(Wp6mL9QqA8$ib!y&1}|ky(;N0pX=x7k}y=( z_H!xFVV;bQp^4}812dIRV%PME!bJKK+P}{w zxfk;>v|xKV_jCnn@}PniWM*ekoa>H32S-njeVWs6%QKtH#be*?VIp4IsFsC?9labKY{XHeU63sXN8(km^ zANyO4>*UJmAlBPydm$(3*6uD;fN=!|Et~-rDve-@q0PPBP zvuBZL00T3u({4>|s#S6u_QHN!#kiGe1`Qa$l+*SE7*mJp(XO}cRx7SHxrTGG`>d@t z5WtgrKU(65|MfBT^GsyHjeFM`dof?I%ObsZ4Yxh)#%wCWqn5`$l2=ZxIF9>_(e9`z zg7j@hz9{ba{p-ODc-<4QoK75|2|#mj7@-bw(x`qE`5|@5r45bOVHWoQ8FW14d9I(H z1+@d5a}C%M^bp*GWvM7|c31MNQD0Z(lM#RJ0zbfc>b6Ke9xD)GJpwR8tBJvnhE;nJ z2Q?N)cbn5S3zG=|Q|FOlOCjrxtC!?!9;?W2odD#l<-mXkcRK8Bh)CSrVAL~>A@v7b zw&v?rf7@|6t4qK>BDZg7R)JeCSIk6#-b+(wK9$CWGado z+>$MEg?tK3N?r4YjEDtIt0SDMv>*N&{0O{6E(zb+=wA*=FDDP@A@v0UG-?CxJ!*=} zNN`pXb{fmb5LE5+6yv~MoQGqjh;V^Mthsp79F+$<9}~aA#JccZseiCpzh69O2N7*} zyOi=z9OmVDAs1K+{UL6Uu`iNyY5r04*>%a#KX1tTMQ1c1>@vPewYV2OY{s1~IR_2U znUu^E(Fa*?t(+`)JxN=g-2PN6Q* z!((`)TlR5$qNyG=N4+}0?gNk$B4-!921j9R|F~73yVcC+GULPh{(r}ayKh_^uzG&& z2-~b3`3JA{dxrmD-`FW}(WaovPC%%|u}Z<^XPeb|Qw>8`$N_|)5vMy)q@K@M=RF0? z)7AuqJUPFcZ`-3--?r#q;&=F!z?t!**0$>|@JahTHnYBvo#V{&BV{UijK2Idkb6s~ zcL7K-L-URBDChCO?ufNBXUQOfF3h_+T}U*nwc=>uj(z{|0j2O<-^sjDf$Y{#>C|62 ze}@}@Wol`8(%hT(XL0~4-2y$-^!wNfUpl%Ll@a# zh=FjR+(B%#n4hg<_@??)tV}Jec)bnyljt&|T8ANI@Qfxew~3|nnYQMVCo09lillkL zm8EfX|FGD*PFu-jo=w{45~==LOZqj8ivny14c6)#hX6}e(!%a|@wN^{a>0G2KO6h+XLhI$$iTR7 ztOkC#MPb(g>maR~7XD5&3mXOs960vCx*vRJ0;-|#fmy7hQ8bSafUHxu?DrMr+!K_u z{P59nu|ZgbX6T^AeovOOT$Cqw({%Kg0mZ%^dKJO=-f7QS>L9xuJ0>MZHa2-Y`(5Cj?-jtI_^q; zqTfY>Zs8$ZSq7OCr*-`u&*m0wyN_HsW0m1=ZvEFrP-e&Cz&EwBcVlqZ$u5HfsYC_B zy-xASSz^Rl*RFw`95nA&==xK3%;RIC*>~@>W~fP9sKsV+imb$PNEEPA;42KpVT2#H z#VH6fMfQ&y_54IE7Pz}j%c<>+_{f;PEuuma`9gTw$krnfB&9C_KV=c;+oA2lEDl@%KtfgzeKg$(%S&@ zt>~47)u5K6hZ!#q+lisby*)Vf)SqFp7oZ2knf&0&+S z?Ae=E@un>qQ~$g=r(G0C(+4a&y^CMH!hC$nyn?U$WR(;qz3^nz_A&+9PxPBH#y_YAAQE2 z3g#}G`r)QItJi|eK3lAqg;l~=xIMYTgR);azoO_OdMp}S6Ct*!U%>EsZ_Qt)Ki>OPJoU*Gn`&x9Wjshvcb&eK!k2XxKQueYZR5B@{5b>^iO7@w zN&jEEDB=n@o}9U5KlO1R6I}sz!1GURg~dWZ1yW}tEdUJGuxg$t;W(N8W*Ff|XjFuC z)F{iaJF`&az}1G&_d5@(>f<5*3rtOgf-*~QCYPe!(x^OTXYkhjPYrOzR;=6n)oOb2 zUM;0KgCdcr2#ZWyk+6S1@Z^CEK9}+N7VZinZsD${cr4!GI)SaPqsx>#-e;lEm;>|% z{NcE#G?XAM1IRjWf`I1is-y3-I)O z=S_mcvsCkM>%T9I&)3mO~Ya&eP{ED znRZZFO<4DzvfU3VNf)WtLSro2X;(LOF~K?|YBskaIutvJTo#F4f|)BeXuaIV%HCxf${Zp53dzU^xL z;J8)IYsSlntAzI6YHJv1Lr*ptr|p@`+3T&rx_%%*fEmBnq0d0|_EwOIud+uO z*bh|jQ9YPaO?x%2#*D>f1XU>P3Z(KR6eaA~-Rtc*62N?IkfpgAu;?(O!5thHx9D5d zz5+gNC7?a`N*1e%)((sbD!@Hd@BA*8`p*S%P`<$lVwZ1c;JAd zo0r`sSfI)4vIfX}-Zw&abI)(Nyx_{oMr0Jw!Ke_m+Avlqu3XR{ScTmPEZGf-|2NYt zs%MDLjDu;2eEYi~;6G=)9ydzr{O9pMNAI8Vfd9Ps_xOL-5c+>C;{V;z|IdT}!|?e3 zaP9x+(f=d-{^!A=|5Q-?XA=L1-TnX5#6W+}&i}>HL4&y?V(QKDew688_u&P`5c_^T zr$34ax)>2F6+TEic=@V2-qks|5O-q8sBp^_2I(uQ zjZ(2VY`wGGeiwl=vHtZ4!F!&VNbfId>CJop#)y<{r8nq0{nGjQ)xU3!5g*Ayz&%KT zC)j*G{1RT0`#A!}5Y-7ib>LSy>j))>CSc@+zi;0AhoJTx+0V75rqG4i) zp;(wSVk-t_LZ-@PRe0_kp89QNh5HD$7#Ih_ITrQ__kSbMG2H;h+@FYYIIn)Mday0< z3mRoy)nq(XXYzJ)0-uPIUH;iQ7#=9|8Wf(CK+wMqriWSmO{iyDJ@5<{-2Z^Y?hTFU!X~gJ+nzUwv_r zT|UF~VUX{EoniX9=g*!&2N&gUy#CjqA@yvJxBF+*82QxBfq%DEw3G`J9|rv|7kLL= delta 69526 zcmeFZS5#A77dEO0QWQZcN(U8Ds?v)TMQKVC>0OY}dnlo75CIht6$RQKjNLs?I)xgI+&F)nwf-&QAAks&y}owe_uyJ z;_6kD8p%85la}t5j^GwfmhLdS=u%BQYF2H73yN-9t~hdp^N8xL8~1(8mL@3^bvF(> z);0GUdGl_a5NOpLo#v9SJ9`wXd zNP`rTJpR6+I&zeTgcQsE(ttGjvq(UFbAY31US(7!esT)94J}3XkzmBtD4C*P zU!o>{w01=yb%pME+i9YI5Q2knXO zPI)v1_^Mp90qY<89H)E-K4`waQqKI>V*gvl|E%#VkNwX#{ue3#2YCbfCw*~#BHb=Y&rWbIi!~3FT0+(f#!l95VTU@+AOd{6F`zDzU3N^cY2SUmcW3eET*NSh{ zV7`~>jB3gg(1P`AH)X!R(OGI|aVd`wto_KVn{Um)r&sIb?>fDE0kkx`(b*|k(HZql#1oJJDqubhh!Emyt~7BZrizD5YWSeO%` zLSLv2xhp;=c6qzj#0yJ6>u5?f2i=TwK-RR6wt7zo%s*bJnnDy%bI4tnNqEQxuKWIU zAB#}*CH1lj2aHiD6@$BaTQB^g*)ja{HT$9bhebveY5^_0uiq~o!>c$$G6hb)1VSs$ z-Edim(A#24ekX?C?k%5wWlG@gr`1dUUGEF9-r1jDv??r4ERCW%sOT?S`2P6zl&KYI zT9;_nKBHFdeCxvG`=@j~(hV$>Xb}$POEN1o^7|#SYwwTQIcBWCL5Qz*{A-5?+fBo1isZ0~k*0&)PG2$O znXl2Ba&|8D>tSGXx+qU?VoSm#`y>4!+tCKUD%tf`x~(3W)sbfme2EHXEyBWmUOmPYuw7))_qsakF93wly_>&6ly)A_W3Jl^T5Z@K`?)^5 zoB|z`LIj-o*2fD`BQ8yZIY(v7j)$?PbI*<0rNe3~#ek_roqhthNVLedYzgc6In{f8 z<8FM4!;*`WaVKGK`cQ)q$0{aR7xq@0Mr2vP*d@h#$~W#s+DcWCSyUV*d49z`-=)rL zd8u)4MI>@IpIlTuK^zjp3l|$z*xSp92{!h;;t2f76&dm3ZJ0BYq-&~(Tm{F8Q4%E+n)4Jl5mnc_-QpSqK=`JG3+z=j+oRSRrB_2lJTkfy=qDNH{x!#8AHBQI(mQDT(=c zNLYn>Di*7u*%zo}SwCqw#vNEIXJhY?+QK>P?qs_6>Xe=TWUp5-=7{%q;KY5tCHY=& zFKd6utEw!<)lBJ8Nrcr-SK33&u_j@)NV}<1ghu!8Z}p{{IC7_)*LUBWcP@HI_R8&b zNfnFgHA&Mgc%LK)W>|(zd`%`#5O;E)Q+10#K7?wM&0L$wdR9fHG1+(HUbpLYIBzYD z+BN1>9h<1pLuUlM4?5aYQ!wo&>KO0WgFT!~-{3}hOmEAJ>ite5#9Z>^2|&EJ&W%!# zNS)2Sm-Wm;F^i=RfyYWoOvUe)+V-adk8>Ut-O6@efa~PBno2m-9z{oH86z8^U3(t> zKI(Z;YgQk>1J0OC$B3I#muTjtnqx@k-5jQ#!DGxz?y~5Sk&cB|PBsSk z@%WooIVVM)yY?Y2=nkC@ucU7O#TbNEUoG5$M+>vfkZ$id1nN|eA%xD=&Z|R5<~#cs zm)p)v6!J-)6L)+kVpA2y0=fC6a`byJ?8Gto8)R|gn9T+RGqF5yTTlHV~a}C zWW3&YV=Vo4L}H&=hhB&F{HqU?Y*11H)-6BfiUOu4`_mph>q2w*9&}u(dPBadU885G z$+i+Clt5B?qriim`5r|x*~~#j%g~tG;|n4NDNTsWh2(8ivSN-;+4*rEnGZW-dK5KH zn>J|?J&961En1h~KU|@Xc^DAG`$hjtzN?8- zU(3Az&JU?hK2ps5>L;F*r7o+q-Y>9}fMMSez6@8)rO?sY_DGMwl|VgQTJ0DP&zwqd zxTh|AUr;yyjZRZWl-!uy&NsT8V?h(5>o(O2lP<>Lr`WL9p+tR^V)D}6fCXG}lNWLo zAz3KFH1SnJ3*+lLW|t#H;}#=mYA@9IGu=ZrUcx1L@QOm4Ln>0*uJC6cF7-uhpz?rk z_H>1(EV_l9;GD5x(qY_TN*D84izW%)gJm5o_2&6HR71BivAwYx@$mFNE_0O1Sb3JNrXa=K~!uv74^Mu-W?J$NkyjASo$oy6slF-V$SVU zm8izv$YpUNBj-hoaCwl4#*twI$FTE6|I>w$jnoEvN06Mu$FoYgXKn;3wrRfm3jcUE zDOwsyb#V$hB#7p`LFnXTc7a!axqGSL%*uZ6mi%SCTStN)(|@%67@Oc+`^gLn!0Yln zzE4|3Yj_(&6X3OQ11ZM=4{(cMX%7q3;~TkeOW5D&m2q*Zxt;QK*YSR@i|of!-fWcQ z@p4+2VpJO1wNym>?e1ZZ_aC$N|VS?@m*0k0fV5Ql1m71NZCg(^$VB^>XwYCTK zhVFEz%#=yfKW=Q!mY~~oHE==K%v7Z)n9ej!QS`M?R(&*_+D%fLkAH?yFzwuB`f;1) z?xt4?mSaq?;Z+X#ZE142VE$v7ZMq*E5^t4$K_Bq)S|vz9_US3;lDewn(QPGjF3$yA zBh^O+6<&VV5YwtG#CPL{oeB0uCd$h``r5QR~c=NbGP@(UBpC9L&&J@IHN0jeH6wjs<{o24RoSYOjt_AZ4$t)c#E zi|uhN*2!zw5S9hilzQP(ISqnKVihLu7!z1Unt~AvxbG{0=m-rLhRfFxAg3p~C|}Uh zk5ZLAa!>1R-~$6$(tE4E`0MC#O5T|sNNAqB6Cl|i6xQ^)1>v=F#RKMao5x=uZt-Of zx6JpYzrPoZLb~mCQ4$jSL%RB^%r`4BOt8cm|4N4^4A9%>>|J3x8XUO}EZBykG&NB} z4_h~mlYIPoC97r;EMoSat+ZS##&T3f@CG=Cc!53&aX*~VG+OkHk?1jaLtYjxH1KSn zVn|;)`!M3=3b)qw!0_|Jp;==Z?M<0Sf!o?qQ0NqI;4!%D5=Pp&zlADv9C0}#T#&b) z0*&7ag{Hm?ymUl3TrJOa+BH>^#Z1m@e@NQ}un^Ut*KDHxU{zw3xJ;zRP0pEIG>QGWrdFAZSZ*b z70k#iHnPYCu;pJOyC4t5C8p}E;fr?6;p!l^03WI&>KW~I3xa~ zzKgrWx8Yv*Gr4ss5VH*~(W6HdRSa;j^lT80s|v}p0xJtU7`Q5tcH1S}PLg@Mx!li* zYFTwva8)Cnxm&@stdy8)Md4~7QM{L?I~gOMxU z>O1Y(iwu2{iOwo;4>lvujr`>Mi#%f|O_gNV=vi$|@&02q9yuaPHO}9LX4Q&c0}wOG z_yq*${*Sy0j3)En32Hmd~l;iS&X&`0a0 zpU%YvKmNd>em|!)P=puZlWuwP{)ePPvz|LKH;x2)Vpr3n_7_1w#uw^mh~UzYW`VWM z+jO~gv;Hu8C0j@BP@Y#O(fG9+vIq1kwj@$jNG7}%hHnmvzbJMuxHiRV4wT%hq*&^+ zMiXmFib&ff|F^DS#k|8TClOE5)@^j_0g``_lQ8OfD-HkP74^Np%6=(Byeh;OsmXdxm+oo;6(6soORk}Nmsgd9$gjICQOg_~u(!2*ni?(U8)Mei zlgm>hlUyLPRR9W3^OKts&p#O84F)C4Knn2o*C%VhPM$RyE4Q1izqfiEi%>tT-{|Rd zJqf3_%y?>bfgyMASF)hCOr@N>88O~srg#Pz|E=)D&yw@uFRW}|LD69fA2m{u;nI_} zaMV=gHljD{9lQ@9$4|=Z~J^91y{3lZ@RI>y`=H*jj;>DfpK^qDW zbJ6ZUm&)8}Ea4S@|Gq?x^OK_WkI+zr(d}rHE7x@;i;hesJ>f$o{B*5f4EJ~I@ECFx zrlOrl=bX)q)^HDd)c><0KOse7k}cw2@ua7a(pS)afHUp7Z6I^>>E>VuHDPnO5rRLpjWWT?^iz_~T0!=KoP;hMzgL-8S zi+7dnWfp3d)D5-Sk^BXNB7@Qol;=P{_XaU_`CNZ>5qNsBVdNu9GRFL>usFAf${f}2 zU{tkomo)cgYVuyy7?~CLz z956=_Opb}>RUo1Ylq=a?>uy_(;v#cZ!1jlbM{*s4u}s#Aa+CLhWl>;C|ABS!SJ+9o z>GoihVzK2M+QZDF-u8fwfzWg*MqQq4ETC|&UE&D z1ZR5kTYD7ZNSMaYc>u15)C1kGgIP^d@(Q9Poz|4=NzX%SsaZMB^IF?Kt~3i%Tx<#g zd4f5fRYy_h%H7rejPQ-C_c2PQLZVYuh@&`^GI&Pz73tUgr&R#rV)B-Rgz(wJ2`aVh zIIiL_>cO9*yZm~<8614QB?V+J55e^@cVw^kRT#8%S$jDRggk7Bym&!~>CfgloMSVk!-u7?hvhCXXHCnCo@xwq>072p7<^gZYS2E>Gc=Q`0nBfgCampqY4EAu5g-LnGkIp@mE3A>AaM(A#AX%ikHa$x zjx;YxT~L}@ep=MD=Tv~P$|mPBBf)b(`~8bdc~^}k zmZ|R0AEDZDdFE-mjS9J^)k#Qp$HR>lnE~yq0N0IfDf* zl0S47dkvX#Wxso2EOT{HI^VKdv?k|+k!cgiA?4JjsB)SHhE(!~-N~C6NKqY|H!UN2 z`1Bd>>-X;J=VSRnW=-S^V6x!peEDwi{k+#6{`kFML~B7#73i;;=oV_T#V;) z`Z!!US(QC8TR43bZDo>H$9{f+`j|jY__8o2;W!ay3KY+bc$yCFu9W!K%Ha~J0|p-{ z$g*&pFMRY@2LQDy0C;o!;}XeH((^p2oHvh#IxC4ONs|2Sm?eYyEe3TdBv6M zhC~|SKN5mlcfem7l{uaT!U2KQso5lHxI3b@h7M+L#oS`j(1OotSI~_T`;*LWobDUf zMx0PpjIyOTQ&ml8YhV4c&sPL`^!299zheQ~Cs|;U#a}UcmW0BG(Ur$}Fa<$vRD26J zgu5NVD5V&)Am;k_f@fUAmHJtXm?KQBf*oEk1em(DF^C85|KxP*)B6jX0f=+I4VI}t zGJ1uC!kRnvn!4Cfc496u~z+NHdg@ zei73r!2>)H1fvoUcdsYW*PPE$y?jCpZ69>5NVFSxtI!4RV5QM>>ett!U1KOoqnP3U z65mg1z)iY7jdBsc4Jn)lyf)8Q?TnuP?xWThP~gkJ__G5$T*T5`RCeV*=6kIP%(wI6 zioneypuR2c_PsK5KtioZu+HLl3v-EF6{;|{t@W38k#6Hr->&yG2 z5RcY$6C}_6`{tw?sbEAY{_r!s3`pt6FkZ~h|9T~7P!I=DgUB24M;swh70?31wDC%( zgzufPLV4q=v%i6*ijY>`J?;cqze?S_dt|KtSu^d&TR_e*cnqvU@}gGuT_)oS`?r8t zgIMW)e~W}$tIS%}xb#8jqLIo!NFQ7_cnw%Lkqs>HJ=anE=L8Yh3*AD4)BpV0OL-`8 z90iN|-kl(!wVYl0A2a@B;MCgYYyUyP`LdjZ$ODvGbr^w|cwHGOdh(Y&f}u?k7IDWC zz(kB5?Bax6{{rM+E_DJtu*PYyzArBo0DI&3<$bUh;QB0nhpK`FDI>pu#qwAM3XpT; z+1;Y_e{4)#^%B@tnEneq@XSS0WX&9N-H*?FMPR(IiVVzZCt z(L7H1@1KMCC2Du*iH0~uIYBG{KNlMi_z$GNm;IiCIFqfk{&dC<3`UO)+Au%+ccT=% zfCHlVIuPKwJxQp}FbbJDwuDjNsjcki{B7(Hltea#NIgN5b>8Ivzc;=cC)~yk?Yn{D zIP;}HE~4~h!lSn$kgz*ScGiUUo%o>E?`!_DTp5@lCYwqPD;^2Xr29D=C0}UPfT#pt z&U9d*zWJ+v<4jcOPrvOnl&|XrMzc`xZ(ICXy&-5zJf0D~lZ&K-1FG+ScdaE~w;=4q zZ}_DubQRXaikqlG1soE#Rj2is|DtTLIE9O#AHR_HQ5=}uj&!Wj$w9!VyyO&{^hNaq zTZ-Qom?1q*&1_BF@tkA?)kRX;=tl`>ErsgW9tGfs^u_JbxnD%%W6l#b%=3WYvW5M&RDgf5_N`EAv68vf(6*2W;X$2|+dgMH#%`^;B7()yIn z>BD2nPh+>nLWyRgbqxk?WSFJ))^X-Ts9uIrWROFj|9>{29)!4G)dN)^yLtH@pdHw1 z;~r8BvPWN5D9XSW=gq)^Q+-WQ|Bs$oi5h7K#0K@y?YB#IBADu$W zV0EW7TI@ij02jVT#c$p?fvo?bR=0~SDAG)kQyo=e{$&*6j)8BK6K^fhwFNdNjcm$) zLmfAY%8BHVPu7x6i@Nw$8F(PrnJK?jLk!Y%8PJR6puZ$%2^qfd`vONGaG94xh|l_^ z6zmqMqQ&My|1i>2h8SndTjMS?N*Q+CzwU*k>PnKq$PqSm_GZF4h}tMj)D z?`5g!73c{#^rZ%i*$uR+#R?|b$@1KNXCc(E`MSuYW`Jof3lz_qF+r~vzZU*`_30;Q zpJixqBS5|vIZxIOm)q&c9PV#e-GjV-?aRw^Bt#dG#iMm9!D#3gi4XWnuL-vfDNG`p zjF;q0Es}5Aeygx$|F~@{v8W|-aOMNy!aDa=(0sCh8N7PD=%*gZ*^>o^sBAE}>-q7$bDne#(DkKR zcVeZ@VadMP8}QFpawIKPo}S^pd!z0H^m4W7a0<|F4}i)59`XrUG?y!?%2C*Q=P7oPgpo{2z(BQBY4iP<()+)F^LwOuJ z+%q3+#oQ1imN-TMqY*$ma#$Z9``2Y(a)R1S>7JTu{YtB?N?#t+X_U;ggd2n8XoYH#oQ!z1c}J)LjRc|$NvMcx z=y#p?RV=;$6G+33{aW~!v~cz^nbrD1wKtbv@rh&Ein+{zEJq*qXwX`~eFal&UM3#p z#TBH$NMi249=ai}p(RhAjKE$Y;*kcz)_AbIKCvq3o4AFV`Yl%kR~`9vkKa}40A!BY z!*h_fB1oI5?*Su4WT@|AufaFIeX;`J>ge@aQ2;kDUM2FI>WLuSufOC(Smbk=GfOzL ze%uNdH==nBm$f)}`96i}$S)TmzEE<3ibxy&RP8)5@q;{P4Ioq1G;}!mLUwB;(@`!M zagSY(IW!1%lxz{31R*=ZbHEdh)XD8H8>kYluwm{6);EBa<)(e>_Hb}`Ve%=ufXmW2)%85@H@ zEdsSeb>Mt_@IT4(Wf$9X}!azvN}?lQQPWD}}3?JknF<^<(l_rnhJsh$A5li7k zqG0y{yM#R`*V<9FQ{n!6I ziTsgX*{IUa^wAb^9TCJxGCl+R!iDDG;sy8hpK$n&W#$DX8CM19GRp+sF^R20vqllJKC6=U%|8P)e<(C#8nf;c>1$Aj9#6X#ULZNc}Vu#A16 z2uyT@)VAcM-v=)w2^3$iR z2q0VZo^T5{_3Xb*sq4ZEy2L*fi1sdkQx@#rM!=OQFQ(2Mr8+C<2t-e1AU?UZxfb|X@2Ry(pqBCr$5)TR9lKvR+1Y*rcTGK-a=dgaEkNr8x% z3UeUwGIbk$NCbT_Lnl~!SDaqCZ9hLoeUs?s3oPnrrpG^q^v$JO;=62wzjCrVLu3DT zR4-dWPF3}HwPPls_<8o{d--$%EiIVK{FCO+OdTliwCgpVjzS#j&<&;o+ zw`ygw=ne*HdkKnrU$@%m5O0l`sCH8wE=!b9ritY6`Ery9XgwOQRsO;0MCVd?Lqz*0 zyXFAeFD0eV1WR+>A~M=Q)<`yEot^!ANfhy-sCOROHX@Wt0N&iK?hB5#lZl3vCO z>CXW9obJai7Da)aFFig{Vi~eL)gaTd>|)R~MZa6{tvdn3{OyBc_;X&pMiVJMgWQ)4 zyas)r-wJUID>)7JNkuRU-VI>k@|+yQtWx0xdU*v40>>M=Uv@#aWh>6| z8_;?yI^OOyN%18=#d?*Xs>(4f=FXbg zf)@ITPXKhVzoD5^RdI=#u$Yr_zL797W&u)u5$L3c%XIk)Ks=7v=Mr2R*TWh>fY`<4 z8I-0sNFmB~^G&2$;0cL-NV?Aj6F*W8M@$u`gb`autrf|4T6nisyQb&AuS} zV+8{6?8=x}^JD~VcHmYV8<2lrletXg$-!}5vipEp+}`@w@l)ks$a1@$9UF6|lO{en&AS7is(POz;|vM1d)x=%sPkI0rgLZK5@UYBip677;) zYT6d@d9Q`c<#4_oY#P1uw)FU0tBAej?5WWkSAZ0~TyA?3Mulm4+a%#w!Xg8A4=bZT z9`lz2cXW@KI_a~rGaqH}uxp`zOY88UXM0FzyCq6q!(NSSky)qyFio5XZq;1~+PG{j z!ZSXk%2qZsAoox307a4!z*>1ULXnC`jy91nJEsw+NkG-!RGxh&%Ya8G~ab@hVVj`qtu&;3;}Ho>SCL;fQ=3pUEhgbDECURuugtY@=@{ zvq+!y`aCi^)0=}l9VWP|8*GP(Fwu#my_Nb!jc|p%I#z( z`Od|S{Knb8e2jJ*WLG!nNiHYoo$e{zK!6P5gom(0r4vpud-noFNn1fJL7BvmeN|SN zwWVRb`aVw!JkN50OXE}3?@0T}F~+dXFv#iK$6PX9Y}^#DX%xsq%tDRYv+dXHT=>1y zEdu&3M6sSOEXb*C&!W-SLmF5X8C8}8QMXKl?LsVN^rbAr{R|rUav8+dUBXoFo!EA$ z%x;PAGs%3S#|vuq>m&5+Is;S-yV;b@EIc!?;~mWZq&ChSFl~!oeK&9(I9YJehccq- ze?8EX}+wAB=%lUUTS(;gJ4%YjAYpNy z5&`iNeCzB;g+uIHA@iw9=gIg5b=4w>7P`dU9jO2Wem!^C%5ran9N%hR=+~BkNte60 zFrR7@0Lao4kxiauOK~oeWtEZIF5@Yzh1w~D%cnp@N%N95tXOQ6#_u_ zB5pTuk%g_zLo~UkZBRp|d&*~)x&RC}uIus%VgUwnhc%LSvnl);c@y!!0_PO586{9? z%Y!%XyH2r6T7br?6eLrg(C|mmfLzYjco#<>`8oA;=_xdiX0oIAq?@w6dV9lRW0L2O zPuerOFOdq90%t`X=AI9-mkYbMQuulHrJ`+MV#&3LiURLCHIP)D#x@u8aK{C-pp9;c zWuQlOzc~kS(vvL`hedWO7k_sIe;WcMFx*#m8GF$EYtw>Amg*;?gk9UrJ(WR^F*O=rt{P6Mr~ z?C}iUXeyJyB0N*bPagxp?tA)sCQb;$R!sN|^WSV>0O+C`fQZL$SRU}@%qv#oHG%k_ zMLw{8sL)WvsLrD956=7@RsYcQv`?U5aHb@|Ov)TUHvG!uIM5Ko_{{2kOmwePC}y@Y z_>l6_bt(j`PBjdd1O^PQDezJaLJaxJ8JQ_hL<=aTGPJ{e#Qub!)InYz3 zya!;}@#or158u!D=l7!n?a#di^8RMK!uFKLtucop2MmP#gz+(=rwcYXj$Q27I9Lhi zCsk*R!+i}_s72asq)F{$6%x`Ej_avrxwSV3;fSX?E`1~(4+#K=JhnbK z6pvs$VB=CDtL0<*=1ct1hPEXR8+v^AYj4%kcDa;zyK+cTTAd0Pp8D_}>bjY+DL>w@ z^QASHOfB}~!0boYg_jm;&j{DQFcb`}&MA&lyrrfV0K`p|Y(1H}U2jx?i@%NE@#k)1 z?{XX|`F?gsb1g?YzE9YWdm7_CqD)=|d0rXc_@0qWV!eGXiy*SGQEXiYD|(-3o)oa` z?DdQwvNR_Ojx~k8ymoL-4MNokUuZ1JAXir*Ouf!J?5>t3zgMWY+>*9~g~^NzM`*%h z1lDK#3(y<*!m3vZ)REsBl>=?I_M}mP7$x@tN4_djaTf_bQ~r&HrXP6>joZ|9OJ$u) zTc;$90ELzKT~ii+fAHOIPNMrWBDoS4i5QA2@xoXwcRAZ9&oV*`W%U}>fola?*h4-? z`F%pU{GjxII~n0KfS0NVvkw!7kq3UuF5?a?PEiCWKgSHPDNMVE;Z5^`3DIh2S4GkG z$O*fQWHx6Wzjq~W;6&DN+8t1I*Bw#h$WJ~Ps!(=B=Td!ixAT*pt1MD>9<3PJq8!Mu zK%@&{5(5u<-QS~guj@yJu*_AtueuRA)G@wRF>JD50&>*$IvK0Xn-)1Lu(}J|$#2;= zDo_N|ocpB=tN15ljrl3^AF1|h`bQ6@Ck4x?Ck3C6HSRl0_BIj_{+3sEtXRSrk{Y`5 z%jK`z5L^aVQ4Mc9*$o3o@GX}vWXC}PjUSgPTC6_%Nl%F|#@kJv?w9G19SR8@pekpz z)+tsS(B5e-u-1GzClydX<=|h8xF=DzOvT%K1EvYZ$#^ zFA3LT>)VC#4C;h@#KK{OVdFbY1lzxZk8h12x2|v;vj>Oo1}Gh?2wMeCngkb7k7 zpc^#I6J=QZxTErH%Zvqqq@z4XnC z&Yb{}dcki^+wg)z!nC;6hj1{xwCu$XCDN)Rq3YJgBJVfLeuY4O{Gj4Xzurg6(a9j$ zfQ97gAFcVkOT=F__?;s-!vKJ~)@q|qaWVS6e5H`OEjx2+acM~O`F2y^bt@TPbXBG6 z@KTAcalKC|@jMvQ5AJ~eR=XV0LKhjHt!o8-6V052xTiK$L%NR`*X}p8Ikwe8Ax_&Y zg?w5ZYhD91c-l^OY=_rw3PS?im48FPiFtf1y!geKd~=_ItfMPyMMKVH$<57Y+w~89 zt5$nlqxPbBogLU+9L9U|81T%#a7t6bKE=lRA9BSB5IQrgSW8uvGNGOKawqd8aT)Z80Xutt&cA z{QN>1#Pl}w#91RyvYY_mXFAv)g{4&Zg`KQ4WvOC4H4p+ZuT?jo6|?q_<0#>0c8VSO zkKuXQ%u3RySy?gu8)C2#^JB$7%q^oFe5hZ@Itz|RFc7e33*1{Gl84QAG$h7-$JUc$ zx>s%{n=GWQBuNCkTtPCGhsRE}xkIW|u?Q9QAKy9ww^Y*(cnTZ90`-)>9Pq&|?@rkr?)$j1Kf5KwV|0zjz`Kdrs9o^slm<5H?^x+#0f?D0cEhpIAkE;1 z;Pg|adJm?ma+GpFEXH@>jU~q@x4C1&!KSUtSLySi2*?x*gCpjK^3ycRk3v_yLwmnlfcVxy) z2*}{{QE#nkZ&lnR#h(63eKyl!V^brF)}3C0Zmu@cS&9*&{Xj~>4cU6uM)l!xhZvOmy|2*EWK*_6;4VL^) z%tkyGs3joE?WQX>4&rR=yH`-0laroW9A>+j-9v4tYC&uI!W3|dZ>wLKgLv+jwi4SC zPE%C}YjPP^^6Va(YqOtcPBG=GlezmGfr>5PFCCNJ`&Y^FM*tFhgrd5kcYe%9$49QW za>PuAHYkR}`9bq*%;*?HK_LX#spPTcD=OYq_X+1v?%Z8*=DIgZpB;29tnOy-1;F~R zc4ke#z~Jx2cBTrNRn2%$*KNIHlSHq$)-Hy?FLC2N*>?>u+XnCU(?nGXXEb^~*}5;_ z(kWlVqljdN(Uk1t4&4H`wwJpd6?-EHCA&s33X^AJM3<#7CCTP7%V3!!2Lf*_Jc{7$^fq0Z6FNWM=33yhDUQh12P2&6`eZt3`T+divv)meD!(4hFH|?1;;=X{OhmfEA{TQ>YdbjW zc6flbI4o~;71t$azTokYQPVRRaPd-BppBof&PsE-tEyUB55~@fkdY;J%$(koVEGTP zrSv3j+^+BM-8<$9xVfhqpKe)T%sTb+iUy`{3ca!kCyOnvvOi0$ zL71xD6Rc8~NMxx{JDocpq&Mrl%@GYRIq-*}1|3-UP2lo5rvlK~fm1e{0YaTWCvEgP z>rxH_v2jDiiJnAi~71NE{xp{i3eV`3h!Mnef7l20;`EdtuSYH=_p0Z|an2M+0> zpjl1i!@A+9uI8tV&vhM)-0I$cmYPA($$aKDNV5=4)cXguTmwKb>a=Lx4bB`AoTGO< zEx~*I)u8%ud%~HDy79u&=%qJ08lTE1sRsNu7c7CeKppFz{0RSDC{9;aS}R+_Dq*u* z^2iCFmn+E>Ao1?;X#31?ctQR+*gfx(+2?eQ%NdxFsn6u|s+WI`OBeX`8teHSd`3Tv z(X8p%y3fZ!G=y@Hc!5QOswrwQ>XwDF<9T}$OXP_-yo&rv^{gXcTJ(TOrer8y_~A3t zJp+#M>x3_vGxRPbp#sIG7T=2^b<4!{MmN3x?Q<1+Ah7Wsa~)$8w{$H^oz&^lT~Gnq zljg!M^(vUy<>1dS;;dfSX%1r!In~;&P9J_`@scortot~}tGr#tmOUNq#nY9A>DWib z$;{`s)%OC5Z%8XP-r6^z9D6B5QaIvQ{x)&Vl({pBI$tXK8{^K(w&?V<|D@rT{^9Ux zZyIQl6Z~|})V$o)@#^lv=?W&O@iDFx2@YCFb03fjR|^tVwl!Ne;^m#-$0l&sKMtqN zsLiuaE7DlI-we)(V|;SVT^fAh1=aS)2_-sA)$l%968U4l&$|);{V@4`- zmqH@r-#Tu*nIsg?4Oh9;nhnXh9uzMRiPvb{K#><;8?T>SihD}lL|;gr7h5}iqTl7^ ziV)JlI!&wk!9A zP%!5nMB8SwbORbC9)UjtJTSDb(UI*3n~TsXU%_#)d#jt;d-@~DdD%q1(WyIE^{
XB-&q`qMQ#|eZGYo)|0q+_xW(~^eei2;;$u$+kRlF-02Lq!%$NXL+8#sFGU-l5|$~7 zH|*`~Ry(@^OZj`GA5&E>??*f8Lz8QYDz|ny zX><4Jhgwtu0=Han0kK=Q!d3$N00E>lE#?cvb4ByB z#~g80n(r8_+|{Rp*!4fU_}&Y_cScqnxn4#bfBc$#lHLa(CzU+eW| zb5FJBWZC{MzJg2^PzE4qkPTZO-TdSa_dQ_yo}t*Z?*MUBC@a@n7|S?~H!HDPY6kLwVDddF&*Yz?bQ zsZoVrj`#ySip>$%mLm-b{b{AqDFTMO(?6XYA!p3p=2|(29oEmw7ua zPnPE#KUp>o7 zZNMPY?(^i;xA26yKfj9s4uk<^W^g+%g|)IpdQn9c4PIs1<;v(NDejh<#oT#5H)zn+ z0p5IjtFIxT2v7%k#(FR1T)!v~^*M>F-Ekrv2-%5VMn`j(1my{5y)2VV`(`f^PTEcd z!n?**gS=7?)*&`nl5K&K=ZpBYr})*XdSh>?@x!|D(8{#&Q0;O3bjRw2rH6W1gf%o4 zi6DrN_gA;S8sgE?e50r)dqDtNn_bnzw$FGu7wIhb@3EHy!b1v9Lp5*~h)BPGW~*-( zG%EkNdy?5gBzE7{*sS6Iq3f-qs$QS)QNc~urbD_rq*J=2kq!wZq$Q+3G)RYplt?H@ zNSD&3q;v>U(w!pZefRmE`2Fs>cdfnr<1CMRzcusB%rnmn?M`$}Zz&tZ?1htx3`ZN1 zmah8~*K7{Ubh!PS${|nzhn^Hq;;AkYtXDt26<0wUkn5z;c*)`!{^FqS`sPQq#7KaJ zt)TcKRADzZ51R7rf#!*u>?z2X&CO^&sD0YT)3EpA_Ki`(KyoI-dYtu_^r)0{zhgP^ z?VeD)5U=SEc5Rx?94l9@!iGf)t{h^vuTQ4A$|+{%I+R-X@auB=wjv(JWjXZCUwJ*- z>pbUX(R$zy`*YPgd%j?EBLc0Q*2ZhpQ3v)xn0T)p|A@8Z*0nBKfoc;XI2oR}cLTIG zD&5AV>VGc=xP0<8edYyaZB7K2UlM#1*}xstwPf($ZzRA+Y zEWU-#*lzLDW{uZLk7q^`)RfKE(|;$-1=FL@x6(LiU5(y8I@jlRXj5w-g^Am-@CGJaP#Ic3TT^+HWj z-gUehdC>FQFBq?_hFE%TSopf#Bh0v1#HTN;+7dwI9;m!Wexe(gkeg0!F?u|m6z>zkl)pv7m9tYZ* zKt}dELS+rrMXDwxDIZM2q3N3Kavt86p^d;jtlv-o&&}dE6?v{oZw-zrd|zxiwI&&|@vZq(UnK#R84P;>;$P$@z^3HQ}~OqUQitC4DS-LS!I zFO6XiMIqGWrl}!Y<&E`9%4e0z eI#9rBtAGfjko*j4Qua<>?g=LIC zmu@K6O}fnUcHNo9Q60Y}zg^VVKpxr*ybN2s z1ZK^8C{sxArey4`wbG}LE{oU(7bhbR_CiiZG;g5UnO{F@bTvfDilNixNH3+4+>!@Z zK3m{X=%}4v0ZR3Ez#Ve}oZ0xVw=*iPC|)zS6RrUTdv)sdeYm$iA|80ZZk9fTyZE?s z9Kd!AczxL3qy4{auads>YQY1CwpoGi@L3!*3x}uWL4=9v4IvuJP{qgNNaT~QMe*ws zg0u%8*g;XfYA9FoJ7D&ZPTs%*RzbZ~$f7-{@I~NBoUr2(kV0AJ27N^VXG6l;;-~i| zYuv2AfBwC6s51??b~iM>tk13-4BJ|r7JOZ;))eFJeJ`HI(|ku>m(#ly@dnx#9Zxs; z@rJj9yqCV<{+~#QW;atPGO{WI&~5drtQ2fV|H}Wr*q`50gQ?5Vnxh2PP}L9CXWd@! zeS5RN*f8_MyWC4{d$OP1*r3!#J?{5YE97B~e^Nxwz}~K|YiT9P6JTWaeqk(wX{U4F@hZhf*Oe4b0_#WXV(OLN}!#FzZm z@DY(g8f7>C+^C)1V5F6wG5QK<%?Jwu4m;2=3|_EPLdc*@1cB;@gU|1^68N6DM`i1;MH*r<9GCpJ z59iId=TvMYYYKE;n*M-_v5n2#!tKdO8;akz`tC+@Oq&MO5mJ7rZTv~#clp{@hm=Wc zWbJPMzPmc$k^vq8XbZIh6ffli!`08FN>>EmZEBoqhN?g|CXF%I#5QrVO3KTskZqRw zpPC5#1)}izLb+H=0t@6iOJpv^zEh3p#n~-rH0VH6?W*5Z^gA)WE#$6`QU@~S#~n6S zsiZK^0e97f$z{fSJj^@#!Z&YAD|rX>w@np9)a>i-*2BA=?X>?$)D>?Hs!fx3!@ z#oT5aK(g5T{Z@`2=T%KrR->r`UGrQ8^|rJ9?1xmzw6ESv2pP0eS>Gc(|DX5>QaPkM zjc1&9i%@)O4Y*1U+e zOPNvj9&_)QHE)D#h)D}1UK1P`N361(J_gvDWG9+I5WB^n$$A!#yMjO8$a>J7B6lTgWTXL`Iyk@hb)k!-E`@X=NCZV{?op^*`$+Cd+V zs;#xn$)x6UeJ-~q%yJBC-nAU9XKCNly!qj`Uv+fQ_U4^E=HVyLgMHZ0DCUW^CA76K z*Y#;IhrjQ4$%*4XWCF!_N_)%+xrcy=>@;!DMTE|$@xJ4xmY>&`#0i>T+Y8^FTi4PA zVl=aPJNEY%#LxU5@PH7Dx!3m27wZvs?aM(jAAFm$BrcWuE>YD`?GJN=^ZLyp=eeYBlWFJaNl*3NeT{E*SPCfGr+>0zXj%E(4syi#4}7SpUx{wSEH+{D zANcDW?ae7z_%fxeDc|3YFXn1+M%jlr2CLl40F5 z;;E01KSqdOR=Of@jO56r^u{q%&qGUh#@=gwRE4Gv7Tc6=nmv~{Hb|Fwp7y^YleEDO zLoe%wOHTI1lZQqo;ch+ZOdxTLmLvLJ>l8yR>DNm!oIP8^Cpp$pV0E0&^ib==qY|1a zb+QN4F{E6{fw`bTtZeNhk)%G8uUL8sGzN5ny0G3=yLR|1B6m9DE_BPA#}Zvq5(a|_ z^H7A3MajIpeF985=&w)vD;R5WRad8QF)1go1QcE zQy3T+c=Yxp1B{rRsG5LWK&BeD#2O6 zWsV3$eM!{M<{SC^6%(d>K8hy62472uz%U8}FIOCKa2GJ5rg&vd@d#($(38zcrH7%V zZMQaLtNe9H;GFWDkj1dJ`x2iTK8(kkOv)9eOVNb^7GmF|*P53f0L`O%LA?fEOkDV02qWTIw|Idqx`KBZ$cbgI_ zwe5+Lr&yo{@7L&i#-0m3fa3jbZ>#14ZY~9>C4Cu(s;a7FKu6Him@Y#(`?11cyYXa} z7tTM2Q&>8)8`HY_Vm3yOE{?1z9|Th7lU~+2JovFTQToDVD>Qa9;!BHc({p@0;IXMD zKNtuLd8mIREjJGf67#<}BwMX5oF>owfqf_GqivlvaoY*V>?A{hzqou@eIy?|JSAt@ zm2;h!f?eqbNJqs9JsuH@n918{c~X3A+H}`W-G|HM`0SpjFw@7U4wl6Zxu0`AnV!x_ zm=8p_@joH{_*AZVtD$$k!q&Zw*@I+4xZ-g_@J$=ltD?pF4-fptr^<;Y^xA*q+w*69 z=h^#ZC}pD(nttJJX!jMZqK3QHlUOh=;d(FBm-n?PMbnWlqCU22L?`_gYwX$eTS)$|=(k1(Q zH;2E1w!Lf2d0PB@t-e2oUZdO@ zjXwQ3TPf~7x@pyiWDDvEZD6)&T6xpe5$ zg_UaHyHTTBMVXt?uE=7oR)1K$nCFgFXZOo!^UICBh_=W4P$E3HVd&DKkN*gEj+ zJUJs5oe1i9HCK5^svCUpV|o02g0lTV-YbsM`g=xN4QXjSR$WR76yXojc@k!>jtH6a zoLhXO&9IuIgz~KxdYP%aU*P&+G=BP2pf+2rGmr*)8+xCa*8a2~D^8lAP{MX2?HD%u zl*nhT=o31YC+OnhvQ-iHRxYxaj0(lmQz$+^PAnVp^l{c_C!j0FvNS{Am9?AhS8hFG z96P_!t#@TD9*DTFFSmXP)+%=F1J>%#Xf{}5w0EAN&>My5kKi#e{S@Lh>S z8Fbb&5ktzO)%@fut6!Dfk<}~q^1(>o2(ZMVC^jXDEN}Sa$uh&~DvNFe;rjy#pA)N@ zD3_Kt-I?zXZ#Jl?&Ky2|8yF`P|MQ!r^D!vM^FABQ5Vkty;dS7 zMa=Df7o)Je+jFiEDHwy(Gt6yOt%h|{-7I0J&Lx>p`pRh4CvUV1zU5iU&1yS9GPR?^ zY$bhuAub`8?-LU)GqpThtMb(?ENGiOw!_BXYbtefeHasVo`ca1yNBWD4tfiwJcRTorE+ppZ_d?3IDP9a^3TE*83FSWUBMI)Cnj*O;>=Iw25L+QJ1X<>$r>9TI z1!xuGWws_{g*1za+k@qyZ{gzNqGMv}uow~gj&8f3d^Zlq|JFn=)o62{j*9j+rs0dJ zJ+>qAk9(A8D4wCCTXo+|f85rOEnA*ZkcjFJfyk# zGuLpI=;sVfuNNKTizX|OwT+V=<$FU&tDV9FFB0GpjYr?iHD+Z48$Of~=^R+o+b~eo3OA(I&*%aJYHb z+-p$XSP2Lg@3M!Sp%ow&s)ktcvN>yU>A?4u&-OPx6MhNv-uK_Pd|f1y|8eoeWTZWC zRwk<7!wd}t@-$N+mrCGyhi&_QL=|(}vX*4P`F6PUw-yKTk9mj^FVQxd)uJ7_Ha5r3e{(f7v*T9OLA$v=_ zZ?VbvzTd=&u~pw{a25|v^T(G{bNH>*_Rx3fu!soyB1x0hO&sk=l&K%bO!xCS3@Vgw z-u^mR{CHPXqe=idpS=a>;@T~|!%1d(Xk)*%^(vvEq2ZMuP;y}{-jP>pQXz7BWewe% ztrkV!UOtMR9?dtFY_uTpT#{eyVLFhG;*U5b|NFggwV??}aO{=;bgwz~1D4?b+W;B^ zLqAhVmaF0X7UPFX!h&q{Q?w+d z>8o)7o}H^Kg_#{N2XXXClAK`ws~O^^XczB(=z0xKGrOxrOUod=p~q)@C8lJ$d|;(X zQ!b@O!~dxDQBtn|f?I(#Sc*WW2#%Ik0$~y-;e{2uS8RujOk?0Gs`HOVx-%jnkHHL~ zg>OZs?-`IbVu$U%@$RAlJRB<>!iqlXoKvnxa zU#87i4Mi%*n0Xa~%P&Jwj_{NynU)?K;oDanYJs(VVd`Ty4Wpg}qv zQiS)gG56zaK&O1Vw5iIu_T*mX3sELa81ux}_azlib3$qoRnlC!vIg`Ief7QGdvkFN z2v>WW5A@dvHSEmJf5gZ^@my=jrB-ftMP73wYxTBlL}D6g>uM7;y?O07m95bZT zjQ8?_#_h-7siZz

O%lE(WPb5W+*66B6)5O}3cuf2_#(lNNw}JVVe)mpWGYqqYZ) z9rTSVCQwV3ks|Z6An`Nv-bv>pZ_pdaqt33xSI|3AQu;e4MnuLkInzN31W}RY%mbyO z*-U(rXuE18cc}(6EkNAU2>p>lh?M`18>h!e43d}jcZDY3YrbI>7|xZ90nL2LaPXf~ z@x3ok*+A=0Fz6XHG+Iwf+BcSvC(PF2dfoaZg6+%u%m-rhNCdS1`vh;ISIXv0htCpx zi8eb_O58qrFK1QK^3b+YGI;w?&s7A7yGZz+q65JZ{f>KPi9wzO@IABZo0|g0$F2T8 z5JFByEST4UpwbFiGgm?eWHJsxc*XI~;z!8?Idse}(my4q&Hg0w->A|S-4{Q9#8lM$ zJGe|!2XFZ4!N(q(jo>a3yO7+ixI`I(@e|snp6a^uZqOYS2GlQQPG78R#oqyFp-+D& zO~D}@^ad&1dk3EguN=0df?(YzjtGxZ=U}j-oMEK+5S%z*to3$9ZlA5L>$A$`;c8fL zO#HU^$=jbtq{EhiUY`8VNheBEf?)lGfKME`+!YmCd7!td5hs5r%YAAg82e#}uL&H?Jkp+^n3S&ibyAM(pps20IS6TT5%h(^4N6u}slhd`K^OpUCY_aC78nm{|BXs&?k&z|cAp9Cv zgCjN40{9$#%1Yqo|B?`Y{n^TbxJ_ZR@C-c2qti!kl`2w#ESB=aWg-7K0hzcLr&Qo| z6o|nyh2U7fxWi7h3lx)T!VgY)IHac1u8Lml zretr<7-@I25)`Hn$)?)>yPtO9cThabcVVkhsqGpP3WAinsbkNH6dyi$G|7_lI=4N8 z&l*ld6b7^cvZTlqrIAVGrPH@h4?T>EoMrBfJW{5`MF!colwplV_YGVlBeGy)k$5NX zd^>%)q`TIMO4>968vo=aq>&d1^YVrrAlVaG#WGj_3OtuVKGjf{j!r0#wVxr5{dQB{ z1SUUOTdei#=x9{mA~pgxm>tADxwXs&@^ElKyAwQ#C6@y4g&TH#eGOXIQRZ7p{bS%} zE6bEV7*W%Qk%v0w1xaO0@)DG?Mns{ZR#J8u|73ZB5ch_HmjfA+L07P+>@@nU&$NH7 z9300Q?O3VXLz82d5Ck7n5GUZ_;n_p6mBFuCi$QUEhg$+P93B%4b}FTD8ZE7_M*xJO z^57ZJBGt&1z<{7XQKBH2Q3PyD&&px8byaDJ5zt#j4jOQTr-{fKuwh||=1tF^&bJ1b zpgIV=6-4HN;33B%u@BK7an?qB3G#F`7?i?E`S*Ue|AHC59d?i%hixyx>Q}1R`KF}B zRMa%F@9ABSVqh5ZBheKDnGyKgw{NFnJDxo!-J|pm2(WZ4`V zIu<0}>q^ume(aGSfSfNTBohKdDBPci3a+Bh9{0owYmR&i&*S#ZkHp$q9_WjwidhW2 zQon=_zP**B!-d@jM*Zl|*U9O+j}e8Z-F;gRCMDb_e4-CbyEeLGJA**CN>6dDG`BZH zy4AV;|8b8xF@Qa&%M(RTKSW(~gXM4Jk6H6!zU8{lwij_e6cq%&*xlV_3{D6I&Px=T zkXfyLsUwsLEff`}6U>}Qh1?Yfz;|Rax!zoQZgHoT8hm^vq=?E)6D-vjX5Yy0rb9U` znO+LF02{Nz9REr{^}h$SjMxF=Z4c6K_yLeMevH`&x`Z<%e5!xLMwC^8AlMTI+OSiglC%W6&#Gq&>GlZF+m#-* z<7am{D1_`rI%dTBN6);|{>R@SAr9U_It8}gfoJ9_b2PL5_Kp}`3@}~o*XU6sFqLG+ zBz7CoR}AfGJpEOA-;Y5Ei^$hW_?=_(n15~u3p~6$bAX|uu7GEO4q;--y1Mep%E}%d zttxHN8dv=R`lX4!A7VyJ4S0a^kow-Yt&wh+d`vkIdCvm{8Rqz~eRUP!B|z_UC(zbV zCr1q^Rkq-#E}+(6UEyO$UZQ7jN5UYk(k%GTFVp_zB!g|x=R3t;by-TtSLXAbg<;vW zL+bytN^o%`YSm}v22t>yksR^Jhw0pip4mp96K2pC9txzRJ9>LjH8eDo)48cAsi>0J z_1L$#6NuP!XhF|?WnEpWRH16NNRH6ZRNbvUdb`vNO!Sa<7s53;}-}%T`)+!Rh zWqm;;Jo?$ky})TS=r;j;1O-}g35kh``OVz%<%~J+$xeFHmxSS^-}ii7FiHPKG@EL` z(GC}jXxk%~yP*yoy~%g}K*!~k7nUz&mkm>wH!cRy+2NjRa7h5#KJ-B1AetW0LGbfoEI=xjK)WpZvcL^oehcDGIw=I~ zXwT$HZw6L-V%|T~0^c1i6039ijilU0q%0;VJ)IQfJw_`n<#trFXBFvOFHh|~_UFmp zYvjzB4SD$`2I-4)(WBQw{~+?9WWHjK#MFa(YP%zV2kz(B!72v zDjOq8Y7Cf<&9R~w(f4nE&j6QHYr=?234t*#;>Q~!F4fYYDK%Qmb6fe=VY(s?j7ZAh zBoPzBK|-W$Das5!=Gr6Y8Gr*Gf_sN2d`Sqn!0V{)oq!D+#?e>L6#{ndKfduV`|OFV zN+m^gBxec(kcXY0&o7$&4(|Ahplzi%UPCt+%-*rPtaea91&7CJP zpD63~NkI7@$7Ioh*oA{1S)3<-xv+waKPaqGk7tF=_*&DP4biuNYFP?Q374Q!9yz}b ziWa#uF~OzpwLkw7@ZVIT5LXUR7y1a?_*nql76C_&XfYM>zu+}85)H2Lj_W*3&FO^y zY&ZOww7`w?FL*WN0TyZM6NvXrxAb|2lJGgSW*D1BOP<2vXaZv5;;VqdTNfK9kcnc_ zn&E5>URfAuM}e#WFZ~@Bayytnqy?ZE8>*Z1_Wr^rbqc(kQqA^(frrfuKrzI4Tl~G! z5F7*wKpD(+^Bdhzcek{fQXZd%B^7l)g|z;R?4uGEC1j($F|vQ}{TXnT&MkhR2|%^M z*G-mSSB~wc?EOji0y%J4H|QWVx$%a+ie8;=joW>%=i)Yh_2*DHVCD4eOaU+fikN`i z>jGjnXGX(KB+`gLcxVbtpR+=m!J zBq{t~2ajj|mB z_T^bCrA~_5E-AFanCDTNuJ|RW&NYD_SA#aV5j~btlmPUz%K_T?YG!|594$ZyitQY9S}5{pQJs6pYF28pm`^b0wp1Pzb;=1G%qQaO_4FUTQC4o#;_s9I}tvJa^LA zmE|2smvw71@o9`PEN>=CbdxjKBR+i+*T}{G)bkkqKvs=3|FRVdxT2ryEGA&h0ZzPF zL;5;5fkF@yzzDqsVIcn5uInFk?_AD5-MveO?hgQN3pWn@3Du|#H zl~g--gX^nmYVY4pwOtJOk%r*_11`kXnFu8mqA%-A3WfcoU0PiYMF29R8k^@C1#t)H z*I=rl$cueSP{R#d?Sm2ufG{DeVI?i7&CBYu6T*p?Wq$&OjS!fX_`dPiA^X`TB@-wO zgG#YBwUuY{iiy>IG$1|_BtrQD=)RBDvFvLh;0qv!TiDv#RyS_W2*A7!e#C*sF$Sr3N)(Z2)@ccOgNNd3-?au zwUk9qQpX-$2hfFlY&jLkf5`%)cIMtaiwbgE??i}n;_j;UP+Jg$bQ zNZLO0qN79V{sO3tK1CUgYeP=KP zph8;Yhi)`ZZc}-6Ra}{v2B*E6)!&O`{`EjRbkZ^lzURi1YVTKZeOHsMq#S6uZWS>Q zDC~>?PW&nVENJs!(2^3N$Y!-Z_&Qm6e|Z_dCj&mwL+26l;wPQ44EhnGvo84%>U}E_ z3}S|S$JuH_&@kW;7?dpM?@C}m{0xNP^q0jP9%em^`j1bov$OZqc8K^c9^sPv;jIb zsswH#*bInZ?C0QXLg060foI0KU;X01d@D2#h#|KB$lZV#$za+e3hwKJ9kur3OFKI; zz+3G!8UNa<(krPEGkX!g&a0c9PHQZMm@Sy+3fe8%>LT&c$RZnF@_m7m+Gm2GqUU6! z-s!sl6-y{TPH>EO==IFUDEIn6Z5T(~-|jm|4-SkT@%J)~WYR;_@JgCD#2yCt_LXQ* z5z(pi_>=~KtV&`cHHcZP@tsT8kvR7vfZ0-<|;u{(}YSW4<_mGnaw( zC?Ge6_ww6#M-W^9tu|f=e(N74{!~PnRt#C)71QBJE5+gD9z;imQb{uc&o5>eJ*boz zW8Dtz1%@Yeb zJNwkQbm!;hhY6#c3J%GW3>M!4Jo5W6fWTt;Ea(bjq_)8`jB(Qd%p%a!h5|uQp?cPo zM6&HG2&63iIBuD{JzGP}6-8(B(H*-P1lm;;o?GpZDpZcK{_RT)B>*HMY3u1{A&cg5 z?U6F=GEvCEQPQ}eZTMg0*e-$$0@PGviEJsVD^bj5^lkcNdWC2U&`QN>R9)y6>{e$E z>$a?teMCxJ03PdhCNZXC|=FF+a>blR0AKM8eXe#W=zr z%_Qh3qu*1w`6hyaPFLl9w1NPmmSoZvU{ggrw_kZ&1v)y)r2}q607&92@9)PC=ZN2f z;i}UNWdt|1MVZe^E-B0e8?;CF`!qaTpnt5 zFJG($Y%P3pw+hEi`Ut#6UZDNgWA)Aw*fJ-=j3^VbFpdhfbYZWZIpa`5Xx+&m!ra>Z9Q5TlW0DJ0+K26-rkXHU!pl$&>;_odL&;*%+^#r5igOuOV(NRssDCRih zqI|s08sT}K$RR&Bnj)Q(Tbjh-@Jwy@R}GZQv6@Q_CyNciSznot;C5BcW!y)}wj_b+ zA2fyyu}E2;&BaxBe*(ev#pR`JEy_xz1hTC1;~EY zEHfxC2@PxQ@PSCq9lD?%ArGhDWA%Ev-cN4u_8gv0KOn0}43~CQX2oo{#JX$ToS%by zwe)L~t6GdHg-M@c6gBv+?Hh~DWEK&RQ?)WAA0HnT8uMOH#gN7m1%EA;xi7AU)WHDT z0yvMQof8UMq1VFdtAcPeS2Ar5S9KHd0+NQ7&P@M{cBl~Gx=(5#^C?SqpZ~?cGk#|4 zENyJhM01deltpH=kO&5F6^y|oX?)IfF7>{dS~XMHmZXeqGfH-rt&yTlJi%a6#;s(rrCel%e)2*c`D+7x{Y@SGJuE!AobNM*O>fp%Rx zpg65}SX0k4l>#y@|x>RP--*J>(J}Xkg{f;CAEJYbSVRH58L(g zjbT__q_#(MBETo*#$0a>lGccgtq2f&!wm+EMU|F#Yr?M{_!9|Kka&d9(9Y83v-6ti z&V3CdH*!Bs$<9Sx4hK5Q-aI$t$xAB5EN3Y@U^iluqBo*|S$K#h(tsRg4cvvBZpr}R9%^6SlSd6o0;>_*~|!%Xkeq0UmGpCPyW*G?{O1*(7Rp)uWlR6g zB?kRQ{Mtajch9=J+;9rqG*!W2FHE8p?)sCB(IZgF_HxI8Ewf^OU7|kSATS#g86+6ui{X2$lDa zcy`IX>i_Rm#R5gJg-%F#CgW6Wg_2|`myh|>IE#kO6`5KY`(DeG+kK2LDu{d*7%eUj zg4Le_4ypBExOyCj?=8Toj>!}yDXDQimM^lp@^Y&3aHJ9_9~RfE^|F3QHgm-1LIl9gFC=YDJ^FeiN?2l%SSU5=aT5JsGWPte&Kozq%B|zi83vys!;KlJ8mZ_Og^q>lFYYAl$6z03NlSVFwc2Fv3gUd1*qUDG*s$6eFD!}jP* z#TNX%ZTt*D2NDwQ?1T+XnywaQOOdCpz4L##WOE*WSee-3Pv-sJszH5fXRg+gxB1lq znc9h@tJK7&{wH5Xo+r2I?KH~ZqBpsLv!u+Cm4fTagy)PDT!fiW?O%oo}i8zd3Y6VMKbU<&Spt zA1qBqz8m}yy`t)SOxhUnh=M9X)XN|dWe_=Kvg*fnR_q#l?YlGogCBXL;zu7t+W<7< zwn987ToM)1G)`yo?osup0+}^*f$dMYai!}D1s{IDa+e(-dAQUuE}h-JwuKqAnJZzqvZG|Sc+?s$1f=#j`}Pfsr5?U^W{kw< zuz7PkO%!Co<_hUwHa%M743U^WHaqDt!cgz>Fi7Gtdfa)gxL4(z&utLh)PC( zd)>}H5Sypbcq7Giv$sZzWQ{J+XJ6KN*II3}&I|e2ine;EE+XaMVk0LM3XtN!j8aQY zW3+T^7Z+z=K+AN0RUZAA1)l0x%V;44F+@sA>S8VZabef7$P;F`iq@a&T~@`L-**_U z>R!!a46&(OtSyrAK{w>PCi9B+2DL6F)aITl`f@S~mZ@@Je0)AP|46{#YcF1=fzjRXc zr0L4|DGK_#Qype~v)PIO0r0_E2`30|{o!v(6%EyVrxL%UkRE82ZTS!0`;GM>)lx54 zaJR`yGy;|3an5VQ4Ks9~7?8b>tsy5nKRM}2=XtyYt#pzE*;JZk;%QTAWZv~VROnG2 zU=V!Q6&En6_e8_spU3$OL8WQA%YL~SXPcbZN;;xRG;g2T|)Gx0X6WbR5MWbNp47kLZ4~smUzN@u011B0ncEghJ8m zqQ{?S#*U})CrfAJ^t5if<*&g0zPgp@;A^?8?pbTDkV`4=nY~-7SE->2p(KluV2%qO zR-xra24ov~z|LLT-lmv-BvrwKRPR5Uo?)~8alwbYrS~Q@cPPfv?tOLU%b4H{zTj^b z-kN5i%*6ckFP2q7ZK4-4`T9*oItGTigvq>`w*9tF&IVgr=%>u{$$)V>geT6(Y|j#Q z0hvk}(>5<0AmH3HK*|FrqIBG@+nrgPExn3&LLI@lS0U!(97E6{o#ieRcWOC+0QRT^@ zlbV?q(a7Bp-ey}Au)m+ECS2PkUOno{DsZ*~X`gN|pa=vS*q&75Sv`csQ4BM-A>!_U z;ebjje#szCK%3j+ZWDqyI@kSOBemBO0MN;Q zSJ0^&&V_CmhWK3&{&_7yE#BRyN+jb{DD1+U9m0v2J}4cn($^Q+ z;2ufi(XTyQd@trSCjheG)__>0uNGXwp+ZaLwZbOFx<#-5ohwP3VCsY+{Hs;oUq!LR ztahMNJlg7H0%Cj?<8e^^3ahE%PoA6W-!mRR-~WBJ`Za|`Cl>snkg&n6p%h1DICvns|RFd#JqfU6!7B2GW^mbMF(2p$W`!DmA=0&XeLn!!K zbo{L=H4BluyJCs#>!mb?@}{D%-a|>!cD&~YH)x^||9kle(>36ESE>7nYTmq|0UeOY zq@<*;ImfUuu9e%V&|E2ynB`I^F&MSYP7O3eE|_CN;}Hf_8W(wGxO%GGc)90fLwj(t z^f3(>rV#Eony;M3`I@p~aJY9{*O2cc3cPFm>5iviNoOK6M_GvOt=bM$8H z;)O5NP&aDX5@)|sa}VQw$rUAj-c$(5jCEr?c^RXKz>A=mOvPmw7_NLJ$ZHxU*NSj5r_G_N3eZ&O%c|1 z65nF8C)VAoUwvRy4SirXP?azHUWo*%Lj$evO{UkvEB#o znoJ^z(MI1&oJm|Wl|yD`Sppyt#JCSx4BWpUoExXK@LnrscMMvV_YwR-pai2DoaQA# zuTrx7QIdd)>| z=k8bz2vdIT&UTrMcq+ZSQp4PCu31qdsPsUX_5di-bJ%62`=$5owJ2yhAWzx9t$Z6x8_HVk49C)$J6i4Qd+_HrM(s7H0ZU!9dnQWcEtA9U`3z(|Arj!hbtI*hzh#>M%XduUNGb`0#9i` zzud~-|FAt6Aw_-KXh-M1JxD$?H<$T@=am=e{;=;9n^}z6NKWKtA9GpB!R1gBFCwEX z{BWxJnQFB5p3DKGg)@wZXyW5SK)giVZTrVFEX!a`CwB%y{EtOH@yAgG_MkRuhufxD zrK>Bt0E!>8PwGiOPzLL2rH9fxfm`xL8jvik?r^V4g*>TbZo?SGeJ7QD$UnAXD8|b@1hm^Y9poX9wi{N993T<^-HgR}22_roXcN zH82aVx~~Z^GI)YbyjiFou^T%*^FeoO={K-6i`r?L@zNdm-ZP`zZiT*ky+Lz&d>Z>@ zWAkYB!@0)ey5~%vTR!I>4kin7DEj)m1p}m_T}kLK8~LmcmxAm6aFeBchEFT>v|Uh- zd;i*}>P>*CVt{D8!t48XU*IKr`@iJoJq-sJsDguo$K-NbeBYY<+V2f3nXLmomh+id z-k|_9owA68q_g`9{UFAp7R;sN%0NQ`xc&h|y){l zh$Cg;$s;Z^En#v)u_YU%cL0VD#Y9h+*6EK_Q3ee-SR8S%}`V~Sc zlpz*TP2Evg${VN9_=}SrfWc{24O{JvPfdII>uW0--nK*M((kMDeFdOCpI_!OQH-w` zM{Zp?G(*zrbApOc%#M2IVTPnvVM=b@m!K3)#Aan$?X_ndOD4qGzZyfrqgXOl1VM)5 z0K0&KtNf+UDzo|$|Fc&WZ!;z(Ft;&XrkP+?c)2R{m(CKpGgZVP99y58 zvdL0GP-Bk&7$Zu&tNR4VenSiZBMQhYVVgh9zx0xC=`kbh=pm5T7E$hOF1Fx_oG`{q zKS}~H96uO{I7flr9MaXMnE9PcpH?JD zpyE-44S_1=19rd}T_1YGBZoT2FC$~tD~ZuVnntM>N=SEu(%sGf;ojdnzVVH5 zba0N2!?X8(Vy!vXoa;w`j7f{Ac|Q|kC~_mH@t^|j>P#^!KfznTig`cfhGs*r5p!-9 zZ!wI2t@yqW+3Z+BGl?DK-phtk^_nWWml15G#oX;b2_(EuCm<6SXSX;uD8Jw2xFc%~ zj_s9_OF0+{&#_sARqj4qgz7nBmvi23Tx?KQtCVQZamG`15o8*Ixm~ABNAdWRYBX z$$>rsl-dBKA%(|pIT)=cxH2Tx!_934LU~1>8EZ~32CUkzpxaxSs~r*jXZ%ik#i4c- zh4mJb$hqP|UWmsn^8bpwm3xhCQASk*MG~`n=q9=DLooZzCFYLP9k-}pYsWoXNFcjG;j03=vog?sk#B> zg2|e>hgtIPY?wZ4bAKIcyZeJo6bR!J4m5-pTmm_TPA_;t~ z5Q*}P(Uo&ZU`&`h5H# zSz+&McI!DuR22j@sY7)dYP}*B5y{!9hyp6^>`OY>apLX# z)M1ZKPvbM`bhNc=u&~z2{SaZ>+$h4J9fae~@)ATpoti+*wI+<&YtrHJ`uL7`-yOK% zm!y&ML_F_&20YyK+mQWl=*h^+fx%L!c9~jbw8eN4<3G(9DZ7&;*aaM|=GBH62$sE5 zFQnr1Ro^h&bh#eR;ev9Kh@(=u0*}SHTB@l~bdrmMW%OeqFUeOEr;Sa9UDH;OOwWX> z15j$A4_;zWBW>nBHeO+=Z6$FtP@oDPV_OCwaA?jgagbrL@xdg*pC9Da%XRMkc4saK zKROz%8rHO)amK~taSpPIt{IEzG58`;xF0rl@^}9hW8$#(MRdttm7(~3=y|T?eUarj zg=UkW05AF4=4|QEkNdt#_8JxFlbbUm*|8(V40>u4QSHE{czYcUm5eZx%)hzPpr}PONElwjk{!cS*`uywp4)O4+?5#c;9_-< zT+oLn&g&|@Dd=&ul;XfC2l~gh-pW#l(;q?bf49v?kc;KC3 z{tAzls(b$$a;|g_ zC5b~D1oFy7hAiL%AUf!%lPi>TH;EUyle8d~L0o@0vZ{H4 z_uq8SMoj1%Ipfx2tqsxVKQBF(X)iGnFDcuPC>X|*WlAHH=d)hzBPq8!4bK*lwMC4@=%5J zNZJ_nS}uC+PXPiV;>)D&vm**PXXOlLD7ekvW8Lz)%Jg#={li+Lha9t&S8`3%$!R1m zl-&Jjr59uuH?UA!ROL3#r`>q}@-U!_L9|n*GO35%#-3}tebxUa|3M@Vn*V_5C`m+Q zP+us6W}UVu*zeJ?+}7=u0e3E~c51kvAgw&5sO9t0n|80eX_@FL4kv7@B1nbA0P8{& zIE00V3Mxb{E-vtiw};AUHh!fu1^kfl>UCP^dAZQxjRLi&U?Ih!y6ClA7q~{u>NDPp zVE4ETG-Q8)N7|AVwGnGIkE6r@ULf=;bxg0Aw2O`MZxqW^bHpXfl3)J*J=0;=Pf9HI;c%NVuK+LE77MbBo_gE6UAg>0TSFc=h&v zRBG97RK172fMl&NhK{88^;~Ku+^HT=%76u``0-qqGPX%v~0KvZ+_ZqbW=d7F=2 zm;Rvo>S1}QO?f2jxuTV`UfBEX{emtfo$p0bW7G!qYRR^ZvO5H}#o0@1cszG}4_X3* z1}ca|=FSUX0;XK)GjR#2hx1MqD?7+q{0Vq>xi^nsX0~ab zr}N!|OWH?BNf$?&Sj3&fkQClI%GUn9L0B?-3}&PZqI8PeL&e-3AuOhK5UZ1+Vb61! zp}jTJhElAf<6|+<3*5kJ06oJ zpP=?hKq*P(&0vJMlkz(%(uwKRC}JW6NgvFzM23Z5QwPa(G0SL9!aGyk6)|zaSP)wm zOtFPwdpAp13|BW7FBp6Q@^oHRu7Tlkr7|xC>x@YzWUA2sVfShWezjtdN#EDY-@bTV zYz4)rhASa%M@L8Fv#rd3!C`1DB*J2YQh)HZ^uAo^Fx6UFBEoh5pF$K=P1?f1D4^Dn zk%yc6lLHAiUPDY`ahnmS;FDDXs~#!fuoD=h^;+EgfSI5EyodlBv~B2BqKRnN$Aggm zfdI4Gg!Nq1vPN8*l-F{0esE7#^cGI_>2`PTjW@yhkZExF4~5&{jXLhRw0K}gs>Ks# zTR2ZwiQGiQ=&vN`%<#4%?Rf8(kuG7G3=9?)>rm_|y{EWwf-aVV&mVQ;tOe(m(YMC~ zNkkbuie;ux3f#WK^EzKsWRekvCcN&vsX$R~vn=|{3*CoJSkkmqHns^(pyEyh2z&Ww z+~VU5W{{dqd6zLg(eNOzX&y)a`E&D);Qu?YX@kzb5u zZO(h6N8EG+Ifj_bxOT?)H(h{7i%kLVJZ@j~qzI8hDhDTI%sIAOK`|NOW1MfXBRbv! zRm9=ivYxGAcSu(0d(Q;czI9ZjPi{ZoGv^_XWd0 zt1;vRYEhK*d;*d@mgP32WeJ2M(yY~y3hwk~E2w$sCun$&;dTT&7Cr0#jg&N{UEhy# zFmUw3W`6Bw9MwPfNfnv~Ge@i8*Zm~h+2fzSo8^JJobYQ7yso(Uw$RhR3hDf~He1Um zJI$8|QlMJ7pb=-HU1B3@7bB}h=GD*kunhx$_dk`zeRbOo+wW(5|ESa({Z6m|e796N z3M2uFtUIl!3x8)tWd8+r((vc@#Ra+mWVu(r~J?Vd_!nDUw4l)L|tZbZ1(tAh5lsX=6U-RYaqPv zvIl}sJ4$Z5XW=^)gW_zKy~%@WWN5#gq6e^Fj4aC@;g1ypQHj_@+0xSxu52TZHC1!WN`aq@5>VvhaRdj*RKdRt+|~#JbvR7vA`ne$1o*%iHqkiaqiI@{O?T zRWix$Bm~dmfve^sDHWWF+6Kl*Kw^u&fL-&hDpto6nv!DtfQF4VV-JVM=>l6%mZKen zOrJWhW=TSUCLrj(j|F*2d4^akARd(?zqxYRYC@tav_heX)j#??!*bp;V?Z?uL`3+@ zS~oX0hF1y44Ob@=up7>BCni%&F!R{;aV39=d*ILYET_6F(s*dlfc$N=RR&!u#S20# z;`LP_?zY&WxM?C2^3vd^SF2I_mBzygI9va6hQ(i(-g?(o5Ra{7M4&%E#$g0~{kQ?5 z*dofbbBaZG0{d>P(J9TIW;+3hG)8AfK!@ECP@U~H%ZXgPQh3TQm%fFD@J8&#+xMH> zyGadQgKsSWsrz`e`dqS|8|@2HF@15w&tYBf$R+HDj@h!9{4Q?BYvRIEVhWa5obvI)EQm+FPIw+!L0Ib67Jlraw+ff3aZ-uY4Zz;Yf<=MyVeE4jT-rMc6Q0yCd-!UFMIDPMEW=B z3xR@$_qw0qe9&R34O*S|Vev<6(^cX1CMF3&9<5n*-s4P|JY;Z~IpRzVxnCMbwE}W{ ztl|(TNB)^)iHh?rK@#jiVCwKL?~zEC_ATkEW_dgmCYS1Kv~M{kUPnNe0Va+{gAnMw z2;mF*;AH-NAHZ|k{LCe+A_Dh&VuonA>9{fzHNn)NUZiS?({4VS)fCf9e7=_*5Gwq; zzez&0d@oCBijx_XVOjOs62wW_KU1gnDVtlF+tNjoJ>_eZNfGa?mE&wmDfk^CFOK8* zKTGoPJ0C>0-QT<>UAojZ#F}8$X$lOEgV5}wynJ6XPPEU{f{9c?7u&Rnl`isGuvf*{ zsQEJ>;X*F%Jy-XGmSH@1`QIxM|Dl8f4ky#n9z9UU76`V!_yVS>dy(~c?bw%k_VN>e z3@MW{GB|i9@DH)!2)=)s9r9*+2MVBa0N#mU@P9Tq!6i*os_LxBa6Asg7xI{C=CkNqeA&N z3Yw7n!g(KmZ++o38!3d;7`^VU*wtMv&)laIQ5YwNNc& zE__+epw<`?vkj3ZGpx{E+!8#WJLa|=KTPPQ1PZZgRCXO+NL&`rjOJWvE6H};M0%L| zh{|u*jfkRLPdY`vn}QW4q+j@mNe6q4tF=v{1tG=3O#s$~ar*nGq}40&=iU%dBqP` zkUVPb(Ku`k3Poz!BNnj;b(iso$)@$AP4*jyD8?Xv81_KJy7GGh{c-*!nK5}|cs?-V zk78|bFU5uDz`-t2_^Chw+Ku*@e4qcYO@yn`r1G>A2@7ey}X1R)T$TxXgP0V`vC6wA%=56@fKpsr4zKGr1SP7DrU=Za&trF{Wro)$ZdXS+X91a+nOme1C@uf=M63h$ zZcK2Luo$$m4u=Et+qJw9Z-T5Xu=SQ4PS7jYbE0}s(0K=k!PPcsx`^(lp`s0y)QWGZ zeS)MDI{qU}z})dT8Bz+TA3B-vkEJEj4ydDJBR$x~s3`mEVyl5Mbv8Hn^_JMv`S?j&?}dxgmyGcfsXq5L9LJU%K4XX zGb&xOZ}Y=3M&-y02wAqlUPMj^D<&p3mcar1f9c3*0JZ(mpTXuIU-zd1wanW>(TNOx zXK@htjaD1Uz?Y9xBS9%5ewT<*lwb8$4GKqXODh}^v;|xULD4UV$2jG@okU2=UrYebj(YRMZ<+P$C)J+$Ub1)eet{zet}xq_@^F5>;q+3XI8r!O z6qGl!RjyJv*Hro)FAQN4a*K<}{e5x7QpY?GGXk-$esivVh0;vo7vw+J3m@|Fy>;1C zxE@+q{9?9rtI(=BbN1FQTeqkDCyU%kY<4CMK5KveEpxp-a3kM1p8}Q0SD~1A1t51q z3s-{f8Dhc`hrA<+sS-XMAA5guj>bu$zo0$fe}2DpSA-<=K%XuN|n zV-^$g7tn*`@nFzlu_m~vSunC=mx`6CK<$>ydr46^YmAhL02aS{bmA%pDP!tiNqN}6 z(}kk|U1;3Y@%HW8P+*|28PDO?7iqCuB-W&6pT6_BmVh0{B=dY*SK@HuK%4(T;uI5;>&tIC3l zCRCl!Q6>7w=n%K`nMHVA5GR^%p&B%V(r?)@7AlH9?dzlBhg~{35-qMLWn2|!V z75+HC2~aZH-K)$=x=l-&n>64ge>}o9JQsY@JREhRJg^F4y-Ua@MQSbQ4)+xT(`?`2 z0|O=o4CYUAztd;0RxlnuW6ykCF@NER@-TqxOOJkL2?n1a_6H-hc>}j)a$ooCAj3f@+{{DgLmN}{{Rxv2PlI^QTP0T?rb?~m zS9;#iIWDLs4yA$OeuH zE8{F22w7|jpfJ)G(5?{G3z zq;%q(s)LQEp)8X`oJDt`Kr&u9e=vc?q}_nQETA0|FChHlo7sT9a1$FW(x7HoO4@SA zPJ40=s8b<;9ohA}J>qg9H|Sm@Xj=LeaYs|kV>1S)ojjiD`QYx<`#dZ;z0Nw&&EIf;UcG3tq&6;W!IzUtV7?GQwEg$nt<-G*h1&8wxNyReq^)h@J zRMgj|k>ZtsVrHIaDF1EzNTZxtde#HS$hV~Z-39CoX%|%~A63Wu?uLgL=?z8XVWk46 zIK)t2JtQSrGIm3_%zDiBL8uZJCApKjI7Cjdl!P+Y9n5IXVYc_5_1%Jj7Ilp~;_wh#ra8=YZ^rK`iCO1YpVtE)A-ARR@ZI4Svt!qNYJ+aQiLGl|)2XSVwM8MC(a%HX2-V zNYkYJcrwL7<1u{_PSCAg>vPb4{YOEvZur)g`RP_4sLp10o>Ro0 zmFcDE#>ekOVor@$(;x996O4HBI9|a#?P{_CzHrW{=-|f)@Iw^*(`SeRuyk?8-52|^ zKYY^Lw#>*B3fzWXKZEB->rHeIH`x2BOs`5`ps-T$J~PY7bJ>%P)d4;Fz0Y8YW@5N1*+&&+)e)RJ~Qx7Wizp+%cy^2<9she7^>qWKQo1u_D*XP`lC z-l|f)u8^0IZMxBW&06cQ3;~yvI{}xSK%N(bZ2h{Z+t8iy5$eAl9^- zwP`Vwkjp9?|8pMw=YlH|h5)s59B{#;u)t!nJA}+96i?TU!i@n}fh#VXRH3z`E>v{m z>HH=Z(P4(AB!@K+{h{M@i8EhuxrGTKZ`u=XYPYxEX9S+U4*lb0`0_J!LX-)4ksmbe zvH(x4Ka_?qq06i7qO7$79z7YuN_AcV*$}Fbjw<9#T5A#C;v5xBE|*u~uULcUxUAOy z>6EhPV23H=`P%o5?=-Gb-kZ3wl56B3e5J&df$KOqTX?4n{rE!5?u(}JKoY8463aQC zSF}z_W$O(?ZzQSBKc`GGy)ZGx0v>1dgu2Je8pKxg5^BX2h$2 zXY0jWmJ^8c^>&vs4sjoY;m&{VI@W5yeV_v8zR^0YAF#Q|0aB5M>y5M?$)_-YL&{gY zxp@X^yQ=KDvcB?6xjE-4c61j~Ez?A0uV&}+^i zRO8bj9)+8_tHsg!SlLxA5faDfYKz1A@x>&eZgh%2ytqG#)PcLmo&Q3aOD;$%@SRtG zyrp9pzS@q=vz=|Gl1}Lw$Y2|GTdizAe!&kllGJQVe(6Xr@@&AH8o$q09`;boe1oJY zd>rV`2b6?YW|Isbv5kYT53=;&7L&JAH`>){T!X+F5>OQnG-DJK>O}BOWrekcqb|1M)g~9ExS!Ip&Xc>4cO zFTWM46+5x}E_C4^vGvO?eph!9tWWTv%n$oK-~I3926@u>r`Ma&3Ap87I40zVNrgm} z7ddR1R4a9bCK>cxhqzWcPHL6EL zU3A044!HF9f)RJ4e9EQf!Z^$+cn<81ajbSY-(G*vOgdJVMti!&&n89&|B0wR-5kyn z4?@nFeKx82G_$~~Gu^ix{v3F@Qns1MJq0_l6(F+cg-)Z45*E?dj458;b{?_D=`VFd zX96A<-71PA8J4Gyy5HdHmp(`A-t&O`&6DTQ1!*Ua?em26fA`=K6XYzfr!)k{?-lzN z_TkmUC!Nc#x7ScR0vYs1L;+vwZ#3|7+l(gpy0={-?A0Awh4$FV`RC?*KdqCqRkPMI z(&wb^1ckNZ;)&@%Ns&pi7+WIS#MZ&D*)c zJsW6TznFIbUPK=sA`2AkY#sttw4H6qBMF2E1p_A*4Gj$k#qup`&o?c`kCYxCz7Bvg z$8hMQt~ZyI@PYr6<=^p8(A90UllC*tA(zZyjsE{0W|i$Ce~r~N8u0tVMWq9yyA0de z$mly73yEN}n>~p5+FWiZme5H30#~jl*Kk|o&oEJt^L(^^R~^+%!#%xvxyXvjC#kiQ zl~h_22lraaVohN*n(#joZRVtWED$zK2>41@MC&b+dEkMv;C;E+aNJ8IQF&5Y{j^NM zOY)hYSY^BIZ^FFE5-q&--k3|dGS~gNAhiAY^{qInuP5neszt>QqRVZs1t%-~fs;v; zyUr)d}0$o1b>J)4O#}i^{ z%_{v494?QI?V{tMK%|Y@!jC#ZF(TL0&$-YZ)gLWjjCHe*Lag&BJ39diU?*yDs>ig>tgoA6f(2RzX zx;A*Ax_#m3e8&sua&%XX*}rTjQ8Ys?BBhF53VGvgz4d&QYUfW{5F~%QU9LFiS+IY8 z(EjN2J%<_lzuf>Fio&o5s~_Jbv)D+gLbK^2529I1ttvRvz@S+0e((EFu=tWb1}x3v zOahuY<*z$}RWLZ3(^8Ht+zSCBLOLvT`aYcYB}B%DwP1c!b9>N;(Ej+)?A~b97wxt_ z#1l}v{iQS+?)?4gcn`SfRY{QSH#n>xfjuik<-30oGuDL7dCy~;cJw7}xl_SVoDdOz z-^Whh`Q2VwzhWg*GVZbiX0hzP#0Ycp70OG zufv(Xu71l5Kf1ny^5Mh!6aVV$x7c+44igqYncUUc{s7w*a5X^tKE>Be2<;b>c0M9- z4GU=YIRBha2r$b&tID>WNl0rk4)%GhML;m>@d{|!dAz3bT}QyxaBCzdg~R=GICYHh z1^&%~cm4E0>Kn^H{7Oj{Dcr>J{vNy+rE}CzOSD54oH41bpLgD4k&@le`DE5lCLVkX z4`RDoWmGP4D$f)0IP113pL0XBs(;uVYO~$N1beGh^8)aj$?Jh|X_VVN*tIq5p0T{f zit=*Lv(~E&#FPf#8R+b`GgP4DaInCqTCOolN1Nq+@#WLX=<|2}O^RCy8gSyN&xZL^ zxvY{Ld@V+EgO=xWhe_M1(B1s@PC+__U_A&={7hdwx2}El#YeT^mn5mHQAd$=W=ji= zZdH0Bz-x$7>J{XEx*;`QDDR;5-Lx3gqv1DEGe#NcH{|?SUR|kGz-$F}&DkG4G;^!~ zJYqI?--AG-WLm zDK8LB`TCd7ObR0lqiJXF#Mciqfl;ru$(8+LOHK|?T3=jFQncCHe$ z#c=`rB;9+#ql6?X88jx~KPUstp`VXe;Y?Jp3XrB^gzD_-Z)r@5!BNKfa&;U`l*E70 zzGWx}yb>`sox;T0LP-aen2_4H<)OLAJ}Bh3V=H8rOz3u1$FFcMS$HCp=7dI6MIkkm3D6))h6!v3+jY$yZ66qqtb!j`kstq`Tp6$(IpE)J-iHiC+ zeJn-_GaFqy_{IDAuEzZ_ny3_7D_J@x*?MO7T`#iWUbFSrWjJfnKomx#p|QTuleIqTuSe6634A*QTEm<6N8a z7IO!s$cvF0JWHBCzF`b<_P&5S$3T?*%f#wj)T=E@_*Ww5Ow$&d?64^pQdn%F#Zky? zargd7v-{77nv9Ea#T0gLe&F{N5D0f`CT^m`+$likF~ie%@@~YS+N4ZRepr@uNrVSTKi2<^vC9HFcUeCD3sN0_ygDJhEqI_4|i~pQ`>=c zf8#?P=bS4U?=~_)JTdpxTXIlRAoPFvdiU8_MKhTC?*T>R8}u?ZI#GNB^QDWP3sC34dB ze=PQ8P%BNj+KGH?H=XHu@hOsw=XYX@nwOw-+hykBfCPt*EXq!a_v|kLA?m(d24>h# z(&V*BE*?-Pf6&=s`{R;Z?Eo=3x!65rF;02fc_y4k$#`$Odqo%*DSeutBUK^mOmw51 zE7hv%9Kt^z^efeK$lu`(gh+EmLZa1srDb0`tBv|T+zXycY1H4&<~b65 zSgSiwxxD2{*RvYQhN-h#&ZIG7F>ed?E=Fwav^!iP0r`cKPEQppna>#}GA_d(35C@( z=qxc=uXkoxga@@{Eu4|CsZb4NtnouU#ma*&=U9pvJ*muiXkyMm(R`5-GK#am z*T+6P1e>&4N+~tIhrwY?zys}jts`xGAKrnUN_zPLZN$A|MOPevOP@B#6VtO$dxAIf z5%X!vi;9>vP(g!Ufp9!lv>fsW$Tz{7y1&Dv12byn+?M3$$XoOIiv}o6d}YN=)>)0Rs=qgpxW+H^lW2;`RMN%cyB3A< zo_71AeeSWTo{``j0rv*ml%0@&_xM{E7LcFLj?^e1X@A2d{*q69HwPK)5Paf0h2efL2KCJXln6C<)@co&J z{Sbj|ok7=&v!+u8AnK-*8VBN`$TWUe>5ym=~UApa2_-o5azo?7faz7f9*kW|-0goYrEO;P$h#H;zba0>zF!mXJk%SJDm=L@M zsrX!RAI}CJP-=seN^Wxb4ddGnIhC~L0vOk8mL zzD7bnEaocTxiYBpYNpaF?Wor z-tgNLq{QhN9KD_Xg&G({QPR=jQ;M zezxGc?Ctg^PKM2HNw9Aq;wLP1anaUAPuaz4U6Bu0<>Gw73(~fVXuV)~_#+>?!QSXr zI_&Vs1=_h0GvmAW|?sd~Dw z=cTw(J!94Mnry5mfBFq}J!rlG45Ue3X*Da7Jr)5J0E4ol)ZRJFDFP9lwB=PugnL39 zQ#RsRmy}wu62&C71rXuj&Eiglyd>}kpwX8B31z|G?=u$X)0a%;8lttMv7`AO6ox3p zWL@n9h5_a5#oKmwB8M%f_38`U)gN?;hXndh9J$ZnTC;yItt8XX4FRu1g?h&;jkmzM zllA5wx&6+wwwGsZf;?k{PJ|Fyhk&q~en03cGj=~{pLM1r3w*8m*nw=^sZz!NCBPXn zVdrkK)eX0j2ZpTlTBcr{mkB`TDDbu(g<2H4hPio1s)sjtVAQPx_#4abmwhWC-DL65 z`msbtOe4Xmc|9GNzjD29B*Z8m57?(q%sTpor0s{zXHv#`PI4@v>pvR%F8f=@~m-uA$5aeYx$j~iJ z-yu_ZW3*UAD`$|iI5`tS_q)Hw}a+`2~8E58WD zeC}U$SRQHMHf6CJz1X^@b@T-i2$T?$D`CQ1}>^FniE8EciZEHb0t8g5 zoVvHW_e8hU?>PVIFYggJ`m4Chwt1+dD^aEmsaKQRnyZuYykWINgOeYi-_y$6^Ft)+ zYO+~&TyU!b?{F4)_Ibne^J|9ftLAzzc$q8dgBUGw;DvVOUi}II84C_KZEFk$(#|$! zc*gth?vb|JHBIt$ztPOipC(Eh<;&23g+QQCW{|xBJLB&OnbEU%fUquaz~>>@ty5V!Mw<9Ut#9|`?4_a%vt?RH%Dhi`(}m*$TN)ix10*@I zxC=qpZTj68A@_!md&7E+&w9q?O##nsQrArFV}8aCQRR8rPLk++p^5V2H$!?Irgk_N z#m^u&jw+Cq?LM?7?aWk9_LYXgfxdl^t*0s<@MGnWDJXJnno5Y{Lz}R~v@@m6xkm2#`9kW3oQ+fqIvAE_uzAKT_4MZ z&v6Rx#lB`={Qk```JfZsu}*((p@R2|8~0=#n<_HA3#qs!IJYa8j)`1}p`P>m!c@T& zm$QN6uXnH{+#8ae1m#QVURST7DV@+^+n|xR6{}~4(8@;Y7O~!23PUDYtO=6V%`QGi zR|6g0oz;bL%QQqcI(@$1ysz_%=$f+{~wlgkp`!|pJ4~LMI%~@+>p~^&*tLt5>iuSc4 z;n-9W8*7_tB!WK&_27g^-O8nufc?(<52?wUKQmEHgDmA9q)weM$6Y&E%*w<0vq@C$BDwFlx)51{l&bU+kWjd8!#;X8Mx_G zMpN7jAwIrwMIrUE`g;AiNSB%;Z?tJRBE)AcOgp?_-oG} zm&Dx5cUb}qGEK0}W<8c_ERpJ{ayjp2d8wL`8>!pF`0V-`;(kcTR^acq1xJMqC8MBP zy?QRu*UiIZBi?sqCt`jr~B{WCc z1+3Py9fOm|evg{6a5WNWJWIDDpE3-xs<2a zM?9~J|Lzo%aiDnUR3>Hzwc+H^K3F|?=Rw#`)}K~$>u9Mnp`OyAkfY(?fUhZk%D72S zX45hdveoGctkB#GT-_hG=>H551$m7s|0GFVBu@8Ok)=c<6WG7G9T`=b@uY{jMW-P@ zcA8tYC=VZ3@z$@rF<&gM8NTO+dPvVajku$;1dYBjj5qx0b%-P33(WBC9vjM^R` zgXQoy1AAyWW1Vqz(kF_ek1MgvUBj$vzMcIri76Gm-FpV=i2FR&Uo$DBqD{#wbi5sx zMIaDo-;2v)8pU^Y8p`)Fq0($>i~08vV-JeV`ahJT^q;5+X~H)o!YHqQ*t0r5ECso? z>&A&sn0cMADspp@9=GAIm$`c1nOV;|4{E!pwPIZz&AzHz@4Eee7xV-}K)5^9#C)i=VPT3MxI{uoQ04KgQ&Le`CIT!X#ZCcfgH<%nhIP-}Oq(pU=ApvBM?lI?Vo{X1U8JIJG-CG4|7P8FN}>{N zl7ulP4flD-eV7rRVUCJw)|>o_;lKCihq?<7P8@j+DGMnNKAzaOLX_|QJtUpJ6TbfU z;s0-7t4{#z{|}CB+D?SA8|tWO)EZhw5jpgqxoZo8P^#x^alXH{9Pe!*Mh~VtF7mz} z*K9dk)hqlN(lp(BuVclpdH2J0(`d|&NS+`s(<;pL{2i|*snPiI@t{+3@o!WVTkR{$ z81#&gLsJ{>WRo{6&6OrEq&$#z#70p|1OJb#_`i+B_YkDwx4++i{O`SSAh7y(mZ(sl zu5{SgA-%V4cSYSFLGdlUzJujljyH3eHbx&^Px|3XN~2 zgDf%fUH#_>@-E+ncgziQ1Z+Sk+d(q?+a5PQ&gDQT#nI)aw3wPYQ;)e)ffWqRl-W#?d50?&udv1u+rr zB)_-CiK*c6ufr?SXzK5{&HE*K)ozo*@k6Xsc9OGL7wZXT`Fs34F5edSN87W8P+E=B%yN(AKf2KZ!T$t9%Htb^ZZ4i6jTf*%$$t?Y-3V#UH}Z0 zTHkMPx{;mC*M+->)_SOlOU{i{T|X8b`P&REBJpPy{#~@I`^zg^VdFoOdFTLO{XOrm z-HZ>;K54pTzqx7|uXH=kp}BkJm*$Y^?f*MQlTnmlxS@rD=8@Z;FE9G7?g`fm-OSLC zoi9^=hyF;Lbr?|Me90$Krd5mB=ChtUX!>R2e0;;E$G5}reJbgG>DspNISKPHr{g7R zBmj}v?gK7X?3!I31i?sufxwUYv+;27ESW0@gI-Bc@Um8k2HpXY+e0%;4>joR_XrZbESyqfTIss$3UdJgz<21h{tM+6s$!)ZG=By^ zKYAE7TR0OLIJ+ABjOT^<@RB3Et(9j*9bJu zDAwk)iRl7u0?5E0k+z#1#)Z!V%wKl|Z?^KT0LA36){W$K{WsZsxvdpj?OZF<8rW;C zR{=j>?a#kxd>B8%hlv&wVYv?O*%v_Lzg?nc-oax#PO8IM4HX z7XuQXX3SPyf}BQK{`U6uwXn7t8?pNc%`?g&w0m()D7vO+w2xN zhy2(c3(+sO)=GNkvQxYo9EV?02;r{@8UnB}n_3pWRn@vs2%Wglq@qYlSa5J7s4wNd zGz0CALv0yMlG~_7$Lf6j?yDeh`F$r}Fq5g-f3W=mV}Z;PI9pt>h}R*PR`46jUry z4}5-x2Qd5%rNcVrEK$19=^Y3t_4okJ$uXSfoHa=rs*P)l@-BNT={79L?yDaz+{xB1SU4|}N;+V6?KNp5vheWSzM%09L$PtE zzM8*lhIj@j^*tEtP$IeBn?994uY3mF^BKhZ9?Pd6hj9*ycnox)um_FtzlE>I6pFt| zU^pKo?K@l9aj~zDUM8a$+f;-TuAix`W6IVeL{qUGkA2)gqUJs50~bPlr(>`X00WzW zRO=RWegGNM^_7^Yu1(d92lVwy?Bd%k;&-*=PkJLO2!63(4wC@hccU+%l&LUHCW&_h zj@@{qw(1yF{HxB;9Y!^)1bpr7s)03CQ^Ga8hQHbQ?y+>q;%kHv5+vzpXa z_zaplfy}FSRJWdx+k2q=j88gb#6+}%#iR|NE}v&B*c2XgFsRdd?d|_gOn(F0@QN&4 z+Id6bwFBy^glUP(tZCO#P6kQ0!$O6{x|f6d9K|jKt=`X6?mE0X3X=WkTz{5}uEB7j zHbnH2KEb$PeX>}LepQ19-o2$-0rqX9My5O`*r&fQJ6ikR6cQo_jb$1>Kg-p&?vHyn z=PoOY0T}92z8Q^1bd<%yh144Y-tY=xPpepN;346>27Ar7(mj#`5gWU-`*FQ$vlaq9 z_UOJmg-d%L38tr~M{sEg)jjUaOWm;Kvjr8h`O#C*umc<9Y91)rFLd0JnY3nBxh(pK zvElN*sG@UPZ?M3%x#6QbEy~+ubl=yxbJV_OyKJgz)u4#Pq)wvPcRst_+Um3CqT@PC zSf<(P3b>pVa$GgkBsXa;uBoFL7Y?0y-O)KW3{;roI8H%YHp}@UW6iOpJ#JZ9=t$|U zZz+BU-`Ypxojf=A)^Q{Q%idniWG_C(`bzJ#F}om>oPBiQ&adbwE1aJ!Y9_yT^jLhf zx4xoRm@+x^wxhW&5imf4Cb1>z;G+xHzb-XU@alBqeDd`4%b#1Z%O+~Y^ zJQA0iDRi3%rBC$ExZ$an4j<0-t4fCgPJFB&D6spwPEVd4&J!|s2z1L4O1@2#^Urcg z3Fij3DOayDx1h44`bD*iEeZWXe%Vw5faQ9F4j6i%Jr5eW4G4g*=$#EEc36{LFoMas z_))^I2ilYbQC^Uy)5-ulN%A|}Yr@u3A!yGQU}Zp-$A6m*{4pw3N)bL?r0*L@b2jVG z5buQG(i&<~G|}Spo)%D{UTw6S2rVY912s<4!Ws~`WO02O6`uAmSm_w?1sP;Hpf`s< zk4%B+fqb^p%a&{YWz$~cUjz3uiFzK$qtr9qAtmQkA5|$-(;mleXkegB6pQlKPeqG)Ue=Yq^~u7<_}^Zo3(yh|l@$`vG6bb~dc&yT&@ z;YL2EOt>rGr{q5C-o|pFCq!x`)@^$v1Eww-$mX)s&iWnz+F9GzgR~?y>-#_w)_B(y zBg9MNf_aaKI!S|^@lVotpzY1qxCDFpt_l=rC(~6OZ;lzXkN;`O3Lp>eES!P^N-s%- z(5So_=n&HQ({`@q8U3X8KxePa3v2wqTu?uMca@Ca{6-5DjHHbRD%VKrmEu-kQ@DHEEY+qVX0SDZj=(Y&Uw?WQQpVHr=Nnie+yKxP@`ic{+ppbl6K!GS=p;7Mx; zm2ZtZbP&G{O?w_>sz<%+_it4eo_q^h$i&^@Z5;s}mC!BX?5%C+I`(snmhgKUqw$j(2|rv=H-EV1H#$pwN1vypL5T$sc8Ny*0^v@jH(gJ+$Qt)Rs$# z^d#)AwyH|*e~3%9jjW&4_afdVdaNR-CZJNperdN@!E3gkjohBZ+pEQ4KM5?6GMS`Y`cJ8F!6p|ku9j%-Saa*F8`DweX47Jd%& z<;_`kzk=S*MwOcQ(;IKk@_xS7y}pXn*FToy`sXk{0ha~Egj z?*v5$R0A0}yj~7rt-ZWifP@-TI-L`sYyxxt4x_6g4TCCKal`{DG!;bikTN}kx5&dG zmE$jhp;-Hz&7ZnXbrVC-$HYSWo=H$i?TY1VeEN3RrpE-VJLqN9 z)a25D?Bi(rQE(iMcXcn}c2_Va@v@Qk!F+mXJwkU4%nR0(;Yf+_R|lcOQ>IufL9g;y zk&6yLY$*oThf?Rm;LIbu?KDnyf>iXd4D zgSPYVkV6~hWX>{4g(a32;24bVrcDgv!QXAz$Lge%_NpdEiuxZIlj4kquW6Zg-%m?4 zzdqz0#y1r2mvCEK&32<#4lX*K-PTrmMHsKVcJAn%vA_N6)w^E~NCzNKD)+S)1yz*% zQ8ZGdBg+Hw`jPX==IRBT4c$wLO=pYo`M~2awrsKODWz+Tabzf&G|Qj&TsG0|Fr+&~ z)fYExH85q6c_WG@JIjiK69zPfahIPWQ=pRoF(Q$OtJ z%KTZ$OImyU=B7}(f>wx&?oEoo)P}OPkJ#>_A9 zqNQex8G}g=?R2^)p2P%^*afwo{6u#$Lq(K@RGl+;?!6~A6*VgjiMpXO#vd={3q6gjGzJaAm*kWzAv@hz$gEExl{P zm8kJH-TPu9J_#A*xN~Qf7uSo~^!qO7ov?kjm%UGT$(+{k-ZX067%nsW0PX9vPR03e znpg{+idp?A&9VO^K;O2JZq*t?wtfG+#fwhyphgU@?!2_|18QAsIPLx|6Cr}U`*&*0 znFwfA=>v9~pWZ$V zVMZ@29r#pkkh%icjoDk1Ac4fXp2RrXl}>)K2fTz=rvYWHCD2dx<4?SyN&C3fOMYke zgyM6e*dK}H!_BXLNnF)n8UR(iuCX^vMaP=;R;L;-g4!Jt)1vSSOF{_vNL8>2=`Cn2 zO(!U4sG)b-6OzMR)@H%MJmyr^Nq2d)d!{8j(|+`b6-ybKc00#mUl!~^a%C_|xbFNS zMel;iM@X(;c+FBVNjmtBxw=bRvfoGfrMf$g9w%mAdYI9sTxiX2$Do$SyxJl3zLY1i zCLa?e|1LXqqjRKW$dGnbTT8vAxJ4QN;EslfC-heRAkn01Ia38GVC576}aNU&$?WN<(@oejo8vdK>zYcK_%UaKDZM*k3HqtFm?xRLhp`qIeX{g#ija;O^gK2$`l`T}ir|oNRA9#Q%`Gc!Oh-PvhrYnWnXx5d>1tRa? z5Fk{Q^>*;EFZU@C8f@_P8;nk}wLCFJ5)@?H$~NKBvu=^jmdL`(YUK}O(~sx*O zqF*_i&3i(7tDeZ6)Qm0OuAns=lby70Nwmk664|#WmZdSP!}j6H8)WHFV(hX+FMIm# zDJPW=Unu{jwn#e&F2)l$|06*^FHkoXAwco|ntb z%Gt!u8U5J01~~Essva7hE~_G)P*ut-1Em-9osz{WhpDvP@T%fM%G>>(`H_P@Vx1o| z@a{>q2sjhE&g)QE#TSK5MCc_ax5-d*v7tfD zC{ee5l&Jk`^6oeCQh9AZ@$~ZKF|ny(uiu$UsU<@y&zaorxKjc5<$Hq0#u~wZ_?>MYdlJ~KRB9kA2M5CeumKHK1px8Et51Q zkod4F;f}&WMvwja|xq_WR+?Ucq*VfSK~tVe@@e8s~Wg zy>m=Hk0dLWqo3|9g}7ulN}c*V>#p)9v-A9hXpO;7{+1WnTgrV23Aefu@G`%4g@JHQ zhkXph599j}i=tUsT|z7$e)FIe;W*;1;mbKdTN~h@SGBfzS#Bg>S(*}BFJa*qi2Uq$ z^ix~sv$|B*A){!^N9i?C_BI`1M&Twr%EX)TcODnjT)Rk`HOLgwX+5u}IZY7J)NzZG z{;NzC8R{xZf6Y9rR(~ydcxbZKw)=EC4pI5-QwZYtj6y)P29aU_BfkuqN_?zGR2sk( zVNVcO3}Gy^=(*O%p?4dzqwlG!7@8#%rsq5cTVLt0^DE+^A&d=Him)|=Q87gKM8vuG zzls^6oIPy_Wn0Cy@mjPa;p8e|&e1xJ7(;wAgfWqaQX4fSsTGknW&Kk~&*@E*-J#3y>el|Hc zKM(QP2u5NSR`~YC@g2Lo6mh8&lIPY^hC3hw&Gq>O+mgD*2G#kWJoJv*Q_F;yX7O+q z2D|kSo=20f@sAt=+t0R>_kZLXIA#ZZiM9?m$uj7ZZlCK1c_g9)o`vt4pN!_bBGwWx z<5N!u$t)1vMle(Iy)nJP*5Oj6*9IXbqJ5pwDw4U+Z%HE*jbY-@-p($qdu?8O!}9L; zO61|k%PHhG!t~{xj=7Fd*0->O%#^q~9wUBvT)7*3)ufVD%j~_qRZpMy& zT@wjImC*-pvP%-9d4>xncuUGPRLsmmImAJY8MUoIZ8v|PU3h8D>xy5$%L^?4Nb&#- zp-Ew#uxyp};Mg0i!S-Js^qQ^~*L}S`pPSl4Qo2lLyBE$eX@+pYt}V_Ku!!2H(AkUVfWn&KO*qajznH^IEHW#hA5( zOj_EOHebx|t46+C6t~I=%62<<-tZH+#ezH<{Oahk?fa`l;%Hiv#?x8_C8+uwaXL`7 z%eP%-7{2wmw^Y6aU|A}0Qg%v`Z{r69hBc(~L=yIWGhl87eNPKx5=OcJ z1|x&LMo^f+OrTHS^MdcyN8Npkx6<@|WHH26g+_RZdZ1#j&NsWnu6}LA9b@}|CHP=3 zGWkr#eSGR?+$Zd2hoBWf*7+ta$F-f2UiAto6l3qS^h$u@)pKVT2jj8#@682Bs=VrF zL}P`lbJ+oH=l;?vHL*?d8%N4)By10@*k?nq&YlA@P01yVD7qBtUmjfo@(gr*lm-d1 zVJ7&FK}!-}lXXTt`1{r1CQBGCRtMxD`1Cvj&H1=xCWnuXnOJOJHVDB#I$AdZG7WS3fn)9J*Ho+0cRivZaXoUJR4woH<(J4h?+^}4B`;Rg zmUNCnz$|_7ph7QSkL4;o)r98~_N%qXnohnCV`9l+uWI*7Ci&S%8d|SD2XD^{K;(`2=9Cw?j z#>t#w8+)Hq!=%eIohEuk;Rb`MAc&;GfB+X~HhxyS|M~z3_su0}4i8yadt+?BJgaiD zoUf4Op`@P@4GK_la3r@>v#DRfw#41`>jMZ*jaLM_ z+eSOaFW|_Ax7e{;e3C(ZpQt1QW5ejNJ>w?=Nkg&XA(R2Kk#sD>*lGmUM=jmq*X~$k-gz|f_=!SdQikwD@A7GS@&tA zd_G6!rp#pE`*ewWjJpUn3)ou@K+#QC zr_PV5J*7;WTwXfrE!$1|tgUhGkjaIGw+HbXn{I72@pn;{$&|H4$woO}fcP@&37I*S zt*!P;P$j#4)4wspSY|ds)oW|YWQ6OFuXo~taJ7UHsDKP`i0de#w|<7I_;VmAy-5Q< z?|{{k#wc?i#2@%>yf%?-ty`2Fp;Id-UsBmr!tv>yIR$rm3EGgySE zK_`gitLZE%;x)80F5(uCz{t*qo?4oiBp-`w_=V7-(pXVt9Ppud^B&-avWk1p=#Y<1tpr>a5RzZ?m1cSNX_(* zZ_s#pyz-k9Z+7r{E}-k>wd0lH(t8}bpN86@qEs=^u>@p-B4BDOJ)e6i#0^pKanwIx zXMbbg&{l_9VqmpMjJ0JQ=BLk+;UQ2-kMm0&NxWpkbe}j*cO|jBUol>mQ@0LehC-Z6 zZ*_>@$|(th_C6!!BS{oh7RyVt0c*bmo{9vWVo=Iz9&y#9WCL+LHS?%gs!k)SL{k?5 zw^)0bMg?37VeJw4-R$xnIlXedq7a(PA+rxvZ?zO>9QNEJX1zLDVRb2{7FRH!U zH|@|M0MAKKMN1VH$k!=lI$YT|r=`LCtGs6rBAll|YoOz#;^0Im&lx z;PP2BU9L6zf-I|g&RkJrTj^|VMG&!sS`da8Xb=(-+e>tPLOT^DHeJe*QxfXY5tD8N z5V>8IfvXhOE!m0{wKIM=#{u@9SDhq|1N_@7r8Dntz7m`Mkrt4~%9bkd_Oh_mM2)FN z7+ufQkhgY}i(8I>bd^Cb0v&P+svk^%ewf{2!8e|`8k46;%xFf0DaB+$WnpFGy|o|O zi<^6IdiDG;NIJl1y`HpOUhvVSo9H%Y!u*{(0M!l>oI$joRJWvNz1y|b)T(AY*Ut8E z`}=3ZE$5=x1y?9Ye^n^x#g(~7i3Mb*_Uw6RCR?z5w9g1Wpp>q2t*elBo%>(8P4;MD zq971G7y~mUjODy89T?-x>W@sX>8s-t`}P&ty=G4FLrdZ;nO($bC#2$oPXAuAQ-jyJ zIrfITV@!LcdBP)?3TtN8Aln7h#xMu(oX>+p#RK7{?%}6SU#s`{O}gByZvXJW9p`sl zWRVbEQ?&=^B;8Q*7atxK=4`p>`nb95K^dAi&|m<4rTXh-727iv6|+xEFdt{BSw614 zC{lx(_5UbYSGgJdI*g|LJ!rQJ_0W#;{T>|3(He}yd^Bm`UQ+E{!~FmtdyG(RhcM z8Y2u;p^Uq3Xf#u>FPhLH)r<^=>T6eH-yoSrWtOFHi<=bE`0CC^2Tj zc)_Dh3X@kGKVP!cVC}=cK^5$2e}P0qlo^TUoESSC;xl$A(By8Lo1i{P>;BC0I{KL& z`q{lgKuWlh#E@i6a66MMu+!H$#nfuesX1ktc@>HRlAEx*{<=x(xTAgWLkt%f+@CTM92acE%*7>S1vZ0U7 zUcpOSlbgUO2>D=YLiD|`s>-kKBurO3r2IzCTEQOc^`1EZgH^8!XHEQ`jEOs9zx8qT z;BlF<&z>fnO-L9(Oa*k-$rM}T#k4hr2v8X{{fium# z17rEr|8nzktN&Rb6<%5P!$w|qt^zirhI+yByx73fWHKkfBn^R3Ue}h2y#QdLP~&H3 zrRF;ymIC*T_~vf?gp=_CKKf&68iH5di;e0vs0dVz)vEr@WR))omxIVU%w?O4=u2}+ z?>ELb%WR+StCAb+9hfUg$(i%D1LXWI`^nike`?eICEMb zeUHaGJA94BRi5r)#}!3*nYhvimA|wJ{*c<`8Qaht!Y>4m9nmi^TA=fUgQW_{9)pSA zRlZjfS7}8eV>j+pq<_hHvW#)x&?J_W`5S`Alt2{PZw3rKEI&q#a=SuQQarMvJm-wvG{W#-#eiaom*v_CfV&9*ShP#0@VAjN*Sc1VSx_cK)M6clQev`UrO|R`IB=sQR9~O^cD3@Q*5%7z*fy%&WhN|^_S#en;5@Z0 zDkeJP2ec1Xk81@+e^#Ak)?TyZ!%2|8KG2xOF-Y`ZgAXGPfCK@|f;qo+Q0Kx#l7e{% zdyh=Z3SqCc8Ykw|C?zaGtTh3J1PcU$^##Gaf=;G|w_$OOHtpvZoNs}V7lJ~ zn$TzUOj%5Yl^-r!e8qCqI*7RbA3*Gd0l{JbpXK{7>u0nu7S3DrCzI(bH0eoh^ll7n z@%2O^utj;Rqu7-{yl=QzVEV{iy;`ew6=p>`l>AP2=>*Xd_ zQ;ip7&4$8dkE(PFAI|Rg@bVNMSSQ}-bs!h={O&ZrtYWTSBI1&2))WWS{8sJmKtL1^ zn5@4a4d`>jW?7+B4*i->5_qP!nHId#TEvGx{)$eb(q=)YOS789KRlB(Tg{wOF8>2} z%(NrU=Y>9<0z>>SyUH{%Wcmi5qr>H%J|(c2@WKM8VisE|AjSMRSd8Z;bdD)A-qi=$ zs}rUhNfbXxAg`wSMX6RLXP&(yFSTOZ*2lX)i&_(AfxL%B1Ww6KFo1b-gS7u1Kw9(w zW)}`Vx!5ykh?Dn1%DYSfi>~j?f#|3i7@h!W#AXY~KP#1!iMPnXIilJ1sz$onA>XOxU|)3PK(JAZf4#_{11 zjN=%zb`Wuz1ARory$2Hr^!w`C^$lEjKSOl$X-R<6rj0|RMudpTG;!b2|LD{`4CZ^a z!B=HDw1*O@p>Gn^GdsizH3#iuD>-#J?fR-h%SNY!MybH zUJ%+K%cDQR`^jX@40cd2b6+hmPuAxf~&g;033hxJO926(o;7NEhbd zd2k(Zgt18Xm(t_yUqz^quk$(WzW&7o?&(y3ipk&T>ev15|9XP_?*qh}iQ(GvA@Nt)h)04e1W; z)d>+^XeX6>Y4EpE`0I-@I)DXEI9aRKec>g1MY}xtXIE#(Sdvv5yhwx=*W02!6rC z`ju9Y#)!D=3%d!uQ+o$^(Jl>CYZLAmtKaBV2xv-Nu$?xg&2r=RGz*{KARv20cK1_y zUmFlAC!kemD)3}2vOiadA|w=b6sAucJ0BV=pZELxts@`@9Jm82$-UF?x(qr-(DI_ z6Qf+Yw+L32<2Ag0y(`h*LX;|lXt_P_2v7@={8h;r$>9;CZ$QBMs=p^g{hP7$BIo40 zx)+d>bl(8oKK#}X&A4bvLHj;pLdjjV>;z1Lly%|;&Y9gLO zG-p$h;=ceR9XMErD)qbeGwQFLJdPgZZBi}&wPyd}gn36W!HYmI>?3!Dhl8UfU#<_x zRUSWeEz9;T>4G6;Iri&;wV!Mzv{EsmKl7VmDlz9Zg z_An5xAus{NdI;NVKD8ou29$w7y|r!2yN-Yr=jf| zclB~HhIcg?j!VO&&DROcJ793^EwF zVqoboG3M00?IXIl<Fn` diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/must_avoid.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/must_avoid.png new file mode 100644 index 0000000000000000000000000000000000000000..95ba285fb449a6cea68cbb3aad2c97be3176bc17 GIT binary patch literal 70762 zcmeEu2Ut_tx;9`z$AV=P6$KqdL|RCw(n0A(0qI2`5JE|S03o4|g_%)6sY($X#SSQ_ zNVkk&XhB5~X(}z$NGPG_Upom!W#-JBd(XN5xpz3{8I!g5UgfLr`qsPi^HD>sb>Hpy zj)Q|^osRZlV-AiLwHzFr)2mj3mRG%zWbh9s&R9#GBdca-4+n=vzwZ$XU(Wy+w1+c? zAVP!nNe~Wm#o~Mg5r+lga0f3haU|LS<>TOq6UR9Ff+ld?6N^NRiD(ZG2SK=|v^WfOb-+SWQV^jIKIx+| zegWX$067_Z87X1#NzKd4!`a-~Q4bBq)s#laiX&v8NA$E!4fF-!8sM`B+T9uaqvh=6 zj)fl4aP`4@f)-6lNl9@S^gqyO;^5-ogI?4Hv<81?9~>HsVJ|^STuNLL!J4hJuLFv` zdZMFQfE7U>uIc1xrKzpysEd?j-Q!E}a%SCw!eUV#U__`-oRb6i$P^s=K1Zw%(%FaA z1f~KPL>v)>sexOe|06Wmq6J?t4q)2MCk2ln1mzHd@@ni4>Ke=sa6xrBcBg2z;AJ&% z+S*49?eRXx{q>AB3FZMv&#%Xr8_6?3%g4dX)c}ih_5i~n16YG0;Bw4qfffRL;xHIO zj?cuvXrwca{WR-IUo6(c7wz?BqZ1Z`adu+c0lP;BA0I6K z%iCPA9_;n8@9_fW^F{AagUL6dhFZf6_)?A==ZD%yfb#7!y8F|(fPlvgi z*(<@hIv}xl*7MA!#oA&?a!#H;SS;vokun!wp1a92K*QMs68D@O+2a6H{OixoOT%a0 znf@!?0efY-frE$NoZ+!-*q1P8!#-F)43g>Pz*g1qu4rFp6E6oR=yp6XCeY^U>*)c$ zK^~0r^})J3YhXRFkhx>97;u|9h%6p+O@eTQrX~y~qXF8npc}L=WN`?nYxY!}eSDqS zcDcl2nN5Ez@ddeSIfF3Z>q7vtXZI)%h8CBVW(~!*bumde3?`0{h0Xu5$Hgz$k)#w{ zQe1{@ORkITNQy0e2e$d5=7)sj`e#%O?qOTVA1@1v%wHK2J5>4qf%bqgGh-Cmlj%R| zAmI6;f!F9eI68YA#p2MutnlZE_4UPi0xftz7t|e`+)+%$&*=^6?Bd|(0gQdV2Q?2g z3JRRQSjYw(a9%90c0mU~#-h#~P;IUi(l2`ohmj7x4j?zMzQQ$e{wP7XdH^sXxW-X! zL%0<|UCPlsz|V>3CFQ8);paevp&hi1VNQp!{`v?c0!ffY7!aiWojjfV4NTpojZEZO z_YrhZ&RUWDgXZ=vpr)I!N1Ep%~u8ivd^CoN5wgND1TiwXN) zjIXDIc>vDHQ`+Cr^Y}tL8t-Qb4yUXEIL86Bby(ZJl2U;wTi)sQD5wLNfFrc!dCA1^0O=3Gz?=Es0c3~>$? z>Uc{FW2}ywl$?{NnHy3=9cyLofpO3V*WH+FMmU%o!yLf6fh;8T-HrqRIY9F9Gc?gb zfj(WG5RiPCb0FxTL6T4hqcT@{99rdJDLH-kyo|J*SYvzW`dgYC6PF(M2wF#*wMH-w zQQz%2`0fto1L*?#jFQ(uOG$!xfKfDwPQV^mGBQBx6Tv!|vQ>9KYNG3FV5$bwcXP)X zxT*OWnxlLT2~q?D3rk-Ea}+|~O(y{9rs?2l0t+zIkb)VQ;PDO`FjhMn7T|E$$x5hR^OD>u5YS|W%n0g?g;~99rH6hd<18p^*=k#@5<#H{r(9# z1AQByr2-7T)isf=YoO7utRR4?RV{g(vpLe=5v`7QgnRfQwSkqm0gnQjGcr*F-eurt zXsUxUFp*)kil$Dp21yaKi0a6td^fc69MjC1a zD2y^wuX}*2v$+|;0)&^NZUOFA=2k@T?_8>8r+iIWD^Cxc<6$p9N4T_y5yBAW?!eJsixDSR@1o+|(AQX_z4d zx4?6MoT87gQZy?S{kd^WEfVdB@#9iVZj0|L!70BArYi~7W^{N@dq+x!5b|I z?!W>-Vgach9{|#}w1GJuq;wsazKN8yp_V}aGrgNg5djPUNdYAZ+QFKb_ee88!%-l? zxVnLaB?a2?`cMJ`Fw(%y5@%>4B?;z(Ffzx3L}p3UXC^WLRsQ^(z;kNSj)#wd{*L(> znHodmfW)?FK5oYl`poO@AgLj-KtEEJ#3O!2hn;W+8ql~-L@-Z+AsP>0+HnH-yf7bA zD6#(Td~got(jEX}5dho@0R1xMYTyRxm ziMllOJb+b8^#$a61PxXR10{B=W$@EI*Xr#dL@EhnI7tF3iS$sIUNXWLcPvk`<-6d@BrFI9A#FCnBc$% z>+8VYPD%dzQi&{FT%NrVTu3DdnSX>2KphQ~=$M=R#o1&o!~BozXF*->A5|lqF-SG2 zTC`AISX6!ZvQ+V9Edqc57)(=BeW6M*2Lix09ia}YDLw=X(ChpcOXv%LQ0!}mp$fwM z#lw)Onco7?zRbtOVF(CKID_x3CuKnbXMJCI6kPn`$)nCbXi%Z}3QjsBzbbX%uzo(w zf(wujTh(3;3k9HmwkEO&SpewsjVa8v`8az3v-bb8`nHsP{Biw)RhC&O&K$*}K{CO$$k_@{m$aem5#pNH)11=8}my=l-k|mjW-}(nL z@^$b*Is5(-GeUq$HmC&6*R1|nn(Vuo1)+a*=QnjDb{*@FK%0}Fk3X~M2l>licDgTI z>-YT-^s5PKgKSsA0nzz><=hJ;!bRZx8~^xU=M3^PQeQg)LKbWpzO7OI>l{H|9xnZt z{qdi+{<*jS^zQ)GYv^Je{cf|VF!pQFrCY`;xbg2zqEP($ zHg-V1_6NEApN<{>M%!ke8U8ifMmpeJ=X2>IxC*r&b?^o74?0HyC=NO}XCI->XHd}c zC9H)ICL3|Wy z)7!qOnZscK6@#tg+~2>+-Tvx4{v*7N&3gDdxBZ>lKnX+=km0`BgG#{ws+;pQ7>sQ( z|Jvk+_{;P7kMK6OZ2zRUIe9qXaA+rh&%UUVEHp2Im0!X|7jRiVyg4sCjBSqXp1)f3%2{;Z_+fkbUC>4nrXBY-ggbLyB3APUR6nBoBu+*sOC>o|+VJjctz=xBLB zbYfH1%*RaF323AT9fTagQl<4|oom{Sg$z zm?9d&0ht{w1vdf&X?;L)28<)w{+v-2ih*0|ppAmeQ>L0U26@ z$(UMvuLF?6SLE$)nPGDhWHHc~^ZJs32CF#Qgr zNXyX636SamlZwg8V)mwG2w9mlG&*x#Oh(>UtT!~odi(!`s4NMCs1sld1zwh6Lb`7v zzZ5tP1+U=D{e2txC8eP4KAfFY7bkkact*?>x&LP}{hwe>EZW|%-+fvH<-P=CU+%-1 ze6eqc67z3Lu`tH}fi1ecBs;~HMJ>HqylDDvNq3YYzA)c=T$$DcTP{~MnC z#do^?h9|$5vi^oAf5VgiBzOV{ZBVKA56}t3Kb^xS;01VA)?HMD`2QK5e9KJ1L2u?l z)HE3fPcKm3Vf`1h;2of!QhLgORKgq{`B#*in2e_1 z`Eh|cw$s87IV|S?F|W@3pakmz`vD+zP$q_h|<)Q7d4cCNaep$gewdL5xH8RV; zKUQ)4sN4D0J?A-eX2}ZAV+?YV`}d<33)J9U50(G{=7}r&GX)`w` z*YZ^xcB_VQeDwhq{lu8d7r*?g=D8a!j;e+YW-aj?^M+-sR@Js_UAkjc@F4&1J*cty z-m+jD>9(}m3_l>BSk86Ob@l=y6mtJ(O6BpMAzqQvJ!KD{= z1xziXt3z~YWl$tJIf>C?k9#&Pxv(d-U}_pTpRIE%{c?RH7sEJ;%eOZBu3k#dswZ5* z)UL?OpZ)TwxqFHFs$s28YcK^%FAOHd$vIh@l5%8esVD)NQtz*jwOx8)+mgaK{#N(b zqWiC^`$;aw)C#v<={zohq!+y1k%0qB z&qfNC6d^~r;Z_QXqd1oLw|7f-6{dQeORxG80%dqS5*@L$pjXu$Q4O<8jF;kBS{64= z!DZnaWlN8cE)K#&!QE?wxq$HHZK@gIvaY0}=jbhP+1N00X#-KU1wqlzQfGL{kjW9Q3p5<><92T8iS_=lTQ$2< zH|clMqv=6#InKoCcP7RQOxM=zwc?kenj0zI7+lUs*|B#iui*$U0J*a-C#FknX^F-I zuM+93+qSgj{jKV6ly?P1X{M)O)jc0!c@Fkq*?*RTy>bm)NuKw0}{?66k zWaGbK*%CPVZv_5rHvSud&+Qi$642k9t#9(q?xTNiw!U?qf6KnQR*(xf8JRoLoiEVC z$S0`0DROn_mY9AoKSS(ktN$?+GlsyruW=6?>VnmJOzN$b$}%H6e2`pMvVNJ4nA`d_ zdAr^bTiJrgHH6 zhpY;~8Sz>j&dFajZPjN>V8NZDQ*~*ThW=j^CaeT^t77Bt`bUU)*<@9o^iSt$s$Ri_ zBPYC96bP#dcti=R3LLPYp0XW1TPU8jsPd4G17(ub+^tF~n>dN&HZBgxn9{4c{8rU+ z?-dcWpZsz3VQx@;<#%FtMq9g_-|Si>TTdX`yp7i8Yj}Z(HJDbY8n~i&XFAV5%O6KZ zbJh3i+ly49OcUHB9=9$sQpzDv0BI1j4CWS9&8EIj+79*UdtEhq1!czEp+|HSc~M!$ z-C4iBik6zMy|@PV`%s)<+B5LBV{-R7I^!xZV2NZY}=ASC$fj`u57s zHzsdeW_k9d?_H#-L*}5Co$vkzw|6Qii@c0b)ZOLzj3uXQ%XPy_+{%#pnvr!I4n1nS zW%+31wM5n8xS&fZ&WHT(u3S{$QtbmW%glXCgMk{-^X0fhOqp1yLzQq2Ez~WK81F`@ z_8gtE8*!oDi_(29AJA*7MR(T4&Y^r|dQ*7o7I)|K(D+Arz_Xtlyp0pkr+PXY3M?JQ z*FFAmApwME0VBh|^?4h3k86aOo!to4yi~ivp+TaDfi5Aj1O_I$c&MW)K*Tfk58P4v zRH^SX5MGcJDA2w|dX4#a1s+L5MyGo!ZwuS6yKA4qdOaP-5)T$XD# zXd_ZrTTYUQJ?(rv0)C5E)B;vCXjf_#IeW?`ZK_T+`)yLvTBbT5sUlSE#hu^)s&3b_+LqEp$O`y#W-vE!-$Itx+hdQIScr%IsvQMmHWNe zu9wr%N8M+G2er6ogK*lzX%Fw=x>Z6c-D9KD4#SVb3vmiu~Gg zzghXU#c3lm98?{G`m_Yj{3{tEJpHAwza)&;d`E}5jYsRg4%e*`r%}&MN0P7 zr{z-A3h}|dGS%$e!=VE_)Q2b3x=)ioCMYItfgftm@xA;qr7DTqFfG7GNhxu!=;kM< zD8>oVye_*w=-!s3dh2W}@3ll?&-%p0^-b)Eud<<`Ui^qGtlISv*RE#r~ z&)rq_>Yd=*1(_}J@Ci+q&MQ@Jr+R{~5QpisA(xkSA=NMY`8QgQNC6)y!;E;sh3|a# zns;5-+JzB3H-M1BX~{dUt7U5xFEJ_vJ-EGtnRpl{#a8F?NE+_aw1>_5lL{hPg z-|)hjTCF#*$0+Mf%jVAyDVr}|w#*+U!HOkJB}x<1tnN(RKUU^ku3z1|-GqKCNq}kO zP>nb|3KXO9{jaypmsX#g;KFy`zu|w2zM_xb@Y$iGQpW$PQS~t5MfD;a@?;f=+FBg8 ziSu)QyQZqD|AzV~Ev$}@rp

XZ6K(h)4JNf~!UCl~T4YI&#n^p97oX~HA&RDE>?nMdN3O%9{^$*v8!INTBj_d0`6kh?LIFozx$~kM#adqJ%8^n7qXML&~om^y+vFXDRXBAHP&Pc zz?p2Tr-)0@{G(#LkM|;Qe*A9J1wzpei%JE1PIzc`zqJ%hcA1WmYPXu38_>*3U=D?1 z3ju2F4=@qjjy;pd2?rXwK1TTy31&4oME=!sSFic*mw!9r-XA`vRR#E%Po5;~Hahom z+t#<})wO!(2j}GpQr-?IHbzyH&v5}1afcjjIzRp@csT8%^C3sYl?zcRoe$)nmd9>o^JjIn z7r5{)F5;w_d{H{SYJ9BP%2HOuw<=)msrg)@DhuLOA^PFD__?NZk>!}0tC1~~j0bu` zI}4F-J>q{(g?;a|Af4Ldz^$^Z#81w98fAaDJI(9rgG#?$pYOfeg^*Tod4c(aFk8^w zUh#YHI4AoXa}l2JADrV?I^>>}-^I0gh@d>kV=rJQP^3Ibe_9$n9D4G@)Uq~#kzP7? zDEVZ5z?jlR_XED%I?Az2_quMc31TRs#`+cI2F4OXW+&csA#-1C4q^;4BxV^hXd#37YeDBk|LgoTg*~Y=y{)qP0Uh~0tXA4=+xoW0l~D% zy2@;$!BA*yM%xUdh0$g`#GwB|>)VKRxxZ{AkXkHjjV<=uZ*)1OQlc~{{O55+0eVC> zPd1O8z|7Q#w({Aw-Tj5s68XW$?LmwWQ#UR%X1!l`kmP4+YkV9AFLeh}w5Y+m?OTZr zqACQ(R__TO-tpOj3NoXeR*EuCxO9W3t#oR(g-$IArOy;n+kzQ`Q}l^a&Y_ubDo;Yk z)X9xTB_cbXIC4|AjAn0VX(yd~d5v8Ax&FMikcnz+NbD|r^L=g?k6)H=75hw9Oj+Y& zK1gyptDOG{kx+SaXVNjiK#yMdUrju|^C+Tnf;wz9GXH9!kv^$1$JlzRjtMeZsU8CkCGnNI+l5&3R}Y`Sr_l|b zijRof=xbokJ{bXNixOJ7%(EvuJC+yq!XxdL=YR=nK>!76Af~OmgFMG_Pu4_>aHt@UdQjskj=sVJ1QG{i6^(xwlcVz3I!x3&7)V%wLW(dsIziJ$?v0-t%mS zzx4|K%KmA&yzbkIbqOIts7w9H4-t}jc^N9H3&4%y3j)`T?DIp+SQak+y+s|6pm5{q z*3)O*UxILXvN=J7cEWnH_0ZdRo-Q@`+qDy*of9>^Ev zc~DdtpW`uB`QCERRqNKo^^2sI1C||YUd}oR2U4ploeIh>9;;|XrL|ln{r2)po3vIKbe zY$2Hr`U~oJ5~zIa-JbJWS47$+=hH7DU0H>L6{mUa-i_PXpU3bL6U82UjC%Zp?1KUU zTTGzb&T?-u(&nq)Awbbvv5j}m&T^)T`VUBa44A;l50*>~-ryR!WpYDiwiQ3JqDN2c zp{edqASIokaFxEa%|Ae2Kl9@YIo!i@q!3GyN|!oEn}JOW;k88q@Ec~OrIs<9YBzGp zwgxyk?F@cOXiML^HJ#4$S`VG56T9EgJ!TFy7^U;>3dgSnUD$`}A!YmTiRJ0MP)m zk}H$<;)TWu&Fh`@Rj!sO1*Dr@+!pKlk~8xbw95Bah}t5^Yv25H`z~MoCS`iQt#m79 zr$=7P<`&mxSrF&%3v>MM~ z_tx~92Bd5=In&%?njd3}F$;P0`dpRe;mz)M^Sd1Jw6VLfZxJr{v#IfGS}F&u(b?6R zdHyPSt?%g71Css{dF72@oNg_FU@7zI8EPi=<}?0+nYKQ)Wh2G(cZkrEk=NhdvTCR+ z&Pl{ZfM>?x=$-lmK4EK?kT6z1$OP$%^_H~)m zYvqBIGYwsqxv1_kw5+U|+sMshmiWwvg_yUkxR*}};OVLg^9dTG9SHqJy1ExR#&G1=2Q0t6V{KDHv}SYeVpi2+(M;M%}6SR_%3n z{AWTw+@rt67^cFn47Ha@pZUZH8?fA%T|MB<-~TXQshF-QA*kBs_@=tRC5O9cWkqxJKNl^)K8F!b$=#S-opPyq{`N z3v1=a{i#J*hP6&krHd;CcxHtN3bYcE6(6-$3`^M@3A5YrU`_Dn(M_*SLnV0Xe&r}u zsv)8yL1>oFTI2rK9T!*ySpbkwt3_CANc;PdckA{T?7FvtGGKXRY5SOrPm%VsxynD; zf4@@cZNPEP0%-QV)OQ~r9#9pyoS3Vi2QtU(DA<9N+k~|eAwfri{$#TZqFXk+uH&>0 zYrTB@`_~W3!K{hhm;g^O`mFLzJs!Jc>)aSbo`uL8`yxUoClOsMJ`&!bul*(|kT7co zy6_%6V>fn4S-$(%jz`)1?ilu-*(d~ro*fI!?Bbl6-RCHtDSOy+pHDsM(1|smF!76e z(wH1{wRv53buNlrv+fNBb0Xj;*FNgcm_eZLJ~Qgm;=Ibucce@*Zu_SvKI&KJP0t(5 zvh}U>TL+4mSCRDY{d`#kt|!gXyepMRA5r^DOAZnOG;=x+kr@4{{r4>I1oGQWz36{- zCpLGz&i-gmyTCDl*eyc)BpMw9JRkM}t1G}hxaZof zWsiVf?i{#=j)v^0rseZ{;1DyxM-%yrWb!bADCOX4{ZKUG$Zfc)#6aWek`D!|(N=f~ zIyOIwbJCM8c&BvlL}NruBK9qR`BUO0gb-nDBdLW)P^(nf(mRNjk4sh?-ICUKE-chR zolhX8e=?;5f!%2d?gi@%wFQIxbxjq<@C;5gE8c(KQ2}`-u%codH?|l|D4G$|ALNT# zPHAYl;1O_?R(&!?*0aqfLP0>=On&#oYfh4a-63O zGEzN|jRMdX7KotK+mqN2g4X(XK+AW3J%3#ZlAHqmxjQ5$x|%KV^ZVxa@j)JM-VT2@ zv^L{UPdwIiTABJDh$m2j{;<`6bF!*Dc5`S#P#>KXiQk{wy{|7brD)1to|#2H%oCbolyY3D@2SaYJrz>D=GS9Fi#FE@1cit^Tj zaK$n%a@%u27>^UEvif|0v4?v7>Zz!x`tN+3lwMgy);}5y!DM35EnjBd@ed~njfM)+ zu(D`@v^60^XX~FoNav>G)*S72&*2;Ft`~XmC?f5y)ZVMI7MV0d|Ce<|2Sm(TF?li+ zJ4{=}x{>!mwQAhX?OKL4;S$(3xvg*CSR3gWG7M;Ec=t77-z!cfn(u2X-AAAsl1Njs z&wDnBh7RLNT6pZrR*7b*OYp4icd0)5Ic0Gj>4~!Lf%cQs4!u%sv$UA$0ZRTJzs5Z! z&96y5l~VYhRZ!16?DGT#6cGehO+TD9Lv>Wcp$_(sqhq*v%peKW)xG4YgNxh_pP57oq6Z>DdxbNpX&Ul^Y z`rGN0V_YMWMk=CUe;C*<+J+L{*nM7n?7iZ?>$-+MD(27RT=xp9mVTm!Vm*bn` zAr$V|cTbKhbz6FLFm9MLMKEA6w1}Eqy{o5tXVN+T__zoM{-FVa-s3niEZ@#L(KH&l zJy!Zgjpr2!q;gPqeul1@((e5BaF+x2&n8N)F8?4gWtu}?Pufo9PwMASGYVluBU|EQ z^k!Q`JAFQdkgf>{)aBnZo5f*sx)fsRC5Pn4#HtaMk1NJoM{_#vlb0@IitT z@3UhH4LwWHNBwUzMkhO__r|WSBoCnJPRUqB8-hp9gjIDkou{_4X1XMmHe-86rhP2+ zIM+y|y`S-V#m`U1{B8?D2-!ju6xbc_=l{goL~gqcc;`2bYxdUihhvdeS>(O(_(%5j z6^AUZ(EO#fPdtWXkw|Q=lt{J-@y)6D?I}v?XjsU^I#PXvP@uAe{M30ub}-Tfj&4I< zeH(ix$}=QOLba4Wg7hg(53KL+ilS|T+2ddTdc1U~sY3%LD7Y%Ler0tGELfo-?PC1& z=$Vd2zI}RP(gD`ac@ys>t8J;Ba#PWyWJBF7W%0(2^BvPXLK00m6Zy1SGO0c0ECcmn ztYW+}d3DCQ>d;UjdHUy$w@p&yE$I?OrBr4`=q%U}*as1lVOCQM73^w-W@fr=UXVham?VlW%_)KY_4pdED0D!-pK6Aw6*J! zKN{9*{=Q>#;C_Ma=~47a?)`bKiB)pB!a%sjPBS&xVh7CCd;6&R{3`ArZ(|ugxQKCU ze{D>m#Kf>4NkzGBZCmBg9g*0?pd3rhj5w3+{c__YF2V^@WY<9{iNY#|kF8H5Di%Iy z{JP5|P%wCuTsd8#SUL3JD(OZ^+BAh+Z95rFPRdK1&2RvREHekam7!hKT2O#i-YM42 zUgdMJf8$B6TCv^Q0d3f-yIXZdAUY1QK65=);%qSyF6f17X?Qd>H zS9V;>1L^mDN{=chQP|z*Nn*0|QC<1CiDu;l_N0 zYS}|_gtzsiZo1Ccgu2hnE*-*Ax3=Wvq2ox}bYwD?Ly_?kh$I;Ap)BW{vAVjXWVWfJ zBaLirZ5vi1XD^%u6(hs1fMQ3)!A?ci-tWYHfE3TZ==y<6Y|A)`zov1*s57`o-reQo z+ADHCol5TKpV)*OuB)BW9Dlc&bfjS)YIcwOKm%#z9hu5((ZZ1@V8wws^wp$tx~sB{ z@9fq74)Ma@1P1b!6{p~)%y|{_>WoV}FC)A1xJ#YKRqtg-ykZO z`!t*sI#9Q^k=H+tn`qdWJ+b?>F}$lu?6pc1)pn|Aseu92Lk>CtjQt>P<|CPj=_ zyy=Y5ToR%|FKWV@7LKiM$*`>vqiAo8xiW5$Kv#_O7{A;x+e6xu z?UvxMy<&(&6-t{qMw=W+8YO23(Hw4czKYJD8+^UNsLWW9Fl#A}zcDus%K&SRu2 z*}74E4dhFu*g>mOEYYX_DanqEy{ry zjg$u*#c>{ulb@kUmex@PMr6 zY<`_V=-Xq}pNslmijO{F_ zo;p2n5qa|XN?tKPQrhTKm(;OM7;K4IZhs|S0&`~EnI5qEO=Wk5O-0R+u|V*>t96oX zgU_oYeoBztP*N*VB+=;@;&65@rs`G>C~ zqsg)Yc2=TxQ+HP^8-dVlVBniub&>X=@h|qs9RP{jl zO|0{+T)5z-@naZr8|}%ahmwpJO-M((SfR9^EYOuZ_QIsX4cF9G-lP&?6C*sa!?Q`v zL~QP(@k1ig_@jxouLW(y%iD8fildD}#`2IAk2_8U$F@8IS*#z)sN+d`Ix(`n8dhAl zNkV}Ta#PB5~2 z+|vx3Jc-)hZI=+YqnnY7r>Tbwj*@g%w^k;9=PaJFylPsZR!>iB1|~mQZqS!EQ+loc zCH0y{SgXz*2T>@!KMvz)*~KnVJ}^xOTX64Bzr~d*04rM?ZlOYjj&SCmlFGw(?_R!v3d-o6CTsav76`KdMTtqr^!!smCWF;Z zkr6-FWZi4)gx?0|vmOaq_l_HEw0Hn;+AGbPZ3J-Z%k1!tAX=Qb3H72YAI|h##eduPgaYcVB4V?MCwNU~D>T`-^JM&wK+l`ao^FFg^5vV0 zqSwJtk{@j}0r>?SL`^tg?mTFyhARgGsouI(wp9%D@ZbVM(+)_1=6+&1P|7@tWStpq z)%)<2TcGN^iP-Adgbh@2S+|!sH*rmUm0;wv?E79p+e14WpkW2@X+3CfP;`t zPrcVLM3Uzfd}F9npYpyKwXePyD>RB-tA0 z_rlr6F7|ki!G5tPe9pHEzNjq@h_fIFDnN73A#I0_f8G_AjW1{{Jn1@cr~j#ZQtvGng58&f!n1)8^C zwii^IRkMLN1bV)xX3?D%x-cp#*@`%KZ*C~s+GeS7ML~BuoC5dVF*4*QN?CS>Av150q=iHuo1tcv z32$`3ZqrD)L~D3hBQ=+!#asn)uLss(br|m%*4YaGW&p&a1yq!oK>U#T2XekjcW0C? z_v2$_UF$4!nGOdF$MDpadWHCWxJ8ob6ADyOv2@7qFlyM}Hf>8|$QXr;zRE{P>>2gZ z6RH%8Eo#po;bin@{j6zE5wQ_2`$CluHaZS;O$dI^s7Z_IRu*gYX+cI0#7x}~(waFi zQRzoAZ@sYd^QW$Stg`S#JvBBMua7AZX&mYyWs%X3{95f}ZKHJRFUIT~p&?(aCS@=T zOGeHjM}CZjXeEALrK-1pk=ic*Iw`oqZC<)xw`%I#t(^-5}I0a7o`HWbk{u zip<2U;PA@VclggY52^alW=Vy3aN4@UeBbo5W5jhlXxpdYd1-n?gLIR2Bn4TMf;@RL1|-&5LQqauUH-tx=?@Xql%TH2>Xt$0 zhN*J9v}t-@_hobc8`;y3I=1)iOAIQQ7-Ft!&62B99I4f~1anY#s`m#kqJK)pG<+8X z@M(d5w(qn=Ro!&yT?=OPJFl9@O&KPm>-$~2Y;~_s)A2Dl9wWPAgWiIXqqB_=YAd}iBXla0^`wgl53tlrIW0h$tHOhQwG zrap9ukC(L5_+m17jK+fOe8%<+KN@;jg?wE?(!3*NzN<-8@Qry{M!z~$VX`7G<*~g_ zt;ouf2woW!XF)deeOo9=6t{euWYr4h-qLQdS~V?9@0@P7?6E0Bny!C&=#m>RF(Ye- z_0jaEWh2}I2Fjx|9a^D=m?8ursJ;l-FA$cZMNmSt&NU2=i3AK?RmST7oRQ zR81}(jq4a`lj=*yKCl{g$_UaEUN)R2At++x5#k|-+nPRg8#;js_XqKE8RPwvJo_s zM-n*U)hN$=4` zzH~<4Z^-AzyC2Owv=`(Kk_Yt*QlNeDi8Sk-2{zK6n6%O&IH5-<)`*(A^S=A=$6vuR zZgqyVZmjN$P=J(xho=2IN_f92 z$+J$Zou9UH!PJkz3A-qHEs2Vg9qUJoe{rtH%LvF#CX)9BcUn&-p4mPKPI5|Gp|iJi zh~(#gwvUx?=YLJWeedU~=2-jA!HVu-z|pJe$;)_1rr3IUt_XdWX?vA5IXe)xUK{BZimv`(j!D=3`~*ZBlurn_4^ zl9-jVf#LDt7>&})K|bV;mms?9$tMjcr=;Aoha!3dHZf?X1((go)Ir%&I(YJ&M_fM=UrzLn+c6MY zAT#lLMK$+nJEAFkjMUN@j7JI!A%Zo1%9oKOqV(-1&*js5y}CtJ>3)U~4PgLmwDYWO zLYY_@{8k51NtIEBQjTrGw<+;q9)J8Pb6T65!fWHDW;d3T=zLb}(M#*L$@=~WZww=4 z_tz*-_1}H`=@$Y?&kpV=liC0H?hH8WznEKdNF-Ls2;*!n=026voQA_`>Ai1La7VVE zbJuCwG2jWsmC6d+5DlM~+ew|W`zys;f^K$8VhzpGQu>Mdh$mo=L^>_tzLL_OXcRJW zp=*%ZW|LYKAW9fJQ~jhkr2!oMlN&Cd5BfOWQ5dQ_7;Vx z9VRNSE4u}^NjOY`Y(1!$rs)54iuxQSm^SN>^S%T5Ubs5q*D;kd2yifl4Gm6)ew08{ z9l+F0y_5Tx&{Sz(Z6znMkx(?*d#4+vGG%EuOG}J?cRSiQETq}Hyz}1k_3q2N0tfTE zP1f^ai@f~-S1K;O@l`%o#yLIVZsXDWYGqy3mbtwy4;ysDqZz)GOa?t@MNvdZ=ccsA z0nSM;4zP{J=+mgNTZ50={@8tl{6L}RfFMC85XZd+<%mA_`j&r-}9sXkNNd+6$>^w56P*~=~E zb{AIF@(!3j-Oe@g-3G0jtHBRHJnc&WHggux5bW1VC9+Ep8oW21!a|0?Z!%D>M%QE{ z+9iR?d*QJ*;?zJMSx9AqbhmJ@U|ouN>Ev5^YSD04_~Z;VG>y0D!-~l0nbGXfY9ZyJ zpQk_aguXn7eX6A!I-(Q?UE`E5 z$>Ut23r_p4F=BJNJy_$!$PJa2i%qupmUv;4 z>m3v1(2%_xp=F54Etv*BlRY=O<4g=mjF~oubNyXQ%g~uoK7}eCmFdr-c{aHmgBK;8 zcC`1077ayWt1h7~%ahB0X}O@qFaII(crRJN>j~#Xr$p$bJ6Qz>g;KoKF~y_xcY*Ow zP_$H%UfXRi?*<`8KUpU8{z`$_&k@7dWsA|5$Ij$nI)8*mP($d2krUMW<@}M-2iwIm z0>JMIy@4?*%u8adG5Lb-*~R|r22DT+TMJqjeMV*$eog!bI_Epc1 zm<954&WJa2YnE^pnmx5Tb^HE2a7=DxsXT=mxKf%fheLu*_TD}fRVqaAjoHJa9j1&t zCpe!h!n7A-UBum708> zQXhCVBt^0OMYQ;AkL5JRs68WoidtH_(I#Cj%HCH! z%}H!itVq!dvn#W_3s6(6;h|fvsInzPkx@ZvuASl|iOv~{5+;XyT31S^0hHN}S2PO47-Z;y*_KDRV5UD z)#C`7o#>YJH>K|qw2*M{-rgWy*dNoEU0QO#so>O`&d47@G$`w1rEnzKqKdvEyHC#F&a0S(f3b-|Q>aiZ+T3e3=JY~#;%Q6KL% z%}!C%-WV!m4(-<>>`gz_(Rtv}i^Aq|!SpmKv~hboAY=y0v;_?}^?*oPHrjb(;~A67H&X5OGT)!J>pJRoB{7K-wVsy}!!ZNVX!xfZZV`sI z?iy@#e%{A8|4MKdk+7jRlP-o9X$hXm3rXys_Lr_L4BQfVnIqf|@F3|Gy2&ga^o#u_lZ2b==MmQ(N8JaZ(Jt2IW4%X_t=SB(Ap8yA^NDD2#I#Rv=9Ya0>)^>29!% z3I_*jS?%kv0ngPN{HDi;B2!;>9sslcs90MwlY;>M$_NlI`uwa+-q~X&dTOvR`@SCW zCMWS$_iR5(MFHadT^_xQl6K1}9m$ZW9==R3y5WB*aZHbpm~(XsO|jg~h}MscQ{XM4pl~bMB4FofHVHd}x;kw9210YDX(8(Aej?YMp?%>^V{lBA zas3gql)@3dVtMcP>501oX&t1ql||i*2lKySL5#Wgidz|sgT_5hLhfNQ=Dru zn@`)lH|Hrn$=I_o9sl{$1Ao`!%PASYm0eVU*sDg$cZRNCVZG+%3;i&JwONH6lg0_y z%5}o3r614m?ckw^GKLrcF3FL9iG%;(EHv^fph~6oT6^3-a@Di~invd1Cv4*HRErNT z2Rnq-K6>d>fZdyUe{(VQfFD^ebL3OWHBO>^GQQbc%gjD_RP%scZxmgr2$!DvPEabe zQ^daUU8bE|23|c(x!I3TR8_*S(|-CBFVA?F)-CdEk5Om=V0)QS)uDyh_phMrDw50G zWwnKqnCn}aHSr0p;yQ5RA#;1N{2)NC=4)@uGs_LCC+xxx0kzvyyu0tj$8%GZ=T@JB z?yXqbhL_2h0`%pArVKNG;cVJTf$7}J?-u4gc0{H9Rx z)C0w;+?_zw!Gb!vE&UB8V-F*7l^WW5EmUeSH8Aq?^rI$B$`$>#~_7dc|An-m9^1>I(pjN>j3r)cJ1 z+VoPQpK@nc$zwsAGfd@XhzC#foRqG&xO$9Hl0B_D)EG4U|M+_AsH*xed{9zCxaX2I+1P=}U77=~n6PknS!erMnyHu1mul)c5C}di@n$j>>a?9L$Ud`?q-dAC6;pYbdOQ^#) z+Zh=^gVu_H{RchrZf=g`UC6itLvbiomyhN3%N~($_BQ34Sn?ETZZ(9^^$o!(xYBCzKBdTE$;R?+BKE_*jR3){xJ>F{8)Rs<~7+Tpv)Vq?ll8-%fP27#SchvfoFNq zDyVq}2h8d)M6z!(6S#t_ZO!Br1TH6gQtxJf-MQG{#CYeoLLwE%ZFlAX?v4!Zi4QJ~ zui|RO%zR=*`z_VjnrG0zmsKC@din-0lQ~@nrA!-Gs?usQYa|4p&AqRmT-9fR1H9@Y z8;BD;jiuDTaY6vMhntz8*F$C4y80RU4cf_~d5X=OJe~JE`k&WFydl;2Lf&2`!MBs& zRSD3L7|rDK<&wr{ty&jsn>jBAwg;Te3S124;#9~t0em!=Y+ZIUiG)%I4EdGzz9(=2 z%j`{(vw9zk6WUk2?+zn97O7qc0x%1ZRw)4sx?6vMl-?zMc?;XsijR-FzWZhm;WHTK zCVn;lL`!yq*LD&pd2Qg*Zr5_!9o`J74)i3)~%$3^2h-V6gB@2FBs9eEurSf z|1-4{AO%JjeiB>~e`1y88}t%kW^`^!TeECt?2tQfx)~cl=k@)JZ;8`?EgF)}AJ5Ll zh_)HJX29P?uRdHgM`3N+&A``1pE~_4n3Z+sYdq~n8BNL4q24UAwgVR(sL_l}{FNbe z2m?ylE4V*XHPX?)|D1E#+)u@JD~!IZFB*W`l8vctIg<^{%~!HFX)4Qk8d2@PAMYt$ zYd}rK=8XW&!Y&cAtg=nU$s|mIsY;}%o%+W;fXjPG149L|aGRn( z1cxCdumwVqRW_oI80)dU2~|GgwZ%?QyPN=Y&-Xx|XmkJ8`B*k&*}B)&(fW}Ytrj$2 zY#~P>o)K%NJs;hJ2QpL z{n&?jC<;;?-va`!WJ#j?GxS-N{l^fBsJ^NJi2nDld~ECm+gpQu2UNX!(#Y0kHvpOv zl&!BJiDVWBZo0a@*B<82_o)BZvE>`k?U*!i1 z0^*2$`UfpSjrQt7Bh^g)rQMg(1e_|1>Au8>kC(AELcoBx)#5mG4R&W}oRM!kyx>Y- zrZ~M-VO0WtfGm!JG!wlkvUnK!)IOi-lT1tb%h-q26KA|&Y&XxIuiV-`qFsx8z< zszfj1bw(!qUbMC@6HP8CJwGh3<=CshXBhJq7_4bXe*bG!VM9_t34Hfi_!!|{@anfl zV>2Vxav?@``PVV6BF2YZ%243O?EJG}ciz`u92^?0KZAi*;BFzZpFaOR_`hv1z#kvt zUIS8z+nQ|}d9Gg#k|9i@b`x)b6=2vU_oY`QedMY^VW%wJ-O0+>>gyz>;mdQIoozU2qVj_OPAWVG@zvV{Zy)slsx3m`xL zWyTz%ulZa)MwW4@fpY4X{@i#Bs-(~Y1_H*Y_uvcjI*a=T3-F&)gWUthPvuv)$$z!3 zuN{DSaR{>?6#8pczl`l+-PF7J`KKWKh1p0zAZ~5lE-;q#qLn7zJyQl1Hg?>kv7dUj|vHsu$#-hm%#(nu&op)4~xn4=Sn&>{7gCL<0Yw#>{+D` z({1cf9)}5T6^N+VncVN|y$o*%!Q=JS15C{qC6UjU^%Z^qknN>`3Hv{@0lIS%W$!es z9R$B}3vJsz3LBCEK*tJ5ghBBiJy&WEl%7L`s6Q9}+4%TjsZM{o3RJ-Oyd~N1{t#Av zr~o7Zpx5g+eq2aitlV3}gP%;IhspppI}#ln8DRxnXCJsuGZoQZ05ISHu2YnHjxedQ zYA~ap63)~_JCQFx(0a8P1N0Qkii62&D~MO4gU`#l-&ONXH-TZSx{giU_NQi>c%8C( z*$u=|&mH8B4}a=YhxD`PSyV3rmREH(@t$vD;_*qBIYAlFt!X7qCb2BBy@m3qFZr;! zaXNKq_WtnPvCwasvDiEnR-1x_qWUc9zL_%;Eo(}iooVFP?~(+ZAp1I1 zTy#qjU++sbjZFZ(4+$t9>8F}q8A~m@tvoDWo!z4NB)}M?$Br{Td7GZMe7vehLd0@l~`Y`bt(+Sqk$t4h(z>^y8~T8Z#xYf??$zNf)}rB9~ScAKT% zP70`|u3N*c?MdL~o8=|GBd*JCBWi9{VKijq&dKApPG;*F^0#mMjeh3m_@a;Ya)86W z1Ds#K0K0flBORmNa?5LOZ~pi3Z_WDcqsX8zE1>)~2jY!>UY|OcLoP2Ru80LpZ4R;} z!sk2a?-Hv%gkri~zTNtA5gJ3C|+)zjZdiLoQt_3Ol;#4 zrJy=WghaB;@bX8X33TH3x@H+eOl(D%b%Gd6OCzx5HTZJd&V4D@W_KnJ=0&}lf7)lS^lj`^HK6R5{z=0C4IIUs<^)|n|opK+1D`#qt^ z3Yuk+l{cz)q0L-493N%HB!znZ*rP&YkEWRr;lm*o${3>9ZZKe$SAXAX37s1bimj@V zRc`3f_!hZt{n@w83)PHtO z%>eAWZD1lP4INKffffyX7>)YLxz2tNP_2f4mX7?bSi@nMOBR# zqp2u`G0Ip=g*BjmUn7h63ZHjUMRgPv@ry4U!l$_we1CYk+ z6#Jb~GM&a%%yV2O6<8SfSHhcb)xJes{r(kW8JR!TW(l${f+pROj!4+aejnuNvT3Z{kV85yO{QmB z&G_jkKM-aeSsj_hco9ik}lxSvpA_9oIL!r_OitjPxWV^d8sz7 zW<_S_Css5xw4_#A@3ZX@H054>8CeEThr{yrY|TpJ_d(TYz!Ubvl2cG9*Spv(HaW`< z#|nzUA1u|Q9UV;z+1~+T-D{5n&D3{b?ae|f{RCe(q1)U2@~=!_k5}HBK6X}8dADUzQb`gmVdrffd=@}p$X9r93l^rpOc&4RD(^z5j=UEx}0Jpw##l# zkpezh=94}z5{xryXpJ*ueJF*SjO{J3S`|2fZTw-5y3uJ{^70MmXsz`Or34luUV5?Q>%OjeWL?89CX0*fwSD=UH|8b~#}wZAv^!$DRP z{V8t0zAbE_+e>^e+@30vV=}=_2eu4+{c3tU&8MyePCfg*{ezC9&(_y8T$!XNag{>6dhp@1;H6 zTUd11qZCpz5@`>r4tFktk?1<+%xzvbm`>&+@#GO(#amq4JHJtLWn$nTUcTz+J)9?V z$IMm-p6*8IF$72~@7@swNkKytg|BMqs)nP9glsPloE%(&c*Ml&-90^XjB+FkH7m0j zSjoNXO|e!a=c_%rfh75Pl|riK*eE`=Gr6wHeCTca)Q4gh8!yf3{AHMwPJ{NK28;@e z5#kcvO7f_1K+@b3jf}TfYR80%fcG*moEr6|5GJPa5PB&u9vrB6earN(i&Cz7z=GgF zr_OfDSZR^ZW_X3+7Exc7I^f*GH93_(Vi8oJE;kaA=%}W!fQ_`{bJ-VJ=IK3ZT%iV8 zuPfDIbs2ok55DCXqcVbIyYo#cL9z=&`AoLtTIY5UtMII6dJc};xku=tsG%@fQiP*z zmnwXoyse~Sf1~HUE1A-7_l`W$YbK{mN7t#>7l^SXZhh>Rr$FJ(SYNz?bXDFM|K`^o=#GtuI z?O$ij21}uTZld7erW9k!6<5ghc-o*0j(&?h>Z#Tq*jhi*msceLFM7 zL+ZOk0qgi_3?Cn#`x;9OBpjxa{<9EkNEad&<}B_@@|SRMWIA=9&Zx7m9ddCY_l*$v zvIY_RZSXtJrPsVZXQ9~RF(1JmSMl5doQD%kdMu_pqda2SIXTLO!cZYT5-IPjGqOVH#bDZbv7DSS{M!*?reKTyEdNmO*?kTbUvGI61!QX`3dP{g@BNL#)hKPbNU99Gbv&BW`g7bDoJ z!Dk=M6oHwlPp_@U!@?r(nt25LRi)NU?PbEg&bgVrV#h1B-SlpluE1;U4k_&yHUgc7932ONQ8*Zmb+^6w^LYz!Mb7z|}=1cp_ubiEnIx9DN*LLweEqUQUdTBRc z_o^oamy9LsaQITAgjQ&$*Nr`j8Z zP9@JVG|DN*DfP)xvx}L>GWohE7JclJ(;?AvW<+p8kjTKkz}L33`}gEOhY^Mz78BMG zc6D_P=J^o&C(koTbR<=cU9z4EpIv=!Du`-0LOg9yOG!i8nI6<{0pD>Yb6R0;S14&< z8U~!4xgRe(RN--dnvXSYd}Ge6eW}*}OS~P%n0HFA2EQ&-V{Yz5P9qWMIbO`BCfb*dg?ZB@d zLt(6$s-8Mj60UcFtdEk3RXB9QOJw_JT{=x}Z&<9ddyXkP77vlj%vjgU=zAr88!_=vPe{vUFqG*pJhz`#IH+RkQ$S<1GwiU8UTVknJ1N$#2* zTj`)lX+IA8n5U24ARk2v5?3)tN_JDGqw{CH&E{DN0JLlGBi)VHyfVkvbKx>mqmdb{ zJjTDJK?jq+HoNd>v^;{=pr7x5rd$V4qg+4k!~S$}a8kATcS)W?IsC)=VBL3jx-dMC zTEsu3qW4;}Mz79CPJ2mw`m#vC7Z~{p8ApyY_Qd2x^Rh8PKoWlLhJ0aRp^$bKfdN1C zG_^ej^C?>TI-$O%=f~h=<|)swdKt4!UDw#s@TcY1r^L-z`Xjk^MWX@u-(#E`06l7$vp*Ng0dAhHb8knm#&U;?A8<-flYJm+BI6lfL#3Y=Ut=MovsG&K(^+PbdqRK{zDo4-WH|d+qraS^-$R>R-HaW7hW;_`=)BV6^d`{> zJ`%``>Fk~zt=?L{Mc;>)`SsMxI=@^yoN6AY$?y>A<0{S&d5Z8k4o^B1O*#sBI-!K@>fd(^O$W5$Qjv-Sz6H~L368iEP= zR#c{s`2}?=agMDR__w-`=|&)n>$-BY@i#@)@T`?OjzkPrvfvfDtLclcq0H@6hji6> zB?-6IhRXvY?%0**i$hPL5Ij!1&tYd|*%2Z6r7H~>fk-%P%!UFv8$Q-si-E{RgBzBT zDO|R%9A>L6Wr%`G=`(wo7rHT-qU!e6hj1585%?1ap%S8)V*b=z9(KPF>5f)+xqu_v zj)lu%LPisc=O(j&ipBf@CxX~%&d{p~`Zg_z=(NS#!QVvg@I>TsR&L8PW?@z9yedEW zy`ydsMZ(wC4St)9lmX8*wMPD;!A)ApB|9Mz!^lu=SG$o1Smuv7GLsL36yAQv%u>Id znCUlrOS_k9AI{FjEaDW z8qbx?WgYZOHJ|chG&Jw(2mBrE(IJl|dzL?N;{{@&m@jk_udY?xbKI54bu7bzt`@Qo zN?1i?*XDbm+*GC0zP;VGI2Lc3MsS}r`)s5AKPE8 z-}~aFu;_-)P0A4o-2^UUY<1Lwp2h^S>Oye(l8IeDk&rv4zP^5uZw8MMbbKo_pD`MA z(}~$xu1rW+*n4!l=}&Vk#$5={jlf$5P~=`bwQShHj7jhMb{zfY=-K9g$*(FiZT3N7 z4R8{J5EL9}fIUy*UlYfY0x&A+KT+IzUxBKV#{V4btgmk?;*LIz9jV2@EX+33F-d61 z3n8^Wz|qS;pRI0%X+mknA>zE2hj2k#)us8auHxcGg}kylY5GK}KdDpzD{9PScFcnI z{j*719Qu4C5^;nyztcD9rq6I@c$gJf&ky%B+lU3eyBL!MZyjhgG&X)072%$kpN76I zNn&Tcx;sYcp+nune(6#)7i+%74wHtz^YKV*9%v!{@)+o_H-%vl*|Go2Lw;J;4H z3T~(+&lN4x{l}R2?ZB8A^ux_Eq?HIPt{*byuI!u9HS6ezmRD zbF5k_n&$xto7Oi1pMAYQj=sTpKOXWWdIRmb`^eN&*YP>7<^jjc9T{CCr& zP^t*xl2CNCnJJ&6OrA4#M>@i6if_94Hl68i^@s4CpL2HThw-{NrcFuHb-1Gwj}3VE zZ4XO^sr5cPpYceFQXPXpg!P?|>`6^Z8Z>A30=x8x4^=&mg*#uaJU= z`4y6@vOuYa{qJ=Nw3)?0@j)^j<^YH&_J2HC>%7iYr71myd5K0Y7W4{{dZEpR;Pz_2 z0DM1tx*;9+HtwwgaNkitwRcoMkom9Jf5G-EVD{V4@Y|DEhp3Qe9`m8Z_Mu#VPoV1U z{*%-&S)zeEUqITSBNmWK4>K|8K5cV8DYQ$24NtC}G0t5EOA0=6u~3xRK8?2oDjIXZ zfu=^sSrBKRdobtGr^^|Go%y`*>FahH1yZyASVZbOrzdaF@wEJ%+sRnY$?2(bHyzSW zf2E4B#&DRx|0?<`j6y+ZX?Vkn-bzsqLMVZEC$?fGIAp2OdT`<}v)n(vI14KNc?d%> zz(Z~5GYfbf@#px4Cysmv?xe`cJD7h&oy?svL$_&u2j8!UhK9V~&FUY{@-0JBe?tY8 zf|==ChWa>=z_gYFk5bc9Fp?U2d$~`Oc#uM;TCr1*2vY?HgB>U-#fgG}zKXUCdo=QA z_wfHtP6iYGvs)wvtDZP@6Z&{Dc9?+p2f`!VN~lqU?RA4Oh=O!tqryK3>LLMnn++UD zxk)0{eyj$WhK6i@K;Q>)=*qE5ACLGg^`K)-*H*T#En--W2sGsRUwiB;7pOA=dI2$o zFEon84BAz&No;203T`K>B3_W)g83B!&X2$nnu6L8nRzC?lq{6qJ9-G^e_29FRM<4@ z*oQeH{83bT24VA843rvj?;}%sId!@Pq!F{`KCH2R8Rjv8YQo3LLAp z6l(GOh?f=u6O0cnFp@-{LAttqraYtbd~F9bD7UGhoS&UOxVWO})2@nKD!QjUz`yKa%SPtbedlqWt1^t1pK{(K9Ea2GYm5YkRpom$T|JqXBcx{6`hOdh%X z$+pw3TZGb+APf9Boqgn{^{)M+XE1crM@y?j*iVwce{I@XX>s>weu>r-b+~Y;Fj?y9 z`ihW4T2Bh#L229mA6^uOKszJ~90+;pf%x-*K!pE%Ij9n?$~7_g!w=Rr$|+Gk^&Wp^ zc@$^%eRrfC^R*2_%nDh+7V2!fdr$~YMueVLyTkFMGXw?Rsuu;Q18tvnodh>8 z;28$iKx}DM{vV^W!oD)gV!vB_oqQns{FPiZfDZ`5f&fT?aBWQ0f~G&(Op{($9CBxp zT-;^>B$uc}tS`P(h?=s(EA2i)9-#gF$m8o@F(+qdDpdN)uDX*Xc%`3|(BsQBv-@Xb)rO-B zYz8*EgAvj2)J%>6xAcE&^Uc@h`BsJ8&nSUb=R1na)pF}Is(<@~eyB#>%#n|4zEbRE z0PIUyv~HvPm;yPO$pzLNDU-`0wX?=d$IXgQH;y(!NINbq9k;q0WZ9?xze`)uJO?12GNz~s8&{|EGF z%}X>?xi;|2sYd2=OlU_o9?s?43P3D|`d61@>q47StS)%3OL-|XJk^-cY?-24p+umT z(lrv>8p)xo5qH+s)@YSW5^+zj5wS+A)acc|yd-(|SplFJZ0u%h5aEz^u!=mtds?f+s+(J;bVb_C#7|!DU{@QAO zfXp+RJF?lufk&~RG_-?mx;vx+kf(C^?Je_@nA<5~QRWQJXpWc4`udo|A5`zenFK#l z?V7s~eK-9hr_C7?1xN!qr3??wX3uC0Zo|WQZxxtFVY)7PT(UT+AIK}qmW#}d=bhf) zI9b)HZV$f}G!Dosu&4EuOg@Zb!&BtxTs@@@xgP3BU+xoEbR(z!;5`U=c1wF zm?eKYWJsEz!Ikq&gSq_E`ThkPe~JV3P&J-wjeFg}8gE&uo?Jz8(E8M$ba^aP81|^Yk|d?P2a(1LR*ymIqMSgjlLQl;71!S5OZpBF&>j zmv7a+5)^Gk0V=zkJTg^~~I2otA7VB3=nx`AR6BWiUzV3N*sSL|&!S;L5`5fwur_12b&eWa(&@7eB3KN%EpMekI6aoxAzfrMwTX!ydEjM$!0Dpua&3Xpl zYT!&drwN;-G&Ns~-{5`?WYYG7hO0QOU%7yvsswum1O)VLcavqUS18Hn_@*P&h2t@2 z%cpSlB`}i!>vb`iFEeOJj?mf!-N37tUysqed?KEpM7#uP)rzq7TipDB8HW)NrVdRf z=P*J-|9<%UdwIWZ#(7;ml=(4}KGV~~Jxln<=c0#)*#>0_aVZIzjCBiU?b`<`Z-{a6 zbgAC$@dnA(P-n#MMC~1!Hzb?s33z)HFj3$fX-7em5*H7sp%BL>8xAqwy_7vTM_d73 z1J-$!5pXQ@OvkqAI&KX|67d<^g?&t~nA~S4C4G^=tUo!-ZPW9L!*WzOZpP=Hjfrk? zNx4B9V`@3$;N~`4=bJ=Fv_YGMD;Qv8A~V^{YUb`9Zm*jApTqwT=3jmKeK{Ik*x|Bb!R$>ooInDS^ZpVd2)do+aPk(cYIt)5re z9+!LnZ+oza2)8?3F*&}3FM?c|942$F9Un8VX#CF*>w|OE%9X|v2@iJ-?>GD1u2=m` zGc=!VVJs0w*{46r&)n6tv$F#WFflWVE8AH5K7_w-vFxB4g(mOr3+XePJ>6C(cPEPW ze3IDByDs-6O~*B_CtgjNQuWV&s7I?ph%9J7}yH z-|PQxBd||1c8`;(Uf+-rLwS3zZ`1tw5qxuB!|+&X+(RJD!1C>C*0q;?WW5oUJOKQwA(t{IK}97QZ6h?O z=eHZ%!QxkVGb3j{KDawL=WnoW?5h<|wbF2lyuI7Ko~YrOZq@mEXAbYOm6e&F_D$*LW{?V@moFCt62;eEgUM;`o4Z>YC0a=Q)Jq%}Bt4C~_0N2L>~)wBzqT zK8gt*Zyx!5v9iX%z`?H;oI+Zi7*3mmRepa)uHdq zdE)yHlBpJgc@35F<*FD4s7_KSHAL*!uRT%y=4b3N zLK>pDAM1pemfGny&LDE3Q%@-YUP)8$usy{3h+pXl(4cm%$v0=J#?2DEEP}54dfK&4 zJe`Zot1(4#)mfqRfnP=R=cRGRFBJ<#<2uUXw<2hmrxZy00iY7XK}sAcgD;`fnFNE3T2oRyV-x zWnEV#W7$S$vR7Cpzr=^633W+-=8T?HB5Sh8DI58L>5kuZ;22QxOt#FdC-v5e(wO>H zS^#FFV93p8tFL~gmpi}vnYbW_`GIE5!?lS{V9{QS%#3h>Z`oU~H#Gm68x1njs*&!Q zRtcR&JO1iXJ+n1@0NwgJVN|F>=}nH<=Ek%p_R!;a6L7#lJ?^TlWoY8AlOAdmI z1}&H+UDE_VuN7~1VT{~OTKNk)FYGw8{yONs$^i)M0i+2u%n&kkjw-C5`t4tyG|q!e zy_N^i?xPS1e8vS2jt~7aJR&5?;%t?uT^R9VEaX#^!*;YL%!Rq0BF_&eOm3~J#t$(t^Om)zyf;|&xT@1Oe5Gey2v>#je%>qR}a7Xzh1(|*YGg%E~+ zpD5VKi57IE)C~gzY{hFFzW*CrAshoP!yjM(snR;WdXAP^C@3sgkhK|edW!=_sRino zD5k-~Q{D=8$nC<%nyg|A6O+DWp8UX7@+!PEMgqMM<`^!!!?Y-0BV&G;U|)`2hooxB{bf#(JFb5nKS`!p1BV%404QY+&@fD!yX%n6k~Y&%If? zWqiQpQy?CHgUNYR;PToR4LN~x#f==d%h_hOXwHrJ@jcER;AD%2xIf)hxV;S8+#}m$ z+kULzDOfIz#B*Uy`^J}1Cp=SQHjqG3nCcYInd56~*PQhDFB|yA zV2ln4&II%@0Ha(}V3bR_`UVyl!;8Q{C>Ypu*(%K-#$ONID;l;n5q=0qa#{4g8JugR z_Otq0s#z@kWl)ReFx@1km!|i9hJ8#dHTr12HxO&+j~9^5ePYHH7+uW zEq+St>>9GyhpMVK0}?4f%poCy?!75R%kF7Bd%wGv+PA!0(r-tR%Ai_VUA@_G7>q?^ zpzOY{az{!r5ge-|H}Ray(5bi>8B$=(4KHyzjU-d{kTbxVxj*(cC~Ng2zYR^k*oXHD z*Tt{uBHCID@?VZV)k>I^gOo1RQ?Rg%u3MX;!P8|fbiN&Z`5#JGfj+Gs;WT1HUXsB} zH3EjcJls&gc=I7!%7OE~($r}GpnDO&+Sp-)weKKBA+8pK>V-I?p2jbIY;+VNUYgtc zihYg2#kTkK5#cF_1Z~$$w!qV}k4V5brbbcF3witHseB-3T!0PUuI+0&FJH<8G@fF5=Ka`$E_9- z!G+{zm-68-z)Dkg7s^tyME@?%utZ}z5e=H`vW2Z))J9?h)PqUAa;5W#bH=58XRZ&I z;qEu8voSzBumQld#l^)*v|)I5Amu@U6#iqT%0x*k51ix=21Q-t^g4I|mrM=v6@_Xw z`Cg6S?kyH%gEkjV?pfwE6||$$il|cjC6Y-zAv6V-igtIMWB*YQ{j2kGy+R7*K9rF6 z=_|nff5w}%xXB7$KF!+d!@RZT3G*9a=^^Pr== z|4`-eO7>}yyqrdc(*gVo?+eB7kFIIZMMkj&1`ZBY0rtB0Er<7X>T*fra+@bjyVb?@ z&4l=&>6tve_2~9ctiagzN~1*1-fS5H3QF9F&twHzzCyUb=mNv`fjtW_L)FD@`qT6S z{x&QuYyfGb<}%OX>wL=&5BNX=d8U$ZhVDCT*`t@T9Kccr;lnL!MPPPsug z=G!gisD6^zF9x!}s*IUpm!FNO7p8%~YY=rm)#O_h1)Xn_26EiQOWj3cd?)7y3n$d; zX>}7`BHsZAeCZ_PGLs`H0QXz^i!-Q4lwv!zOMYoB`pY!<3=f^{{O(aemE}w)qFP{rvXQ=^Md3|N7 zW&TDbo8K>rz9H(BMg=JT`WA^P>IYL_W_+IOQ!dKG$CSBFcCE)>p1xD-;J) z$f@m~0wO;CbKzexSm(l-O;FJv3Qcj`HA(-B@DW4KiMrmQB~zoOV{_KnOm)dOtvo#- zH;=$>TnsgsNq*XlsUD*Lm^wqN3x7yI70koI@!e(r7q}+<9k!xAf6NlFa}>7Zxj|fV z_{j@s@fO0^i2sFY1q?t}jBqjmVTy_y&h)1qt3V^cUG&xEDFJ^v%$)h{=3c-9wi)wd zEzSlP!=$88+{+N&H3dWIsQ1E)_r-jb+(!c8??yy9tcj7*u(_2Te_vlBH{70Z+4469 z>nIYh>X`<}EAcrZ;+>W3u8apG!M3FP=|qZ!^7Zvv-I;hKLFCZR2S|Z#kf+88LL;Wc>ccAQ zu{m0&E8#W9Fn)fbu~Y5F7NyHus#m`yLSk&3B8b`=1xklaP3owE(P44e$c81GW>klY zl+_R$A{QAZ^!`@)?vC?*zLQUrqzZ5Uvup1!UOc6+?f&S%eRVSVWDcgvN9<8O<0O2_ ze*j%G*q8cFmm<{%z~-q9-MLWOP~fGCT}%BeT=5lFp^-SzCIPc7dYtr2jE77OF%EhI ztQfup2q{ON1CZN?t^KRN_^P6_s0ib++P!mm;ji8UG&xnu7NGCM=Z~vZo%APj~!Q6G{hi_pr#80KWB zrp~lZpFr513Xhj(Q2<9{4QGCEQy8qbDA(_J+6cR@x+%cL8tv9tT3S*e)v7X;TvK`z zTnl?qxI?QYHbD{Cyv#$G7ZCnUGeVoeg&InV%lPIu^%Gx0$(DcEYyc!Rzn&*NI zje9kL1AEavOwv2@vfgMU=?l+&*mhrZpg^1GoAM91+wc8>c#WsAKkJc@TWP`!W=gMV zanJ@KKwGKaWl9aj@95T&t**gOGVY*z>->~K+KJDUCioZP!oaSz^n2l%S6;VgjU{L{ z`|*h8b)6=)8;@ompXi+E zw|JjR-mx&Y!_92+J8TZ#I+J;^ z5p`)R;zyYSvcqkU#NfRR+!4QfNGd+eiCT)jrNINm?#6}ufW!HiK%*puwyRX|9?C{n zwy9pXZ?17@R8&tr0j|jph=IfYDfo9Ey6{ z@haDCpey(-8$B2Yo;@EYZZf?$LN|%%0l^HRbjlNzk`&ne=`U}px4IrDq?BDjXmn*r z1o+^I^{(3UYoi72T=|V~lL;RYcmtnZGYC^{ZYJ>~1m*n}T}X%A982LGO_hsFF&)h5 z{*N@3iZbOIhJcgSqhlfa)j?LTr8YFlR=j;qq0^{5cW`vBpBd=`~p_twW52tmUwWgdJRXWZJcxT0fdaXJuj8|~! z4h($kHRf&9v#7(i27_-+JdExt+ec{&d6Q#{{XDaxPacko^DNu9e`EMVHzg`A>RKx0 zBeg6Fj5Uks@PqM#9+3-Hhc|+ER&rq!bOo3jB_t)*2D&HgA=5bb>|m7l@I9vew0at2 z+}|~ON|U0?)rUpa2;Il>)Y&N&(_d9{m5b+nrZT%1(*})s6Ogs}mW7HP;E`qe%(Wo1 z-Q;x^3Dv)UG)4m`kg<@ZfilWWHYj#j&>DUkNQy!usSH^k=so_|J7T zt9{V7pNZOye;q|8PJS0E!lBCve7Ak2w!`N`ZhrMTN{|H1K!S%qgacn6O_3bdiwv=i z(6IaI@DXy$gWpYnb}UjI`j9(%cUSTn`Fgo2h2K|gLLBAi7S^3?7I?FR zZoXGS-NUf{7Cld2yskbUKgQ4dW?BA~?IT^=&2Qwx>!cKo%%^D8T!WuNV}egc&{2Ai zXnZ}x(O6OgzYL_wo+b}aXuq+SAKcBAlvh~J02xdTQAcV-;>`5d<_39q`(mcc*{My= zwpI03`Eq;Y&kXJ#`}KCO01-nXZgw5|;>h4!VQto_R>yA%ik_Ii-;SHYp*MzS)9JIOp%c_RVgLieZuEw-D|_i<#Y zl$bbJKw>tzQ!?SW@_{~`n1>OH9S($oXU@!fh&o1~nLQU?7VL-dyy@e64vgo^s^bCS zh=mC|=6}VV3`z=jbi)MevOFg{+u`J(y-@I8_0^|&t#};_MpmeY-?hlJkL|cS>h)A@ zwpZ?iPGcdGe)^GLDa6d_1jDJ>egpbe|;D@(`~ntCrd* z5SrfD7Ev{=Ys#0ubtVg9P6^F>pvjyFj@+2V;l}Ec5417a%F_Sd@8Mb^>4t0EfZok{ zc$MRm4ZLA~qk4X*vf^0taD$wnRlGg^OftA(?W?BjN4?ALY$M7xHI}FIF^9o0JMxe! zq4%($ukM1IF%7}PAFD1h$^?IpUuN03&8<&{VpM$bEwfIZ3m2Z@C_+#F6!t-G-j2cjKHc1AWr%FViykHDKK*tE99>rwQ0iBzW;itB31g#*+ zdd{>Hp-;S38fD>yJ|mLQE+WEkP)khf*;xOp9``tE z;%YkQj&`{mPQM+oH-WJ!^L^I%iOeSBfaks44@#}@#Sc&dl{f3iJEHcu_`B=WeudUd zdlli1Y_`9aDnM7%A>X({5qI#mpQ2iz-qlprWbneSlaBl3mrH!-XT9v>v^gkpe_j2t z%oysSSI}g%Rss3YEz-Bl)2-NzjTLGs(Rm7C=hWoJp|^bJ@j=M{4oJoVp-U%8m0R$#(05!PToGcOdar(gXq6s+Dk%5z0C~w=YLpG6ZIew z(oJqx(^1ta89Ty~QnLP_;SYVA46`r>S@~1cq)xj}Po%sQMwH-e8LrocegV z!m0)bisV_UQX#r$GyRx)BUPH}e`>u&k2%U|3^K;wfx!cZTM;CDXUZgKF1v-jF!S^l z+s3D0sU0x%8mmzyq}CCI^pJtj0h`F5cU>qqtUT+(84zM?RmXes)q=#hJzZYQ72!>9X8Sy)h+U&30s8qTN$VhU5W zeIC1^Q^I()i>{A%^?T4wmHS1&m7KS&qYjdHhQ4A9 zSp1qldH*q!9cJlbhF(fL35ZmBm~GI%$1yAbjzv|texg*S{=f135#q&@Ll}QZmB9w8 zL%>BY?1eSjk>Np6W1)I(2?L7pem;F>yZ0UZa%q3I_z^S@mr3b#Z8dj!=Hsk>!{e$# zYSTO!o+5?iYVWl{4kU5Trm)T@Ya~TDVvgH^^|^?F??>35GJ8�IVte$`Ui?M~R~F zOf2CXha>Krms4NB-B9TQTi%fdXh-4z=3mrn!b^Gp-i06W-LEV+V4%+DQPjV(H8*2I zkf0<|WD@GQ*)TiRXKK}MwC=rJ(i?F0IRJDv*NU@EBY7A;#Fk^oPbT06mxlQ(#}Si% z{D_EWGNWd|kWKA%3sL*RsV8~QeZ`%7aS~g}?*@UDxaA0Jcqa-b0F_^7 zAIzw$z+&OG)_8i|HcQx|h_oqsFX*(vhI?=gCxmtjkJ57?O8o>%T(o+T99vF?_8Mj9 zgP3`2_%~v|q$-hEevItOzA^~tO8BXV=nJ1JS8AI#hR`PidOMzw!HXA9ug3Af(6?i< z7P&kb>|!s1>i2>GDW6!#3_zbKkypH+F3}@p&*Gc33~{^(*U}Zn!#{HO9LGS~%(AmrhmlHvx|iwTl_jCS~@iV5pw9{0YI>ma`dC~SP3K>T(_sY6U07N0w2 zKu))=CQrlgyg<{fG>-nS;pE`}(g5}-kq69#`+u2%_5W(@E5M@cf`3T?K`8-2X@l-A z5$RM~T1x3|mKIP-6p#k#2I&S#=@O6zkzBf)dzSF~{Qmd(-|Mr_x~}`aXU?37-^@F6 zj;EYqU{gPTObP)J`DudG`74|60*61VCzCCIpGct2Xbj-*-?JbXS!hT&K&bpqu~uiv za>nI`nm<+jbgB9+QyxTHky=A?=rq329J@bdCxUR9;@G7>AAPf{Qe?}rE6*-k&w2r# zrBm;7kM4LhseUHd;ql>RGz6jy!P1?mV!9o)#U$^HbcXg8jamm>Lf4bNQe%ieBJ28F zfsebTjFUB z9EIZcz9s%<+xu&sY}qFu<~DK>@~`Yt{>|UbtgakT+7k|I4kBcw;i^w6D`Q^41HRvW zVAuv>N)FqBaK{;W2gG2y2U}5FI*Orh6P`%PI(;|MnK#|)RkAA56KXwgQ*D~W$$w|F z&CxNn+e{u0idr~oKUf_#0dZaEzAP&R?^rlfh2nSBk zbw(c@x3^1()8|`!Vb86@_5}$t0Z&G^BmBqtajh1V3*W7Iq93tragt0@c5M4^F_=D> zz5{6DZDwIXy;^;y7%&JZg0i3>x~7}p@ds6WXI=3~$l9-a&1ek-yWJ>sCpR7FoC{aQ5lS?-OSGWyJe3~EDFmUsa+x5D*uj|7rNcp55 zPp-)8!X`l+rm(l5)Xn@3Y%Z2e;1|TE-xe9JL_I_J!gYj~;&)v`qz-Ix8uYl41%@)> zyRaIdWKi3-wn!^}er;J;F3oeNY!coTf5_k=FBdxn7A7ya1NtH0C*TQ!uFBRwc-*|W zK;@Ns-*rl-oX)f9q8O-f%+nKKUM?2Em*8sWowzHy>BKJR>R5fGc9FP+4dkByo5&j4 z#YCRNCSp6Y$Z?${io9SY{-iwHb%zjxoFM1LMCyo9VYR<6fZ#d&2v456_A@Up*rjeS z)<<-8mk;%|3gj8gN$8P~?wSjUx-AWC10o}d=Jj(xbWj*33qRpC_Ac#;?H)*zxG*dZ zo*h#QWRCbqUw(f-6i_6l!G0utCDsw3)7HfJpW_bNU{?s{1{ntg5H$Mx=B|kHm9Ta(b?~CIT6BFlh`l?vq@(m_iSkS5N z;Li8N2drrd%x-U@e!$#E(FSLfZyYW9tYcb`B#I@(t8Q$sM?R@|QdxFPHFG@GOXwQ! znp5_qUn!^v;PhV zW&{^}>VR@9+ufu8Edq|=;!0KhLR%}(ak3&BnOuH3q0otIOHcZVYj>U8j=smso$cX> z%C zC*I?Pce!lQxJbmG0xWIrZXy(NDF-V6mU@s7=~_(ok*bh?pkSZY_64m^Ih?Z(;9X#< zLZb3k;Hs+Y{;~oA4Yi4&cS0U9ekqQO$#=)fvi)!{j|jREHd0`UI{?&yGmcp7 z&+}d`I-rENt88sAyZ`Hrf!eCyVt*{@0|eO|9bDoN@#=k}+s|FXQD+j$xO(4K-wkw;5m80^sp~@mPDG-5vQSc)8*}jCkIc zsFjz_MW+>ZtIc2K9ws2ktP@H|@y{$S77uJ-=3$;s`>gKjazAkS@k?}-9gqp3&EwJg z(-Cnw9nf3>K!iT|;*E>@cn||)Y2F$zi;xE(x~GVt{~uF-`C(5IEN@L7#_6S1D41Er5S3eIVQsW?$DzNi}B>HdU2!kX@@O(X~ETjqI8es_j~PVf0a1JnOZ%^p_4 z9LIXYf zXtm!X91vEf0pEruy)-;S~d%grN&@#^!2=SWuZj7nsPSz$K?`&^e&x@_IFHf&!L-c2S` zD*{Ovlm2;)KciiJz=Ey2`5*r;EGPnh+Epd)x;gQ5<#sJzYXIMfD^uEQtakkFH{W@E z>VlfyLgjEz_|RPREOXMl9V8tT>G3?QMOeQ)*HP2&2vZwU0RuLp4noD@HTg@6uYJOw zac_WyUckR-$N+2g3`r5Em-Gp`SXuu5uR7W(A%|VOjQ{&Mv$)GkuGyHNxMpSW9xZYZ2N9ik6zQx zy&lUowTzSV65gI5wHKj;+75rC9%Hhr9j(uo{2`S+U7$O zqF4O$+MyL^Tf4l?w|}?I({|K{(M4*J_(xNl(WGqYf`x?x9X6uP!GD(XnzKe=JbIb1 zy-RBn8{&bCyfd|@-T0aHEFy4x{Nv291@w!Kxx1g9{qeVsa=(a4N8jwSMl5W?R4V)z zQ#C@H(iy6Ja3b4jBHeTX;?P;@qRo+Cz`=CW|3S;w$d?1w$YZ$3&3rkxMl6sSBO$~K zs;uFh9Xcgo*?Af#nP^fZWbgU(6E-7DcS4Tl`EzQ2Hp*hUChf?{gtpsR+*t1#f_r@D4OmXy_Oa zX|D%W_=O^u-5i&^zI;~%u0j(phfVSVgMob^=*SWSR<^Se%<5;;XK=a#zlEDwzsbPr z_-w`dK9 zW*cvFBg!{Uwc=8b$L3&QAlp71^Mw3+eAs6}JRk&0-y~rhtbmuSNIe3G5bMqR-Lso0 z3VX`Bjov5;C$V*;h_n{G>cR8gb}oPH_x)f`c8S3x+N8be?)`&WZ>&C%mP)Lj9e8aI zItu*HX^nn~HUjON9a5<~yHiF|?ZM@tBq6oFkV=oZ{Z#hFjYoL$>02H_A5X)}V{J)q zF3z*2ApchpnP3PN_nXxve(*rYF7WWEwT2=G9&cv&aAc_y7F&FnGKLcwa!P1JArrQp z7%CPeTUP1}rc7Vcn~0}<7omto^AT-zdEwcY`eOMX0uJnVUg!G?g?Vs0&?{PD%tv^l zx#NbCscRl=KUfK(AoX$7;*wKSqz^}axRoxZ!$GRQA%`Z1$tf~xHu?_iJhW+J{T~{K z9|4&z8BXZC#8*`0I`Hr{0~r&eYO}lx974e!Y?6i?RUzNGNI8xz5oW3_#*(ZG8>XrQ zn%3R5T6@MAr*~2xqs`;#+QjfU^_6M~_+wbe;Qp${8ffkb9oSE;KRX%ZZFURjv?b3| zVIcItAx-%_vfL8piT%*3cz4jE>4$2aEh~nQrAj~F#KiMdMYwhXJOiD63Nb-rrw^Ix z)?+`?j?w!bo70&(t#R42c-sO{KS~R2*etIliw%OS>(G9tC^*#ERWc>2w4>>b2q=y1Cu@xUA)1B*@65b7E zc0Y?2RSh}Z{}uGw@lfq0HPMSLk#XUS7aX+j=cWAEBDxhpf#@5?ueg6BNC4rV0w6@B zXmn)&D^Me;6D`JF@SeRU{wO^kk`rv4T9nZu=Krn4`6P{>=|@=Sc1kR|%O<}1ZH?Aa z@8M5$9Te?x{vVlBZ|V!y#=3n^XjHj5wmDWj*ZNiG)P3vK3#~Mxpz*Eqz2`SX^*hm- zHMecfS`;*@PVZxfzL3b%PQ`)W5|#KO=-!b7;7y0+1>FBjv6wtznxANedg&?xu$dIV zfrqEqCza4bpHhog3jRl<#wFa@a<96h75ZI0HO_u=)zqpf%zXPad~jONZhE%Ob5`|n zW4iAEH^6zxspwef$DNSF&BlgX=QHcL`})InQ-hySoE{CDYTgh%*qaJ}u2GApjxaxE z6H?4cXA8;K6yUw#!0_&VltN6|4bbU5+uHX(oaYVTNet^}pI?$rK(3PpigmYn0LY@0 za`DMAO(iNm7+I)V;AD2x$w-ZLI-$G&OZ401he#a8wKa1`f^|6gXEr5yaRj8l_ny_R z)E$D#Ej!`K8kckQ#hCP(rf;oS~CiYXEa12xRhOojt;#pw!Yo^%FoJK0DtWu=L->5}+|l zySWq^+80^ANb0nal{T0iiO70GMVZIW6tuv#u+Cls??3RZ01LpO4nn+ zpDwy%_P%OjKzl9SQ}{-mGl3@2hin3vh5k~ir-iQ7&QWXckP}^!1@FgKxMgjPLMxL74HD^0y6|m^Df%+Q%;NT&9+&PVTj9jloiYSa*G8-pp5ETQXd!a#$ zYIXL_z1d3GvnznD!36&b^)LGeJdk0b3z>BEWlU!&4`Zv88?RqmK!^m>6S=G)d1RIh z1f!*So5*4+Ly{NHDRN^;S)Iu}8CyCSMJqJii5P*xFDa0dd2<$~>_^P0v7}0&O|iwRR?Xrd4J`0b)auauBpTZz zt_jk@-G7$c)edNee!jpP2^I?Utq3d%1h zRaxxv&Z*Cldlx>PHLXpn_wV@{?Y>|ttE1UoWUbWS=9YG2oW@*M#LGfg{MacfmEMl4|l+a_3NVy$Cq2{}0{**KFf>!`Q< zTv?<1OtIVQjS>0*Enc$BhVf!fik z2T&K2@BnrV8VDaIEem^=TRZNlKtL*Ge!SAhOkd9=c-20;|*B`=x zwyU7gT_tw8u;Fo$ckb=SC(Gt{;Rx^Jzugq^`;{e#ohr=}G)iyAnTze;c21k$&L=@g z-)DHMVM?@tG3fDaMw2hgCrK%i1Mti!Y0A`i9;9M}&+P<)tR|#wtqK%D$cp;d|EI|aR+veV&>xxl))`~-G-|8H?pSv(1OR^;O*#z`^O zswTqvciQbV{66PTed}nv<@dQP?EKLPNM4yixUv6BMia=w#<_T11Shbq_n2M?CY1g{ z!q4HQ%(aLgfdi0_~J9oVa;U5uBggrdoN4#RwT?$Z1NJ2~;R zVlMbYc&>D*-m+jQ1Vniv$4>HQVKg7UDJr~gf&7HvuJO52AIG1i(#xla=e>zdMD5m=G~$(x6{-Gpj*CG7^R#y7qi>aGeOJJ^||>_~rc=R>wl z{#nTSUx`uu2*8q5f67%S^TGqbBDXbTs_5GMaQ*^4G+PrbaXgNy;BldZHh0OfI3hQX znS^j<0}_a6|Q8Nj41EeZl`5$Sl zhzE%(f)>MRx4c4-9!F+t9BxI#CX`-9#Pw@v2hP69%F_=W)BFV!&vC2YiF?w1ks#Hm zVCF*jMnGv``YhV1o->>W#eYqJ&~qYPcYaB&gV-}FM;-Gdp(9k)flH`cyTQ{EIQs%y?JYqMN7?DtxVPCj!yVG)&H(_H<6Rz!2Ja5WG!PvHG#s>Ejc_vL-9 zJ|&Lv6)hCT^p=C-B+kBKWlonx2}AMJwCA$A~S~_lr%Cmy*sAQqbDi0LNO3TI-mO z;tu|&M2ygz?J;skzYO05VvUzdQ}sKy>L+Ipy75GkSWtYF`1TUDr_{7^C8);f>ruv& zc&h4epgJKUyR+gyLfQ#S)!%o%fBjtLwov^Yc*xor21}*wB=#GHM~WrlX7q`S++nx# zCm)Gz=?nH`EgOuYd-OC;6r6}lFU58WtoK&`Rv0X&Vb1BOwOe|gBA0tI|Lp{E37aq+ z!;PAnm31py@D)iw<-tvXKKF*(cfg zY{6Leb#G~&hq-iAe6NbRDjtpvWuj{7a7OHc$VZzOf}G`dR<5=3ik6F#ma(OV-s{~E zfThzzwq-6$`{ADvK)0 z%}9-MxQ(WDXZ{p=E!wGB#R`vUH$9*5Me zd~9APj>cEf3egPvf<5;}7#HQsd&C!?jKOX_rJb>V9*kdR7wV-!ZmtXI`^*)4rcsfk zv3u=`0!0iUHk>Le}f26I0On{2rUbNv&?aPx2k?M*gQ~XY0$tcvV!VLLQTItGWnCSb}iy zS8rV4SeV6h)c95k4>$x=vJJbNwvPlYoPWN6XuVxTT55LDlG)B&9Tl#wp*LEO>jDFuBB*C| z+ba%=@RWR(!`a{Ec}?f#yngMLf^V^}S?y$KUD3Tc`_3)Kj$!;x{z{VNuuF`}{k$@c z7T(!34Eh0|uwZBlZsOPqD&${N7EI*5366?r)qEubMh7G~()EtOK?ZB@n!Tx}V_{BH zwt0l_TwTbRu3pQl98;7OXAzk=iL`fS>JlQn?44UH=&~|>Gj3s_LrPt(`>qm&P5+r< z>1UP4?LQJYS4%DMR2dD_Wy2!YcEa5%OvkMrKD5=~jE9?u{v3Qc-o>C~K)eum1kYC? z`?NO4d*-6u)|WIM93lUrptYMRn0SwoJy_tQmz8yEU{Yvm3A(2yA>vH}DN|!Fsnr^e z#Z6=NI}%dKS2rlxsd}rFWy<&4ZE)ljk4dC^yuncIgJfALj$^Hr_ieADW9RE$N4>5t zE*6b?SxW@nel7auxvu}P&(Jm@^mr=6`Uq1RwQqH5R}l!sX$}7wDPhN?76H^>6<6Om-6MCMu*6=OZoETK&IJF z;g^#rF_528qh?cAW(hkg>vnBQg^-vbJ_v6&L2?094B3MG%86OKS*QU_5aO9 z@4O}N&e!7H9YLztS!bU!-$Q7^Z@(2}kyTziiq^0;X_1=VV&W(tE1J?|q%RqpMA69Sw3AJ`(hrf#x0^q5_!#a22Z#AvLinj-+wLse z`Z9BT=h%pZTEwT9TRU?s>lOnM7M*=hCeGgt?AAJcvRieagGSmQO!$5l__wxtcxWS` z_MSGhr(Aps|8V-LhdE!oJEuYj-?>4MwT<)fW>uQeivIxL0t@+32#H!+iTXBw!kD3u zO{JS>(a*f%@R7`6d=_d<@nE8|UL%v!SKZkjzGN1ls}8TN1qu zt*_POHcxoRcE6+Fi#xM8S(g)Y0*S^E>sdyz-0W!uM(m77CyE7Q`!V-lPq4NvW==ty=x1fU;*D z&u=VV?aS%AoW|j*-W6uSY@i{1ypcH~NjP2eX?1k!%rSrMWkLIr+dz)(#IZM8=`*|i zPqZZ)pCGd5;f!u_Xf>3pEjWo|+JKZ z&)_!ZLO6|$d#F7LRsSC3?daFK=O{K1g7i@i+^iT}s39@9Q94@kG0(FYhDkQNpPbds zL94cIOAf%6e0PkV-(x!occ{%bbAgmBmDSkAIkQ0|`})A?n!Gr_7XB8IDVT_eb~Igz z2<5buhq;Dihsn+YXW8IRqZMME|eSI_X^1d10RCsn8_zF#} zuBLv;LO{`RHFRAyXjkm<>}w!Hfz7Qw8s?{W6^`9b*z+^fN+&a;%#G94Ie`Gt{67T9 z53UBSE$pe&%AAa|!&2=$y66}po57P#gSbc17B>gGhC^q*Z%4&pEa^mP_ItLAEgvlXxSSs zW<^v|#y_p#~B8K*0pOFIWL7hek zLkrgyk!-pI$jNY0r{9H1bVP8&=#44JGFi4GOK-~DJ^l9HTP<#e7FTz`*~f>wF7rAJNO<0^|j%ky&fPg}p(4~(yddsduB**VXh#>oyN zKjD=lkdYBEl9&rG87ii^e&C#}^$oIS&s-ek3-|WVZw793dBmB47!v|*XZrIYL*?T^1g4(N| z&Cd3{qF_K{$Y}Y!MJHXaU-oV4bJe%(1>E80?fH?FzaD9jvNx#&r>gW=Lb*Gs?QnBA z-!4DWVWbAVzkcG*eR4iy(DiJ5NPrVD!PTzl47y9-egC{nC&I=l+m2GOEG_AO zUx9QoK@0S+d9_blrLyg)%9<)ZSSyLf3ygiBxA7V)-IWTom#mL;o;RXSyDuG!n>SYa ztI&8Mnmbls%Y1aU zVykI4W7#Y`<}Thl$tvUMw(h0GvTizhV$y1S7W=hSvFlVV!kwAmOEmh6+P2(Hmu}7Fp7Ff(?GT9!F)fV=yVcq~7E-s!fpe2{>yj#N)ZPiFzI%V0 z!so#2Ka)iKwP_`RG!tQFWVS*mo6Kt(08-xJW98v)!k!J2jPBTT9LO zjCl1IQVD^9&W-(m!QafMu?pMs#g&I+Y};-D5yX}aJAo5oa*m9+%2Sp`mF5+$VcFye!;L-PEWwESv_L=gv1cUs7AxV}?mT z&}!oP>I8jXGcj}aMtMvC+(aBf&EJ3y6Rb9WlRnMGYQy27g7biLHM8^ez0=`$Fr3&!`9?}Yf5kmOs6U-I@_dK=CKMLIeM)+uWiqWAm za$rF!p+<;b^GC2nd<gL9ndPqgD?OF|KTUaym>O1!*Dg+6ibdPU7-lG&;kG+?C8F5`l0N^a&UVcISo0qae z01gG+x}l;7mH}_n=AfLzkfg8h*2t(+;&*dc9SsX17X;gE{xsab5dtPWf~|W7%VXHLf;vFT9mY=C zK7Wb`Q=zS@5A&q%KLQ4{aK0cIUr8-@Bvz6$ePBTT*F8ptpy9<=Xv@U7eKQBcPeyao zwWg9{DYb7b820Wn-b<~r;LdK`93lpBTIQnvA3y?|uOq#n$65*1HaYAcNb!KLoaS;S z&}Ah>`CLRG$dwC`%I4jJk4=hlrW${|;7lI`1Kznu%)pv}*4{h}r+`g?TI$9Vf zK=-1q)-I_fWJT}vel|FKR9V{g?}+Jy91Mo3G=BjoQ0d?ic05LU+Ov4@?kK&Pn$d-P z9SHMmd(o1Ytm#}gBT>T+VxMSsi1_DuBO508N_UMYyuZ9n0a&6k!6ftxZhZh@1&E!l!tAhm-sleXP{K?MUaDw6AC~O znRl&(dz5P7^wGgB{H7Ffj<%=vch>nI$r+=8cm#O literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/pass_through.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/pass_through.png new file mode 100644 index 0000000000000000000000000000000000000000..19b5cfaa07626a177d460d9d3cea323b22e5a617 GIT binary patch literal 68871 zcmeFZ2Ut|ewl<6i=7dBA0bwwZo75nw$vH?43ert#Qj=+#JSLQ+qX-HDCJ+!1$&w5N z1qp(HWCbN7B2A{@uif1!jyPw|{r+?BH}`YSd4}D!_pVyCYK6B}y?ZX`YOCzrwtpK1 z1;tJ^RYg4t3hG7*3QFcJn?TE`LWw>2v%y18MV=zFo@JPVLT1EM$;8tcYm0WWq2Ll$ zAYE|@3EE>kJh_AwxrBtQTwVFC(N=cuR?Z&$E;gQ^3EX$aSfg#xHrAwPgam~|_yooH zVB!XX!d${~LW1C5f)e~f5+Y`#=dJ8)T*w`2VQ^?CCo3)?Wl?@X(A5zW7>r9;9$aan zUA(a1FIHU4QcUD1xRP^qb+R$GL297ExXPl!aDHJi=oJlB11(K1Aq8;lgm$z6e^hKx zju_|_1$%dlGiXtU!C?G?(EmWAzLl+&J9XyN+&$137xEND_(k|(!X#;JJgw|V z&2V2Y4>KoMdkr~FRWrDXnx&?-KIs`xUsoH_GjeB;d1ult-gOOU07@YWX*lUH^5^BAimIb&7atz7N3FxECsU^r_mX)s|SaiUnD#g{C& zprEigNq9T=)se^pLk;?9-0Bp`Z`ygGt!+HWZzJu%L}i=Chw@>VEEJ9mtii?ssA2?N=_wT-QnmlIIe*B<1Y&~}jPd172atCfc< z$u4ZsSSYB-69<%AZ3T`(YJs}4^0Wfcg(Q)XvWK@FmykTx8R%F+S5;fc%vW9nX^izk z;ao+KDo$QjI6<_Ps-7T95#y~XY%Of<-|07CBPdfFKe8Z7gAW=MH8pyqopY4jS@C2i$ixQxrrSs3?n?nW)=pq1Aw#x+;23W-eOLm8!O&jWO0q z7cJ_5RMqm-GVyc(^7?3+$lF`1*oj%2sC#HAXcOB|D$0UZ3XX7Fee$y|p3YXrSPva% zQE#NP;kS0QkC&+s7N=>T4Mz#<`67ipoit6XUCmVWFggzMJ~oP;5}MB19w=WyoQ;r~ zD^kTrObw@o(=s;o)dKf)6(n%hs!kqe1|s61A6JwzQ5HKZ0PtXd?8|VV2>7axKdVuufrLC`K2l})}2}AlN z%HXSp24O}Xj7prPAv8-x5phkSuR2mek;ZmX_ck@w!>vEA5?W1_G)FKFPSe2<{B{KL zKx+YA+exUQMPNV?f6 zUlCs|6H`wuV>@9@2Q{p?{bzI_{;dsN|ug@;^JyPxbP{`u+_)gZ0)zi(s{W zTx%S8t-*@^$qKNQr=>6A zqlK1(R@qlgQOQe75w!UdpTTMw*a3~2{`ebb3TYa=D~HoYLn|kT1^o$u6|&P(Ahi*_ z7l$G}_tlHF!0H|c&njVc^hE@<(Q>|ETv6h)M7e&j=+#*&NVw=a_;{NE`_dE!F$pIE zWfWm~kpDcb&@Mzc0L3(N00u$ThMbMp3Gu|Hzs@t?vWV%1i!}-b0_G>by=xSe9_}cFA^3p>kwfnq+cI8 zR+f_k^Anc$@N~yG+Wh>^D#ie-DvtrZqdg(jivG8)sE8PhUznV|R~Hoqhpn@WV&tV? zyN0m;(KQtL-witc0&FL|$hLV=T*Y#p)o zHpWK2CLo~bI$#~mjLmT1?`m=;CwXPKnX{7zQqk25DJ1HoBdjfma+Yv6Gr%}#IiP$& zxP*Oe(}#Ilndmv8oUyJ*V<$l!2PGdJVL>Q3kw6F(tW=DgQ6OLe07V2YhGYO?BIM)% z`d^!TeQgW`(IAxi>L{q$pDwr!PG-rUjzo^5!NyG0jbLrr%6m*0G#}NnZSE;qDaN#pugi@ItF^sI3Sg+ zk;mbS`7_dGfrZ^=p9YvIfmI5>`3J2u$)kgaOU}oqGuD{7+0HxBO%Hv^W zEb0V6l`jBTSkNy~uUZb!8WX`57HZc~5W#5!d$3Vd0`{P`4&WlKEdlqB_U|-w1B-3$5>xaYvlrKMFe}0jJ{e5B0?lPfMihu>q5K-$@%r(4={uTMpb}^ zI2!^>Ra^Te)GH43O7u`01E^OBzNta*66*Eqy`S_-1_aQ?L6=xrAi@E6jHeZO0|oo< zOCE3`ehG3W{hB<)B!vGJA^^1)7&&;a%_gfE=6?hbkTc$20RkHrYdNUG01~td#s%Pj zwE*CIwD3dP7Zg-hmWO}>>CS4}2RKJq9_+x~eN8~GUw@cFKLBVV-&2I}*VmhhkgAEl zuxL->Yy5)35Pq-$ze#Vx1wn0y`1{+d;O2L4>e{%Y0lxbafV8pxQ+dP#_3Y!X0U!y~euK8U7&Is$e#Nx_ z#)u2^i~Sh}i3`H`g+#uATe69)4o}hyxvReiS^uRRLK1@f;$q*1Bx&ZWZ~Y62JgwaA zY&`!95($IqCxFsl5&vInll(LhQU9wae*oT~<_hWRulx+<!wB(Yvp|Ihh?goKdTk7E3%9AGsx z028o+HoU9za)kng2V}B;ZRl$qd$liT?4QDn1YB%A%?b;yr`dnK|NVPoiVOaIHU4{J z62kyVVSh(C|BW$*T&w@981rw3l{H)VzslwRuLcbmWZJNwCN2pf@%4;+)y@9@Po@8* zDE3dtpXAfDf6un9tvu|%X4ExRE2v%9$`gP<===m=Iq1ms&kz-~d=G9RoJq!=g5qSH zNy44tB4Xs#L%;kI0D_Sr?|1z{`1o6g#9t63`ihAECY1f(m#PK9xitCs@he7z z!^q+9Kj&O9K@liv!O4L5=R^M!9Ez;JUk>%lp}_77IMk2ja8Yr7Ve)Cpf7+@3*5LmH zw*pnDf4R~75rq9pRM6)5e`BHooTwk_D-!UpJG}p_UkU%c!T%9{MGi!NGhd;ctUNr> zC;+RzD{*{lUV{d|M|rm3fSF9s0>^=WMuiYgBsuv10~HZbk@d0yj10y9bEYe?{=lMt z0(k!jvn4zK{{?2dX2bEd!VYaWNY%!lZ#Dj3GI!EkzX5wuu~iDkf7IH+rUE7`28Y4m zVj^&Ip!+I>I5A!PsR;j%u>Bv&Cg4=V#@z}cb9!KGp_2$_P`XDG`L>|x8)*`dc_60a znjmdOCOe{l8AE3`Kd>O3(bm=w=W<=f%J(7u&m5vPAs-YMR|7mm)cg-}ibMf}=m*p* zE-Lul(F@5Q*BlxNfr63p#Ol zs45O$bIkV7S?j-XX8ccPJ^$AUNLs#f5QzgKWc<6#Wk5_)_qGx;^dyoyj9tC0j77u% z83~4TKK_lJtiQ@mR{tBsB|$RDN&Op>*%;<(tzzU0#sFld<6?lV3%51!0c>nNQKX6? ziAlUlm2y#2ae_F#1|-RhY^{v7y#coyqEq>r8EXrwsj7=Y#0@~@5dkyywSg#0z9J$J zrO8Ug$kj~9UJ%@es6dcLzVez$qz}L^{zflakJ}7*&qQvsDv3c2F~N}rN?|U?eLLNla^>wE|lB6NCCkvev2wNu)5MT;G$zAfgc z9y_iQeS9HW(N9P|D%!3nz-$NPCL&Ra*qe$rWM!hz=)`#uNpgQ8qM;!o+W#eNVVEGq zW)KA5a|w|E-Jb)$xG*4HkaPH&)D9DYw(COV;JP-siwW}!|IcRkzrkMk74iSgZ&iLp z{GUaEUlIRT#Q!Hne8AZO-^u<}z!%~d0^fbC{zDG&|B%@KBdf&63i_5<5Pa6`jsY7! z(#B=Y?tL{CfUg{#Fka9`{$G4W;<|>DNq%X~*|z+j_vb(R=!7K5e|X<6A-YagT>=mS zh{rx_*A%`E!E^OP;s4|&oya))$)~leY@~0WF|Xw?5$~>kPEEQ&egXQrox}wT*i(9# zf`Xj_e8XjcwHWK(9DBmBTlTZ1s*bA8kz1#mjw7h$5ZLGiJ&Q|`+f-@qUQ|E6#KXR2 zn_i1?T9WE!B?Ajx8mglggHNRxs|7dGs?N&}?z%GO;+-R0?DMIrZreafwPg=GBADV&7meDdf+@P`<$kz9dUSwsPf{`Wx^E(a5r-)$ zJ!7c<)Z^+H;KfZpd(oNFD5-7W!;$rcvWIQhfD6+qe7|=cfx)oOl$7|6cowDgW#&7? zj=*GZg`Zfz^ZQzeV2ijbch(mzsgjCnh)?YOIgRx@&)d4C(b2=5Zv8pu#s*WARvzkd z-MXHt5lLcTUe4N)9IGn&Zh9dMw0n{Y-kxFRU%&G=U|v~uFOUCZ9g#pO3~{c{xz_Kz z1I#N=LgM0|*PryXnIN$txzn?qG3$5k0Os{; zvA?&7|Kr6zxoN2FgqN4p)T?H`DyyHY+okhQI@snAP7mLo^EGI(^YYx6G*MQ|@7B;g zi#M$n(Olog3C5>-3A0gmqNI~ocCm9%4H0k)o(b!&ZQW7eYxTabdDi!}ArvrpHl5&s zpZJ3WHPuj^gaGa*o*cl-j+p4*+9gX)cP*b7!UkyAfB=GC(bOxaKtOPCwjcwr<>ky?6Empv*Y?I zq`G06#I+G`o3JNwB0D&7Pzfn?n(&*Vm{!{hp-3 znpC0n1^czs>*(dzQvYD&h+kg)V?6ui)!zpyC;{nXa**ao=@Utq%r7Y4X+{{UmJ$)il;5 ziF+{0luFJ?vsX@s#7JTbGFG}eGZK5YMO z?OYCmj^txS^`L4g16MT>l7#qE+g8Riy;ai(Uk3ZRBmt z0I!*IY^LLK#YyeWG7GVwEAS>hfH-tX>>+n2|Ht8-A-?IYo2$<-?bWDwXd=`(Ug~tm z>mcnn8*EesB~4DRmXk4{Gk*Tf#9JXJsPy8yCM9T!47%<{Yerg4oEv_g(|fq;(xLHG zmo-(}#vNb=wz1R!FF?tbpNfdRbxWQEGYR%?%m|xM>dlL7y(>WTJf~$?Lz&A!$1jU# zZJ1OA2X<|8&7f==XUpw*2HN+Usj@r!{4pbEJg_x9>Zymqv_oP2`EMKIkXBG8FBm9+ zf4pB#8&$zGgTT}jy*>&Jd?f41JCh?l7ur7_IHk>L4pXl3L%ql9guh}vm9_@#HSPx@ zx5f?z!fGZe?o6teGz%=GT_H*Z61xHl@#-OEY3A^W-_9v-dlM6NIooN+?5U>5c$RO+ z6G=hfglVzOKl*V2C0nWrW#FcG3BF-Yu(GN){-25=xMMJLGP>5>KZJ;#|vOs$n#6-d1&*Y+`^ zxG-x(jPv^@>8qS1OO2#NA$3bQ5Dmw3XVQ$q&kmj&-rf>;gLBOh%@JMjHhX?D12}*2 zIZK*uA9YpLsRs6=38g2)Xi+b^#!ogS(y!V2-B1B1h*BP}zev+06)bU45EIb?;*|f6 z$QXah2fIHEV%%>r3Hm54Tx31gLFaLs_M2T&4P}NTgOWJB&R}Q@1c`GmJ(*+LD^S_V zC(^eJdt-=vKc^cW@sWC%fO>}iV^vE@xj;2d+RiJ?Z%rrf)4LKd9r#%2=0XvoL&!Rf zq7-fC7Qu9rdRU|SbMp9|$ZvjhBnLR(tDMe;szZngJKE%8s$(=vjqiImDJ}+~7YpX2 zG7?Vs-WzR`ENjh<{!~BySm$IxXFy^{qU6ft_We2|ZsYwoSB5(3GlF((|1|ac;H`X* z!2>NUZOV2z;uE(&`D;!WdzaKdE=Zdlz3cWe_!~>TJe1x8v z-qe=ftE*f9Nx#y5w~2}|EYG4S&ti1_ah$+Iqwtr%<6pua%toh%tj-!3?+tJsBdRa) z@HM56EgO4c&XYZweZ9;?x5{ehj8c3SB!22@gAxifu-f5M2JpFiq8RD;J}f`cl>Mep*wWR=$Zos-QuhHcDHBY_S0fX-faqA@Iy=%(8D8`r zXI9#iSla}X+WxwEVl5e?6c8+Cdvtex^#-mzs=E(mP>nSAzr^yeUV!&a2QuAHp&w$4 zx{z%VF7WgL6XmK>C_>7h+?-L~`qg=F7`z*gJrGqDXL>0i@LoX6qQ08n?Ud5j&8)*~ zN0kOg^0Tk%OuvrGcc@WJGpH<4>gt<~%I0GnqF>n)Azjev-<7mWs|J`fMyX?GUSeRB zk}_^_qZIqZKBwW*^0#THBVslzfMd^=2LYdQEk^_Ao)gl_3E4S>@f$-?RV^~b3Cyy7 znS)i#DGVoSBYeF1;5~0ki^Thvanj{dSZ^t5Pa`Q|CnG882fl3bkB7oTvX^rYX18o^ z6>!lr&%L*d{!*&kZ&x?ng+=wk8Bt?q{8jDX$6!GZj)&F%T}T!DDr!4{urkWO z5#R0I!}Y0jFo7j?zj2E?PX-;l2cKRgnlzxvPO!_V&Mbay{}Aywb!qNPqDUcqONwJV zTsNY8*D_%a6@j^1Y3_>QAD|S+e}3NA_9~ z^tk=RP+mb_LVx{*k0|Tr=?u*S$40}2`yL3_^EO|);m$kkH&7qQE<1AnPTw1S9p@UE zQM!<{C-3BFP|7-?usg~&ZP|$%n1h@P;qV^uyvCN&qS#jRJJEDWS=lvd1lxy;O1q628R0ha&m@Sqv8RK(_vqrRW*z6-23d4ybS5pL(e*#^3I(RseFYsK3I3~ zJj-65QeSPB5+xX+aa%~j78ZA_ijT8f8vT%M%^qEGe%!{rzLfZd5}bQ3Md@LOQc0EI z9?9}+$IMmrUwLkC40GexSJe+UX)vP!R+f>F(-k-RdSpJE5}(l7;$gdQq7F^J&^eK* z8f152a@tj7?5(GC$|FPGy`vR{=kl6s=)ttE2W-H>>dnyMz^h=H+tYwPm^?P%`fpMX zMZiD3{hgu|I~CY@`%-djDs2*D|B0$g$xKBHV8FJ)mMeF<u~PM?Gtqq zyzryumt|0um445zbV{^PNE;TqX@*9ikS<>7_c_?_9vx5zVXOZ^bQOp^%>CR5fu1~6 z7$v@{A%voIvWgPl7opKi9F7heZUzij`N^Cn$p`bMlM|?f$E0%}VkP1H4AQ&e?D&Kp zKPs)Qxq_Mry;W+HzPOaX0e8%|l!-B}n!~HD|4b%us>%}wDDlYnye1}q5>O|ohboJ= zHHN_%lNd2B)VRq3LcY>LEtvjcgg{l1q5KV`NU@7jaL?R6SBy)En}b}iMYu|!&jq3*4|rPrZB8zTKYU;{=; z@E+6P9&CRk-xe_DL;>G6pz~vp&NCRA=|oYlyc5E;&`@)CjZ^tHW)>)_&cD*Z&gPDa2nxuQa9sMU1jX{M&=1#1g0b# zELne3?vcAkZMnf*#S0vOjeIIG0*^BKfGL6dO#Mc?8q=Q%_Y`<)t~_yvIlc-#ciV?P zDMi^hlx8y3B<A4w_7=>$p zwlqEId?#${!Ot#zMWJzV8e!~F8nTQLMiQZ^;tUHt)mK*H@aL*+_vh7x7ow%nbK zZKgim;`49xKQQjB#{^T%wKwh3ho)}wHzy0 zS$2DqUHt~<=Ty^=V@YbbAuY)oH1d+Euu(pHOi!Z$UdUnDyVM_7&zPih^O)!%ts8W- zhqc3x>L)qZbaB^EPP($hWNesU#DR+f6mF2N&zv>-UEH)OjP ze5Je8Vrlxai|u^3Wihj*PnHjS`7Cnaf$69615{s@S5i>H7K?;}#re_hm5J_?vfZUU zCs!UzmKS6dV9NJ@)9`_U-h-J%%a5u3gCuyGm_1JRmKXb#woX_UKMs7HUcP`cZo?3= z8cYISj>+B0sfq}fz-UIHEsKt93TI(J>2&#(EjngoMa7Eqmx+JeJ#}+s;7v@w`IXkN zk+O?eo z<`1`7O44_x?$|Wsn3-oZvy!-UJA1zF#br)Z_Jt`~jCBv8sBqDEanUcM*AgGK?6sqD zbbduY(AYe%9jxQbDE#Co-+?5%33lmOr22lByAnf3 zF>|K+{z0Y<)5mXCD+dtj_R0L#v-IL3EMQ)#uLWaCzfpNd#B0m9=w%9UPqeh`g^)(o zhM+Q+vZ-F&aP(YnUP09R{wnLNsPK@d!ET1 zU>P2H06A$<(C$EAcr7e$vi?)uc^3CjiqgWPje5JO^@3%b@;Fh|2Yg;Rd=60FeQ;E~ zuC!>^0}Iv>+$XM6@D#8xPdBsLJ8??1_4H<4;4g4}*{Qq!Q zV_3=w;}~<3XN_C&+V8R^&6YSULfcTb6WnS2V_GOZ|KFZ^s4);@xyeKmD{0Y(}pB~joU(9JlNBQldTfp*viZW*I(RMhcyCXCJIcy?zj=m{Dc?(_{>^GUE2N?il7f?5o z1QHFE0?}vBIgo2DkM|4}0*Df8IK;mX?53rdva0eXPsl`j>DTJPq-H|7kS05L?@CAP z8A=83rMTDg=z(qT-TZv8Pi~Y1DS2WkUW-&ulB{8H zlu=-`_wi;k*rEKe%Kbf&oBoDW$7qHerhTV%(;H8UQGKB=WKRfB+4hz(pumK~=;GO_ z@sf@$ACBl&Q3PZYII1GU=N9)#$ft7C&MgYlq_fauHv}ogueA5+f<$iWcmY82QfLQY z)HqLG^AyUH88TU{PV|qrpGPcH4pyOHTs`&WePW{gw9io!CXa79-;YONsA`y!CIW3M zURco#9uU+Sh-*_Bn|mKRJEyCP;b+`{%fiQl>Ptu~*vb`DNilN~cN|9yl8RdfTk1{D zS`6jdKTx954pRZOi1x95Rd~bOPI8rI}puzGz~LtboNRY3@HT8Pm+2RW5O- zsXTpo&*a=y^#kbw^dOPb6k~KH26$pr{QEmXYj=gc9p{{i@~V8!k>Go@Pj*m=SBm#` zD{OnCAKqr*H=x4YtH3$#C3l`8IcPuiu}qm>ueOu@Uup#!_OlAxYCb3$xG`DWOK@>f zc_5EjinqTdO3fMt@9)E=-8#Ku&AV^n!sVUL3LmLP=#OwCdPloLHC)25lg~okCIa`B zd{(cxy{HtvpVjT1EltW8ENgc25_?~XrHa(-=}@I=#W7D@MT?J;Ke9Vi%P1;Vf~W6B zF{jIldBtS0BFpRr-@*KyjS~yT6+W1Yh4_4Rin3OB8s?0>u(B|_#WES`z5vVnXKFV) zvu1z!5E^5Vb*5iOJ7R9ym{ZImqp5XvS)eazic@B(C)7%TL#EuTqEU`UcIjk=O?lRt zc3GKRcPCN0mBwu}0_DetG232Y0>t~yIC5OONjKRz9BnudwRE^o`n*AX`9}d7Kc_v} zT^uy$o%X>Ty(TmNtYfHF-zFxtii=UyhD&c3RTU%Ccs+ z#tcknB>;tw61I6jL}xP{5ZG`YE)}F0Yeng7oCtDS!em}n03U+|_I<2K>LV)WzKRPl zo0_YI)2-$?ZE13k4TpBd?WHd$d}7(3S16R=9Q({2#xWCqZ@*Fb#jSY7r27H-!2 zFJqyJ2k5iwHgijt_SM&vkC(btSSEzeJ%Pq=1{JBmHBo>;>`R$Dv`n z(jFx1q`!@k5k!7|61uWjQ}RUSK;rLTO3Rtu-Wt)^jfrMOw)I>znbM$XC^PVFwi7q>@%i@*LD_LQ4l`tCfO#0&uvD8D-^V}Z0Abn~8eVR=<=aTe!ixNHU zYj!;0*(83@AX)q7F*qVo&`N%0)**G%@J0Zf>28Ax?gs%^jAj^fzwEs6l1qen6-Ty9 zxT6Vy`;cxH;`oMzAd3qo{wtxJ1(9>DDcq$?W4<)A()-;iT4@qx4kJ4%X*ka-OUY)q zj~(w+^3SPD!{?(kcpCNFmzZhFeUJ3zX>glgzS|T>QF^C0ULxACclhX5PMLj^%QhU# zb9FVxTPR9Vu{SN!&&|ZJoG?9Vu`{80el{pQfamBFi-}sA#P;9%e&5K`nab;Rs^Vgp z%2NNUnd;=yuI7YKL5tcIH5$1=8T%_Nr{_Zt$g;TA=x|0ZyV+3V%r02)p%B0(Sd?J^!Z6oJTr_K?CnFJ^he1iw3zR#Pmka|g2-aM@;g2^ zul8*=in$3Mz1Q9=#2n?&wO>H&jFsn(iy$*I^@rTvIcbO{P%2RmrP`sDJUeKYGJTA1 zq!McxuyEK9k=KYy|!VNf}~ z#ING@ihes!V9{w#?~~<^7;)S!e1y(d26d?hzv@@WOit_fsEr?k~ z_aTCB1Mca`CYF$Ew6O;~`fg*n6D}6)7n<=xIyrp=ddMc~VbhRhp-A5=O9P`DDfErQ zPj9yc!H~tfm3TdLD^g_lU#1+)UGeSs^6_36_wE;(JdgC}mRmcc38nB85=eY#=v6j0 z-0=#w<$afpgA-WAAJ-kF(a^eorg8Xve9PvLzz>C?hSy>XelOXdwDQ>_x~zb&t>?hx zg=UVj5`~Hj#r4}8XM29@d$zHYEpEmn@$>c2s0VbDi?jpOLw-(7lXnz4*or^caasiM z^tG_n%eJ9)<_>h`UXN5YeojLtXF->TyJAO_bTqDt7m>B%_-Y^UBYRN* zkJ9T3Cy9m9kl#UFf%>##B!ZE0pU2ZbrA@6~_0bx6ct}} z7<%tN5Ls!+4b{0x3!DDEW~211c=}$Jl~1EI=;&!bhOolP*cy{EZ$q2ud5J|u|IFv= z6FbZIPcD`ZGA3b`@hR>!PeC>=X9(MEi#TXZyO5HTn+bPhO6PNF!vzt$= zvnf8;yaLwQu)Wd8RJQNS^G-JN?kWGAS(PsQN9xT(JZu)eFNS_MN=k9YG|j+M_WDcroC!6HD_zcpxq{W5DqnE3~mniYMdu1{{Yx8t;UdwG*sE*9a?S&yG zoOa{0ENI-GiAFz^IyRvEXHbQ6SGy3hPC%KZT%*D*G1kXc8pV**Hr4Xc1j_ZvAlHiycHbxE zdMiqSvN@z?yg1A;t6xEJ`{IpY>J1(_Pzi+%ti6P>a+bIK9)(3lrG(tEw z;zjD|4CtR-?V#9GGBRF{$ZzZ~+7SCH7oqnGfcof;W+bB|J@sE@Y zi_9{fzK?K@ghjau_Xva96gpz~qZ|np%Nl6Vs4AOw?u>IRhI=3Ib)q#cHWx5;Ptv06UsMNv~rTdLiW%>26w5 zZI@n;(_KO3F|}NJY^a`O6mokb9%I2a8R5ujk!ax?Ym2*Y%YAfDVxf*=2R9dWn~uLv z&lbI;()w(gTFr2A@AEa!h4n8d-c#}PvK~o zGxuIz?lP4i4AQ7r?9G1ZK(n}HT(Lb%*?%@UbfZ{A;c`Mv;OJ3&uYX-=99y{f=aQP! z+WJGK6V)8byQAh_k4HP(?CRp}D_%4*OWoAK{D5V$z>YhMuUxeP!xpL9S$a3a>XRfF zsB}?hA#`@@bmPy2<~jsqMeyuCskQqU;VB8K}O{V_+Go}r<>VM7+mRq&P_sC!O5)OmO&9>Oa)&@hU9Np zn49e9B%C~mNWxHOMh*5YV?}4RAMC$_9E^?kE9L$Tc-HF;3yG`|bMIb9v&sZn*m!y8 zIr*tq>-8iHniFzG*&$Ai|*@O!ct`Y#Kh4diU|!+I!~>jLHS><6Bw}Yst5ax|oFYILgz5 zW3nVc5ZA2U>?eK2mH~avSLX{K8DK1gCs#&HCU!|amJ5#pCth8nh6h8;K-kMuuM3K& zC>`{kPB@ClGJZ7)qT>*>UG8mnB#D@N280o=`-=T><@(~i;ZCoI9=MLo+- zFthsrjawwf+#wyXg&YIJc>OLBk9bNsTai1bv~fnhSMu6L8>HgXJFi(nwrqHuo+JxJ zhUdJ)oB&601HOeZ`Mj=C7qV|qWaA*(w=b1##n@b+6sthBWRdsCX_#1kq>@Jl_)yLP z9EG>t{t#Qn0JiqiJM0sI=y{-W;#lDR8xfnaH*N&#+uay1pLB|h!Uj4<-ZAajT=fVh zbMAv#R?XKE%(C$AdY$p7uYso&Vd!wTj>k1nibkgze?oGu zhiRW*#UDiTItlf_{Iebem6}pkxd7zD?+_O1PZwkQjVI+JMUB!HJbCGBt3!#77zy!s z6oWu{X7;>klL}Z{(Dg=Oub}pY*Z>qnc}Y}`T_pq*`268uGmbKf%u_CrRj!`N#%6k@ zg(K{s4wQb{L36TJm|K694PX1Sdlar(dtS)BW1LJZJe>SdSAUUvCh{KYI#U7^j~k7^ zn&AHBn(%&BETLztydu%IKU+RLT&I1zw2v`;KBGAKIJEMQJ5NHbPWNB!?!9oj;6+N4 zj=!DiiN*5;Q>hOUTmQHoIEojadv|(qc#CHo@P-Ud!Bh3|5*}uDh05wA1EAvranbCA zAJrF{LXm_>mA(jnZb$uETiDUos7c}iQtdx{X)tY>ZJEC>zB4Awj}4pacECuO=ut0@ zgO5EqlhepnIS)J|a~mZ=|6RkR`jSXOL+KQ-XI1ke-u((5S>|V{wumURXHgL5(KP7+ zR;nj_p4Vl+R%RAW&LPv%B!IhmY%)ARc2|oe=U^GzSFx%=#sEqNhWH@8X9QmZK17#f zv03=Vn@IOh)8K$Tq-x6tdQg|Ezhn|v+E96+SE>|tz>tU7iG45#svGX7k?Cv$kS*<` zTF82mg;MWg6%e(i=&V9!dxxVT{E1+<43VPrG%xrddDsDR)sQ|AS;-Ycfb;G`0Xn5S zNrU6F|Eti6>i(Vk>fSQ3_*Lt{4sC+p4UFE)ekl=w*$DLjXLNv)Lr5RcNoAZPiCC3; z^$AZ_$zD`-WL=fh_LyroaHsh$Jc*ukS`xKzd|@xM2Zf3=$vxah!6%i zG~~_lgZ|p8(6>C-9H3$XB59CPdTS$(c>yo;tjuSV24?R=q{Utnae?ZEfHl=h6<4*Y zgW|>f{G_7hg#u==F?y8s7^{ZZgFt#(_D10l+(vw^SM7);)84ioR}ZJ$*UHk4Z%7P} zBsH-7T0%6BNi4D&?$0CXSyizx)T8&NAr`HsVwpxXs*6b}ghpmlqp;)I`kF4*v?D-1 zZK&7ohJ6gRSw4vPxjNwyrY4{#*1-?s6p8+)4wd0sJooPi0ZVsaB@(`$JKHGy z!ZdS<>v3Sbe;Cn_?^5L4UN|dfUhsy0OcjEC_O>9O2scEQ5&0t_dqEu25WH{> zkraX0)}SBSGxSIelzywuD8ugrf?oFA7lnG6@4HkuW0&ue8q#tQlBQ7y2t%;G?Rf<< ztSxxxtMQlmEi-2LS}p}#`E-kKCc)WK=8 zK%K#UA_Z-ay*B8?qdv@nW+;Me5SLkbJBGfbng|(%UM6(}4hF7Kbhq;HAA}}z1bk&* z`asz61W7|`RN%z!j&j6Byw6#RkYxc^N6iTH{z~~xk4!Z$PNVz}I-}1}gv?Vv-VT|- zjtIw~nII^P93=VpJ#aD-<8W-}IpUl|5<%bd1By{wK5)5eNihapK=#o21%*eBqb5rp zX95D&$etm7L@%N1efHAh#i|P_@rEiHyGSfqf&#Ej*#R{H(#Ecw9y^}bhQtrmuvQr* z&32;SxKZBR_9|S$O-^cGLnU7R4A|FAzBCb1u1u2eXa@SA4*?sd=nV5~7yQ`#Sr~~% zdgLCE=xVcrE@`&DkUa=9;^dQPC>yHqh2o$fviB()2$Sk3*cuq$nBBXcfqZRpxQd}8xoS&p8p3$P z0_$L8=*L!qW<0j0JwqMUMKl3Q;Jys8)(Rx$1pp*Fp%LIrdqn%)K2N zkh>Ah6H|xO<7Ium&Dj`5Wu}&dg2IZ?jQ|u;-QPfo{e46yMZo*BjFChW__8gYIjZt1 zwzzS_uE-79fdE)n0G{J^`i^`c&hLn73hBV{+HzR?H8E;|k!%cbHRo!&N>|T&|twlczL#bMcT;JCi<;iVnE;0R6~|kZk?~HaCrZA%Q^WI zxZ!(~;KZ=PCgvnVr%SQ32lC_F^pif_qM3z#7qOp;29ep747J$<16d=ZlToqFo4Zel zoU=W+u!!_z%gub5u&v}v4bNm>@%!2b*M2<>LL#0i6$sr^`fF$gVS7$hpt&MQJjMTFoXeNBRGzH`f%i!r1!8bTbWm58+RYO{}H$aAN=Dc5(D}oz5PcD=?tj^DPQ-cFEQoeeEDy0 zo6L!2OnU_fE)1tsUshqgPCWq5dTYB9GIE>Lvk5buD%);Ef7vQ^08=?XX`Q&!=@!$a zvqNkb++e($W=v&8x-8hK2UFtx-AjO;?H4X1L=h`>3LE>DQ&g%iT@HKGy?BOw$O394s*p+z_q2a zPohv&;TH(I#o0TVB?F#4G_37#%#@hbH#mIL-+k=!1)ZxGkt0`+y3Ka`R2v#w?DOgN zGA_<8T_H?FP4O2d+4St8Pl_375@Ujr1bd@DbVAw;zm$@IbLjGDkcN4Uym1N|-3jj! z)E0k##>Bf_{ozA!u489Tm&;es8|Vko7usdJeR>1jmL{vKCxTWMvC}QaIRvU^?&++6 zamVo)2F=ClDaP6UisdAwF)teh>IEu9;+ zT-l#vTXzw}9~pD2z&FQL>H->d&948k(4Ie*UClZPhAr$a=PJ(f|HyOG;t6_X9;~B) zOVP(`*r8kJ`(6n*goAh^cFolG`rL?d`To?hH&GM*gOcs1A2hM}&(~T;>I8ndGCq=S z)6=vSy~FsVm!a75O`jf#xI1rpbLkrZ;uo4?TY9&765p&-4G~e!vjt-FmFoO@7klQw zeA!ZNdYiSnR7*E@MsfxmJ9tuIWudJc*>qQ}efkfhz8E*dfn4n2`l0?k(sk7}*{%$C z1?cmfC13mdG%t7FiLt;Po$2)H#m?P2-?5WJnvL`9{RzL7#T=bc-p6l|F#A)E0cNLG z2s2^B%_(;L!!iZ$0p|axm;#p%3aAz6#|zg-6A%s2^*G~eT#~!g#PnCQL@W( z{)6!W^%B{`wsBtOF&m+ZNr)xkON`r`)%mzThCB54h zwZoO>m{QT%#5T(yLgDAWF!Meka7I%h!c3|IfKDD!4+ViBmh(`G(D-m=dC|@agm%IN z?~?;Cq$0zil+7vk9?n3Avor5r(S6CxYc+!qhRxtT`dBpEXS%ZFV+^L&m$C0cHuo*| zt_05DwzcWszfq&7!55u(nev)}%C^+zjS?!6Ec+zKbM;RIOt(y4(DCOGYq!4Q6pa^c zJ3)K&zRr99ZKe9DAc6pkyMFe=(OlVg!5bgJH|eRyKkI9=@Z(zsYhyQ_;{FO&Z5@Ka zDZJB9TrgnZ?R9;=vpsH;xl57FQXgaai%5-?Yxyo}yLV+AyPMq&Lb+*U+4EhJ)`MA( zN7AzUF7kNeZXJ4#A9!kH?i?LpfKNKT>ms^2+2*O&wx;HZmjXq1*<~{vRyuo^8HVeE zt*@zPOkIoABFw*z3cOmn^>R2Z5^FTo5pY5LnUw()_jP6L& z-p!;{-b2gjDEahw>0Z^9&0~encTG{>Pn4W{C;p*P!OzfVpY|t#_Zp8kmw)b}olKAO zo7wui=Wdyqp*#IA4|iflJ*%$URWX>mn4U`&*+hAdR<*Y`dC_NDt4!p{>D>~)E#5Pr zTBwzl%9>a2wM>CmG}quA+8rlK`-f1GFVin1X8`VPuKpbq35Bsx4qLfx7btNRi=|ue z&Wo`Sj?B+_Cvo;Aqou!Fy#JS%lRz1sE(Hw|gYn`YE-5@>#{+&({jxN5>QVbog`08U zXq5HFY)tvmz3z+s05ZsIchKJxZzPfO=-D-4lJ>6y1qUbwv9s_80{1s{()e9G;R zJllm%kIDW0ShN|~gK!+9egg0I)X%^D*i7$X!n3|NSu692D;HGQ0z}N6Z$2BwD?d&0 znJv~li1V8E?u7Z|pVc^qDV=V0WEA)D+IjcXv9q-=$KRi4ODKLMlcA{d-gnzA{YGie zp~eRn@rUHi_!2s_cwXzL+V#wUrGaol4qT#%dBf4)bhz3NO?VziVPmg~JP=1%oNAC| zOV299mCW^pZQs$D-f!amk}D^AuqA-=N~e1*U(C%!nF!s68L7HCuV%wUJ?!#xEVo7I zOrq*gI*gZ*^AWo=VLwwI=E56e!g$trplud7Gnbr*?O+TfRzG7;B&J24k)H&1UA8Wk{x z5)DXuS7etMaUj1}rs;4*+Q-8&maLA^{^tCkidts0%2)zBoP3JXe%I#Zx5LI}$8Q>O zr<}J*9yih(=0ya3e!7`+d|#|gTB6Z~0=}cFTDSDft|vU3HfXxW8zuEcHNWXthN7je z8aT36dpdy$oQiX5!Q!TFw^9(oh3i8(BgJobk4)EhXqex-o1xy6w%8CjlQX`nXnr6r z=d-jk=an79g-sGab~@yPI1NAN{P|dB;G*ETU}ShNCUU`Yv4L7|-?_1p%|& zaQ?z~zdN-oxfG9!&En}OlcNWQ^*638malYXcHpZNrgw&B8YKY+VeXfutNPk#pFp#` zm2^u2x4CKJ3_YLYb=Dk!O2q&lE6z3)`ZS3>z-foejlk$zoV`->9}4GghYjqq$*F@! zVFDIAJ$lDRMq$b051Xc#nwX7S&Of2=PFa3*R>O|}sQ*4$D|v<|cXdv+m<0yZ@=X?< z-gU!ouJ6j>>SrGvPKHX_I1{l_N;? zZjtMVc1k>5Npgl!({eAm_*(8CCC(CK51(^TzfSc8Wb5%`-n{{{)b)BDjN;VCQttvx z==#a&W1!i-<>{;-X&2x^W3g`v^0_j0sHNX^+}YS1_-UB=U9R!?X4$!?PC7GM@NSW& z<#R2D1F6for5a|h13H}xY&zR>`G))F(U>oEeJKd>=n`=D$W{g6FH`O)r%xhezHUztS^Wq?XRm zJW}bPme^D{_N8_aZ&iZ6cWN63wBf7n{*m}(uLkdBYX1L^vGB)PF8sHvnp01u{lj(bOa zUjgMR3(TyL5l{%38IBo!D2wHhtw2O27=lf}CDkv71o1?m%vPop#d0KUZ zLjMf!8pXU^7_2tsxzzO?Gx+pD%$O?9OiVUlcgi*GWu*VRv1iR=)>0Q_5{&|IqxPeP z+>+jrmc9PAFSq;3gtc~mi9OAZeP}r8EM>~!xj#iaZ07;6jrxmUr*|46{6U0Oow7TE zXke+S#44KJuLC#)_pj{JUZNcfx6O%>>af3gW6kKw#lb2&DZKaT_$up;*STrlT&BsA z6}pv}R>Wz3xD9$ULXzdZEDGLxf~mv*la0@HHy?4g|A!O72lpy_I@J7`6q@&f^IYJ$qh z_Z$Z-wmX1j)V}N;NnJRuEBW=Vtu+0P%549o&PQC$UzVR_0=)i_sNFv5|Bep}clAuNnybvV^ui^*BmJ@$2-qQl%A{oJN~ z6Pq_t{b>!@t>S5P&1$$Wx?U>PdoDpbU!b-K)0&RiPmged+wLQpWrxt!>JCyu_`<4E zrQ5c+X4ZoRm6g4O%IDIn`&=XE(`EXotqM|eR| za(e^QC)&`qCd*hXC2XtR?AKHXv*^xCsa1G>4pq#oZG!A}!$CdH$~W2b=BoFqZ<+Q= z7S7O}cJ<|nnH{#_3u6bUdR(bhu2#Z1Ti=2rHJ`JlA`q<|^kP%!X8EV8A`I8Fky7^9 z3-xYWjR?%Wo(s3KwH5K}5dm*;z~o~SM{ILbN(UEAVija}s_%Ap-L=F6B!J((%o`YW4HXy(Hh6>@fxFSx%b0Pe|9Q_<&A*8P7G7Lu3-*6?G<(~IM&D7n**78ABAL^O&+S0v_6D#HV z9wVl+Bhcb^DWzk+(`DV2iXCE0pZ|d7A@@yGIItS9u zla0I6{yUv@Rok;4Dm2q$DJw^NutULUmMZP{+6F6-}5>mn5$! z=*fB|9MH~J^`k_E)dY_7(0_!29kzLU>h*Oyq7Hf{CSbTRg+8WkeN*>AKiaoi-H%7U zcGl198+%*U26T!r3F`ZsaeNgd44YAS8cJ!9;dm z&;jNMtkAeJ#K&jSa^xykp@w#l`wbINR8wL0nOEk^CWw9Cl{@*2#7i^e1|Bd?>?&94 zNUrFo%IYLMq(hf=%SLTKUj6(ac(FWSg}-Jwx^P2vYArk7G|^!yx{^oL=|YwcQXbq^ zEq_WEhkEziB4*q3V2U*un*Q4*O!gYMdFiR#Jcr%P{F zA<1QMcQzWy%e>Xn*nUHc>q_}<^eLG4H$CjH6a@{E{_YbD0+x67q@qNd#BTY5sI&yuVo+8=c zFD!K_S$x=j>Q{ad{6;u#BYyOL0HKA${DAz-hX^?nZj?`6oM4E6x0&xEN6+;jcR9?* z>a=klmxE2$ZVB!#*`8*6&Wz7}{`#o`DX%64#hpYpHYIkq=*Y;b z?H~p&_Sr5A^uU34*vngB7<^5W#kiRDcIPCMpk-T}$ZAP@EU&e!aK~b>f)Q6-lU4+? z9DkCSgCOgv1uBXF>w9nJ!lhP)@Ay1)=xGd^^HZtG*Jky$|NTWccVR9?vcfJwQ+njr zJ63@`hoF1*6bm1{^bF3EQL_b-kda)G0 zx5ZAlJ1|CTCknT|IN1AT;B*<0tIc|T44RI%VW3>t`!GJR`jg&FxaN#Iq6)Sad4E$m z5Z&e84~;YkEaE(kAwP|8RP@9mKHYEfYlp~@+++3E2$pp4k-;!Z)SrwTmc;yat_ihy zC~)6*rkn>=s-Q*L!<(>`_aO4}`A<+hrt};K_FCUwE4#}~Y-dtZALj@Qi{yj7?WOsc zSd^x`Q$31H;@O`UuC;Fov<+2UnNvTQ>wF}fz9!e3;SKJAyu#bRwE+1Z4o)=l{V-v_ z-ZV`H5t#6Yuv5a?=Lj)MKx2o%h5DonnpK2{uK!s;ru7P z%vY|?W|SEy^`M2hB=606^`C07_CY<9#^i2@p|7gv8Kk|w2-}Vf#NEaZ<_)=mQt0Oe zYWk8oa%Y)iTYa5U@(BmYMl~MpFt(zAs%6}2rxiQG!@ECcPNqcE3^w@(s!ir*7AC}U zMEoaQXFEuJKA7ByOCl%bOUkT(nR(A%w8o}facj=IYQ?=LC~;xn(%$W8j=P8n5o3Xy z-p_qBA9AfS*4JV-+FhEkg1Qg8wlJ6R2ClC0{24pa&gCV=^)~?gRhMgG<((Q=)3+w= zUww(sJwxpM&_vm1A!vJ+{lWuJR(`@B6f2JOmveK_&DHJ}R6JM@VVyzC`X`t5(fTxW zPrfRmSsXlH2OBZHETZNJ$67Hxl#i!od#u;EC9+@fY3 zVo>w)s&>Lv%_I@mDqi*G?ldv&SGl9A%xA=IZ(AVu9LBo%<(iyOBYLUoRnQ3$2*N2D zCDtupLYE%$N6%98P#mZ!K;OI%iOD}X(dMLlVr4MA4|XO-yKf+9fN=-zYu3JM<4vFF zNm1FZTE^sGe9bGjiDV)B(~QVRAMf*@n$_~o-o*Y{T2m5Oa_yGo70S`}G<_oFSr4@t zuXJA$o~joVcD`CKYvxD}_OwpsKYr|X|tMd6jsC(XzvXG3_{ z9;-GYil()Khz-Z%gCfmXKZBWllgXE|YxNx45qyL-br9?C$405)tTutF*60j?+9hdI3MRv6_-QbyUcs$>c4+frY`e4skn*0F31|^ zv2sm9Vz>w8sEQP^)nDq%(@iYpgO3_FoM1gA)m0|MwEf%M)*};K@N}3uS8rk6K21&WCQ!hv2>`_$g+`UaVownd>y&8>c2T*N_c7=}_42IH zOcd1fq1ZsV!&TVwBSi6;@ElI4uwr)ss#9^b8s|9Qgd*Q@_NL*6>`ceReWZgB_eu>$ zn`4~6woO(10xhX6Ois1z0sHGAd9-?<>Qa?rOP#| z*SLPA(q84#`oOl=-YYDfhS^(UQKOuhTU^Hlx<^y^mQlgeLo6O^WnQo3uN!! zRZ}}xS5iH*Yhw!Kf9;5`LibNa#q8WiRxI8I_cjSSjN1Gp#YQS5iKng|H1! zRJNQn;8C$idNB`GEl|ukInYhHGB3X^PpV^vjGqb{zg7OM>D8R_uMu>>Bq@W}gny;< zN`Jg#Zz*5DRR?ug$~@{$1y>PNBHk(PCS6^%jk2bbJ+f5k^t?i*nP2aixWw3ZdZX0$ zZf^oUY7LWo6V>Z7x8N?kO64%1~x-!Zb~afs{I4K z**`UFoR^DuTooadepp7dWL(NtOMkpmFLDUJB$;fqM=M{p5nwlS7vzB}r{JK}Zx)}Y z+k_U8&hki?;|%cHst!P_2cpY6x}6(}3!1mA0>+n?jJ3y?1e|egUMZ=?W1B)kuvD)y zIjFyZ)Q!kAR*9t1pG#HzPgg{KCE>lx1n~NcorKz9{jMU^PXy<5wYRK!cXzp@7___a zZFs3{)pEoDN3=F~n{SC`=e=t4jO^~bSr%=699^MjN?CnhD)_Nnm$Ti`DOKl_8-E%$ zzTBO(x>zeAFi~4+xwU$IY0%5H5RHkwn#To^yJme&smtmsiRWG!LG4cp2f4fBLo?J> z#RKm70HwP+?_gRVK0U*8dWI;^y?$d_d*`#cW75)gR9Wu%PA|@ot;h_2>HL%=q!6xS zJix*zKO}kSh7dgM0vsi8a1LSpT&y@(47ahr#W8J=Y*?bYjq&+bjX8BXHRjXEMWKC_ zXU;!rTrk1eb0vQIh*&`lRL;{W_z%Zwq`b_?+%9X}&REyhOdX+iG#>A| z={K92masm%V-+y8SL*Q|k6^PtxKdF3=es!0ZVa^_JRWJ_)M2mEzrk*({G)fyf4^iP zPq#VzV@DmY@v2#gcl#xyUneWIOxmB(FiJnd=qq=MK(qt;?|Yq*5w|B*` z)w*af5X}Nx7Nr(<=noH>svjR}uja~9qh?FRiJy;A+6{d@8%~fZioddY4{<5Fc9iz+ z>=^+G+_((hRAR9FGoSgz#40s4nxv&=-=#(CS^GP_jt}hG$?O-)eVVwhA=WASaUZ`S zS{j0jTb;9_Ipm_h4$CDqV;E5tF6DNbDry${)xL~ZE)Oe(V{9Dz?NOIVDGI2+*1sBM zNQY`V6c(=7sK@ce^ku6XC1i{?1HlQ}pvh1OIn$caEgR#$G}O9o-kjwXdTwr1Gey$f z#n(SIwI|1!#!z06)XT3+(=dxb7S$Jn4+dK1$x2%Xb#wF9|Z zi?(vxF2~pYP=yfBfs2)1(?M>trrj^RX@qrnq2w zlPXYS6?*Sr_fx7Y=Fsqkw$98{-Nhw8F>oxf`=?EiiyZuU}+E7*j2B+I>#@~0R9YerUUm(Jy@dA z*{^sHk0FDKU_=MMZN8rUx7dHxGT*Q&)R` zon6XfIa0=VTbwoQ&6{X}27;kl> z(sODTjFed$bkecvd63&5rzxOjXTfhYR)8+Av~-Tw;)qCoua;sOJBAClkQxYm=x(uU zUpa!rN&&as_kbxz>#@a^l0kJqV3+@cRbb3_@L^3-E+|o@;>}1z^lK}Fui);Xj_7HVyDl+r9f9RD@8RB9m+OO3?A=*`YFf$SvAer#VzH#{B>2YUnkr6hA#W#i-dz`B~#gA;k7rs z36d5B!obBr%boY-vt+drQeb@jiti2&CjBBfnE5`XgG!?t zCc|L{+itIbQwZxaX9o|9?Jw7Ux*@zGj};dfo`e%8^&iA;5TZ zBEl$Z%p@iypuu5QDEgdrH(Cjhp-80e>ZCT2AebtrQ7(iTFm0Rq&F^B)FiRQ>{|+<% z)dIXmD53ry@H3wd-tgs8JV{?=e6k1m=g;FK!8+?~#J2wSZh7Vlb(W}pRydN9n@ACA ziU<-?xD4WkRi{>7kAFtlW=a}O?2pB4e#V=QXcr#r%*(Wj1j?2151gcMu?r~jphnOW zSheb7++SI^zlAWf3jC~>-{z~EbGJ2`GliV6J00P&V?wXyiUi63jlSO{m71@a7lv$4 z_7oaDyLRl=c!7#zbSUEyPw*0{n%(Yxqjvz}S)PeZY$MFWO@$x*ESl!@K~@KHeRQN8 z-ui~$*0`%k-Q$p%ZBDTdif|oS@#T5CvoGhih&XmL2wtJD{e{M@W3SxuYFm9iWq=g0<^^yJs4l1 z%HG%#2u;@16uN8Y#uD1&8~(NYg?d|S5tepDjKL#))J}b#dRHB=qAB*r4@GZGl*&xI zKz)l_dOd!xwMijlM2gNXy=E5pT$kvnIEWNx3k)0uip4SJ85z-tbr6+|X&sqaQM_Pq zuBAjvLg`D()tMThf+%$7a0xjwDG~D$@)+ng+?*s)%>AST>Vab?;PU6kNuGxVAB=lz ztKC+HI)_U6it^2=;9F45Ku6>oj=%o*d9WAl0rA6q84~v;VA3&SqO)8faBVxcke|wah_;f ztobXxX$qsYDT$$rFV)fCC?QPCH&qfbuhN1suuts3FFi3bo4yBzalD2 z#!%vR?XsccU-Vs4#Q9p4PPYI}ajn`dS;}N);rF?2fynQ=4c$Z8f9*{;^r5DQHq+#l zD#QM$a|{7}``E@7ewQqj%`2UuF?0|%YvN`R#byFX$LgOF!ysCUDz$8%v)@Qac5u(F z;0va5&aLy=ey_)?pUAM-si6|V5Hn?;#wejP*OBVL0_`i$(@2sY=}@b}1B&9h1xpV%b9^UA!6y`F$FgrwEgJ&9)s_KdR0Fs~fFzt$~m5 z(9>{K(2K;=uzsHDT#ZXj!c=Hwe9JguwavMbQw4VISy_N+M2elEo`-hB8Yu^et$@GWaQH=+FE7_(yTD+sq+OuFcwElxO!I!iIsR`htpXh}%nRQ< zJ3rheE);SZh(gFWC96>IMQ|?^al8OHd7!vKg}c2!CiZeuGEEzNif3WP4Jp?E8a*HY^u$atEqKJAccH}>V@ z6*<@#W&#&3H3QI|!(e3YlH{8rzFu=w4>d>!s5S%TmA6R;qH9%H)H|LA2g|?S(PV5_l zfpo*Hg(}y$Q=)JgpOYwOx{~y{IDNKbTbEVJwpUx9J?Pp~_x0%7JM{wbY{_GOXffrY zZ!Z06gLR9~OLX@LUZ}L51;kzW`cl~@Ji%{sWNyW}Pz-^ps~*NXv2W_-zG*Q~l{rwK zNnoU}j}Dmr%AM^Ka>?bP;v03-B>~Y(;R6gZ0p8XU&lbiy+a;wXA%XQc zyLC8AjeN(h^EKft{4`FBkyDR8?(DaCDKT9N5YVME{T(W2@y%B!XS+IW2Q|8^k{WAv z${T~pzY?Ak?ThW zWTIuI3hHA@D#@TK25FgMxXr9$QjsEOt?ff}@eD)5kb&9#IhAk*5w-Dv1Ao`RS5>?Z z3!`6CYg?t@?a@r)_v#I5e@hJgacbxkzSUJwKk{uMWZr& zwiej)9~KHmENRMbS$zyw4rCeYrnHLqkIjmF|Nh$j`}eIxy*KA#fBg7ClEBbU^qtRs zQAmIIjq*pes<#fDy~{D#j##_c z9^cMf=PT75Fk69`fiD%6&A!PJm_FB4)6%rxt`w-LD<{EA@Lop%bx0DFetykzw{&tkVix4YM3mvsXH&UpY88tN ztIxZ5EcS|PwEghzwxg8}S~WCnn@F0BL^D|R6-l?20{2P(omM=p^jVK7^?Rl^T+Bc> z`O(PvZWp-OOqhDCj93=5#|sFU`EA82Dl3mXoj8v7%2o@Wn;UVRB}vH%z&nm*g=(bT z=IBo-G$>PcTpdSZcV|4uqb~6ozCc37f!34uP9Pdjpr}6Hbe`*ADBCnfh|(tesO1tkYmOXlWV#7{7rj zC^h6gRq00*j?4H;dg?AM?Viq53F!>^2#5LOhY-(Hl0^OC*oS&n4nL+N+ErL#HZ0-c z;cdi!5CV`?G6X(64Cuh7xm?;Yx=j1I>CrtVP#YwGJ}-$_KId1cJLU zZiwlPoof6&M}|UQ;5@c7dyXfdN)NE}thU1$FSD|eYbGrAm|ibVyi{l4C&Sz$Aij+p z*>Y--=EjhGrPcso-`TZ~fyGVnatHgmMXNn`gkSV}3|q#xb_|!LOu#m_`%K7vSEP*P z-H;{X3-!2U_ip!gT-lc$-IdoF#uyuYVch|z13a$8<@caoeN1Ke-{b2IKf zuQDWG$C36hzh%7p;%Ptgd}eBZ>2|7sSthij$SsUT=*hlUg7CA9m}~ynOa9=+p%>C_ z7w~+bOcZv!*&NOyqW+~USzcOOfq4k?Z#q%juH9 zC7OgQTV2dcJi3(y8b0`~n}}UdWv|-ci+*-a*ro?!)tTT**UDJ|m1-w{3tLx0ja9qe zD!c7T@!S;Rw3s)s+`A2Gbld94srKwOX~zN@{IEaiyVjpReQL4HTYPs()WJR>7$z>h zU(%c`((Ax*El_fhR(7jtoL>z29#w#0QV6D^iB5y<_j$v>6CvZyYYIgzp7aK zQiXZ*nd)kFdTX!Z;1Pe_`+W1IcC%_}1p@a@93k;7rRbVO%ql_~j6a%9-kvvu@x=1# zYnA-xn-_F%dmnkG&mB=cUM$~mJJz6|R&%TVVmR$RjCi5yLGM0R zhbP!KY{4B~qs?mV8CJh5|M@}QpB42BXYq9DR6i^qpF32eMB2Kzlx}LREJJ9KOC4>* z-G?+5BH^v@3TP**)AE3-sUM0nZOZQe>Dh;{M3kK=5b0%w&CuxvjE3h(l~<$|z54cX z%xyjcUDUn!>LZ+R(3!$};J?u-d_mwXBc~YBZ&OJ+A4KG-RTJoa9OY?xwa!Elg@mXI z_OokbnJVw1c~%>o=JKQ(^@~9Qf@HaUd!Qvs(0Y40?9~A66zGLIRlT^F-zjq$KtQt< zwziQ)q#JK8@>GjGiW^@28{|h~~BZb?1ovHGn>D!hA2Y2ZT2Y z%1!f8v+7Q?95O5LdWQWr3!SWo7?k)`4}be0+cT6{S>>_HuW#y|eL-zU1e4sQ9!yWu zw-pa{z$9-oQO`r~4py2-^&-OzR*a27%IK}{N<~;(oy7w&L`hNTd9K%lz8u!lVuP9? z>_=a=f)ok1v*Bbu{jEf&IiAo4ElzOS+=biT$|rSrsOhPqUwpsGshA10RfQ#Ms@~Qu zFwTB+f%jntLW3nD{{4sRzT4GKfhY<{k?Ez z&FYkU4xpC6$I^iQ$O8RO_$_;`hs_;wKLceUz|44pR4^!OuOHk*t4bs zQssGug^2^7Op*Ch?F|P6-h=(ki2Vwve&RVUhQffU?=LgtxGQYmtpPIaMf3ERJT*7Z zmjC%ir`Bs-gZv{1n5XlzUF&!ET_r&GkrEzY!kuF;Ze`|(r9emF6`PC|_JeBUeoKXc zkK|$?Y{`^5IyzYfF>}x=Ak7G4Cz`R^^}VHygtT8f?HS~cdmO9AZ_rAw1zza< zLmreMWYtpEEj^v=aD4*ufL=9_g+yBejNLhmB(9$Zk;KNJr2{dN_(|qdwxCSIxJFu- z`nMK9+=)F49P2_-kLfdnJJn%xYJt~Qe$J46#cK>0c%vIp41mcK6P{_C z>rvV=oK@BDT}c7Twa-1dw{kY+<+ztl!^=O#IjnbKpoBi>N82kmOXYo$+hkZdb^1{EDC}(9$k>zIS_dLZG;Q}fh4Gr?h$UOxUWow);fVFC1G4qyoTu{RoAKIG}U0At>kRDV2wd3zHALiy;oM& zZQ_}omsBM7dZ;4AhXX>p#oMuWr2N;)02r4hK+;46ZeZtj*MezhLg_e?GeMn-0$0Ok z`1>1rZQ4SoYM(Um`StRywf!y;9L^r{uG`zP1YT8;=d%xVWYixE>vj4x0y!(2tC*E*;_8fd>>AWkvX* zgNyfMzD&&etc5f-(aKmX4oN1WAqXZVQx{Y=;e%G=I|kq@eNU5gS0mtNVr)H9mmJ;k zR?pEEx$J?E$EP%sB=tEB{^q%|x|pZU=6G1G|tJ z(YGwAKLU4OYLi;69!kQ2j1A;4!2fv%i5PAV1Ri+kxFlG zuSC!3BHfcc!Am~3jfgP}$fSS58qDQT-yj-m5*i_O>veP7yyWD8ke@`TFh1i_r7g zND;)N#RvdeH6D;HA&TSmo5N$%0tmwgF;7mw=z4GoL_KhG)!wg5F ze5c5pNWb$z{fi&PbKS?YZ!T_tIZiDRa{Fw1PZ;ykilwowwsYwr zgw14tED;|&DMU)s&2jar#Y{_77n@8ziAnHgZW_!`M^{(rAn6cmJv&0S=f0zF3NyfX z8hV|)z-RaXjY4QUo}MP*sx1=Fr=bd>VG?c0(M+;fisLH<4vwmZ#y=sJA^VK&?|C=| z^Y!BsMWAY#zus|jadFKcl96O5d&9g}`uxQqR{oeN;63&y5p2DD$)_my| z&qVxeK}hH=&{J+8)N&-6)M_BuNUycmU_1(68!z@u`T?EUb#gI{`HnXToU(wkYwM9j ztchKgr5$T;?I3^lT7X4DXNq<4rvc>hSnj zhLe6Ra6?z+@7)gn_Z1R zYI=tK9TURI|Ia%2LAnz?f4Xt)Sb4x9d&C_9UE6i6Ymavx)I;aY3z>ks=a2a;73$Ra zxF<+?qLofbhtqb`68zWp8kacaSa-1>2sF>@KaJGA>u@h=hkpdtG5o zW!=Y3ZUrG!h~K)6XQF7vk>hc1J<>M+=e~`^M_FtWf)G@utX}@aZ-kVS1rZL?zRN=7 z{P)W3$7>BhP?Ghq(2(AHO1LEnQP;2X5HvTJ*1?Tcxju%?GxB{`1FNJuBB$GqoLGQ=(n zPS_r^*MF!&5gcg5Y5e@joemKNUUVh8h_yIi-9h%0fD_Q-p(YE%8_)jdwtzd+fIpA-BfZRW zbnU&1E%rOr=5@>Rw1d3e@Z)VC->3&9pJ-E{t!hUfQ(q4%@JN&5YU9TQ!YwpT{C)n> zk+7uzY1KaY_gvr*53oD(($mN#jN9w~UB#pl&=&$v`z{_!Q1baNrMR&tKf$4i{GUS$ zx&aRDlm093BcVH+MaHlq8}aU4tZuHB<<|_z=u6Yj4|rPBiS=F?#QgNi$psNm#}?C>B<5QK-8(+HqYWhi zOvB-M_OUVjuGi?kDxfn-9N3way)?H#pmhfN`{iz(!&QQCCZkh zth=rdvr**^qeI2or1?w0SwLFCK|?yHS-s!J_NWui@t*R($@g!>k@)yVy~YyU7+o^- zL($4yl9R`Y1y+Ad)R{NG1S$`4L&lKwU7`1CZ$7+*s#qp7=?UAwPCJf-KT`;02>y?eb0k7~dMGOL+o zd>)*l=f4>tyY~q}hRMph)*8bdp{S_%^(S}&NU(IL%J2g76)om8u7RMt$!T0r@Ut-N z=eK{8?d%sILZrU7A1)u!_ajH7ULg9>Y!ruzhQCcf)!XORd=i^~!UWpdVtHpL0uDsB zeu6HK8{Qx;=%hL^VhY1rde20u^l6x}2K))-?wBAVprDh80Sg**X8=5{19!94oi~zm z>pAc!kLFZYTN$a)45;(ni345l3TLi}KW_Vejf)H5J9XC%K#RErqR52n0fGc{FrkH5 zWxu{!MpG;>+83MDJbZPA`9_-GMrg9E|47Fj@)c-NHCJb%RcE4Q+nNpYY7Dpb8`vnM zc=gMZCXE#@6;P;eG#gAS8yP^rssPu}YDmU)P6G@ZFzVRbQaHi4 zQDv1bHmw_ZF{||ELKFDFh`!tpD53KO8XHnE`}vI_<-2yxo^Y%N+opJEiT zYXJ$uEbwG5<3U+soyyWsVGJ05(vQiXg1^ccX^R(d`qjhaJ5+3D1^}0*&m9U=kia#@ zt~JqWK1P1l<1NcHQvc%z`mwl@5lqgKiBhES6RVQk`0NRao<`XB7bmUGFo`(|LwiJR z`>rtv+e8Z6|Gr1;*)1ag$I~E3JB`24s4C8>9{Wq8z9`_=TL!M*h%aWi!9LM=6ORPY zzI_M0EaG(a)GMYepfO4V4q*LNueL!ii$f(TJUo|`-x$oz07+dwa;h^I@FdE?PykqX zZs}FMe}Ccpkkd%HDhxYIZ~nP+(S6Xo%rFdgH{&CoGv4^B{~jjFxZ0%^j1J8PDGw|B zo}cskO;y%(siBYE^fW#0se7bt;Ke-e8p5Rt zNK8C0X(tFODZgXn1PoEJnW2>|e*Xk5i~Vygn%D|d_#8+IN^9DD4k-S%26$`+^hc?e zWdeL!PV{5xi8^?gfzjY+z0M+3Gi$)uvX*B#c%RLO$ELv^$kr7bIIoF<2j5mkO&xP* z3JD+CSu@WeuTkb%Zy&MhecBF!z=x5~5&p)vrE_=mw=&Ydv z?$f91LOETU^Pi*^-MQhSo<&eA=zZThmc6N0Cotho_ZFzg7M&M*KHemEYnBB1z#7DB zA*3U2`n~|s>cqm0CXgF4wHyC+w}1`X0UEl_T2=e_>>@)Ux2P6S@mX8NTL>`s!p1{S zZhx&QXY5VoTQbbn5<(pbch_vCLvo@=gs&F@6lgf1XsS$7FJ1O_v5C%%Y3 zHgKjo(>kBI;4}C}j?B10_fC7hGaUGb-@xpR*c>CIcMSmrp^fw;7M*NRky9UOO!P6!gh|nxB{?6x!j1;WLS3&eyl3e)UF=G`nYmMX^prtOM zq3t>Z;c|sI-z6@-hS(RATOtaWm8uLau02s{KYUeN4qtxL1U_&j)78~seSN*lqzC9q zpG{o^a%m)YND<+}4PP?$9EJ8v*gY;}uNvRq0<&;zf2GL<)Vra_hWArA+)OL%VukGn zTD+5Ck?B*F;7fty6}HUoG|`18763{F9|LXNUHk(|>Z3NQ7u{Wi`HC~QT5vn7PDR;A z9MbDVW@7@nI`_hFSH#uE<(8aFhhiD|6sAW8o&l{k2e-ldG9G&mhpe%y0(>Aj^xHRw zG6s2clEO6*{ae*ClyDb?n*Dez_$r558v^QgIdhHRF$U+I`0Y4)8gbs&h$wl&7<4dqkXv8ja+x^}y$R zG%Ng6EiAHzHH+ANl}X`oT)iR^iQ|*Hp4m{DjT1DCSq7P}#tkcf*##1S=}$@@@4Z3_ zU+Og4DtQag^rCzYh<3vzW;4&UT-ptHjY4&xW>2ewHyyYyU?~=!Y@KU;`d`gW_6P(d zfdXfAk9-xj2Ncgi^T%U@_QZuVk7=GTi&SjE7ife)Ix-22ee^^dqsHre<7O3%i(RdN zQf+6v1-(~T^W7xr6$+j?+C_q-(}MD?)5`9$b?*9X>L3#wIU$}edKp##e~1^?ZoF9` zh1VcN%1BI{*1SPKUJEe0mSEzMt%fWfqw5;;fLE&LWRJpZY`FV>W%ES_a9gjN>J1%v z)q!ag<)&rR%5REvznn|A_9!Zj|6{nP=wzQKwlIKfWIR(N%6C3PDy3{Rs7Pv1pk`Un zcI<0Ob&%Cw4yU9WcNMW23wkd zP~!8>)eh8?oU3b{E;6a<8yFn&nb1rWzRjuk>mAd)bUny*WXvz{JDTKXf}syjhYPSW$`yCB^W z3EqqR&s6#)CxfYIMW>;4o=AsczOo)~5bMv)1z5D zFQ9`py^5Z|IqnkuMT&Xd9E~UdV<#r*oRC*%m4-g514{7x1L$tuvuWi7Y46g!>B1lv zP;_UBS?Ha673C9rA4yXr)mD)ef;L4&b2Bn7q3!rcGx_bZr24mB#q9+Jqcsql<$%zK z&c~+R7BFW?lLk#ozkfeEzXnpLn^xTA;{&B&m!`rrcdD2CjR&9D;N(W? z!wZ_iHSSAXzz+~b7OW{Ow=boO-(h0yvrL(NE35P1q>}&<7%>%ScgN` zMAx5yZ)b|#9$fk~ajSZv_fiDUgNw;8OzmzZ8rF7#!G5%948&yAgqM z#;bPTXB@)WOq?#~v6okhje99PEO^Aum@JhTM|JWAa$YhG19}p#4v}mTdnv@$Kquoz z9%P1la|L?mzg>x`Qg#E^z1M%zcXo=1C=NNBB*_-d+vc5D8IA=_q(d)y0SR0UEkIWy z>3_NsQSMb$1n&a^K4-l0M6IEU@%-!x^MWJ+s8+k17|*(>&nG4sQ{zG1A>0l1^sR6$ zB4s;)a$zJQ5tL>=DA)Q5Tew%_;m{i`&X@&;dmuMjxzj#uSqy<;vFvp|ThYm5iUTQ2 zpApx~NMvr`?)6Lm$ogr4e;+t}AChVpL%8?u1j**GI*O+n?KwRqmTq(>6e_Szb7j=R zkI#pwh0lV?V+%pgm_JY+og+KP=Kxn{NG$8n-md>8fIp?Thm>Z#2dj8X$n!_DllspUrt20NP;xn z28aU8byHQ^YkK}A?I%UB!0EfIGX7XIt_aRGIsKWtR zLeoGiBI(Dt$Ebs#->$PRZ|dI)&qE3O#tUMzT10rlQ9b0@o+Ho-+(ee^KbfmH$=Ihrdw-13i7q zm~-wZFo&EyZBc$Y1v!7m?@of`zqlR{Q5g{NiCc-mjiZkVXYV!;uOxgu_4aSc`Co+r z2JFJQ?UMh3gN`Rbkp+OvjNGog{kP`}uvrxl|I7Um5r z^^DL+CFIp^Z8Y^2>ox8f!Gxi;Vy5cVO zSGO3fetq*@n$tJzW@n1CowZnJn;KkOzrHuOzLfNOZGQ^ev>CFqQ`=xo zB`q~MOxk^Bx16k2u5B2X`I!1AG9h!66fTwGdh=LX*(04H7C5G>t=vlI4o-%0mb_-W z*rKm`4L+kp>JwS?%J#U9_n5S#AR))H7XSL>p$6DBA(j)H&F-LX1>L&Xl46$S%t3~^ zRkwfhZ%@S`>Gr{xXf&&*@*&7d%@u?p^|63OeR}$>oNSJ9nJm}i&DnG+oSp^Yn8l6~ z3NHXl-tp@FAV^$kU<9Qgc!90(#`?9({PvXPZjrFfAQBn-G_spl{w*B)+~84izRHIp zLo98^Jg(OHC;`T?^wbs=oci~r&*cHbUFSa^bI6Bl`GBp>uuU*$5I6^%BKZ%(NR%W3 zcq_+FnheL`Sx|%lsrq7^*OSam>SJT7|M2C%+5Qe_6kxd!AF6tEKzhJmE#7}32MW1< z%Tbd253G1Vgx1Nfek zg!96KxZ2zItFyi9bX>3jYOS1lVRx}QSk5BId&Rjo)Ts7zqG2F;nWWw+|6kV`^ntB` zy_2sd-r_i1Cgl9u{Xm!`yTQ207u7jfwI(4{F2$S@nKxc(AYuEc=EXq41@7!Oztjl7 zr6thuXZ(n`y}9$N|A7f9_`xA<+8-+=DNgCK@ui|k1{3rVfSB*-vi*%+5A&VKyo zts5&!$Z_r0Fj+Pc?2XtJjg^(EQDI?ShTduwTbcWWF;sKx=_yMk!ohG zb8?m@rChs~-4bV_!oTOf`{-%qyyTe{`WO{M;p=>w0=zu#pD#qYaBe2;Exr#b(Xg2a z0u}hfeaF4HN916Od>5lA8>G>}_5IHyDJA1Naim(Z~)#N+t-*3Ad zI2=SJjsAa)eRWt=YuC4MIDjHxA<{}7T0ua%kw!^rr5nkiLq$b8X6Wu1P->hZ27?$n z2Wh1n$&n%E+XJ5Ok>|Uv?|uCX_jS$Q_rCXv-&*Up)~z3Ba#ghKS)A9FnOo)%dwUMrLYH_hWGWiTjuHlq)7Z^0RbR;>v=9! zLh8dFYabGH2!(ZYP;v9G)Y@0uWJY~8JX<7DiA+v0k-f2Xn!>y$ge#0v&BEPf^r|`Q z!?IE8EG`{LdfaT0PR6l`p}6+ga5t~FfsUxBgx)@r3iz*wyO`<)U@EcqGe-TJ`fw}0 z5;L)+M1I;kEtiy(PnJl-yR7HcqumT{AMb3~S=8`MJ?@@#dGI@R_S^IRgg5VrcqWef z@BTdaI7Q#Leql20<=}5J$*0?oc!J+e1Rc1Acl+z}ac8j>#WT;rCLc3u9qVfIr8Jhl zWo6GAf0oHDmv6dmsa^YVFP@u`G7}ZfY0EPAvqV`mKmbNB7B_wbI|&j%`Eg~6fJ$|_ z;#sX{;`4n@tT?X(>gT#=f$3fHG5gvtE0EtBO56<(6ht#_+*t)ZMCDwM6WCcKl!Z~S zpYy>#IG$@Eg9O&Le#kZgb}hRpK>hTsnyCq=DEg$$=s1Fzx-APCGZxD|8`g>w|9RS2 z{*E8Lc1vD9h8t-)@vVVO3G35@S)^W>afwuw~QA_ZOcE zgfGa@MO={Vt03Ju;}iXM>Sch{&@XsEacXu$Z{PfB6Vfy<18i`B3+DZX1hPQ3;YKG@ z@(*AAq&1%x#LJ7HJ*yp$t@7zb!NxsCT`fXE{00wHI;f>sTFBDlJ|^D?NBN_Z`vxun zDjE5wEe(AN7%xgRcU!}mJ$NqPY)s(iP}<%FR-AhxmrrxN&Baj=bfDwX^|eVJC*|() zFu=l{PenC6mhds>La*WuhnlX7W68(Yi(5r}YuY09XstQO^>B1&^HTJYs$xREdXC`2 z%P_)z&fJ1$pG6HgfIcK&t=``Xbm}agRstTRv1#`#H7_GW>I2mFeu5$cU_wa41c=b` z)UWr`FP=@xHXX<$9tE;iu1PXw+P;PoAYP9~%hW$Q!G z8HBz=J@YLM`ULL&-FvG(;ISgIk2VGEHJ#=P+v(&>^*W@Y{0SBK2XB z8JS$vNus7|3@xtP_d4+kvKbX8joUk7FOF8LsQ*HylqDoW&I{phS-S};qVGn1 zHK88XkCCS0^pn@&*63_Z0rW2BlVgg&h zFGqn-0s}7-ASzpEDF5{C4M4l!2CoYCH@_|9?}n?{xP9Pj1UChA>J4kQTU%=#I<+8H zk0PSNSOZasschHtjkXjtf(Nz9hkC)G;faH`wf2cWG-#vO!zkdt2A46#Wdf=M*CkWiUahF0(5mn4m=J=JVxZE*k*D>| z@U+(m9bzT5nfyv<#U}*uhJNZs-N>UxlL;Em3hSr2I;>pH9nC=dBs~6nu|E_jwKKjo z2opWS3*W6n(}|b-$~r|LR3g<}w=$R|)3AjB5yXoXY{t8-S;pDh?kJ-QE|>V z1ykJ^31+!`6O(vd{{?8sF83}Rnz0^?{Mk^tSG^qML}yTMwAeOS?Dl|X))9Nq%l$5GBA9yrfRJYZNM8A5`rRpfB+|jDHdeLS?8(moFTT7G=eCrwRXED!Frp;+kyMLSE9|8q|2M4)g}$T z`v7<~syl}>y{ezXmTlD@JurWDqlf7ZSZyJGAdE!;SB^AxzNo@{7@ZD2-YRkbu3Wk% z9nVD)oe5Tm@OT^bF4hn1t^%!s=bL;mxt7tk(vAiuC^v|w-r|h_=~jCSJp2<$0)(*} zA5UIKyZgs52BpjPyopxU(Aew6#Cb@8{Lbujvk2iu5`{YCo%jH4)*!Gl5CAYo@x&Z& z#YzEuPMX_V2}9@ zj@nGC9A-bM$8<8KJ)||)mZKfw;v42}Rf)P3mao1QK+S;b*sT@to!VU3d^jBp_jJ)4 zJ%aTF?__ONp^n6u{V6ls-5Vm=wd>uVmFU6WC-TN=rJ5NHL{{RQYu6=xwCmQyW{&pS z%pY1UPR+)r$8WtMjSfm1;pU~plyU%&s!mK7-6om|g6~A!aACb>sttr;Q_E>)e`039 z2Ugv{W2 z*r(a1D)FuFKL)o)G2+%gK=pGNhS3qPUI5pX0(f(n`$13(N_;0cDGR+WA|JTBUF)tg zTn^fIEQaPFSWHHwU8iWWCUrAnsJoIzUainp0Ci@hW8bFcVc^3C0GbZbl;aQw=8GgZ zD~@X%_01UJc}=?ic;zHUi_boYVUxkUjY>HGDy{$u_Lq;7I=w1qeESUnmI@TW`X+`= zHT0WAm4l7Jcsambz%4*EUDiMLpuSQtXk0nYeu^q>EKHN|WuEU!xdB70p(|2{%IP_V zJE`MS!I#u>j(mBuknUdy`T-*b{r0?>Xsu1lu>2FVMf#X9FTVyK?=wO#^07(#ac?HD zP})h{sJW960WweV;XLFXMkHb1K=*l3eNEf7Y=4)wls|1mhztdg1@a(mUp~G1>~`$S z3#OfcCVrjtFNcaXFQ#k-7>_rbfU^ASJtM#>7~d7+MVIZc*@`4Vlx=s9=j5G}wjP#T zahO(S9isy^=PfoNu2z-d?XY|R$(ERXh}GpaXm@{~nILf2)W{%C7G}24Pjbbaf10b_TZ?UY~Bl0-Z|JM2bRmcg}aItrk# zs};Ckc^7+dQl6}`yM9abP+_f?yNQXqzCRkxtrl{5dvYoob6+&m{sjs zde zWNRH*RYwK|M}?*cm1f*8)|m*lEJ;8`0W0hzZQ#&!4D>LR~Q0F#%O3@!jMuh*(SzXxUD2=Vgm% zRn8%Nyp80Cg{LCWj}3HcygdCAg#O0r>Qv*$HQvhL9vc zUK=l~f==c2&Od;>HsU!P{7qHnj`OPZz({4g& z2@q`T6n~~A@N{S+9#q zFl=LCuZWFl8g*gJJhD==@6V2edVJjaq*!G=a#gUkSH~6dS^tY2rHzo&k^6xUiefP( zk67e7G-|_z4!feYy$llXwl^Ku1KW}a*P{O>KnQU}pI?s?emw+WzSAf`PQCfd1<5=2 z3|G8xS)c4ii_05CXB>>5-hVK1!PFS48a6*`03Bh%pkE=RumwkTd$G$dsPT+$P1ky( zj!|9sE@ZTjRkbAd1Kw79lh3b#X40pvW+tZ7gERM?=wObyOyY5@&_n*awUaE&3OA$c z%>e71csv2nLq%pt{{+V}&A?eXo@r0SQA8d`KS+0S7-+06B>@K zxQ*L9JU4(usVfiS7nDvh7*qsDe?{gfviUCOa92rZT#)o)~{mUGk-W_?B z$5tmkpvAH6c7{D?hTd8a@(l)|eo45YqkD&;{n#pts4q5BVKFLke$e$E(sq=zFVH)X zhV)+@Jzb76kWB3HAUwSmx`y8q^OO&o?7=ntyG_q0ytEtTOuSiqcR#N7*lDRo_}nk< zR53qkFlO}G^4}4WtSGyqweOrb$X6{9ytZ4rz27k1eJ_vcqlp--+-cRPBEuCcXok2f z3Oh6%7jgCK*d;DZ(OB6E@3fv0S#&5h#y$I7203NAkwDS?HV(m@RSKN?mp=2UQRbzeJL%O9X>JEWTaW&wS7d;%MUIn!wI)_ z(fLD%O0>VCw+28P*w8QzHjf}Pr1=Kz0dyIy?HoYpnPp~9{AX-HKx6`#0AH!IY+h_e z2%tgvt<4D%ff8ie1$(t|i8H(7-+p*G>`b#is$2)Oj+r zLN*}$|ITapoy(j8kPD`eJ@6Fey($FOf^cjf`vAz)Xh%0Qa0ZJ1&-|KYWOMrHulQ>M z$D;nLF}C*=p}`eieYMccQN8W9g{`M-XiZT+W|h=^Y#+S|G~mvG=g}Tob9ehOCJL+B zWC(BD6?1z+W# zkB+#On;LRZ>G|C8ZPAnon@7`xLr=fyE+S285ST6s;r$=KAGTe@pksm`Miay43W5x@ zSU7)hBkwDc99K#;F&eZ)F8Jg1b&;Onyq(`;gfW zer+7!oJu#DWn^mK(y>)fN?V-X&>!j5G~*SNp0?=Brnkk-?tz2b0kYMiJvo1lT1Ex;-&0t$U!A!k%x$T(3XcTI_J`-i+hH zJSMm+3ki6ll1E%f=&bdyZzadg&eAB7?mK=gj~nk452JDLf~vJ7WcLq88&JYGJBMuJ z+FAT`uzw3o0P8Xd(Cwxn8y@`C(C;^X0tLr4O+H#`Ug@Ub1m{(6ayO)JSppCZDDpbf z+59l-^#Ad3HQz7n0i6=O&pIKK=^aE1MV(+Alrr3n{!q0#F+4R%$uB1LGX;+lXebE2UUka*2?`0)%R1QB zIb2oe39uh-B8K&0<0dK+3C#Ee zG(Y=f?4CW4Z!;7<%eVb&YJVaCI5eWNeC5>j%n?mo2I!p{U@?(i;mdv=%8e@drq17f z&2MkTGZgxRK(dRTns|H(;7nV@)|^u6Ml{lD&kT+^uwJNf8PQF!-Ef|9p*EA85|RNG z5o7ly+vc#JvQpu@O*w@UQ$^3vJIpee6|X$O^LzhCYpKj_iNAqWP?gwMQqC`hvvMX& zSC*#-ML4@uh+NHhP##v}yi%X$a8l!fw7W>{oMEI7xkqW@GA>p-i(+z4G_WZbw3Kku zl3(@>)G%)Atnip5udJV`gN>$ht5Xb)9kU?Y>a@{_gy#(YcAI|gT1jGNYsWJcubZ$50oX~+o#r9i zapgfZwJ|X>?+o#d-5YPaS;}m@yEmRM&f-G>*PxF;V`}w9h5`rp3&Sj69?U4@zZwQy zfz~{Ke}iHUKi2h9TjKzh$JdK~dr zBUGD`CH~h-8ctcAgYMKvdfC=(^wpJl1uc1uHV966Zf||VfnVQhEvyT2eo!rM5up{HSyQf8SpxX$rBNgI_wF++_EAPwT5bfoO z(sz+f$P`ogf@PQ)1|A=q%(@mmnJ!k;E6Ew^XyX6Z>+#Ds_Q(Hr^Uusu^~WM&OJENG3Sc}rWR1mSOMnCN#6Izq`B2tQE>8! zP}lIIk)HkG-un3yYNUw#?#GJP5~HxVj4!Bf%Z~HwJCM9hB!Hhv0sJ%yB+YPy{giw) zhFo9Vo4()z8#PW2v8p>om`n#=gCSn<7D>nkMTrBjrX3XEe%)X z2pNe_Lt1YPU*fB;Rxh_^UK+GV85mUkz3>giYCq^2N-yozy1S`qcvXx2zWs))z_T9L zg`pzi`*9oVWxfMZ^B%+!NOefXlw)+3$i7jDPQlxGkH)}kBa!8UoaH+Gg3sGqWehx& zTWjNG)y>KfeDC?sW=v&YvbE-W z8{5>8faw7fe(-IOdY$(rk0UmgC(+-UZ&C27}@82i99@B7VVl z_#`WSHw#pA!#M`0hPNJ_mUZekjQHwxx@JizvmiG?y&|~4-{8(zEQWRoo&4Y& z0RWg;14syk9`=*~K*}3RPrURlXRn^5>1PHo1x-kpmo_o(1EmPedeIwuWpX3pah-xx ziAi1dQ28wmy-uol2dYc>j3cWU7tG*w=5dR@FBYm-SV`i7iKjCTlT-K+5H;N?F>8v|t-NL1 zQEAugQnCT-yiJ?w__m@ugJD{KVR_>ofGTbP*3F>?XR`(n>g9NgpXlM9w9Vwuop%?Lb`zjE-%)bWcgx+Wk3;?}=EOedlorac9!62lx! zZ^Zt%4oUms4=U%3nV#%hDG_iw>ILwOboZ9DR-@r1>c}c@zO!t>cij4wo!2xYdd$rTQ^%)6 zPeqid82g?`PLA~AokPw2x%m8@1`(0hGVZ-;hh|Zj<4l^@^O+tShd~s<$J<@_d5{0% zFqzw=z$VJdSgW1F&nwrT-<2^)34B8bUHRFH&eX}~GZj;>{~`Jh30zGVU+)|L6OU$k-8|A zf_%8v!Zgcr`Na)GG3imGm3kkY!}p8Qpt5Ce*%VAvmh+Xpp=U7Klfq4C(&xOXsok*3 z3BDgqS=zt+wSf*#xd2NhRP}`mO-<3- z9Dd$2L`@;nC>qms<@aE92JJePHw`%>tv|9KAKmsKsfXIP=ST5F!8c{YWN%7`YhfReSFbX%Q}bwo z$)p8!T;L8K(91;J#>V*pi` zUXMfgX{!F{x8dY-1s~-SkA6UErfQ~-&DiYbj#uH!%R$KWiGnd%cvCXZ-bwijKUFzwK%nfW2GU@HyuCq+>(@)%DG%5gUm;AaTA&rfl zmJMcQL-hzPRW<+0+6662GiHNwWkDlz?S8It%m}J3uvQ=3;FoS+Zj$a`y5u{$eSene z)-B2AK2|6iiRtJ4qPDg#H4+x=s8U=4%%3#y8= z=(--MGVQ>{P`{G$&BRhH#klj+fX3lK=chHL#yE+ozK&gIf5&-bT89EZFN35FdmAdF z%zb`=dr`%t{DAUe>!BujFOv~WemBEw;t<>d9AOoqQSy2*$_bZCowE{F-1_puWb!-w zY{368&_V`*?beK_VmjUKrHksh7Xo=Eq_mLt>-Lom_0rb(?c<^Tj!^Hrg)9Qh6AocB zt7R2|=)GRS9;r@GvNF}l65+c|Wa>%$>Z0q1wPL{|pTv9*GPHdi58alR#rLkE?YH{% z6|oFu+fI7pF(!6RfHw<@DE$%!DeZJ+)lvqrMfKDXyVq3P9`o z4aw)bUmxK6xo@)@pFy$W=Azp&OloH1nM1-}Dk?1(QPM-Vjkn7R8W5AevhPRM@$q*5 zS{l$k_AigRZwY-*~_LWXuchK0@wW z$45WRL|7i^0JGbJyW06wtlPHM^LX(Lfk1kw)M=+Wsk*?>Vm@XWkrP~p!g;S}4`81n z#nDq@!R=ilsTKlk3WepcRK!Usn_e(C+ZvLR%ZPwaj zzW>l5wE<1D7+|}8bM)gNU90p?XQ%bNui)CcA~2^mV)Xo%eu-Bsi>lN1TA8<(UOfqs zLUZo<66YT%#3bs$RAg1EohA)fm~ITwFs&pmk)|YVG`=4)_|WupW7kc7wLeX~pIFJb z-_z5-+*=s?g>bs>_VK=B)x5C?Z|w4*MR_o~uK|&xbJDoAWd8{sbn;!K7iRQH-SY+* z)*eM!4ud%EVbQiO@x|@W{l|ex#XA9i zrSJH^9&1k2ucKkw9}U+j2ZXL^#Rwkc;+L!NFogsaS{F)l{JuJ2Hor8-qYKmr;fJ%Sk zU$1AC(J0jUNzDu6vQ`j7c~W)9j$H=X`aMnEmq zf%I2ku6y}uruR91;PIBBzoy@KbK*!%XK1|5XdP0iZoLfrDMqX$vfjYNDRIt<-RH2( zmfeuR-%LMu3Gk2N&QEu9ACq_Py%^x;SB6o2kHJXzOyErpJ-*>)BD_2-<-a0O1qET^)8V(=#VXOUZFiX8nCXO4`(u)Q@7I!aq(QG0)bEL{=6BI%C?7Rw5+l_wUW8S`ubj|$ZU4hE!0 ze7yg7p;sf`-mO1q1o>Op4&Nq*s0-ggt~$%7V&gDum=LsM6Y(Er(|T*(ez>Djfy zh1AqxP#;pgMW2lE0N%HwzP>ba8t4Ueto8F&dhxYQDSV?y7OtOSFaqk>65F)SXK8x@ zADsW;4?)GJdqg7J?3f7}RDDvGeC#rm(cJat#ScH|fmm7nG{$-k2LuE-N4rn> zE`up!iTzsQj3uc?tvGp@*#{S=H7qu zdaikIQTd3Xi^=RN~eje`OOXjmW!Av=r@L zMRU$RKE*dPM&I-}ebEWv=$MTjk1QTnjSwkA%@>RR5o_QtYCwnTfA;yFPFW^M171n^ zQ}RYJU`_JUozC@}kbc95k9jR7r-}i>|88f3qtp0$wiYDeyXYUl?4+YoQy71!1H_rcN-_NMC1Vr`JcA+dEo`g1$vOtPjptKi~(HPszG@`Ada(yc?TUJ z(EAB?URwA7ejaEvbO&*|(Cb%jF=T5!C4=0)@*a?!=2!n^+`r)``E$1hoW4KiV&vsM zf4T|GNyFCM)wi9wgn`@X#9C+UpWgtD52#OrKHb@QcY1q*OTU02qOfP8gwdpZpIfdf h37^jds1uz~Cg+LDXbyc`y8!%CQPfnZkbC;#{{XIy%S8YH literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/soft_hard.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/soft_hard.png new file mode 100644 index 0000000000000000000000000000000000000000..a92b819b94d1b25d5e94a98bc2209343fbd0f1e1 GIT binary patch literal 69601 zcmeFa2V7I<{y$!+iWZex2bZd#wGLEP!rmJh0c3@Z2qA+?7dh(p-Jma&U_vdp?e>2e2-1yy( z-+lAVHygE%su_Os&6?B35rcAA>H`yj zi3y5G2#QJ>i-_)nE5jwhAL8Od5>iqYOa1N8D0lXN2rLof>T0(SrXemQ0){$hCJLTW z0av;hcOO6Sx1W@Rt%R5WxKj4;a77_eCv-4iUJY@$q!3&JdPL`_F+z7AOch+aVq8$* zFHMxa3l@4r)yWI%23j;kMMZ@~pnpN5k)5NR7iPr}&>nnIUN{WaoxKGyAu%CQ_|j@o z-gfAv=A#4+Qzum)guAD@wyv6?y0Z>md#R5%!2`9_2aUy|UBQgdm^gboaLFQ^=u*oG ztd|4IYpDq=1-1{azE4CMbcOzdtFlQ8ez@C#WwV~#rw-pI1>YyF%)U@jWnIAbsYtO0 z#jpu)=jrOG?rUgku1(bO#ktr!!wgM6o@03?H$P1;I}axW)&b=TrgQLHnhXw;Vl4}_ z5ZDVB5rIoBEgtQ)JQI6jsKE$BT;3x4Nwg2f0fl2fz4W9v7VGMb@%XUO9_#LovS-Ty zdqg`gFD(AUZjM-2_Wsy?Jb?IoFgny=^a-h)M?_xf)<` z81E$oI)U}}#<~G5c7<-J*x9?Fy|6y+4yssJEF}95C`UUVS3s_JBPhFK(2(kRV?98t z9nND(E*vp_kWo=#O{l!w3KV6j1sclE+YVTlr4_+6aK7k$Fcm*HKx0*dqk1q4f{NG) zq@RyH(L?NnrmK$~Q3PXm)KJ7;4eP55cYr$(#Nh~nxUapNy)VMpMO@!VdZ`~l3ysng z#hq|RNNc${i8vfpme3_ggD32L9Eb>?6L4*JU7{8qp{DF>54UjF!l=OPkf!isZqi}~ zMp}3+HDxrySY2G#`4~(~?HC^1_pneC!5C|5h+CLxJ0dVzV4Vhzb)JIcTCK9L%(FI;wiCHhWDC5j#~ENk=1gUw3aeJER{@ z-%Z^2gqz9xb`0Lf9Og&VHP(}~hZ_=3z`R{`%^W-|jv8Y1omKECHE(HMH$9v^L4=5c zS$Le##7k%qwTK9$IROFg8K_DV9ge!FREG6x?@a?HO)|G!(G|`v$ZS)pb_)19X7sX)0%m3H(gfP2nwXR>>>Z6X?U&|u)%G<<8WKN0uR2ES=+Yj+JVae*6Y$#w ztOw!+bd8qQ!ib52b%0qki1t7pmS}{)=n}y`ShQ7fF)-5hMi?uL=sLUL5YEazdPual z9zl$NFf;c?AklDLXDvSmXAQd(Mk0QCs$wDtBRt+tRb;6hBjRVLX77V=)_@^QJ-l^| z)xkK&{B+e+u)4-e?YhPqSoU~+NH-BM*D)VGHFX?9^FKS!7wPf|fByoV0lyI#F+aqo zye6`F4LJId6!@{Ysws^_Asu{AU{vrYV6Hw6M}d?$1C0Wl(>GEE+J*4ZGuA>QjKuH= zj55S!f|i=P4?+#J5mXIOBaSfPCq~flVTcK^_IJ z0{ox19mbs%4nQ`IZGeGMMX|l{XG}b+>CgSldvBwO0>O{B7Xf%2_K1>VVr(bDcJG2P zQE`}%^ooDPm)3!Q?>a@rq$Gvd%}y&kr??1vEIYQxM!%a6awUJotARdjr}*c4f`ZYH zd?!0P^ZgTt#qv6=uoR*%-U;K4GV-vqhx{8JL_eU-$s70zxEd64f~ePZ*+cDv!8J6L zmBIetDmZU1tPASPca~!ez*QA27#-sckyiZQ#!+bzQ6V_ndoMFpR8kZ~#t;)$vQdJ~ zu9Z9#{g3ic?0F>v;Cu|Qf7!QacyneF5?BrV)raVOL~d``f`UG?F5BKB_5UKYk!XN0po z0hmkCcWp+Z-gah&uJ&$z9w(5lBKpqiczw7CWSo|Q5Xe|*n!4Eog9QR8R^Vd74j{~6 zuFhcmmCl!dG8VxAQ%cZR)k535Lwhg>&JT^z(sXjQLpop`pa8&Gd8K0((Srgk@Z6s} zW%VVeyySfT+C0YQE9W61*z-WHgB^S<1p=CSICC>SB5?Fe0hf`MFQDmCK%)r-I3j+) zl>q0C_XCbv9D&3GC$1%;Ya}MFr-|@mIdmg2B5?e`4WLCqJJ=Jek2vcZh6XOh$r-pP zG0=|JgLY-p>_<6cg#oM*btfr zxUv=NaXtpuW!-lHZp;A-_#R}fSYK!D{3#%0kJ;SBMZ6>RxI?fR->L_Hu6C^dB;4_coIxR!Ve1?3h-D&o-d zAdvdpSb)CjFo<^uATO*rK2N8W>jJ!D1$)pM2?$j&*peJTYf%S$Vcmn)`R?8)VaQT2 zstGj2%>+oQ*2*WLQHfwwmWHB?p;4jmO$!Pyp;6!6`@*Q~fB-r;7_g89Ryg2=^|oUl zphW+D&O;P9f3_!m=R72&#r|GI0I(NPw((x+O_n{(eH>)lN? zh}7?SjB@w{(0G5Q|7Qcf6^U=*0R6fVPKabCrV$S!GrvVlN z5WaU|r<6DhE+p}BkRl}l6M~7o4?WooT%H|=_3^Stu}AuA0p;IYh9q1>NJ`@Uj7xNR zC-{G7LEd&=Xq5Lqu^>2rCPAG0E*$@JTC#hy!ri~u^OLBU9rpd164?8A`LcpyNSOa& zjrc(BzpNx+Tn!LVv*jEINay{L<}K0w|A6en;L@MUzBG`;_i`vL{jZn(e?|rWX^CI9 z1c2vu(D8Fwr#&FMfP+~7=aRirk(bAE^ZVGUz{NjHS<%l?_V1rY|Js~lB7fbI{bO^o z^nQt8e}y>zMx(+;&c7NJb}nJrdH&}ds-)y+MIR>pIniHMzW?_Q6~IX#ulK267yUE8 z{y*EONJ{(z=K3E~@GlxNNpXq4PR4(1&i}bag`HIVGo$hk2PZ2~x<3oo|F47||3j>V z)ISpe{nJ+B-{=?FdE-A5;s55G=|2x&A_&S51O&l3|7hM5z?#~=b}$of7BqzP@U=sV zNdPEQ^n}~7_qk1@<=m$BUw}PD*bu4q`#dO8)Wbp3lmO-cQ0OrUkn59lG{%EmuA%q| zO_QZOcK!h8Y2eN2RTk%kf#I?BJ>;ZR|LRpAQ#GNbAaiBXZ4%`6sal# zAUkvMrSU;NQ7ojsHx{+5Axyw8fC$(tkE>}ASn}vW@qh-1+jkwV`Cr~`+rKVQCdV=2r34H ziHb@}h)J@uneWgRX$hE+$clg1N8lB}m8ck8NDKyJ-&h%KOTdNTk{_L!|E<|a0MW8A zwLi1{pN20Eb~vYZ(94S4Bh+qS=k1O1f~sHup+w-H0*#>MLx>XPhw)~Cj)06(5S9ae zFX4_-ViN4%?}0~f^BwL8^)x_vVL*2HUHbVwhA9L%13eCbnjee@HM}2?^$X(WJ6!YQ zA^*?BSz_VC>MzaxU!hiPaOSI@`s$}3wE~6hpTKp}QtvRlf2mqQ!Q4kqQtC5v z|5vEhU#LD?5&qe`+Tm~*dk|E8kO_O=ydoC-FvfEPMS|=Sdr>Hx{9*DLiV~M7`oBMq zCMhlTIiDcPj=TPKlKX{;#Xkz~{wu`xFBIJUo5Xg-apPT;ggNW*^G}sbEKwgk57dDz z5gvB`%c>|KLHx*mN{YX$%>8#OfRr@*2)sP;e}w|DF@qK15U77adD%g4<>0W6P|b=P zDD%L$FA*B|{_Ph~l?}bJvcgi^vEN#;2eJ$uqd$3_#SP=&0KGi(+0x?=?fl2Z;4ADt zNECcpW!5K4W^8^w{91=ZYugyXF>x zYA5CRCL{CdbJFp()P?yN|9*d4dOL1y(M)%U@H35HzFEbwdfoTCl|H&SVto7;rH;)i zA2ly`+%CA=z&88J_Rl>E`t0WL;av6kfxmxq`WK~Qo})LGhx&MOQi1&!CS5nBqLk3d z^)uq*N7y?63l{x&AIq~4_v|(pTXS{)7Z$9PF#5MoXuy89`1|iu=p0&GK1-+Xcked9 zZ&;q?qlJ-d)~##sC*5BE1yX#UBD?mZN0xgk39nu~SgiE&)ED@(u3^`=U)W0m4+jU$ zW;f_Com!I{JT0&%(cJ;OX`3$e}on6?fKi34MVj33q`;-pwc~ zSpQi=k>JJgtxdpqDbHbK&aa>E@{3X|7((W;*nwqzdnaws1IMI+u-Z*>SNXUdX8QW(cVc*!vDK-^u?`_Ql2L=in`Cw_tgg11kyVq4#Wq* zLglB;_MWXnDt@=y}`dArkh<~4y?GUr&ApgbZGIJs{H zK%eobEnbBTyFM}_b7Z};4_WjEbNv@5SxA^-L4kV_#M zKUO>$)pKdc1u0nA)o{mXvQS5;Jc2ymryC_lxI~EaYQ?m8mhH0i9o_$7J|YXy=hA9c za8|dPR4G&}c9!3_dFS3;9xcW%0wNoP)+trQ-!iR^xz zNR7kW*f1)Pxr-;F_N=7ap(6lQdfRXoqvqGWw+GF}R5qK4f=h_Dk*jw@C8cUHlRsM2$`mpyZMfV!jz-=Gk>n zex;?)4O`iP@3KyHdi(0J^w4lt*6Se~O6Ims?|KBI#{}7zv;&(aztd-;x12Cheqhc= zZ$xe;vM-|cP2crO=hXD;f_bfnWQQNxKfAQ6@cGr6xt7|ADErV6_q?*g&T!$N0iBR` z{ck^5#~XgI4(7uh;n405{p7*ui=aL^%hzh{=1HC^rgs+F-i==z&SFgGkz;W+(&#vU zKYHaUnSi>y5?Z?SY^1&6sS&QWOA3Q2R&PUWy(Jk>!jVmUdMAX@N$LkNz_nqeHPqkfe-Y++_gYUwz^CtNtTG#%G0gVs~_{v8Ys-(4>gHGjI7i*Cv&i+N}-Ftu}E9U zCATnD-{ReKv9MC=_0ug`ZKH*f#c83zQ@8Q~&8f1Z7B1=GCP+)cTbiLY6P3cYh5HbD z^L{!KG|He(&f{wPep|m~dozu^NXwLyM`@4HwwapkNe$)idXAa8letIrj6+qVXii`V zIV6;tSN!%5F2d9c&B?b`G)*?&h``Ufm+;G_fL6L^@2B@GmABs(MU>9?7G(sqU z>SfyfXFo2O-1YnbzC6B)gTv?Sl7%^_^-9Nf{zQ#j&jpLI9oQnz8U_SoNj5=v1O2%m9m|T8a+qj9T26KgQ!+R zkn+1;>G%?As@ufDFW-I6YND;HDXD-<;ySU6VOF z*0A5>^%|bu6#d|WuoBChdRmjEFnYfC09Uca0(XRMTxj6bt&TjBK#1>I zson816VD%uTJJK&JN)iW5MyVqYv#b!Oo{Ph8PsDqwr)e4Cn_}D0A{PFHCq<3Pv2x zC^)2gc2lf%LnkNC{lp{(TC5YU0o(Xz{Z~$LSru zm5R*q(AKTzQ!j?3UaIUo{|HaP7v1uY>|PZ?we?UwvvG%MMcpJAia<=ODSoRf1=OtV?5m!%#?Nvc(sbNw-#w@J=Z?! zKYT?v)A=v7btX$Wy7Z_em9ZME14bCbBuO1w0L&tCBE>qgP5M^sx(eS4wT5%atv9a-xMJCH?|JrRfHp z*$dMhfjoAzQRvv5I?MPl*p;B+sd`PmC|espJNkz6hbQ&tCn9*HZiNKVQUmUmVFl*< z^T^e$E}0!2HVK`fAsD9>61#2+5?P&t)vRSG6?0T?YEZn#T+Htm4!(oH&CiT8M#h37 zNZ)cc$&T3M#LMa`&@8(KXAaj>IgR*rG1%o=fOeZ?YG5PNqc1$i|5+{8f004WD%aSN zI8)dRS;@Xv+<`|EI#c)R?Oi#0_8E}55N~>Xgtg;u*WBPu(T|l8k9K>Yb>1>$t7X(G zI*no-K_`y|b{x)4Ih-Zyfhp9vF{i!I{W=xB2o&TZu4HRj*XIG&kW?kCad5zDKy*m!M+F{>+DCV4|Jl{ zxP02{Z$&oIBs(8I;(QR)Gh_?g?qqE1uw?V`lk@XDWZ+ZkEN*X5F-2AVU43{;9 zO{vtbi<6Pe@%wLoBw{788$+^u1EX9hHw208Yy5?Whg^=8RmI?fT6~C(jsqKNUTt`u zkiS?phQsAW(R&lcTb;^{o|WmzpMNvt$L-DYdz0a zkEy=Nz!qws1)B0=&f{)OowuiRq^#48k~S)Qh@Va=kyso2wwiaUT;7=(XB*jA=!ri2 z2acb=6up+bSkL=*rnl7vt~lRRB{e@1D0iJF$ZC_H(+LeXX3J9feSMXn)!I-q;qEVj|xBI zJ0?m;eN%V7T{z-Hi_MyAwy&2X{t>ree)ax(F~srXYaLAKQTNB6T&nmX=Xl_B{GJZx z=y&bZ#ef%`?*qo;%D{h>0spnI-{4fUem_IEiYqFTI_W^~%2Je^%aLYUXA>l{#x{4n zNuN1GRB=>1Qm2uynIm;<`r?L#vf;z|2ZB82b4-frW)*h3@kKj)JmjVfSZW4*W78+*^9Hn)}JKpm8Lx&$GrH0sS`D zbUBZvJ(IB|O2xvd&hdIYe~TeST`?Cla`aU9ACEik`%2;G9{7%B(4ZDK~g1Z(M&HH|}&MnaWujD%7HO%pn|dYuG; zUfl+5&$bBP*7J46hplXT5+4<#-zW&Fw%yr@dv~-+Q3aV-&g)65*A*S9gNu<58@aqD zj3>|F&5@TQM#uqYdViBcPK(TDURKKDpgj)NtFge&1mq1bD9RqGEpewA-u7QxR{G7t zE?`w)0YPgNi|f}CdQ-;)7w*zJ3ob}8XVd(qbn*hsosW(dv9GP>IPv8qVso^ReZLc1NJ*EzNAG0GOC(*gK!rX!MUksBQ zEP3(*1bleCJCisn9X#Sj?D>3!aGY$7Z&@{0U|xVg)?_b-S?_?L<9wtYlg1g9 zx2>YJ82(AwwDA5w>&|VkpF`I-%vGSt3{W;yDSPC6TT$8sX{=c8(J#Gs=&s?^CTjs5 zIVsV-LJ#+xj0;Gbqm?ncGNPsyDG?HTNJLDwOvW!tPWufncmGLB2~~;(e!5nVea5q%Fggr^=R7{v%NQE9sbxXTMKW7@pN7Fj8A{5K`NeRUSf~S0zR*eM_)VaKUYjm=n+myL87-qV{8Bxy zblWDjO>U6zsK_Fe?k_88AFbj>wQhHbfC-R@0%)WQ2k_)neLKf8;derJuK_! znp^F}Et9UJZ_i%Cqwe+V8hC1JJ6F$IC#H`xmlRhKg3(D(BBn}|$(CjL^}A7Wm<95fB*!Bl6CR0lJ@ zsw|Vkg?6;<+&+ST&?Fsob1Nf@e$o+7!|r+)$yOZ(MQg_2JE@ZVVL7sDWVtOc(b_z_ zZRwJI;c&6ig+8~{KLWpt4eKphNXzfw$$I+anzOJjVQy&RIfWjV{Njy~aAo8*;i1L( zj^G7X$4fQ^VOr}ObnF^2>Z_lj{YERZ&l_6?MOiu;3z`XMSP3ukT_yE#J1-sO!SVPs z;QuxY*TmdBrSZ3Q-P%)?lWG}Nr>2FH)X`+^GyTdWVn~Lbzn)HlO=rPH`Ed#_?Utf1 zx5(>zu@k*^vOd9b-Sb0P-7l!%$|u@q@)ftDS?j6QgNZK&A98TGINq5*V0733GpTcg z@8RP0w9E2vA#6=^zy70h?2`p)6R1nUzxw^q9r)@bv?Kl(o7Dq(`QbVPT!qeO`c{#> zYzlDUYrjv4$ZIWa9B>()>f7KKq(R>eH~rDv|IM3MW&6?P{(SNFZ#jbk43gZ6^)Oq0 zNQux$?fGt9+O@<9EQvU9xEP^9`IT1uz)J&N{;~|d?9&sB0ICsN@LY!Ncm5mH{L8fz8{L&Pg616UNMqCe7&E1^~-)n>PO~{&l{7LZ=MZ%T;iUX@Y{&%Z9XKhG)kK?ij{R-L?}WhO0HL zJXB5Rr)mr4N+!E(1yM1+L)qwr#Xl-;O~fA#jl!G9t-443SxYI~q!FH2cI z(I%(@x!?8Ra)px{scg~;e{PYY>pW6!>gNkWfYEI!$eDFc0RzB~Pj-ix)5GJn$MN^& zCuqg+zL89q0A;N+ws?Khz^=T)x$P;nNpC=8zZ_-Icv2#~%m%Zo*GSYnZx2guEjnKl zz36T(aMm%v_xVIDGUhz%I0A$)1XRM>ZjdYd!7NN^a~!^dzj$4vTe{#q$1_w#4qB7V zZHZ{>dJfvpE^a;nBfbYpr)NaRs%{7738=e_DlL@Q1|F$Rm&^#e-+HG$oO{9ZddWP0 zjsRCf8>X)+XWMFt>gVmia-2?#9NXC$9gaKN^n57Gss4!Q12bO@-jpZ%tdRlZD1(yQ; zj2_>;(D185++0qEuXTL<^{A*Ys?n6JfN;a?eZdlN_OaMhKI3}zN=R1}-!fU;04j;? zDTULTeu#{u;nD!+A}LUAOvl%cy$7DwD_P~XL=IW}F=J{KzM+*90h za;#P%UarW0xYYbCV^?(7%#R_MviNY@duaC^JDRg-uPQw!L-!0yiVd|$3WOM z{TfVioQ1#J2(suWG63gBeL49&lokVMjX9xsfd2&yoZ2#*`g6|@Zw`{mh1U#aeLEd- za=N?Na`QucUD%iDH)|-N90W1k`MNTTnR0HstM@Lg%(S$uU>E^(nb2{6a;z2x~6@e>dG2 zBQqDJCsJ;$9yF14YG@PXpf_?%V;HqoB>&9?`gfi;j+FZ6XB=)SLphbDrK>EjmA2oa7=?w&hdd8$eOn z?dux$7+C#gV|B&GD#|82{bAZ0PKy9k?>MNQ67)A zXO;ivY#wAj{^j)jG!w3-vk%p64+y4OEYX*g52Sn3dXD1n4~|~6Y2RDCu3nZ9y(=!% zPe3Vt*YBCv5@qupayEk?zJ)|QRz)FC=LC!uc8z4XQ1goRb;%9fHXJFXLpWoF;F<}&&dFSK;UZWoUyJmbZ+_a{cy|L#un>I$TzsIk6-af^jr3!?#x zA+|BMcG5w^oI-sI+VOgr#%<;N7yG zCXEduq~8c7+kcOb@i&?;ye9FQa3DR&!ouX0y#GjeG;=zybqazG0}9F(9#r0#oI=MV zHaB(B#)9$Oo^_8osrLL#KLORnAzP-lXCjfZ&``Lx#qR7bXYNCR^_yhFVD4G6f_yR- zRu^sCg^Q^s1Eq4E7Z`8BBN(u36&U424o*oJ=zXk z99bu)n71Fw6mQ8LfwhKHWA9ydb~;Ro%TpuF2^IFH+Rj-R^#?N-=xDHrYIv<&y?iHg zzLwdG19~9PQ#+1^G-lVFjByZe-{5 z^}OCV|Is@eCtp9=l)7+#^KJt-(w(TN$_c-q_yf+tts{XLPkq`?X2PTQ-yQP2&x4@I z$kcGx#w`!`Z^5~aKHnBqcTZvN)~!U?L0Ob*XVkVV7t^Y9M_%yPi|i+9a|QG_+v7TG zgG}MgAn`PDt6m>_qbz=LDtV{(D-!NPUdMDB^3Zra5`VvWD7EE zO&Qv@&FOCY5jVoPcLjL37x!HsHP0-bZj~OJpM(d@6uo}w80~&T;MxI7D<3nz7FAn3 z?R>=E?%W`VAQt!hg^#VRHd52BSHz=gxi?#lK|W4Kl$lY(z(7EncPOA1Ld$ zjfyjOGpGK@8z+fk6zx6i5Ruk=T|82Zr1yi=97ujLdO|b9#ZEjuXN3byK6^~UrEq?t za`Ly(z#|~L7jOT(`?^S}o3_pU8kvpp+MX_9MtTbQzW!m!@j(Tz7wGu2>X%E#g610C z(OLIKhO=t!cJL*wYb?w~X+^vbE3+3Phn>+nBSs}Q^=jC`i`qchmvmD%H zJNNJNqjYk-TV6-5@j!lPpZ{2K-gLst{INM}-4ngfue3PzT+EssOht#An3ms7&A0*b zT4Jt2k{#Yg=i6#^{knhCjlB1^YgV8Y5iOA}F`aVkR)0R(@5%ngvzI_hVk+XJOFy>ZR;1MQz=7N=EH^WM?n=$X>Fr+}I=I9Gw z3GK?$ZHkh4n2qv~i_mE6@N6jq4lBEC-KD+>O8I@O5>LvyOH{A)5VXX?LX&0XuG^1` z^X5cffVW%ZnOSJ}hl{goC&TMI3WhSGLxdNsrDKPDE=d~tkI~|Cd7>Uru1C%MmWS$( zM792Y9USIMP2OOuB8MaUChumK6GsPFKU`OZ!{vu(`;OIA_hssDPQl*mOs(KgQQjNyHsPdK?+Z=wl)S|Ojf76c(Osg0 zzp6z03b;QzzZW*%gRQI|>nsvXvTFYW6`B^7=ivG*$rE`wSA852dAlxY{d29me`^h( z%XXDZmMqfTU%_kSvKp|{JihKi8Gb^)`XCh~seZQZ`F&m>1MD~!I9*R4R;B1 zA%MnQ%$%d~&%ZrOSdeHFLthnCIFG~Owx^t@_V+(8k<$)7B_Vu)--xR*zQw10E7LvE z?NL@OdiV;}VIX9&sSdN=?Z=AzM>VSl`((KqDkX(9-h_hZ54ofti;1qZ3-Pq3}>#boAafGEnq4 zr6z+}Cus;ntKv@Ww#c5E+H>#>_vWxu5*u$>IcajxCSunN_U+)=yRIR+XBY@amQrzm zJ&8DZQP%fq=P8MF)A_X5s<81b*y>(xSBkUIP+aXVJdTccbll5dMzr5Z6w1%>-Ir=h zKOCHYN&*_lSUg*R&w#=Z_B}jwmNy?40#>=exY&D6=!OkQzQITyrDb z9Bw)Hx~`Dy5;{Ddfp5Hyt$X!YAVY({xZO*DPp-8s{ULe5pWfpW`iC(@w}b2UU`+wbq47RVmZyohNlf^AV;Y?8}+J-8qhvW8o}w`neG zYF}Q1%GAEaxrrxpMN!T*UhCa%^jJ04IrdjY5ts^dxBZTyDY>oAsf~Pw=JOrT(>rRa zt#i07PI%B8C)6VqT>7gt9*7lXJ_(&Ux=FG7oC4i)Cl|lWn*^wOpd)ZNkGaU0IyMq0 z{8-`Sk>i@wevObCGWjlG-7Q)FFw^x7h0a0l3nq>rCzOY<=$2O58{}v5EMW1EQkx%c zR-f21efL`uF*9;|>XoroJRzAB*}T^Le99JV))}CM!jXWFJ^7j*l@a~X_^NXwTU&MI zPEd7ax&;N%if`{=vNF|}9fG`zWwQOUirAzZS*}1drI6Cupd!Z0H?T~0;`!cCZ+mWj z1-ZG=Jlhe4HXY$&Z`JKLV{5AAxiYj97MtxuK|)=xLRh#+q?FsDAeVLUm>&<7m-5ZX zJSiP^rrMJpWe>M6$Hr0GUC#|t~clQ$9V_m9!ftTkz+yI+?cYi)g^&4b?3dgPML z7=2p`z4LCSU?6uhGJkg3r4feP zWd%#Q&0KNc0f$08mol55&s&ks*D6;?lL0BA*4!cSllCP0BeXWl2i-RnM<;ilk_b#n zbm5=v3Wd$EQqr{Urw*db`3I$IG(O|2=AULGqC<&wz}EcNwS zzPptMJvHC^(Nb+=x%q?qa@#U|_^)<+_p+wC+I$UQc5ItKc9gVlOKanx{;r3C3=yus z**%RyqN~s~nf?Jc5giVJt;z|VV9CA{^2edc+V!aY3Op?wvNDnpbrzFG5wBhYhfOJ$WgKvDCbl{%Go{%&NtW5)5?$a59REo;7j{7i2rz zPcPR31XX8RFcy?=O%&&U>qDhJi;t&nYOq|Gr$a?TS2Xz>=eHJ-_DT%jybVWJR|Imm z$18u!={SEkwHjXPShCo^%QxnLLA;2a%5~cy25?*Z_2tH&%1urZ7Zl{brA1Ki2G24J z234BK?G(;Ud@;(*MLiocdxkVs#7_Ic{M=R1%KiHD4xPd`f3UHgr39y1hbv4a`Pa|& z1lz>_WS}_EV6>Brn3>%r=HVGys~*eT-Wc36C+yA)k!6yiUi9p_U~PM@hAbQ(j4d3= zZ4aba=MRk*!f8=xXEmc_z3SvpnL|2)ImUW&uTK$bY;okpS0}mqf1M0|(UIZzwl8?m z-*#lj194r-REV{Pe(lxGoe!i;VjZJA`88l&r4Y>w6U#YOZCTsX3B2o4(MP05>O zef8p{qZ)$O+UGAC+VTgze4Mj8aAq6x4IkPw z;QXWhFl=l;OG9!RO)D?(*u0@nB7@@nclX_)-Rb| zp^DOb>@@@_urdBY=|yhE?!D6U=k~sQLyMl{x;?l+_NU8FRNC4${4gdwB&|@;bU&QD zNDK<($=f}#_^^G9d%6qXMF0Spw8HtZF;imWVc7U{YZxk1&{hE<-m^e+QM|e*RDXar zmlbyt(O4UgYO-BDIO08@+ryai+2IzpW6}58{O`T)J4fRgPNbbEJFgw%>2KFr4@JsTY@x+Srg{ zmRje+n|s4@c1};Iul?Mm2IO|-z8tp-%2|;7)jmI9&R6=naLG(}z#^CJ^E|!ig>Rqu zw(qR%%d{v2f9izEf=*Ulzti=kuh;IB6zsBao5mW5yBzMc44xiE`OC-j}jeimS{K;-Hbch%Wgj#U9dq755VZDX zuk!^%9Xq>Z4yU$f_L?vpnuJpQ7k*&Zstp3%i&C2CnYupU0KM<>d~sJ&j_UPV^aH)z z@;5=zCrKbBUFXgLj=jX`u3+XUhKEGloYn@xP6_g>_xFRdHH9jS>BOFki$^@r>@Uu7 z@;?`~Z|P88rv;LtdKT5^8z;isWA{$h2HhbZUE7p#R8c1LO~m*{ZLmh)?QaTXic{Aj z@8nH7-vG6bCfl2ZC8-zW>bCxRlQ)v=5bYYa8Npk-dl^_+1M;D}cDM<6*zuK*=HImK zFTp))`eRBEe%JPy0sO+ zc<#8-{^Q@XldMWVkP4n8jI4IAt#8>~P3{^s;D}Na zDxa!yt?;uxStNhB_hDKz0`}le&yN=%2L6060a~$lIPpMwF2M9set*=&z-3_m2y7It zaBSIk*z}57^%4P;xIoI^^7v-mn{AMPz^cKC*4s{#%pDt{sbJhuF(x7fza1Ymo&heR+g5Oer?D z&&yfj`5C@|1~DAS6V~N(gg{*KLf*lTiYCA~R^Q!w&r7KCNtBKAW83Ok#={UBZSf}d zyZa)+t4IZVZwaneh-ve(7ZsMf7gKNACh9Y^L6rmj^WH=A}VP-E7adk;C$L#WYUF7Ufp$nOgpGL8K=5kV}FS zhQu{-bo%*5M0AhjEVYY_?-$Z6)x-6-2P??cx<#+8d` z$2l4f#JhhRq}0sbXD^*PBSjgixrfq&K_UH;$n}F#PTBnyhOh1v8F1BSmOo9Z8Y^(U zRt>u=V9yJEA;tt`TJ?l8q=f&N=0fGs8S#RXmUaeb2E+yKKf;qfQk<*3zr;C>boAe)-zO;Lg!JU7g8B(Iw3m0k7qBY<_W-V~*M%6UV6?-)6`g7EDF(M%+vc zMSTO8&3}4N(N7eS%7&?PQfHU_& zYr!Yl1GdQ@QEz=rIOk-^eEJk2JvtGm*=aT_wHDeeNqP-&O9~t+RUy^<0P@yZZi|Mk z*n}V{m)`&8JKt+~UD-Aoeq+C04w#iCz4~`G~XtQ((=j5OZNo>bAtGbfaZ^69LF~zYfMh zrM@nbmAtMHf8YV`nFC1vivk|4URP!Ns{BAaC@!~m7Oq(^Fm#0GuWNynWTZ)$SyjJL zcuL${BG0k#3_VqKc~E_@xSpH)fK@)-nr`D>8D>buY2`kz;k8`e=V@r4d!T*hKGFv! zQD`7ai;B8dB-?X$V;XU3oCIS~vU#USW-R@YCeFXa{AFg4Z}sa*0&3B=X<#HQn?>=f zt3h;8DVS$WNld5({00vml}Ov3h+%wrcj z-%ebrI_!0#$z{b*fEwQ}2zeMUhHt?kF_X<=dvSrC1{O>i=<6t?Sx|mKi*7jyS?EJ= zr>!DD&46m<4p1y0--f!g!QF{0vs@{~8tBm5Ik_vb6O@q6d7UjykjBjJ z7XcyK1wQ$L+$_tIsp>i#XlYwXlM^1(RTno3CqL}4_iWRAm;Hai;m&yJbZmj9ecaTh z$~S*MGC79xgl#W%Nug7QQms;8L&`A$ zg~!U)QNaqmxF(tg(-B^xcu0fT(gw6g5D!2Q!-i;S6x*kO6hG~%hX0A zHy?I9n(@5JTv$gkN9ZJLlrg}F;=GqvA^WxYV2`BPS+s$BwXeCXj>+j`v8*lrqO=91 zzz|9jPb)d%pDRw}v>W|cPM>HE5J`<_B41)T#Bnf82sVWi5XJk3lBW+5LaNG{<9TOm-ithDUmN2Iaz#WNRB0`FuynZYF znDA(F=W{pOhFZZEiM?5BdkY(RmWXd)2h`~_4>>APF^=k-M`UQm389+B;c`fa)UDV^ zmiE-Oa$MVwr~p;_$mrYtDS6WtQM+GN(XgN6N5dLzO!m`m~dVp6_I`WV+t6vSIOj?**GCK_c{s$Jl8#j&^ zq1j~f0YquEo=Y+ba^!nnlAoVFzNuy=;6SDT+p8$qgANyI4UlZgXuax|yPiiaI1}Nm zCsAW#p8tAb@G{F{eV-BsC_;4UY&btw-cTe!=_M0#!#pXqupG@LBwnl z&ggH;1H*S{ z;{Z>KSRp#`-5zbg9{r5u0ZkIFt=6ju_5%OwbU!U}?e&&Dm69un1*OYfilZ$?^1QH% zl6m10{hALPOQMj=qLHu@FiARt2nth`lGn-IpgvFrMP_ncbyqv%O>i1ElsW|;cBa@E zvMt5pSnbk0N3YIE7nrCpNd2c~xn@+D^2YAdVS6xxxJO3%^5MsBX*8|{*xp184QLt& zc4s`?D>3WpkYrE+8(5sg0^9|E$ zB$g_B0-`)KAN-AFlstUms&-67oQcRYx?Y>u@?Zr!E&+DPxO9YR+v-l#SVh=U@4tK| zE7b$SprmEBU-7eBo$BG}r4%dOQ9?=tOY}cZ6+?|Apib7H= z+M_WW%NX$&Dr+BTy>~Bl3@~+#ZBLT%%*FO=p?&;`mvXSC)dK|UJN9o_pQ5S&+8lv( zg=z}D&p&#>K_9;cl-dkm_BkSNC>r@g#$;y^J zBjebsjLdM%#o|XoS@wnS6J3O1}2-LDBvQt&a6UL4@glR0b?fm%KE+&NNMeN}5Hu zf!2l_Knxj#=Mu7Rs&DA*2Uk-d$%q-ZJxkuQ&{|~KRq3|v)UYD2h#ypgf^()b|Geqn z+i4K)o16XEO5-+(i#_S6(`VVDbCeu{A^-bc(#y^zExn&Y&!>hJ>&i}{1}`NSnsRT? zh3#woG+7gIIcDlN%I27VL?ol1Yo&fVvJ^!^eZEav*A(^he@K|WG zaKe3#Cax3l0@t+7v!xd8<-p3x8*u@=taXl)OqK)>-IV9LzRZT62A94?nL$|l*I1qh zOb;hrz?DUDKwIz;ZLi7M?imVz3Iy$#hTd5-z{)(nt|-j^e;G3ykl#h0hqkgbaucN3 zuw6lujCZX+4I+5ehg*N{Eh&!c765p>J9qoDRum6f+}=|YIBTQ;RlsHj^Qt<(6T-D| zveH&5;Prfzo7~S3d1IPth zWmjy_{%PLT(HMlyF?R-@B(sL~60nsenI?PbFXaYVa-|n!$>x`f<}BScUUn5diHxFo ze7EhVxUU|A-=-7x#lw;Th)2v#jlwi{gM~JnqebDH?4Uvi*{R0Lr2pJanJgoKEQy95 zHrcm2#N(_9;)KC#o{P)gy3z@MFhxYZ52XDCUIzY+tt`irXLf8jdU3MG6XSlH6djE+ zb34i_O9vxs9})%}2&%{W6A#!RJ^it&GH%>NQkufoQsNT_+H(hCn~EJ+TXBDl);35X zl$s6KovsNRj>lJW1C()Ehz*3ix6{%{P)ZSN<*Tr@qsUWPtZ}&|0PZPvZ>+4XrLRm( z#LQ8>#a%I?{p#SQae*T4@x7!C{Gp{JxcOY};~w)Bm9+ksDc#_NHh6S50Ej-8YQhl?rAiu>Wj;pG9@i6chVR{dkE3%<*Pq{2!u}%d6mI6x@IKF@R;9}}y&0BYje_$1P z^Qh4^ABcqyjtaXN?1g*eOSyn-NpGeFOGp+1j;Mp?2H{gLx&UzsrX}1mqMJI}C<2Ny zl+-IVKyP>ZYfq3@n@LeIwXv1;gPD#I<+X0z*EuKfSzWgm6vFl{1u?Mp*o#um5On+lk~r)<-*lJSq7iHQ_FTyCt4Fd1Z;30b$Omx zyhxVs0xT=aA=$A!?_KeJ11Cjxw=txG$MO$_XhH5f<{h>%>oL2~DUA|S20YR0w?EgE;UZkS&j^9{(x2J^gGm8i z&muhz)^e1^_C1})*b#R^%&5WUy#@e@h`DXjXzIrXn-+-?IL6nv1Mny1-g&JtWbE zGK&>78Lx$~i10-kI6j7rxZ}L^!@%OnTyPvH0=e-*Mx8n(E7}k%&Npj^JVVpkeJaDEDSRl!<7)5B;yCWUsja` z8f!dheNbonw8@oWW7_V;&O+YXgCZ8TUXi?d&-t$H&0WpCsxk@L{v62HB0jp_@#g3( z7~J3yq4V7T#JO9E{j}Ios4hLl@(;rtO z=ZnkU0A&k-cpGOLX>4cRBQ6pbPLnHs< zKwiMcAh(e!_bekz`^)2RuM5+wsB&LQe547i=( z5JfB!Ff!-j2MO%VIirbLqOWQ*s5yNg^i+)@Ea?{UUSbbJuF8k0BvgAE+SwtFJ%`#U zUJ&XA{Mg}1x(gCI+6L}s3aVR$b}>`!G3j(8-p0~9YbF6U;^Xh`tPHW(XSgl>zU|UJ zV|W4yKg&;ej)z?=_nhzh^|maOJ?rz5^_km*XP3YO4^e!$N*{vBOrl_Jihg+;4>WDzF48>tn?mMAWcjpm|$V zlCk%;<~KjO{xroHXE0S_Zg*#K*K~VO!pQ9xm8;23{a1b*UOJNSl}B9((sSlq1415u z>W(dJRJhDd^)*k~q#{B;evDh6?n*9x_U))CHsbvSK1@ApLv>I)*N_Pz;i$m#+%JHdNrFvuPc1~)h!&aZ;} zEVNK&7F3QAZm)X#0?hrj*;tubxVsr24liK&0B4;an(By~d%4P!S6Ux8nt1O>FA&Oh zxxDj3fi!I5FlT$-Dj*ugHvN3eruzBNg!WE@n*%7r#nwpv$f~bpIO68foO>wti$&uEV-W9sk)fpr5MfTmfUq;UPPV>B9UuhVxW@vqH52CpUgoOG*MD5P@re=|)st7kNvM0NNS+`J1 zIHu^OC2eHWyYtC)ua0E{;T*9FxgaFJy+L%Un~rlGnW?s~%cAPcw8_8(J0TF${54yl z&*hfoI6Nm_>eIflV=gMzE4D5(>_2kslygPDWIHQwRPl=;R}>0=6!jA$|83yZ+)CbM zUVF@KJLDf=)qlYZ5Ybe4CU#7vnCn6gusz@KjV1X*Mt7TCD~-~8XXCNh>i$@*AI##5 z^M##Cry=R9=kgPW>dl?>OKd;6;;Qf(s9V_kRE*?cK73jX zv^&PWdd6rapZVxbL6mvPlwF9)Cf&myp;xi1DBHo$U?_w2Ch5HFr08EP0RH?@a8?;= zsR5Wz3z_0pP$6sd3mm3`k%Ak?;O}i8#X#}lQof>pIYj!w_wBT{l%SRthCIw}x+U4{ zUZFJ@%KWJHMQ<|hx6F}avl}eX<}PjwVN|rxqQcd7VYoo10=C#UB8dodUa%0S{wuHy1Tf>Dq@1UJp2cDEc7P8a##f@sQv@mLse@~k*tE2H-)8LU z_iC!z=NrlRzH&-hc?sm2Qg!U3Rgd#%)hZlOG&H7lSt5NX?8isq5;}9^mmi0t_3^Uj z!|E);&b!Qa$@u9?qs`qmmwtos5jLA#0G_#!kQHl^gFKxfHyyy&#je=Hq}a>Ei_W8t zOC1h&#(e4s4tQ&L>Dn8z3dKTlsAieI>sc{nb3i8zB}6VQ*RC#(8Z#;AKjBe9EwlF< zx*EQj)5y`ejZz2UT@xO6I+X0t)X6LTBgkrY(J?E(NtEo;Vf@pv)g^HYFcVJ9l5JfH_GfpC@32e1A@rDXBC?!VWzuv? zn_(F0Y;C5Pqx(4g7>CEtaP0!~q_4iMB;o#RnIj`sW>0R?m&6Uj?kL;T9Y-4@@Itx+ zc&m7bB=MwT&vEn-T@mF(sF`ltXpgN2CN5rV0F|JRg>NdqmPW#7=kf_O=*w%7=hOpf zkPp~glHgY&dIZN>HM)G~3^lp0RhCgx(!VuAmW_I*$G}%fMz!P05=k~5BL&QPJcy~8 zbRnr%h}N_Gs`t(0BVlGwmRb2bne)or8~vw3`Tfo?6h9jWLn65Fv*$=110o~vR>W=! zx`d=O5P^%sRXw)aq~%99k1r~nTorq5B0)iXaoyrpBaF@Qa5>i_>73Y1!ddE9zSB%; z`WZ?xV3+A3oGM72<7nOiKFzE!+IPG~MD)Dy$4_@GvJ5L=pN`Hla4Cgha|DtduT(eA z0O3={!p!t_8F{|^#@sYO-4f?PmfK60V1})e=vai?dbdi-f0I5V!`%x)xnNGcXmM2u zakQOlMVt+9`Vk_epSKEvg`R_N6Z^&Kc-+S^QtJ~8hM=QMIg8wRIp#)LfBl8VkJ;RY z3)waGcdehw#ASw-Kbq_{nncT+QHXy^J`GGBC-vHbM2X={AQS(o&4ra6S8OVOa7|B_ z(_{6nX#8O5dW=(aKs+xpPlmvnuO?Ok^F?{@VC=2vNPygKxxxfA_9 zl(WA=N#~pHJB`v~?-MO8hus7(X!(m?BFDu1^iPl*L&Y{&zLOY52~grXyQT&E4wJVi zk-@^gCcuWQ@`_r3-YDxpc-EhZRIe1RP`J>-c*hJY-3l<73sxoi-(g`<2-p!9w*Erdc}qR5?xb@f`*e9Ka|Xs+aQ=;=Rn@uYMC`GX z7akOWcso{i$_Tw&+c-o_)F_p8=}#;aTP`f|(nQ5?aLbMqVvsJ zxN^eeN~5a?Upw1HT3Z&@O9I85e_jreivBI?m_KEDZ=S&`M5vgBLiY*3%4*oHf^tlx zA?%ZQAJp2~<(u@@9~tH}`;p2)$xI^ZO?h}?f%{+w>nL^=@QF~gGx(#4!tsU{xq8J0 z@9mp5`m|TW_zKQk*J5hY(?gbT%VoL~rt&0$s8-GkDdU%NB0OlEvE8(2ytDynffBQ1 zLL|^K-k3mM!LeQr>A$X$hW^IP0^{Y*!Nd!1h13Gvg5ChY*v=cA0L1+B3&c~b-%uRWRH$WZ2=)sX2^}e)*#;_wlK}Om# zo2PH+bf=_t7kEGi@yy(jvMQ>ck!ANDMUfxYrRn_=b;OzUguLu8)kAoSula6Z+Ed;{ zV7O2L^Qjzn`Hq2(s~BGUaSZJ-a}(mPreL-?wrjZ%EJHWuoR(ArY$rxjkGBFC{qxP` zgVBJ0!?Fr0V+N6Pmkpof9+_*8rA9Nx0!(~}FtURIrX zG(G;p89_|A)bu9{rRfT_$(99CSojUi;cLe?-=>vVEE?tNR1a4@ddh#!RzBIeohULq z_LBH+C=NBc&;eq4#A@FWI;p7NXEAL(i6CIhY#RD=`m*WbwYLqjiR|Asv6Y8*K@8XoYJAIsN%xih*ZII>o`z5u#u+D)F9LQPA)%ckr^j}CgPpdHU zXtm*=qGGNL=GpVSQY&}1LNROxjEmo&$HC(96QnS!g3ucw63cH96pL2C*pr;Ho1mTp z7y;g>lA(E0F`lUaKEgyj3fNJ68mn9?C@JZU>C4)Y+kk7@m1kI?QSIUG8U#Yinu@Lr z`@)}FsgXvG{6_~EX3AaWvRoHO_?l5Z*q-j=XuQR%V|0Cmol@DQrFUHmRS_32Q(N_Bx5rN6clm)b-*3Eya|HbRqMdoI&`&1@{r|_aiO?1;b%s z#?jOhv9%#XGxuE(ehz{qPMSmEz6Bd|?HX#6j2uCcb+O>k?t|W3=6KxWQi^VLs*LTO zjtOpcXGh}fMb!dMEQQNxUyi#IajsvvUB8I>N0ex9X74KwQO6Xflp8`;73gE>gkj8- z^=@ZbIT+8NSKJ~_6dm=N6Q)}SK!u_go&LGL1gfYPh%*@$GF!@Q&PipyIB842>VBoc zAiK|1jB2qPnQs=<6qowyER7YXLdcIu3Q_g zuray8_Hj&+_2fx2JM~6=lg5k&T??v_PaGCtE~qYD>X4OPMX_B!>?SJ509B=rA}n=> znmcLs=fTB#^SnkO+g(lU>L9x|3H<<(^fBAkL=eZ9#ys+1mf<9-7cgg5c%c&P*~X0g zZW?8m!_~Gkd%=Sm6_`WkViu*XMVTYf-kth{xYWdvo^jbqXxYxSCVZ~I@fHZ+-zp*b zi`(&9s347k?%9mD9U9zmxoTe#WjIzN;93A%WLO~N??_*Lf6rAxW$6+1?f@KV<%_)zK6_?_YKMg5J25zTVTrQc^) z^)9J|6ltC!c+8(#Y%T7`i|rbTn;zcaV>?B-SuZloDE5PDCRbC~8bq=A>nt!&R>qDFll_(#q*`|GufMLgu>Kyv%`16C#^Ce zNQz&v$4!7RQB&D|?7g1bix@gruX-ujrXnFC{7pfpP>46l!|?w4Ws}f0io=xkm*_hn zo}?Vz@?v}AMHk84-+{9O1tyR3?zp@kp4*rc`t!?AMnEgYRm^(g(V$uf6BOSM}%FTCbWzR>>s_&jmS{m|JFncS2>su``{zT{jA zZ2VoS`5)T9>V2{AN$$Hl+rL=j3-;fwIifawDC>h>Hvfui$%cR5M>{zL9ElKO4Crfp zK0?j;J{WTM2r)eYF3%9W7|f@W@!m_Xs2Q6hbrv6tv5&-Vp`*j$pG0jU0+>6iCPVlw zdt_sT*%5W6UfUbd0xs6&^Vq!dmT-xpzRk3lm4svLf7qWSvIof7P;U-rUmi-Kw9|Si zBDgw#7Zu~z9ZWNzD2q2wW=g}f%UOYSgT=qr_klLle@#Fq~Tf_jbNU|E^naH*;trfBJm>BR1uNyto<>!?c;dHg8cW?pB}opN^2?JS$> z*Hd#Dr)Dxv@eF#BwhM6#;j5XY<$&seG0dw(JetbgQt~awz}l3e4dqI|Va-YLXyqWW+d)g+gf9a5Cnf+{*Qg|-`? zd`7(633mG&+n)XNJ%kja0~sCIXB|eJ>?3(6-cik!biHHJrO*m6m%RGyvW;q#;&)nf zu2X_*aMB5M?ln~J6sbtpX=*yM=p>6P4l6koIU)~;qKml&@?x@p;gHz;mRzB4Y-jV=Xw--=u5>sKE>8vo2Dbjrxg*u?$^}z8HhcLEU4JWoRoINnP>?i; z?2~MF7KSbS#Kh4u>vvDMk1}Uf=BZv~PQxhvRptk;AouUToHtMDE9JHl%sJ=ufV>9k zH?`VBQ!ia;2UeZFS>=q9w26S?F(M6zh_k)w>&uhGCJt{) zP|6=kXlQDh3;a^8))0`C{peoe!mghBa)WpF+q>OPAG@+Ob$KXod(yuh5= z8K#5_%kdn;l23i4Vx+L1y19Bno}wnQme;NT#DupVh0AVky_YFVc(3mbE*^aMgRAvY zQb)*nG1*KWrXZ?hbOS{N5-CW#m4oHeN%+jGm+IN&!F^iNm4f)zi2WLK5|Gs--6+rz zQWaU5oy2cp%A7Rw49XaeZtizEycbuQd5v;F8sTTE241$1{IZP8mkB(JONX{~-Wn-C zl##l2WbfTL>7n4MF9Pqd??07hp#6!3b&R=XjMvW&%V_xb&Txq2@5r|_vWdW*S~5*m zELQilS0NDMyY4^EEPAGS$ZeT-uoBBAnHEt~{014n8v_4*YUt%B*S!PitD=LkDM1Hr zEeD)d(`<{Q;okPvF|BDL4D-EiKHZh08EzBQ{|*e}@9_zP8$jTreRncJuLGe5&lkOO1A# zzt~c%dJ}B-P(uZXY}(_6czW(_tl+Z|3soXL<6oT)AW{Mbuq$|A09O81j`5vGQ zr%!6$q^){!eE*?k>cBF%=80QRf* zD6+103U~>7mPMS*S+t`MJsE`xDlhEPt z%iSt2Sxrp+s;1idHuKb@eM?OL2$dM0&%UsQ;hAc$m4YU86=K!W|jGQ>3?9B)e%?3r&#p z4kqQtK_t1@Ro|V*Q~WxPj^s1Uf@&L1PDX>c@P>9C>lrC;*XMqwf2bFVEJE1zZh2S7 zBw<-yntvu)b&!^t*n1F*)pK5bl@DoySfob~tVsBcuM!(~Uq%ksWHxYzC|eq7xM;R* zx_~nI7lz=2RUvI@SjC(lX^CSm2%!rf{y0#N*P5I|-@sJKd?|x-H)Y9g*8U)P%2M1K zI}+#6c>bd5%1N}H4`a5LuW791Tv6*}qz!N@&>>gS98Rj+nsQc6VL^pIn}YAUbV=*h z=+CXQjQ%A}0)#!!0pSGSF+=>)w=27t5(-}Bw@mI2C zkWvaFXu=AKZ99MI>jADkyBv1Xe`L#@fX=p1wjWhbQ_=+OKM?2_IY)0$1=Y#C$pGcP z6wz%ic5j2lYC`bl;Gji9E-E;()4^DM`D&`J5?EM9<&AW=aP7*LOo&(l9!E9o0P2jq zA=*>qb|yK?0t~ZGmnR)m`^s&O$zX^iqb?^B&i_{ibY(FvG|%3r1b{>H~X(I^peSXa^I@9#L@YaXtsvu+ua9Av52KexF4 zDIBTz_E$`vd2a}TzWLEupBT=~d+Ya~U$dYQeenp3m|Ok`e2%xj#B0}J3 z4c1{3A1!L~#x>`>v3DHQhjpv#a(0s>g4EnnHNfX$144=(IgWJWjS7p^1-<;INKnWW zvlihX3Q`a?Y{a$2Jt&qX#FzqbnmgllYX#CAv@L`if^?*2cS@7!1ojg8Hj z0&OWQcGSD}5EizHr<}d$9@fphZ=I+)Ul@Ro==xFo{V%Y`T^B+AxD9X)lA~KD2Ec+_U8kM8oL*+oxx0~FT z+g_jUH`WH#M&R$#aVHMm2U6>e1R#u7`6`{{iNIYb>%Ls=3s)&s{rL<`vFFAQuJYA* zL}ldqM2~VdsGeUeo1bir%+?NJAHnu%nVbK7e-Xeg3?DTH7AfI3zAO%^Yb`hQGzM{e znc~$;5%2Xob_$(BC+#fFualq1w6*ea8P~Ze86V33p`@kl?^Zs)4=nSwh!25#!Rp?R zW-5wbr_gqh8)k80RsblWgnIPh65RgxgI*H1B!dD8%xaoTI>w>Um5NP7%h!H)d@@(g zapA5?|L6;u^2jPXjBqh@Q0?*K#|u$tkt@ZEr!$(Cli%3vXKRO$tYqc64L`c)UH6~L z$$5Ab;<@(rba{r1pHD|;OI@J%j&8q!XYndp0N8zU6S>&B_iMLd8tw#q>U?0AWXY!_-^eJv293V!sCsq>K6^5Vxqr^GE*?H{0Wa_I(Nn*dnaz z_17)=S*u_U5v5Lv?V?o-Xlit`*jJ^3LcS>>pj%2Zmkk3m1#KC_3}`~OM&@rRIrTzE zKCK}$pySa?z1l;i4&yXEtGG8gt0&GSg2D`&hrD{z+Hl!?u&Ny&t)(*-7=Z zra7z&YtpfbGK0;s+Jw4|4c}_|TogS_(h#7YhLU_!Hnj%KeEP zw;(927h>Sr;BH>U3UJ_vCIC))|3-4RlFt$&e8mZ{&fc)Y#}3;o65pRVb1#mGM@vC# zB#mq-#k03JSF=asTxU1SoT{1zXlXyDE2u7=xvCaxA>L!>SDtRB6(afaIz>FF$dglw zJt00sF$gA+bq2HJ_T%OK07nWLkFBr)?ObSWk+r#>}XJdPXg`3$mdbyIcUC{ z?a?B18-GfYF)cOk*zR0Qd*y-&_p+$*`pQy})=zH5fFQ(pk@f~Gwznuj&@3QJ`-@k- zRf&=aaRI-*v(hQ84Mg@;wd{wV7m@HQITTI@BF0R^D(d(h!Q}?az;d zwl-K%4QXSJ3$3`yN;dAR_g@!(ei&#y@{;PAcg|~M_sM&S?0i;@`?2t$!(8O>=7Tt8GEP#$j^z*3Eqt2TH$2#igcU)%yDcb!@}bofEE*r4x4zBt6G@W z62Z%|z-{VYDdX=yl<$ySvP)2o_SDEwsq4*`1|Lc2-YTo2Et_=5S>Zb37I2ZyvlA_Z z@79-9LVCj|%lC7;w<;j_pf)_0=6i6!WIuQVnUZoPuD7xbwdGIM*CVxlMJ~24M>kp9 z$V)e2>gSrMW7p|hmZT5^+^1!d&-jQDXt|29x`ebkH9_Mo(fPM#64ua zgX-DkG5+U;IftlZgIKvY{|HumNbMc#$Ry!5h#TPL3?D}rtA}6xkty0RRH}8ks-22C z0};ahHRioJTG)0V5rjuqE4VX@Tf%v4rgC%(WJ7<04AcbfUUql?VV9JF;al!|eSQy6 zw68$#;~~$Vf9A6uH3IOQCHCb5!z&tWepQ}{-)J5hYjv+8oVQ^4vS`=mvWY-!Y!M7U zlxM0mE*oSj)W2;NBVw-=GMCpQn{a_}*%SCJI~&>`Rf%xFj&u@zlKZbO-8u7N?%c~C^VKHJcf^ge3T7x9;-dPio5sf*jxb5 zmv>gtpg@|n8YGgIQ336@?Ps3@<;p(osJVlhSUrfKF5BLVI`xlB^P<+lFC!MqxEem> zVv4#zV0AkJAd^7 zY!ztnccv-#V~-q7K}7eC=IJE8{2grnnWkvhQc?;4k}OQCod7IC+IzIx(~2E-4^sl) z@nzP?e_Cg0Snh*UOk}@xo@@WSeIPKfPld@%We1j(Y^NqFYsr=W`ut~mkQ*<7HcmN8 z`AELpYSc*9oPFsGlj>3U&-Mbb!O}|F$H!cS9 zm1|Ti55TAZXu*(d^1Dqy1}PtYBNK>hmOd)4!?sVs_c&t<@j2ye+0Mm72YQ{vkgrln zhA$qX?dR2z-rXWpiChf|4D9)ESdas=8L4uG?AB{LhM&t?nA1A(-%G3fviOX*6 z-M#)D_|4brPw#ESiaJ$VVEW_7BtYNVdhn}R0Qk&?Uh#8RI8(0Zf4uI2oh~Bh^Tbrw z1CvnYv&iS-eQO|YA>>Tc!KodrlzQSdkPfAcJJt78RWNx;N6szbdv{#_}N2JIXCozJwHkZHZ;8{K)5O@W8 zFs|bp<$sLb-VSnJ03wkOR<;3?n#^OP>q=0%n=m+$e>xe&?c zUjqCOd|U4O#pryZS3mU4UJ{elq(z>w)0iMgkj{2_lLtqpI@0JVO=} z?WW29k?ikTK(cf4ZuakcTL>lXK%TR5StJ;q9cVavx>8Hwf7E8o80a1Q$%9j;*E-y} z;M|!wuSUls{pueFM_!Yu3=nS?x7dB@K16|}U0YCEjcw;6*0PC$-sQf(KhVZ4ppCyo zEDj3Wj=7Lo>s(3uyLAVz^FE2(m!Lnm19c!owxUOp;b|mXC*tM3 zf0w&wa6rB4;oSo`7^tjJ31H$DX8a9jcVZl`{Ex7&fePL?`;NE!&zTTA>%T6h7Xmw>TBxCL_Q1%VePrVb2Ms?LFz-{4|9UqpQ#(gT^}d*^BXJ?^hp!PfCgDIM5! z%@<) zV}UjO_Y&iiTfdJToZjAH(*FY6ce)y)K)1hrmQ49R!}Siz?-$A~rcwpmhJ4pU)ls>)amXfIa-qcaq^CE`m`B97juPR{?yywy{{cJ^%%UXSn~v z`S@zm0r)bKM6~(>6{QXM_GIh=7=M1Y2bCZVXjKaca$^5cSt@g}dQ%BOn(und6*n>a z8WTuQvQW-eNqRZk|7CGw?jOR3fWZHk@Im$4b=biVal2l`neK`TDiHxfhjMVo6#zGw z8>@Q-J;n6G*zK1ucis$utvi?@a!#!Qyt~<=Y(CKw@G%VW?#dNlfG@G`7>6ZbiOlxp z##AhT&o1g~8@hy7cpR=PgI*< znwg9s0gk7GdW|6i*Vd-QD&#_6_2Sok=6F!%)brd}arlM8=A$X}D+aTCYXJz+VYJX^ z4Sd`W&`#i_`I(o$0jS0j)NRYBKL;8NSbK)?8yh`|xY@P4vnt*H#TU=?Sub0!IE&>Q z^eo7{O+YoihYG8Os5szj82Vt-6j@N?82M?BO+1P(2gL%1>v1B>sg{JfHuGJN>-b1J zPCOFvGi!|~v&koQKjEM05MR^)P%;-hnA9`33y|4@UR!R4FY2hGMV-=IJt}r+7_OBj zj@En6^~?W?1vtra0754MGSM9P>)y#o<2*nyDXr%HzPmB^Jzw7<=gJ4#PrPfzh8=x?A2SKlq+`AN6K}Ly3WeGdWnd2iQ>IXl0ibb#ZcO|vr+mbNKj7^&X{GuJLPxD4bu(UR~R7ldu6gR5o$ z!eJ`LzMT0?nsUOzOLLo&)*4`O7dA^6u!Y%PKp6SLO0Y|x@Ia@?B#YwO(H=jG4kmg1 zw;UWCi;YEPgRFKs z9BQNS@Gq*#Z^TDogkyROTo$_}cf|e?;sRhY+4bjs^zQp_dPa&a){OL{B^!gJ+o1J? zn%fvbEV@kU=A<%a@EewEkh2{g)#nw>o-tJEpfc(t-p~84#Qdtk&9RcWzUtJc-FlXo zBxrlR6=u+GQeDDKo8lzeb$;O2Yz<-v?9?JmS3d)qs@`o~vWdxi2EH2&pD$<OuC z&iX#oE;5<}z(z7!ml|P(i0GamN14ff)TPr|OBX7uj-^si4XxDK`>FuO%)KjZ*LA8d#IPwP}&a@|;aqyZMaSpp2% z9Ow-?kIIu-25fsQ1D-vW0mB~4;M*W9B^?T+uA2d1$p-=R#Kaa_Z3jvdBZl2b%30VQ z%~34AFTGa-wS2vV2MZh5FBH}Du}eZ>6-a-6edBIS5HJe>e4P1e98D7QO`Sw?VF?ji zmH+e^3j9&+2uha?MjNqx5)I~EngNof-3VV>gZwWY8YZV@L7pZPV%sJOKiAi-$2k{0 zQam6|mBUxD$mi7=r4=~RG6>9+ei;jybkOE7i_U}^=6I1Q2mcp`ILZRcW-)wzzlwo0 z;H7UzmRqDRxdTi)?5=(gfr9FIY0NV~BMEA`sj@ok)(tb+TtJgNAv&UGJKLpsRZv5d zuvbq;&5bcit~~zF#iMicDzN$8El4uv>j<%^@d;ao{vo@=rB#+sUApWPbB7-r z7{p@iph*Y-^bHp%uvr$Yc$R_JL&2vMqXi#31OXP>Cl>D`L@?s4ooY26472pKKWZZl z$R2d2hLQm7Z&R>j=L(;FI@(xNP67sMg$HnP*kDq?JnV%3X!yS@>A`zoGAMbEsvop$ zQPdA?5~24B!|xTa)ibrgtsODtgD39-8d{_kc~s>CL#KA3^ARjdo~$X%Kp3x6XdJ1H4(vxl!mFYw`YV8nomuXFYLru15!8Vsb1)B!9Xn@~fa& zK(%0-2+TngU`58Cy_Vpy>|ZgHB`uBy8F{Py{X8-v`5<_`0K&Uuhu)|=`x>iy=_xT@ zQp9{E?knInz;SOjyFH(z4g?9{-z1di57a*&H8*=`%jIkiF#cSdR_SqR=IzmCERJbV zt?q9yI0E2(%c)RIV?!MdWNf>Z2-Z4xakNG{1#EZa47LKrV{g(wkFn({!8elto>XjE z%U&|~!mJkUPAh-S33oESJq^4*b_4LF($=5*_qw8nmO)sy!_wyVPq0L(4dkaZe&uh` zK#Br(FgH_5ozzB=y^aS(L z#6UodRph&zlzQqjZ)Lo&T{LYT?+If-uaga7$Itrc*BT_(Yn(O}n9 z7JjGzi`Tl;aNiW;X?NA6t>K+5t{ltRW8{+`HwTL^UZEiR(lVFlkK`OZ#X1dGg@v@t zeDf5$fS})q4=af=EwSvnG!3xHKBzL?w_AW^n*o@EU)hGVHX5NVgSq-5rRF6;w+9qe?bz^a)TEax zYHFdF29Q}Jsz8`WIs4&HWVGl%IpX`1pc-pC=5XV{7n$-sP5K;8$e*I=!ygR;{tf|1 zsDkz*61wk!pekKC153wv02*gW>i|VB8H0zVFS6=M%R>kD@}kOrfm}qh;CaLFDVVq` z_!vDLcz0~O7_UZ2J~n!LxTCQ9db|KHo0#*9U(UcYRx$xJHO!~i1SRFQyY0$6gn_=; zgo7Seo)Lhx{aG>qs(acKWGc3P*nU-M3&G;Fke_T@9zJhzsb7U11B4A&G?0D>z#E++Ko*Sr#0@Kg{=FHoIA zARAya{h8`bSiwFc1puF)w;(XXQFL!y>fQ;%)a4w+!u zvaTa~?!RgS57L1Vb|V{js{#l_%&w?#SC7}!WAz3Omq)$xcBJ& z=idbR;j?Gvf0O(_)G5W}mynS9Kfk*7ug~{@ar{eA0*4_(k-1mKd&3m@|J?A`>p8zltfZM7}qhrj}iejc)nW*l5Me7kLow(!yL8jIRm?c?&-X42P_@7!=Q`F|_#b?NYut7k2w$QQJ6HX^N7q(^4t{(ljG`d* zvzB*-F-S3S%Yl2}cv33wU&#IPet9!+)L3_CJ3L>rXQWg=&&7e_xaP>9+Cb|#~c4>(k+`6Rr#NfrwQ|_?l^s{5@s-$?1 zhksw~n83NF1IQf%1&w~{sPTv3`N%VTm&W?dA;u?|*gT?R}tu*9`>I-jVIY`)?G$Ii+^C{d#=cBM*$o zkRf$|x%UQz69(7!m22Oc{C98TEfcthrEcaxEEf`Po5!R5PoE7GugQo~#@6pw_7;0d z9=zJ;h|B$ops&==E6Tk0+`j_)0Swn=7qzKV*w>eb;95Pc8^XB9iR>|REt>y|K12hQ z;p7?wZa*f!4)X08PL+_1$!3?27ypH~?B5tNLB6&_?-s+}wU(g28xj#7(C&UFqiL$# zQS-k{BqO<4R-mA;PpkM$-c)N*N31Dm?qEZm>i+9mQE=^tLZ-I8Iyk2uxHj1=^|@0# z3Z5aS4!!>R)eB48|z6GP7iEs6S4Mfg^?L|%ecg601w-?EJ3cWi}DmN#* z&?Q~L5EgqgoL}=1V=I%^r!!QVpDhnJFux6CdOY=s5!^K=!{Oh~8L%^F!EY09b<^z0 zMc$caBxHN@s{Tp?owqfqUU8^=8}eq@_cvi?SeDU+G{fj(o!gzISCApk6sT=5B2i}j z={e~+4cY`|Rd(yYM8^Z%x7qlz`P)6$Vny-nIGXMnYZr@pq|I+;n<6`0oh{FR(*JAh z%EO_2-~Bgfk&16Z*(;?8A!Ju7+4p@*lr2WqtP?6)ELpP-A^XTS!we=Z$Qs5rV~n!J zn6Zwr&Yah%-^q2Z>zvac{+R2U=6Rp@em?i-{@ly6>gQx)(6=#Z0uR(Mxol*9i+Q@+ z59P!90QmNm2q~VwH%VZj9FR+64>ILr8oy>?cV13tHOW|R8Xb#!}OYT9d++Y>Jr zu5BeoGaZ)5I0Q678m0g4bNG{600zj-Dhli(;bCKer(uCVe+c51N31(DP-niDx|&>q zwt(EB4+@gIePB$H@zt)|P&Q@1IgO4L>+XHGj!c@hUl1z#>cWoBe&AwKq>t`*DtP!B z|1?J-PF2YVwz9|84?6DDU>kP12;|e)1Cl>bbQV1%77wf$Q8|3Rb6eE){NhBed3YCC_Q~-n%hap ze3WZ4Cg;n!^_7;c-eE*qr$U1Cg8_S@(%U)Wbp6I7SMY7+XNZlq)rN1FN)Zby|KaIe zQa5dG-Jg$YZ619jz+^M8zS#0YY#T>+?z;oa7sbj|oV>KN8H)J*k!;Ma&HM$7m}4#f z9h>d2M0?KKiC$dGycmb+sg;35urORoH0+||R0qG@@AuF;ZD2V!Qciz9u;^!c`z z%z~2(LdW!N8<5%6Ct`W9VOg@V=te4Ezwk8pMe=2qtgaUt>dVe8Vb_R55Irnq(i;rx z-eg&a#B;W$l+Na}6d8U~6E<6kddaR>ycVpU)ET|n)QB!5lzWCbW|~SH9AcU5=|%ml z39-ue@URV%NM_ z{#|PBtPjQ`Nqh=?I@y!U{1>Qc!;cw5neL0(eneXSAxLZQNfge=OVHvs{CXnN1kw60 z`z24~^>GI5zx-WpG1V0S8oA$k%kuZ3SrY*U7MGuF`7KW((ZO;!bW&qmq6B6>_(q(yB3uS5 zc$Z(OFU{&3^0B|t^Ri316nJxSeM{?`s5U-e3~w{%VYb;Aj7j+g9zKPwuxsczVD~C!L~W0*VJ3707pKK#0J{4X1Zyi?Arx!=~9(!uuN=4}1;$bxaRV zrae&bx_lAFJ0${ZcI$&OU>+-K>#<;gq%&M;pa1Y#b>pH5d(>ca+vhC@-{IJKN6MTl z1sz8zILD1lONzb}IyB7wLZvu3V4HbkdqyQb_Kbe)M8Cbq-@qRSq&MVae=Ct*IjUEH zi5Z#7t1Xh1-0_yk!s}flPtl*2^SPN_h$}*_C&6qn_M7=7)VpM}ZVzAp*W~cj8158Vi~BFli;{BX z(=ybvyso5XJ>L2UkDE)<;xVlVSGO4==~Z#^`SEI7q~qF}AGb}c^{M}0pe09F#7o~A zPuLQ(8rP%!PzHSVpKhx^%V`1}FH5rE_HPyO7DLlvG0>z=VbAu# zW(FcIl7l{PI%|68`=!YfHTGuvII9ax!t=epeRegU$!=p;`stToHIocpZTY6zJOtTx z9~R~Io^a+PUJGS2W*&-7ihj}8^qD&71h<(pm3jYZu~LGgUR{m8N&NSD=sjS6R`q5l zW9}mIDfl;-M*y2dF4EErbW8FFHGWPKVp6Zl-XbJ@H9UI%df@WxA;UQ?xTHu4EheQu zfEG0W;(Fb)?t-kuY$Flg#O>j}%cXEnoU#n5YyQTnn);T=@V$_sE^_#Kyh(pJ>0XP+ z4X!)Gr$llR5Hd($rq0JrU=T~=vpEw@K2tdnZlfz2i~pL+JXgg*k|s|5ZOl*) zDNB5fDs$d4$h5v-U|RX!=Z&D5%zM?wj5;RaFa)Zk`O)7-&g!zmZeVAB*IR~NIqWE_ z4}Y>AU3VX+O-R%;Ms5V%P$rz`K2n!9ll1`Eiygpnf3KC9pG;?V8J-Fk%hts`^!F!A zwtON3fEFK;X|SC5;#*Or1dJKn5?1S=fUy~V>tK(ZzFm>}W9StV`%7MBTbZdSO%6>j zBv}ec>e%RazU4qLXiy&iKv77!+F9UD zxDV*R%%nx8Ov(Ub=+`Q`i}Q|u%GrPGf?oP#@mdNq z2olcQ^WZSQyq=erS698A+@^QIq1_Ggx-DQ|va%`C`)0eh>wuxPLD5QTX!m5Ug&TP+ zihpFWT)Ed0;0jBdBdRPTRkSz^dE0z-*m7D%T6zLn#X!7(8>h@EeRW#qQd%xG3Lz@ILGBiq)lb&reL85E&Y4V#V_mSMyDWE=icl6DTeBY=io`~O3t zDo+=xEcGgeTpRb7ot+z0D7lyVDXi<`{J44p<<)JSt*^Xx<$;$%Rz7_Vg>e501J7S8 z)I-@6xZq0%L10H)&c-`ATk-(0?1xURUo09d*m^&o^6-(GULZ6=w=8L~3(Q<6>PUG? zTqVEsRoKo7Ts(Wgy4AxT`HZkS98OckfWUL;d2YX;h*gN$)_BOi&v3}9lS%*fpsZ=l zOIq?MlOxZ31>>y6y>Y?6Em~FJ6mZs>^z-O0C2Zt;T&L=G20_TBCF>@;NQNErD2YoF ziAMH0H3kN#DpXcURS=PEj^aEWmLGb26I8$%$N6=S6t;U1^$c)a=S`5n6O`F%o`1=) zu(`F4@<;;KCow-*CgzC``q-T&8t?5o_^voj_VPS~AM@yb7dI-V>{dH`2G?zd1oBQt zny34|BfENUO&c@kAro7GetKMt)ZfA8KVc66DaDB`u8;mH-~weBd_`D#7m6u7nABr! zZl9!xHxB+nDku%*+is=$%(tLcNiqKJJ&R z%X2jm&5`fdEMEO~-nc}Q2^FzAml!?cbzKJ+Kz6YRy#BLdB;GU6O>J18Bc}}X zfuW$%+G{j7WKbs)dOKk4(b2!DkpSxn0AS-j>{iRGYBM{Y)5pV>v%BV%zAjq(KXTu; zgFHBs>x%U+#^$(-W&kwL({oBseNe5pDJ<_zOLz)rXjc zKU8`cLxq(dBxq=S<64>03k=#2p4aE?Dtga3uhNarq3!fTcuIBsM}VSxu5jSi7Cyl{ z2)aDfdW&KBFq)IP3J+9N{A{lj>Lz95Z9t6sXrYRm%<8trn^rn*_2pohAOi>18a?mI zj%O%#&@jXokqLl23Qq_jE_M_AUF`ljZx#L`O-PS#ee^R9C{+$z2$lw!pBb}%-(^eC z{4wMa;f;E2W&MpX3J^nD*H{fv(%sube62)kL|Q{{oR=WAO)iZpeD3t`_Oqp95Z9(zlD^L zK-kn)^|v$ITOP9P!f(X|@A@C5-jC*}yObn$cUluK_19v7>w zg0U1$H$F1MBgTEj1^`AWx;%TtoWoC5fdw%Z`s^-foWbHKn(ahvVUP5@LdJlT=>Uz- zgZ;!s=3XEXXi7)ga2mNiLOKUZTfc!S9VH>s$(BxVHbrC68RtqaTQXE6$FM@%zB9DJ zyYTtas={o8-Bs70;-lp)O8qipX|qAAyuAlP3J{oufTcTq&+XnB6(_d_lK@h{{b)~Y zBEWhUuu9gZUQs%eI?C)Qp-=N}x3zhUy?Ur`y3NQ}FIMVCxMRLvpptwa8CR#HbF7X~ z8uvQEpdcEWRrpj*L)hZ7tx611GH=|9DY?s^AGwdPqaC=#!kA_rXLW@DAQ7$UR3Df+ z=Pl3)e^1R9Eg_)%Aqnd<|G(uxYQ}~-FP0rcPFve}QNNwJ-ZsM>55?80bK=)uAYoI- z+TBKsh&Q}4vvgIms&r`qi$Ro0olF9OO5l$4QN(wNwo=f>-EEzAv4XrNud))VX=C>6 zmstz=TkIy4orZu60j%-pUIWVG5YV5N*v%xUX79W%2;{@fTp>~KTpjLFgPM}0qdtzP z7z$1C=`_HFYxKZZiI@C^HsXW^7>arxF{p#C=-=t#u9Vvuo96+yKnfU&{g}Z+kiU7Sn zK>K&VP^iiQWcF=EpLC`R#fE13L~ruE99VvH+VaEP{N+RS!GA$A{IHD6@%Cwufn$A%CQ52G_wXZQ@F|(9KGNOJwM%45gilZLaKffIA zn@!Y(+sqD(o*uCUG$m%!L6=qU>yRQ$wL5BaSe)NFcWZs=xlcVhb90n&z_qX&;%TBf zj@2>IYgig`_*@Q*qT9bTd3UeRf4k%J(Rt!KpN5T`0TzRk^&z4w5n0RAQwbK|N7g8z zHAIE}%wd3ianXF72`L5Aw@M%$zUVU1U}VWljxNYEk;VB$+~)D3TiqI>;hm?pjzI?vSYXCT4ig5hrh$%uE=>2luTjog@C-yRn=elEcL(pEz^Mrs z!ou?YLJ0khO&kxq%s4ADKr)^luYt`Ihws3xdjtecrKa4!XR0+m3Zcvzo9zd=a>YOD zC0zZXAJ1i@)U#dd`t04tEI8$v&(<^4b{QW_x2J=T;=H30c)soouXsaOLGX4YAJ=;B z<|EU##+A@5w-A&gaG@rlC#A%&?(B>m(BL0aDiN`_1{w(Hy2f{tE`V58$y%tF*+DjNh1KA$zK2y6l$z2#5R9u!O zTgtk#Pd)%VlNSmDNG)(%-{ONlD(CXXRTgI%8aCG}1UB*`EsNckKWdgSdV6&uz}XFl zjw8j)0CdlWLbw|AL10*0=I7(&C%>+p`cJXI&aNEZk!H;6P9LSqP8S$~4YCWR_>@`0 zwE*Bm=^(m7j^A1?o6KYj+lZ6pbm^#OC-pwZc|*nIXcPL@@8R7f7H~c!6g$;OT}o;< zF1yzg7n5Qzt;C<2bD*8-7daHIK|GjCg*EDR4`e`O>OONeV0E4`1F3a8g_yr<_<nBt`Dj>9Qc)#257n+J0d9z6`XO>gMI@hiOx{QU~ z@x5;V0lb0l8Z)f)H!yX8;V3$mPscPu1n+ydOMMZ5YXq@xU}Lu2~dlC|7GEsh{^7P|b%K@qq^fn1yCai^ud z)Ek)bhMX!paH3F;=FvbpEi;%YyG330>5=P~ARFywA{kMSdL>0K%0j+jhtA+ll zgvbuU!EeKoZdAly%yD)oDEmGp%UK5vq7$S0l~}o`gazKsM%!o~@05er=eEB8gEPF>OR zMLqa(kQkhWdfToWKNdrq$%G0UUIaH!1AUP0?SJ|pcUPtQ0dR#8qMBg(233dy8?^ll zp7N`I92w_64I_>nHz5R5oGdFm3JA*I(;Xf->Efu%&yt}4k$MXdsZ3*-ryrty!Ma2X zJZmz43Gij?Z6^mZ1{ES7UIxo&Es^;HohM>R-xbQ0b^L9;(^LxT95A?z3YmwvY3iI= z5g;(4+~w#dyNj(mPyz!?=)JHX!lJ3Id`AjkAj62~gn!nY88`8!vL%D6F z447X0H+6ErFdtm~6jrm$4apm%mg~^%29F^}Y-Z+*aiTlsPEwX5nAFj07zz%O4zaWy z-x?m)%_gOY9@nnNmk$)F$5XZ1M`?WhYWq`*}x*_)IY-<4mYPS3rr9oykhyl@_` zL4ZNM2N+a)=`t*&pv|`R!<5-@@;GlJt)FWf-@c4911X1wb;;%4d!VNA|09<>VJ!wP zqr>zC72stxxgCZX8zdX54=~5%VtM zwIQz+drO(F6Q=2%R7{ugoD6LIlW~gy!bRy;OYT6K*d#is=1A*tdnN(F%fn$$=Ypn! zArsB4cb2w1LI-~}%un;Mgl#I~@$-}o97;K0OZl`~=^#SMpsWfM+L@Rcmn8sFZv4J+ zLWPEt3HZ?+*|AlFLR#KFUbUtI+!<3AlDhY3*NOru5ZFaBo$GDceQZ~?vCj%{Kq+p3 zk*^JY#$8+=cVND69-ODwfmk&hWL{f((hFYys=hSZJU%678~n?w&iSV&L@}Yjd64&q zT)9~ChwpbGw&n1jR;$UaWh%Dr?>oA6lkG&)oq+iw+m1EC@kaNi<^%3mJdLzaJQRkg z5og;YkL-g32OGzcPak*lgvPvbP9NmqlJpF3cV0-dINHcGu)e-NIPB*0$h9xTMj_eu zbhp?vOhwO+rIGIG_Ae4lP&>CDy(aNy`Yy8`AwT3#D_-m%yFEUVRpyas0k57v%%5^X zs3fbt*J-fw(g>N8Qw#J~Sc_Ay#^S-0BYr8(*i<%6zy_EvbUoYS>zBP+(??E#cQ)$h z(_7D;fOpnr_BLXj-Rm>UXu?J_$GFc-N6%9FCQA7FbyAg!LcA5Y+R|&eUFXrUetv{E z%vw@ZW0u=850*1ron7SS{06b{pvdi^3k^vf`M&7w@G1jZm{7SCSXAti_^a^B>652j zsjp*>B)z?Ezx3r*koNXO-l_EkINpE$0Cbr#+ zjGPQBfTdabdLem#}y3Ve*K+2?z_|4-*Ww)a5;{*H( zu?v!arW5SO9SbjjE;~K*OZ1MVu|Wng#@X4bC8D)OqnEl+5{VSLH7Y0RJEA|he$|*p z{mku1Xfzyj!=6OrD7kD7f>P4Dl14uTr9?-o-FiOaib0Q4UOB&o<{*v>DSUD#_0432 z_j2{9+C=v4*D!1JRZUhw_LYW^QJk%4?RE-)t1HqH{CjAMrw(wLtF-13I@&V6exenI z2z0r!H713<6;wj_J{Hh)zGw*~tCxa)6JaAn#AJOjvffX8^ZA|5MCSIbmCH6~oNKuhnd>Z1xa>43Vad{Jw`;)$g!NssDm3m@lK{U@p zsL~lFTS@sFene4x-*-Q8%<8R{Ae5~jA~d_1+byQ8l0Ch164W59MWS^bC0NzXf74l- z!YE3C9S9qO|NL|Oj>gUF#(m!S#HT}tku^XqwQk4nVK2X*FBoW6BkecVqMW*Lx zMJU$9ZpNfQ;iA(C0dVT$n!q+eyxR>D-9Q*IkQ<+_@$7je z3#ovObUR<7v(_;?jSz{ZlAS%QiqKKN!zIwHW-xTBfOU%nX_MHN}rJxy3OXU#% z%=WJS!GOS8oeFPazm=|K|M$@`E{~v3s|KI3G!KQ94@Sp^@pvEWP?{;!g5$&qK~Yg+ z$iyZWCL&~Mh;cYHyF)uuIkXVKq3d?-!K-x}F4<5u(E-Jf8gfmwKXrv*m;8Rpw9nfn zsN9N$!Piar!rq9?18CtyifSs+&mfI+0T{7%y$^ONRtaS_YMU|`aMuNtjk$1>g@*RT zu~ibf|Fu68Gx|9al5tg`%vZLqPnm#tWvgbt4H`%k^yWvjHxw*J`m?ly{dj}}r=$BE zd(3*}{j28ZhdQAR-!{3^iMTUBm38a(Rjzwz0>D;c%9VNQ@# z*EMZR@`p+;gX)B}LVsnOyk;%5Qjq$0&vttPJP_w@FiSrHYp5qI`+Zq#9gIqNM2aOF zKH+hXt(CvIfJE*|g-3)7-oN>p30Bq1<``T|dZ-tdn0Kl#7x%#V12o6a!?uoTn2h>V z*{J5BM;yg8Z_UlPFa1=A>_D@tti7~WR+y}}DlP*hZ>x8=HfmD z``4rufZf*ule9>Z7bodB!=O6meHe`tfz`Z_`^OmA^2P}T@Air9PNBRN?M&%flI5VE zC?>`F^D5H}k!W?0J)~45K{gI6rM*tno-zqVX&H<_73kQy% zgFbmYbbVvQP6oX6rJ&=GJixvPRh)w+u-_Xm}U8_Q8S5f8QA0<{h`(ThA$ zfr}GgmZ9ZH3Y;YJW>8u2>^w;R3^{t5ZH-f0 z1yE69RjUiyr6r)`RM`gMjds>;)P7i_XJ!=_<7`*`Tl!?O|HL`9KuU~s_Co%yVcZs4R`%4!3LcU4&2C??p@fJ5~-S4EfKmV|IrwHX<=a={tD>9J$kIK z#zqGeS-$!d;pY~1Il#GLeP}T(4*`sh+t_UT-GsaA6IDOD10BEcTSfFpY>dWW_fvKI zhIm0uuKR14&M?Rl?u>o=t_yY{q(NWl*Ht-*=IZDfM6QxM`fksDL-*(6m}USHTOk9} z?N)@PuDWM{$F6g+e;-UqPdG1jp}qy%C$OC&J{?8Uo|lKNW6T34pu;k;zD;ueiuKnA z9=fnhLqf&~l0lfmPBn+onE?{qdjY}#0Ek=Kn!7GC>Ivk)tWrZw^LtY{ZhB-NZ2pwln zUD6xWjXzWI?-WG(rugNOH!4uMK-)MdM0_*yl{VoNNZli}&f1%z@Su+5L0cPkJAe7= zkcAwBuaj-Z-^E7z7_9+~&i~&8L%J>QJIg8%7N`d@Vo?Tr|%r%u_L}3kVE;a&lb8_peerC zBOTR9P?{Kib6}z|IfEt_hVYg$-J5n516uNtj2fru%H=;N4le-j4`k^d>W1aO{U}4W z0oI*F#xm!>D{h*7_3sHDL6>uf(s6SZGfa}oCjKy?Yezl+d(^l6VA@Hj-ThUiV31~f zzxRsF3@*B5(hj`%CiNY%Z&1lQ`l#3UpvEehus{_4z=7Y^^E*%l0Svn#$$^)yy^R6c zNGsIl`>9o!#QH6hO3K3N;o5>b0B$A2y5-APEJfsnwVMmR)=-@Ew6270K3#d-1BUbJ zVw!(7<#S~b!U|G4H6NY)Me$P!RGrnKfCVtO)mzwT%4Qr}zQx3I849tgI0aeLy)mj7 zP*#e3a))Vm8-UqR^AzTCx9>0sU$2P?i{aEDO_{liiE1svrGywBK2eLJN0Q17N{-!{ z(J2z&D&8sJ+#^Zv#V?l0^r;Iq*K%a}qo|{L-K|6w8&Q)QovB=u-P=nl>!hzRcmP$A z!FQf$zSjk;0HX;TAWtr<(-lBf;7~#8R|a4*0P~h~cQ`%;he!8>jynkxfyexjb^04` zWVYW-kFw&KHX(|ek+J`{cz|aEaFpK8a8XgzU+gEi?%~C$^#s;J?02dEoyRiHLI{L@ zn8ak#F|YbsO)q7obLoDZ>AXbPIk5{PD-Mur7p^zwSHojduUxP_`{~9*t;f=!No-wZ z@MKI^O`l|Bn~@5__{6<)^~HmAQK}8#(9*p|z5$dCkFqEx(>VuYA#lGv=g+Th*teBS z@^W794E=Z&&x408E^fvqTj8uc_2cqhN4d;*LPZ_q{i+LIpSpZ~)yAOMXh5&|V|ZS|(+PQIYMCFn*0SI3ZJQuk&{)_`;yj^s0OZ?^aI^6*cY5FK&-0W^oUP@;orgY;Aq2biF{AZPk)Zrv zXs7E4v5i&P3#}n=JM?rQf$9JDEUMYm{GgUj(K17W{);UyiyiTAq$*wXDoSydcei;k zkv9HSz%OcO8^3i{I@aaO8EEekopI4cWu%($_Nrgh)=H4n{f#yIfx(KjJO6j=2S_`e zn`I#9HY~VI}-$uUOU%3VhAMqES;#{_}#A<)HH5wEoM~j}| zvZXut1W-|E>UlY=;aX zZhsfXsy+eO_MtV-CoS~DzOZAc%vY0ZfwTyT>-@95&{zQcyzbYxyWQzPr6N8o3~(9z zcS4|hn8H3WK&KzG`-hJnA%0{AHeLL?`Oh?9L2ijB_XbxP0Kh7+JN)i~=RATw_xwlr z$7vz`bnz2h=i;vz2})`RI((bI*`f@7{hm#9*_Z{JiobY;5L`sepVY@9h4~gSCG*F&}0GE>jJB(%{L* zx#Pk=9@wXsO}cSOQ{X#jpJn4pdfeY{THwi(vX8X=r`h~e1BD$5{{jAK+|s=Xy>U1E FzW@MsyJr9Z literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg deleted file mode 100644 index 00802b074cdd7..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg +++ /dev/null @@ -1,296 +0,0 @@ - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - -
-
-
- road shoulder -
-
-
-
- road shoulder -
-
- - - - - - -
-
-
- center line -
-
-
-
- center line -
-
- - - - - - - -
-
-
- threshold_distance_object_is_on_center -
-
-
-
- thresh... -
-
- - - - - - - -
-
-
- Object -
-
-
-
- Object -
-
- - - - -
-
-
- object -
- center -
-
-
-
- object... -
-
- - - - - - - -
-
-
- shiftable_length -
-
-
-
- shiftable_l... -
-
- - - - -
-
-
- shift_length -
-
-
-
- shift_length -
-
- - - - -
-
-
- ego lane -
-
-
-
- ego lane -
-
- - - - - - - -
-
-
- detection_area_left_expand_dist -
-
-
-
- detection_a... -
-
- - - - - - - - -
-
-
- object_check_forward_distance -
-
-
-
- object... -
-
- - - - -
-
-
- object_check_backward_distance -
-
-
-
- object... -
-
- - - - - - - - -
-
-
- detection area -
-
-
-
- detect... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/limit_shift_length.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/limit_shift_length.png new file mode 100644 index 0000000000000000000000000000000000000000..0cb9eb893943ca2951ab8530a8ca6a7acefa27db GIT binary patch literal 121671 zcmeGF2VB(G(m#$XYAjfTii(KFV5jW@3nERLC<`JTM5MX2W$DW<3rOq*h#`uIh{h-u z5D^8DY5_zPR6tb9A|O?ow3Ygs^V!7!yGis(o_n9~|8MSn-LRi>&YYP!Gw&(qbB}D- z)tWV9$&3jTCd|^_qP}CogsF@P6DA*=_8nY#V9V5pe@*nbN)(@id|<-O9(yOP*%nEUnLe#*5}=&whqPp^#i)Ml`0Utu_3K zF;0qo#fIWxXYawj1f<|Z@fxC%s_-cKFJ6tqTKM5=4P;|)ifZ6RPIt6_iO zL^sQE26f~xe%n?VD;GPw={B)#_HO#_w)QsahU4cLnThPHIfz7aGyc~h=I@UJ! zF54-dj$Z5yWJB@tqL5)1yPzAJt!{T^#?7hu=t5ma3qNoebN zQQY9FwWk|fFZMY4BBQbyn^1M+Dr^+?6*QE!mo-=yHbpp1Pal#fZnG~Lc&xU4i!RQb zwprT7#Mj%F?j~)c<>GBkmvpq=vP05Vo#LZ|x5L}fWbj0qjE^nZ)`w{5ETd;2&wh@k zO|sXL^0aX!%4?GyB<;4S%IeVM;SF1FJ37(Z2EWx+hptT}s;m0g;>}&P9XI2wO^osS zWO?cB2HI3@byX74P(wz?Ngt=Ju1|&gZszKej)q#AGUldR_YfVmfzIt(J6z0NiRiB_ zx{~%LzAoDxWt?ob5WR?|UQR$SRmXI*gPj&h*3NXR=QcH6?3%5Xrlhr+GhvSb=UG=T zvbBk?ryg0x$A)b5$8|@lw;9ftu4AZ6u*L77+2FifbWH8s%(v{I=s9hs+N*oX>yULl zZE2Epdz`tOjTTi_o32eKnwZguaBsVsJl$@Ki>JAvv>c4%W~+(OLb5i|2cGD9TAOaB znwjpPXgf*E*^-T&?9?_>%uQTet+&8^Cv44lYm*(4*065ig_MqyhA;2|@yA=&K$`?( zI@sb7e=!w$qqX2c{Lohx3Jd;^U!si zjNrF3(1T=w{wB$5J4#Cd9WaX~-4^tL%_E|t4jtBk@piNGc7v^6L_<|c9Vcf`qLZq( zt_jIYmnKaknwohLO-OhhCv9IlCrxV`14&<9HEBtr0hMa4Cdt0;DCujhZtG2S(!>#s z-Mn-RHDDZlUmf+$6dgnMbsa-Z3THfD6S5@CrSGk)uHi}4`tQ#3r+nd(?-%eHxp>=c0WEQY9R-rpGf;)yMfBD+)Fu%P zq^U$lRU~Dawz`HlQ5~+)uxEUUh9uyq8TW6x8R9g&t4h~(M3PhWh4FA8AreuIeGS{a zbX)dwpLa14q^l3lYWV6INK5KEs?uOy8SGh%E-sB8S*4o1>vkuqk2&a<4jyb0T^e~5 z{ATcfUe=DT7#u)0jbnhpsM>S9F%J`uUHWT3^M|+5vIp?vRlQc_ZU#NTl| zJPrrf2=G56|8Q^*^$+JskmEQ{hf$6bCo3&3!+{3Y9G^}4JR@=@U*gx`8ID{0>s28* zI?j7?==AvumxcKq445JgQym<=>^o;zeh<-N{%2e zF3oZ3qopP#i4(_3v!DO3NR2c1UrFu%WuWmF0K-X@N<>bTYzvOa+|At7PR#}n4hfky zHC10-CueUxbudGQw#Zo`C-t?UVGIx$ar%0WL>iH_!Vh{rTmevL5ql;)XL^Nv900w};-z<&h z(Nl+K)j`U<$EBH@=t^pD*+DZik)fNDSSqflIa4GIle^IY=VfV2uEuHjjc^M1UX2MPtwhK@=HXHN;QEYYlLo zJZN*o*8D}Z>8VN6zyV4kXRE9BZ_;MutxM-2k1wZ920((OE;w><(sW&ef0H)Yore0{ zGW~Meq<}V{PnD)?=nVQjnl=q-qM9>|?cicG?QVtIdYBZ1^T=OV;$Z#hF96BPp-#%GN)C!II_%BwyGE zFdhIXOwVoIw6|>av18wp`D)q#&SJd6XtRYqr-AhIe@YvKBdXqdAX6gfvEIKaQ##lk z*u&#M=twBCWvh!BUZ2F-nPdq1yud8SL*i5s*@4)Wq z8LGO$sz(Jy$l7Rw#6AZozOaL62q4>I)(Hg)&XVvB3X-IeChKv7=dYs<^g;s<)B#vE zqy3xI0eHqC`}a?Hhcucf1&|snyuReWNF8XbG+5|=NF4xvBT1kRq@s=cH>pFu<1h41 z%hwG8dC&=MwCky0y`?Z6QOADcz_NjN`0RN`-N!r;geP3<2CIPu*JDPurRq4@qJ4?^ zV4@*rLy-1izEYPCVJ~}!ji}o@0_KSDEo*}{( zBeq-vbOYHrE-8N1&esO%8sW9oBx&HSArK$!ZN3&kI0GKl#((B4Br$a9f8z2qTTT&JCTF3Nf^o|0wRah4p4?g0#cYA$B-*#+o*tw07Y@_jPdpjvpr^DYi$3p zXNG_w)In?6_6&TNG#**easG?vNF?w8W(eK0E#ugc5K_nSu;wEpeF2KlRo4c2kRb9i zLpB*d+Slk9e(i2G0&l84!hOK~Y#cdmonK>15K2;a2I`Ce;~2^Oo791Pc}d}`s6%!h z5_*P4upjluAh3VPJ88f;Qh$#kzIh&sB3u@BX1=kagsRbH0jqkT9l0g4mFV#ZLbs??9sg-~BWH zjS2;Z$RZHI_nJxni_~HGk%tZa8r~Tqog+ftLI2;h1~|aQI370nD<}iKkVYwe@NOVo zjnPr8*Vo2lx==zO{t;oL)&6OOJvs}eOGl*$tnh@8Gai*GkQHHPvy8yPlaLMIiF!wm z1708Y4fZVNcSiljvP`-oe(1|kIXeS{WvdVhXUCZ+TlF{Nd`U*g7x<3iI7zS?V=OS} z@Kccl%?lx`{YMN1s6tPjM@%_7KKtt&>4?@LEC=3TbcFNO z`84G3Fipd9q=rzUcKVwL=gVlrgH4mt9TR8senq! z{82LfuarP#I9&RR!u9`OmOv#T$&aPOu^uC5Uk7^=W11-h-cXElHa9V+!@oy*k~qCh zngnyQi>Hmco3{;4#zhaW3+Z`z4|79`6F@*Hv}j9xzGff=rOq8Lwq!`Jnz%^nL26YG zFDVB-8SLIG)T5zgOtytS4d@%gO0PzozA00jixZ4Ly61?7Qubh&A-$$evUSCZFer$J zBw9!T!dP zAVuKd1dtaJ!Bnaa>ePXLIii!9Cvt>94_?oN3ZTM_u7h>#03W`bCU{R(#zq|_uTX($ z2bu>uct+9Vq>tCZ?n7X#Zbw0m(+uFap1Q3kQ4P&&O9wikcu9q@3XGe z`X#qx4b@l|)PKTZ$jD1VGmNbK=YPg{51cd(`k#2T&_HL66vwZO_8+nw=ks529UL;h zbt{8)ncG|69;Bq86 z?rG~^cib3Kp?!FVjE$BN8%K>eIah5h7u1Am$fnGAkF|-e4>ThqN63lCx1ufp6rG{Y z7#c#kV7R4`Ga8+b1S5`&%jeDz_I8D?kUty)uV&m4L$HP2@{3xRZ49w$Etpq`KMc*G z@{P>8F?7>l?gBIQdg>%kFvpPpLZ+4^jm*EEx&xNiA(Dyk4CJ{D^}WVCV~C!C_Yn0O zB;Uo0`^i^dp#3}_$|jap@~$|BqFb64y?Q>E)>3$57DqlHys zu+g-1k(Oa~PE5lvcr&gBjK%B!SK3?g(s0BFfIm)3iXbaZ;PgL!?v<301B*V=<_ZT} z*nVJi&>)S6u1OpRppUWocyT;|bN#Up%ZQPu6C;E_&pqHz4{;fc zD!8YPjxVCOv772h8rUyiM=$gmMm_vJ>Mi*7$4ltP$UE$i&)#m_Hv~K>-X7SoK)BC| zw7jf6NbrRV>>~`Ew40mtABXM#rzbH-MVm65OycM`bL5(by$k5P&)6>=@CrQt`q(7< zFz6pgLbp>K;nN$R&x6Xy%R<1+SukP|EFXu*NqtuGkr~ET`tuoZD5)`C zMxz+@b@SliJ1LrMmVC+bvB%+SAtMKS|N0%y)7U}Xzk8DFJg*dIJN$20tiLcqwl3D5 zo{qMd4FlW6u~pm$f=Ao5u?A2IG>L7R{(%t#$AW$O#{RP*la|2@;Gdc@^yGGX4@WrT zJ?;?sUz#^gNn^Bm;{+T3zh~ZL!N$mp_2D@9#0{5?`S;D6j0~KrA3wDeSlbc!Fk+4V zZ<{xs%NWhUuQNV>YUE_37zd6Jp zGl+ik`UJu#SdP#bdll%TK>vH+uYfdY~sTd8k zqycICH}m=6G%&G`)`cA!8oHnf22kr)g)f?o(~3W&h@|p2AF~)OR3sfPq5jEtE&dxq zmB!17%l+{Il5s+n`jhhfh^$8obp(2i7}x*k_ee%Q7&l6yJ2YT(|2O2RsVONbs|Io( zCC~q0>?|XL7nk{?(l$<__`k2i{ofNV2R4loF4qSA+Yh3RJTUfqXQRygNZTLTmxMmg zCvIa6$W+{p;_8k30rr(XXh|6#ZU4=uYB+Z0f7dX}$`N1>v#0uOjsd`8Mr@Qh9*J*9 z@7j@T|D9dSp>dR8AuWQ%`S3kSYxoGzcsu-G^Ul)$DK{%EN5Db3d#p6^viQ&7b(BEy z@EIsx1@r%qf5pJwpL~6BBzFDdOP8Z#Qta-?7dP2AI4__Npt5rVvd6=eCQMj90Y39( z=)3Df1+D9(QMz)wo_y`(%cp*8AmaomvoD-aE-rrlu}(s{I0I)WXbrORwE%Ac`$`b#liG=Eg#aY2s_@&(}gIMY)WBY^}s%O*}MvFwwdF>Lx_fT_YsKF|o1{-0E)hc@@ zOyt8x9QorWBZx4a5guwc8QmzhQmKlhhEB=&)T37wNoh0G9eM8ao7-ni45G;Nou7fm z*|K4IJF$H4FZuk8ZG5ZFinkLFQyj-m051laPn*VYexVt;9R0Y($H%<&lVd$Uqo^<3 z%(BWtvv4QZD--$V@ma;NCs*H}MQF2K-u^5(kdMjmi}B!kI>-qoxc*|Q5wL2niVYB0 z{oSuScU4(@FZs?Zh_acnO#n?jX6eP7RjMqG$-c$b{p*6ctWyhg6s)QuUu8aR;$!0I zb>DNnGPivziNqdeJ}e?_&QDnc=FoITXG_$R>1gUPGhACyb?`sIs9lX8W@3{E!HOb# zRp+wm%9MjB8R-V{V-}3@MrLw(dz_|-p(>*F$dt($M})R}(1Ix1S^JBoWK8c6BaU4J zDBpH|;HTJI2LYrv+l_&1#*!_JAd2}g?m9mszae59*DESn>!YIBlWzyfbSg~)!S$~O z2~yW_>)@4xdxbJe8uqP2n!Y??Zx+FQ(pGVacCqQF-R@-(R%Be_X0FqUk&>IZC3P*le}OJBYGa(Ubd?X}*^d@oX8*fE86vRRs+no(!t4`+m%pz@90Y z>-I2tiU0N~Xc<2)oXc9}s*?A9N`~k}0bN1Xsz=Gv+{_i5JUQcz!$l&-X)~C^?EdY} zDH)D~`LW{dVi!r`T(3-+81Lot9a{HZ6jeb-Y_u2+^ASduQ%k)~nxwWic(Z2Q9RpQdA(wy4)?1crPpY__-AB zS0<;ue6yIn#b8B*wtatN5AMFR2v)j+smJ&H(-;DT^R*xOn7{0u9>dQNsJ1x6&D@2+ zPxIR^R$-iu1+K;Je*1}!d3(s-7*_KFAI|m4-n}Lp6((V{o`)6H`Oih#^cRMc@Xbhl zGg9A-6qm*MW~3&6Gg9A>)Hfu>LG~)&kkmIM^$kh!jEld8d*8ynZ{gmUWDBH!zJ+^} zr+v#wealIWPmO*;jUA6yhCbq#NSo_f zUm!L_YrGV`b?XL2|4R!@jw|{1=bZ8HUl=%hk>v7&AMQEF-g>f5*y?)J)ESI2ef%Nr ze14WP)FN~zVPzV(hlGCo&)cf{pYNNKV`O5vfWY)JnAd)}FZNc`wS?vysX6ETS{IAF z4d^$tpWi%#5%$r7N5$qlC@L(Gez6cMDx^W3>-{VPr3+0#Z5Kn8mRKp&pFQneAGJ2( zR7%e&3)jWDp+bU_rq0&c5t&7po~prJ!*co&%3k_-@&QEqTfw=kB#Oy_2%}jHp?K$W zZcSI+2X8xWlZ;EqS<;aZ8o0^ljeWRj;J#Tlad%!F4H)d}Ui7|5Pg%H7v3KXdr^3LH zGS_q&*R*#BSz-Y)sp@Z6o0F}twajdPEWdJFKyPZzw%nxxY6oX(7f?%M%{qcT3xll& zss)cZHKx{`aW5#%Sg6o?*EYUnb$g496aTz1%80~JYzXznqMWx2(U04!mba6iU3a>8 zeIaWXJx|m<=h2a4rz?AUl5?eC8o$;%CM69vb;lP=H6F)TXAU)IE-dkReBn?|c*el{ zU002&%GN(!xPm+T3?;|poM(4r5O{LfrBYRvX0$-dcy0S&qmfBA%e`iy6nUVsS1zZ< zbfgy`=YXJP@x^!-@v<;lXI=J{eRD!`;%W~>ON1;Fwhh^I>%+xxs3oWF{9zIj{5bxl zUD%sdI+0DsycJONTVyEOPM&;OZI0aXg&Rz_@14D5lbkrKm1^5vViLcpeVau3{NaGE z7gDx;T^e`J^#@btXUdd^i3Cyfn&`5avW}iZg#abj)C>7NThP4uP}vp_zw&a@wYjW< z2>j}vx1NQk`ycQhDCw{4&A40rWWDW4Bjc;LE2^{8`4$jalhk!3<$$cvf=F@5?YQV>Q4L_B^*oTyehJf^p^6lyVTU z-S0CQB7PqdUU!NlTbWpp@7!$(QTUC*%%JVleDu>4ew+F^fpX^p`WkH{1b2DqyJS9` z{e=^N?uL+-+gJJBr)CJ$2Mjh(X;$iQ6^hY2YbsPtIqT=js2}J&HaJsQc0-28OKo9h zT6+>czbkRIB{Lw?1X$WAZ{>Z6bsH zy%gF|wLm~;vz1`x`!ZH+YU@4s+*q?q=aOUd_?RJK^ySR+3h04Q>fwH8s9MlPOJ@(et^5M?t+^y^5ig9(wfZ{LfNenqM+KNe8dnZcymXU1> z(|eBQ^!g|%FdEc4p5hDV8^l-!`n$mPP3k;d8U@O*Cgu>gnel=xnam&QnvVo|^EN6l z8=P3zp59jJXIp!C-jvE$78K#|VOFk~s_cUbZPM9!iDh^5%3f}sr_ruJ?`o(nG*;3Q z@ir{?eK;%oSI>-|JFMCmrIIII??V>A_Io@5sqg4b3OkdsW_i1}3U*mV9qpX&uJSQ0 zTvJ4I7#+u^RD$-dEKsUHdwID~JlS<}y2)@?%(h@k+EH42)%}Eb2Za^}CO7V#_##;^ z`tmsizn%{^J8M1_#ps2uu77Igv}&C2|SeT{Kj!^)7u^2ZJ& z`1f@kIWcwFB9XEAw{v!H-nE`${Ib*QpvTOgYfH(H;Z}(5n zt_j`P*C01=c;%_oT;uPiF)Uu-P9dK*mP=VL`Jf93E8>GqOH`f&9LfvdwM0NqIlaCA ziT3L3=hhD^pWkwC_8EAckUgtBhh+U+!KU`H!~UC!pFX{!)n|(;4_H5qBv4-9f+I8h zTGD$xoLwgu2Nw#?-nb@2VTcuSYV8;5gvrKw|8=00%4w`>InS5B^R@jRrWZ1)vdTL* zxRekoq~J5J>vE*)66R0=^-RDWkJTHCr=8K7DYP(DvFG(~xxqrp8FwuQ=+PFWg5wY8 zD8#awbMEG_bOR=5L=|^!7{BxhL9X-XvV3eyTOtr&PJNH|#F}f%ShBlnHhHkxH3)t} z@vg4rH(DAk(&I}@5^_aE4B|8BFRTKa2RdyZ|GXl9sW=#(;aMfzJsYUa%VKz0*$TvQ zX=pql^Id(Qc5Nw3*0p3dU`MqX`R{=newAj(JMwIfDulvB$R zg8m!fx!4M-2uMsuvl&`5MV2MDrN&FTrsaHknJ>Q0C$Tq>Kxf^wb|3!mCOfc|nHl)> zZuhH81<*v*Kdk7&J@ENDu%l-PuX~VEoR^O-^Vi?3%k* zq=P6%_kN$vV>Dz5H!j9DMHYp%C-A##i&!CwL#)&E?vev7w|1S}DcY57rKsr8UUi!B z#-5M4PG*bPxIKilrxF}ovoG5K1yOoP=Z^-pRgsg9wLBmd5ko)7OcaPKdi&{J6Xvcsp-MYHZlY7L~piCsig_6MolyLsDf)| z`W4R(Au#$+l68Z)2eTAk-rn+Y((ZnAt9^LNz(Gpo>I+UmZEvgwopyS?J20hbBgN06 z+`G5pxZD%@lDd&BXQv$7Nv*UGXBA8lG<-#Sa5W|;R6LWR?++_a+G@?sQ_N6ooIi>@dR6L^ zYu9rI=WLq0KJNAo(KzL_hqF8Cm50r$Eb>~{9Ob4419DO9{R~}JLo*E(+sPBGd|zlJ z49-?CEa+1X>`i6Wu2xD=w}gJQ8^jqujIsut@!Ic!={~d%`-Pcq`NSa(A|{a z@k%gYxZl0t4T+zzzI5>vZht)2K^Jh}*)V;yknNs9CmtTmwM^V2b|)XAnCw`;wyU37 zJDIy?2eoMmk>@8rJ*_YQ;hox{oWWkEM0?y$(tLFu=0qO0qo=MWnoZ>y1bQ^W-6uh9 z_nL1A=_wC-O=Q$OBjhSDKNURLT^LD_ND|s42WWh5Fmv%x*}x|a@~+065ewJu=fN)z z7%X2DhfR4;6|{mHetjvcHL1+iz4IACFpIO(O&5O~HERx7@z#^0D@} zb49Clj|=F@T|nBab8P-*ZYJzbfpOk{zZer(#c~jDYCc$N35YgoZmP`@+goZzin`l; zu4!OZmy%zbaAsdg{L!~JG9gBMl&idpA;_v59NyQ&1E_BUfmseFSs*j!D-5iz)Vc`l zy%e@OcmH&OYNRuKw4AtP&EcWJuzkaWZGoXd7G$G=fVQUV@ynD08!o)|3L{R=$Wyq; z3oXR~LbT|_VSRf}>k!=uMspbP={;{*$|k$amIt;pTZQT|ss-}y2Mz&9d|v2(<4TQM z8AU{JuxctFv({3dTXGYEUV-T1A|tRyL>X|nbrr?ere*}PYD8*&7tq`Av)1vYi))5E zEK=5%1iHP@=qO1nShtl`-S9#R;)5v}YlUpcJnS|Z9Aepid@!1^NfZ$q4a73Y2u{3+VQL1%!=ovscg zlbH9*T!mJ`e(i5fPu`n>!o+;BWSxUU#RhuW1tLRk2}7xs-8b&O6CwCd$;dOevF61F z2nfqA<4<60fXv0S)JU)btE0Vk?Cc1Op8uQ_?WxOf3RV2&0^z56%?TB(4{7=09Z~$^ zYclv5VRs%q;IS#*f=f&yl72wQrC1y7HG=0fM&^*n@I2tF%eD;sqLO}KqEQr?QEE7}L&Wees;gsn1~ z-N!#wcz&*MAoSXLMCs2(laGb-L3Pk6`%HeZ2HJ8m00QbNs+RIGA@Cvc zviZ!fR2InU1>YZ@W;}J~qPc**h`6qt>z9P$PrEWM4}KsebmRyLe(jL_3pX4N6qY={ zH=s1Nasi>-%K+CU!5Hdv@3o{ZXx59C$IF(xJ*-a6BA9L4z@76@IZp=tDDzr{qI;Dn z)F4eYs46puPVzX~V(#{NmGe(vgRP@#k&(_kcZMIkF1DUH0FNik_-xX~Dul{OFiS?Q zA#c&;^QACHx@N^n{^<-0+XbwoI(zQk^9e!gV6$B>7rukJw|Lmce!=&&7Jko4%2@|V zvwR0Gm7U0E1bfLiMZsw$+WNZ$=CXR0c!zHIv7H^ttGdyk_L~-7w$zwZS zxdq|)lL~zyv@yEQz>m@^es&iC!9@=h$5eOZib(YIT~+KkJWKZV@?C!2B`m<6CIiXT z^kz%vN@Zre|w0tLF{W*viKhA@L z2-a<{e?t*g=wbn(%--}4@Si#1AxigNd!BSf9;9vXjhic2M0PY zi?s}_RF7Q36r^Lzr-Dw;wxka(fz;}35!nr`(Tb^SSTFO!Y}+CI0tu>WtEn^B3|XAy zV>aSRIR}MYO^fd|u8N!=ID^qSG_2aqtt%Da_*!lRl!+n2(?SrJF0N=N#|0kCd}#*y z6~$A(K&9f$wTjgc^Rz+nwO=bFT>)L$`gOXp0v?YA)}|fjJ`%BfyFIM-Wa>p(v?m&5 z;77cE@8iwzxapMti<|g~Si66rU!_1P(@ibZRJs!?5*yd-si2Xhx=t;|+guEmU6(<* zm$xcAdf#_*Lh`~bjTxEVbx-96ZazHPwsOuU$(&#j=F{(qp%Kb~0WM0r6YWDpWNm!U z;;c6p72;%pkq$JTv8NmPr^{6!0H@G z)mi|kUgdn`01wl78**{v$O3hwr&q$z4sxxV%hHX&iR$)gJ@#YG(|V+@B@#8$zr$P; ztU+)fIPJIA*68tZ$;L~tl`gS#&}Im_hYU}v9RyE+ZL;S`WZd0*&JC(Q%%T3(YE}bD z?ls;8!KE7sO0Hi=*D}U)Ra86RZx9)-UEL8BGzoavU2Krhc}RI@Y-Zl7$VYdIE-(06 ze;vH{&b-^QN^=xHZi&6ubWQukRM$I3kb^sxfGQN-C>PJi{9QOf4oP(Ex`TRP*)1s% zY*Yq_H1qnFa2jM!3@y)OHrOM)~W6DIf1& z)XbL3T^6}?;N>>)BluOi8=B-kUb$F(SRz2bDl%>TjBx@-qq8e>csyFe`Geql(jv{f zv#4)xJ4(Gjx_(A&VxjzMr8~LH^6rcHRs}8c$(pDk%uf-xo%@sh(}gVyAM)T;G5C9nndDXlw>66{ARyfM?KhI%0IQ@+*0?sDJGXB`O@KI=15-&uTBJRc%N z5MM<+V>n^XV%(1z-b0^G-ghnEbdJ$@Nkfqo(0yI1=WfkcNApzXV9&AjF*#~B%AHQ!=+GQ@%tT&dU?3N~OlxY}F8Ss|BJ?#%sl!9tie>tP zrlKlgcAx+x+U$8H+HUTLYH|>J_wzA76sjzk#2hIGoM?$lu2|SixvBa-RuFPo7HPwS zFIb5kZ@h|#woP|RhZ0>g-&v%bTYH!r17uZ00P2Hzh7 zRjaiO!C}ktbwLtCeh*PeI#HJvi&rJ1N!g&iB-%jRfF7PYUdQL69o z${Ea|!T#Km(w&Lwr_U_OaKBEiZGYF%a4~e@rQ<@%N}9`jtG>6N&M=_n^^G;e7;3MC zbF9t#N6~pLh%(8Claf8qvA5k&+-Ia0VB(~s&y&|h=d6zria+PdkVRR3XrS0}X*%Qj zOEGU=TQ&(qmN!adpu9OPZ{|Hbm<{Ro8TIKsm8rhzo=t`9Ew*7m`lklX<%5~Ze9Ypg zTS`3k1OXKa*f~UYQre@cEX#6$>LE0IZev%JSI%Phyg7k)ue4FR`X7Ln4ENsTG0GVT zA)PCCmtpZ>-QA z0%*LyZP#h37t<{L`taRN*K5)!0r)>V5pqU3re5tkOkx*ZJ(ad$~k|3-?6r+K55skg0oV#SI<;s3NI}}{g znm(;mJ2-zhy(8V7|Lz;Tl~w*-FSL%mgR-?%mw(5n;O!~%dSuU4Jk_cyJN}Cl4?TPd zwyx-n1y%xFhkAduRygQfympNhA?&RUXuIQO_?lW|+M-a<$c zxbR96RDz!LB;D=Cc>W7;YHQM^#@{??A5=laXVX|(>Xma;DANM=I{A9GJhFw(Yh%J{P;XmL)(HN=taQUHvym%Ox*_l9&y zIX!fa;ODS)+>5_Lk@QqG9^+Qi4=CRl#>YI@9G#V1@1lrZ9cx2WR)c;-ZSTU6++%3` ziKOyR$xtkXuO}3~q2tC8h1`uU_*aDs4OmI;=X3=97S3S!-GJ{>oJ;JsLkckthDAZO z$Y=8l41z89gOyZ@&1d!Ogk+H-sX34P`NNwn<$jf4hL=|Q`~VoiHX3Vdb4ui#Y} zj~KxVOlsM5jY2eW&<6w@lO>I+6gW*Q{AsqK3gWXjvZ~TngzFD>7hTQ{&+NKXO_{A+ zeORuk;iAI5+|Owb{Gs4Q%VKm+KY!7^iC2}X0@&rrmkdc6+67AEt|IWAY- z{*eDrVciwUlB=qMhEd=~5!vA<=L%Hb3SW+#QcD|Po>?XK&%ewZ;x_;_;1o|y-?VR>F zWDaPQ~S%9L$W<@ z{Mvk>srBgFOvY0wsivRR=q@6B%w-q5ck|#oWCwk;FOtKMpb>=CoZbN;~l{e2ZKD}2o&&*2JqABudX61+d zZ~5HL0!bw3J%EL9isActM$;L?J;|BbL(p{=syyU-zx!2khD?U%{V6B~aQ&%CaZf*U zSZQ|OK)v9B^x*UN=9v;m01?gMw-6JBTv86E71Ae}oB zALZ`@v&eM7N17IRr}tO1g|u0D>BpxZHLtRWs5#HBo{!etARVyH5wf~(ka9goUxy(n z`t>^+@iPQl13$RuW*1*I2(MbCWTXD!c9CvEw`|#?b=PBGmKkQ#QRK1b*_j35yF9d| zcd4bfCq4{O$RU8bn3C_5(Bs5W0@H#U!=JwlDtAWqRT6Sb=TV;1d6$upWl2`@J89@8 zJq@rBS|;^2WG7`Ww0KljYDsuy?i^?8*K)`9{YjHnxt4s1%%z2c-SHhrQ4#|`ZQImU zwQpNoLczx7M+v#Yf~ey*x74a~(v*yRfsegtWuuqO(LxT84mynN?o8BWWM@Tte-f3f z<%Y|cAt|2q#^3p!G%^X^H%Ccs_A;4uZ^*Vm6#I~UJfcw?^t0}HD`$`4I})%os{2Dr zj1lBt8ajG2htqwdK1NY17bmu+;i1QXDG}b3eZS4D^>p^sSlRyJjCZVAgmTFwruCuM z)`x_v_lfjvM>a=HF|%mjl#Hl_-J7_#l`Ar57P&2Ka|R7C&-!=Qe$Nu$_UR31f?!=i zFwL_*2fB1`7ynF79`xMyEQQoV@2D#slDE%3X?!%pzfT?QJLrR3m73R2kAw+Q;^>#VKP--VAoN-oUI*o?-i49fzarnvz|wd z|L3cKONw&VVzu6l>)|6*n4)>lW|)LHc6g+{m2PBKhjlCrq7?1=j@t;%eQXJa!*6N{ zR=*HNCS||W8?~mTtQ$*;swrZVGlm7C50}^+uuFIFwk9wv7U0i~bu35;vH)CKt!8)b z`CjsbmZO58wkCJ~v_<@9T3@8SR(y4MLFBS%`uQw^_taSKQpwM$u!!E-*P_wT8-IXB zXe|m;{JkKE!ep5}J!Wzy$$y1UXa*nia{5ee2eEwI>j0^y+1@%-EZ^?$Ts~LgQ9iM3 zNJeRybM{tZsGj2US)w#&As`@OPsFCr3*U%or*E^=7V#CeE73zhG@ zVA>LRCUA-u#ibA5|3SdQCFMOX{Cif9=G0iML1E1P+D?M~9F^)!!R*OxI9fn7F!I>F znvV%_q>%?DkoBoCVRw`gv9zavtb2UHxv0`ER^=jAk@IDMtdrg@88aHTZ7o5!Tb?A9 zVUfcC1;(!={q`!TZ7?SLr{rGpJ=L~Fj2*G8E`DNYTW}Bn{_RQMfq2I5dX;2UJGj%? zgOx(JVMVUFpnSu=ZTo#MG0zYQ4Z>wnOVUql85Ybi)=0_ zE0!VV0#cu4@62Tcr+Hlm<*`tpFcGi7>AYBc1$x-aj&yufU{<0rVv1}pDQ_zJ>M;~L z_xpaTXqK&r3w&d56Wi4v^FLUOb05psv8MY>>nlyQRoPF5KQX^vFoe+Ha9Oj=MpyFf zvWSF_lxQb9gEA9BorAYz#_9*!(D#hM#m7Y@QxL!5Q(z4GtvTpi%EbHG1wh)8vQSWy^~ zJWzM!D+hU#)mu1h8OKbsOp{5C>uhFaZyg3PyAI`N<}8$muLKb-xw|VfAb+RR(7>mJ zPkW!8`a~W1#A4j{aaiGU?3P%*4b<=y*#O&CUgo=NZ@zPf!!X+vldLiWq?#-JHm0Ag z_clH6QdRcOV`Jal`_SGYQb-tl`X<44=FwzXMWt@wLep$h%ovX0=5i_w-70LTjJBbd zI&gJfj@_KAo>i%q<%@f>J&9$NLJE(P5{!##4Cc&dU2fgm&FywPP`gT{YB%OmwE*J@ zTkG`vym4xV$Z<1wy@5N9WvRCPtYp*F#*V9SbjpC5#Uo{w0&vi??R*~^{`^WXoFS5{ z{I-Bdgl&wUI<06=$0vohK=VhzZ@da!U62t=PR@?gLa_NHL~F*k#E61M^;x|S-A&5p z1v3#BdHo}-KSvPX=Ur$7XZ-t$%xylshmeASo(eT zAh)X$46LRR464=xpqPA}hZ9xlhw*w^o?>`=397=nUd}Q>sNPtS2jx9Lc}rOY7JA5_ ze(?&Opm<182*lF4?Ak=W77$ojG9HT+oUrDs2tH^+s9bHzqn6J(YergyrY(juIgwQS z6!5-jdN+CW0#3Uv0fioBfexDX$_bPv*)xMN1)6Yo^Jqq&>j2&8Wf@TsXxD6C2@I-y zHlGD;1xojMGCTtq?yrEy7_NyJ9=Y}#!@n_ntj$GsQDA8Uyz(_b;h+kuH*jewUw{BSjCgjS9asmJ{}z&-a&Z4!z#W3ER;x&dcZciL9TPJ z_(5!|cpHmt#{m{agub*b3rAArzk(S&HCZ|eIm|IepWVGIL%G?)X`H6&xXFK$m>Azqs;7|ef^4RX7Rw& zD$6l6IB3AJJJ6CHnw{=$u&JU;oN~OS`eK6X7r&_Y$iE|zkzXt1Nm_gbUnt_AyS+DtPWJ9tG)%YRNr_HF1Y$9`W)$qMLD*|}Ix zHa&lB0`Y^8khEeYca97Q{fP3A70Q@JRGB)tE|X7CUe?iCc=Pt|Q$n%45F?2*;b$MDPb z8G)U>xy8*loaqDAldukfp_EDHXB6sC+rbMf7srAJ_ep01=mS*`j+vkFE9$bSRurO? zzdUKa1kkav+M>dnbj>@9RfqeS~wA9?LvZ)tuel}YLiHPBOtyCly)m9Vr> zsX5m7qw>L=ay|d^jijB+Ce`eHeY3HHe`8Td!fYgh$=AJigt3uQ(kg82@rTlxuOlnePQ8(ml zTGf9ixh^H}&Go1AQ=N4S#c32-aZ4tY9O6#vOyZ$KM08ke^f<|x83Gyk8A3t}SW4X| zlkNH}dc+4;eth`h>>RtzjdUp87%mwlj*;|`!#eQu2INC|=$^_-Ktk}%?Ow}=d`yX< zZI?3#-`ih)ZRzRc^JHqGc4J@V=GBb#tBSaCs_?1-D0QTbkPen=Sb|JweB1uETWvX- zQ!@01OC#|uQT@LT&HJ>==gA2^=F43(*rs@lO}&jyu$NGu51@OypF`#%h!PQb#X6|% z2<7SR-n8Ekb27q&J5RWn-^)mTKAm|qPkNm7MwaL~`U2DC*WZPqdqJ9DY5SWM-lcv> zO@N^SGgcH;rdlI24|&r0L-#t zPG{OPgJ9^=n1j zy05y0r32BuMX>FVCa-cbt@10sPwQ#e_XP2V|IMoCXU3PB{rIE4UXvHHmi3?681tX@mINIZK>tPbs)csP+DI2I_63NU?Q(h3(g8 z%Po%?WN8@%$IRm)J|FN9Nu90cSQ|7dZX!KcgK1~K`YawVT!0s5-?`g?;KKPv_NF3S z!Z@U)&m%J3eFZ`WH8EE#>FKZ$wj^nC2EU;A(<}NHKc*My#x*TtG+mAH=z<15{jy0` zgH36@gKhCwh?EYIg3RU03e7PQLv@Os<&nMXDsuf2-7CX75YzPr3WuL6Qkj zaVq+3chSpke|~5|`I!n$SrQHk4A$Y;O&+zl{;n>IxKEO|8oui(*J` z4^N3uw)Huv_jz z+R>&gWau`@g? z05>LCRVn!Ac+%*tv0j4%cWZAd9&C5T84{-q)sV~@i;sP*E-5W=-qm^LY)_3y$!)(V z4w4+b`5jPCxWb3uWRNY%IuF{^vH(%65JuA7R(jG(*XNDP_TGazL`aA;NwwjHd6~jP zdx9teE{E1)=4Xt8N=Ji@h4R>Oq?@}Bqfiw*hV)>>Q{}-cwcUQRI->0E(x=Z1Y$n`# zSW)DePb8E$PaEWspLRgClYG~xBUrv74$&pR(hY1)*_2q8W5$XRaQ60Vh*>;&ncu3# z!Z5e&wW6yMkNQ9!8XQA9WdAnZC3f-Kz zu&l>{gKcNim=+$jC$wHUPOjiZ77@sDZjCg<$U+^QE%R7D-rnznw3g}CoePVV{_P<3 z@QpK@t75l#JU$RwH()h%dF^G}??>~T;|0!WfFaqSV7(08doBqB`%TX1tb3M!k*35i zqHxi=_m`mNHEtE@Z<-pc>drL}?aEd4;&t?-8@LmfOxlC>amyfcqE)3pZ7tuF)bwBj zqw4k&=8AjHGlDEu+dojyd-l6UtIN?wwzn87!Js`*2awIzJv|i(Ra!>{k{0CG&q!4t zfny(y*Ks@5jmT%{myr|D5^iolKBH7mlOMdb#qKa2>_`}5`Dd4YejbdZc|{1zM<9o@ zzCEt*U|REw+Nps$;;D+XhCI8Ta=VA#zf2eUk@8xBR{zNEsrg`PV18-XaEiwpwUDJJ zTyE;#Doo0A*ZR@VCFS?lR;@6y@=n)l!}s()Hiz~Whxk)JJ}M3>ThMuKpy=Ga49{}A zeYLG^tFIsbz|1u%&{py`F6>>Vj9;AEnq@ol^5!aqMT%tZmA!?+YFSRCvm;vBc63ga z*?6}mwD5%1$(akoe;9hHz54xek?38s1N2KY1c&8Ox3LD9er%3H?elV4u5g9b>`w}e z%&y4V#LO)VeZ&G=CCmx(y#{%^EF`X)=~tB{$IN>e7A+E z6E#0RF3O9K-{Lx;Ral=ro#_|&bF9L(`sNJi>8uQQ!Mo<|E!-4-){j^iUA?Z)@5Ac6 zrt4jE7}T;&@{Pjz(GK&Z+tM5h>(f^=jukzu_uuo0d{iKsi(L=%a z?)`Exu(-3KZZJtt>C@%kr#T+GPO0*HR@xUm)Y9_aK6=ZIl+^m`ndgcH9`z``v)G?6 zc+RwS^>sqK7+*zwp?K+KYKTyL^d=?Ih~(w+AFFEpM0O&|3U(|QW1cWo4B7}evF4ev zeh6AP1i-c%R{Wkd+pTb@>0>RK*|2t9WszUO>hOy5zQvt4HCFHKH~w`xBXrZ9`iiXV z?tZ=1hgx2o&Z71Qhnckgde$T0*2}}SuiAbr6W@4ZLpyoM%5@KSp!*!@eaP!Q$FL;d z0wlTSX^g2XntW?ltwnwJ{3vgij|GG4`zH#mX&2L-n%QNW$82qD>kCOL79Z3TfbUfh*sv! zebxT=2+`%8gA39hQlA{J4ZN|XAT=Y#C%WaA^%>=zZ5g3n%NlZ<-&pme4JY5FPhtkW z9q2L0o9EXZU88w1OsjB9#!y-9e!QPjf2ZItlYHRpQEj6q574Iu2} z-4>ih-RswFxq7v7>hCcPzeudgc6?iT{bd$aLyg>Bea`KUZ>X!g46Z#2FY%`CvE9qC zJl)722~lSmE#=2yLk23~1Lv=XZ}@4qPXjBmWuJPX zd*@M8*3e}>=ET;7(CCPPUW(t*058LjLzBX#*ZlONe<-E4ncy#zQlDT)Tg?b36#LED zqN|8ooYIi+RKt>))qCDDj9+g<@5ASQ52zM5A!bLzp9y`bFD?tA-Ton|`0>ajdx{b(LV;a^H&g zuWL_D4HseU>bzqYALrLcZ$DypDD=m~x*wZ^n`l%D(;zW;HshFlYj;QOJ-;x)xX7i{ zyIIM10!kt&v`s#f~B8`2==LzXhfsM^$_t^oPa7^v++n+FjZAIloXv zha0Y=NYOiA;awSQMmj5}?U$Osmqn%T{8nZ5hl&o$s#W=wSmr53e~2gw5%{HSS<|Ov zfsFTo@2+ser{&viVKWA+dSms0I5;WWl1buYe&5@!H}p$dufnz&bKWS*yM)?R=;zfG zt_n;MO{vPUyZ_+a8N!FCvx#fgwD|Az=oq{->HlNz&!eI4-}rI7q@qHlNJ2#zG1jK;az`O#-&*X;$eLw_7Bto(G#F#w84SZ1%lA3l_q$S`@9#e6bAG?S ze&;xOos*f@bGe?^^|-F*Iyy*SIEF)B2^X*-4j zo+qz7xzRF7EE=@M`RBOgNzNey-3n)(qpS96_#6Y>X!QPo=2HcM7*rHYMo~7$801Fx z1eQ^wj`t#$WuyJ@4Cr%Z=NRPTn&M)f8u4L#UJuupML=g$p0Z-AKZ48LSE~vE(SD@q zWUpHE04}g%lNKken+u$)r|VzaBO_Z)gb#wTvHi)7`16bNJeIw_n7SlI(c)#rBAv^N z9x^#)QN;C!(ciLN`zTI}9odt+b`3 z0jmXgqaCxD&_wW?vkd#{_XGU@f5ZQ;R%ubLvVf1YbR69(q~#oN8a7&SvP3njx621|b8eufKk6KIv!=7us~ zq}BJ(zq;NpLnEv8yD)TvbmX3vN{6jK=Wh$x@WuVUNCZ2bgsrL}&x;OPL96LAONcsJ)}g3C1s^k!>NPpAfp zgt7z>WH4%0IZ#KQ7@0ih@x36KvBU)FO@g}|DV_B)T?ni9U1e3^hT-6H8LlDn`PD*F zQxTS<1i6&J0VlN0rYHJSG`*jBsg_%Z0a?c{wPyKgNaS)-#M2YWr%*PnyhBM6TF&yM zN4r40i{x*0_7BH88XW5i9?Ee~9in*e-~s{f7QiLHIW_#re93QRDvSpJ^UV)G2H@?JkA)}SYA-}V_+Lv8}NU|(M??b<@JeLyK6Vd9s z2PXh2<`Uh&F-AyK`>8c6!tpus32RH8mV@*ZCm=}RK#_|=8qa5n&X(C&=Gyg}9fgkq zdWSf^FP4RZ1`mO&$})xG8mN>+AMY5C>SpHHM+T0>#Dz^CZ9@LIG30v1QZ>)=Mp4E{ z9!||Gv0xg)#6K+suUzb4UD+TzL^{lBI|mf-*rEuP=nI^_*#^f}o}))j6AgQ{m36I$56hZDimY9GF)=iS}*12t2NyKu|oQvHU%U z-&p`?l2s*{yXYAsx{#v0>={+d;^=WP^Y8bJE>9F2p`~4BvIMSllXJYs?z!}n^VcH> zTX%0_+Rbs$x%~5U>#Hu2j4hgv88kLv)`bJoXc<)8+F+sO&{CwD!X$_FLBF2qvgDE9 z<*%4RkWKPx-^#^FrG#(;#o_n^&aVmico=@By`9W_oW~#9%?0b>i{NC?R>|uokP08P z4I+^y0hwcjb*Sb>#rTZ|q#SA@2Q6h#eeY=X`YpFl5IG#4&JTw&Umy%cD51jF23*k6 z4qVGg@lTB$YI*#i^4#T~H(Q4ig-CaGQfj;D%@^^F)rr%U*a#_5^QCXbmjEKs zKPtSmC4*TM87u?dZ_SLfuk%8sLu81vdVZBid7#_ozMiKV&MPW9I+ktuN&sW8+-MeRPjJ(%DBzUfOZ3rd0e5NQ-`PBn&^i|l%1>R_i>pE)?Q&M;aClD z>sCgqb4K*&sL6Y&xV?Xd?qod&4Gct|NRj0uO-k`WhAUo2pcS10P~kjw zetei1h@1~*y0Z(z7zJjfB$Wq4PduGn84kQ+4kxIZ(QM zk!acR!k2x@l)A@%4-PA?qwQ0_5a=>pZPDuI;E$E&W$c65b7S3X@_aiv{@@c+^myqa zF>Z@1^No^hVt%8)GO=T#X25O4Xazz8YvtRdTBLWRqnG^SR}uifPvn###>2omQKSKrR@5 z_j=c*FAP{t8?GT0hFf~1F;MKRx%d|hxHZmka1-I8>R6<_9U=yyu60jp6yH0O$60}of1g}WMz(*hU`l`lsboF#(mBn4*yWToHd*lwl`W_6A#c)@bUnrk|564Z& z;rsmOeb9|%TJ$}y$NZ~mc?VHl!Bn_GIb>xZKZ(39Cjea7K@T@q_40Sx-bxD{P$A!! zVRDgA1I=$P>LzxsPpMIvS6}%ZbI^#s1&Z^DMEy64I=F318EVpAl#)A+CGE;?aJNOR z`+K9^FT6nJwJ~;6Takegis!{Omn0z(mREK9AcyIq1}!1bcU00ZAYkX`GI^3Ynhn!-it&s~8lU=y(@Vob01yp_lA zN(+!FIRQ6WhGG*G>w$pxaLx(n&-aVySPlsA@FYB&Ss_=<>_V+1_*pirl3FBC7%z>Y z(|<5)4*_bSSJBz36J|?kElZ|G=`{HWii9eNN)6CCxw;sCItqVLrXbDiN3NIZzrUy8 zcS8iCqQKdj@}dX@Jd`pgoqqCKq7-SYmu12SM69woWj6YpS?_Nmg{KndLS$to-j*6g z{3(Ar^99%%{fO1AbmC|L2f$aERm?lrPFeDgZ|VTQs+KGrMdUdpr9M~ z1|He|X^jj4oScgOF(}|Y<&Hkbw1b;X#z;hU#tSq#x+MXW5}+WiUwLofgRH!b%BXYM4W{HZl;xO~$z-x9 zhO7D=|HshPJDts+b1RA6u#VmPY5cG!{)EgZdB`R|c2a0=#_a32iS~u*L=4(F!DfJU zS-X@aCKsh%k0UhGet97)CRaXyI<(nw+{g}8RAE86>6>_#%uXBt1v$H#ey<>yIu9hb z4i9J9ddEXbD4cbLnD1EE6c;Dvc)3C!!kge+YNQA41?jE}HR}wwzIi2icA+U%Wo{(& z4ccUAq9b+WJJv^foglYvaL8Ea1y6JpFNofMRBHVA~v(Z?U?I; zp*K_4dL+v128Wqc?yJ>TD*`S7?x56qUE2(WY0>LeKa(~^W@<@MQ0Q^IVPwcZmltfz z`P*@U(*q3SRl{wvRqrg95_!g{_E%1mmBE8@|C9vZA2jwT<<_@eK6a~hvFLS*M=jt^ zrUe8%t64^|KM2HQ5ImOoHdwcn_nQu~9VqvVQUBk(XQW&pYf)%>(d9bde#ra(PQVF! zptG)rux_X3fEYVv3c3^y;eVULyTOGA)Je>Za`h~3yV!M=+KN`6aH!t{DWX0Y1h$IE(baQ=MGx}xVP1({LhgQXqDkb4`X zkb3FGFOQBt>v{3w+pN$j(1h5o`d{o7tl)en4cF!NL^B)0qFHmfhuD*S|J<@9m z5)Hn7$f5P)JE?f-_YK@lr3G}YQ+(dVBmW3QO(8f#v;VTTeo+$9AQY&QMl{YH%1M26^EUwmqcf(EwXMsPy?|{Iu)-cT;+lM(>*=4F(@0+Q{ihf`p@TrXmXz)6y`gqj_^{UN1tQ? zgoCa6!~c%`Uxk_n(yN`YNRfZyz^O{qoh=-~as&;8mpvq*M5ORPzwasf5scei13}EH z;oRkvJ)4_AeJe zVdSl>xlakhSk2Q``?RU!f4DOQ6cq;3{KG7kzIwaeG*K;14}5O;zGHlcMi<{7 z!l8<(ohRl>;Bz�ZA*Wm@*K7`1CU~BHYx5ObINvhZoxDzMKZgLU$m zA^u2=?4+3f*}gcb?F0Gc3>Blho?xR07^oT~`U#8fe->BzCb4o!ofnXqltL(d)9QcT z`u={?1cgy_TMqKH?`XfH;eUT&>yngEB#?6`hBL^<@jq|9x32SNDOlB_ePAS(kY4rf zKW{~qSYRW9U^vmSAzV3oBL{SEI%afypc7Pg(K)>CGj4*1At>T+8Kf4SUiO{5X5Y-Z?@lP)P?`<;c^fEASyZ@ndX3K7p_9Nwf z-w*Q~E*a;QxG)SFoKx^Qfz6Dq++=U0Yx%K^ps z5va&EnVohom3D7D_naJ&Q&r+j7%#ZTP8FlpmLHKx;{i9|T6%gfYsxN&Ka0QCPblZ% z8BJ~zS#5PpYPFeaTbj8A=!$sf1AbFeInW&zEY+VHd@I(iz4>O9Ox;!;uotvd#Qulw z4a?OA70+wRMD_F@fot{eqV{LuLL(?YY3PgOuRKLos6;1?t}-ILBUGD7WWs#!jfw$Rj4bXmF>R_R>w3Ql4ht5d z%K*Q_3MrB)#9SMpyuWtA=_&EZuDXMM2@VQP>27fRF#J?xkA{Tog@n_shM zwcsxP{!2T3#^Nww$^40J;BspGI#7e|PQdRjCw_Fiz$_^ixqvS(@%XqILn|d96O-?f zaRqz_w5Y9S*}QKheO3D!WmvYl@UO2`$M!48=J|T!K)VQWvoxz8+#p*QxDvgbD1b_} z;rwofT?Zg-Q*0=u!u|WsD5g>KRrL9!Ec`fXsM_y(MY&a@LtjQQ}n|M%73 z1-GZxKe3|U{!*N>FV{io-7>c#bz=~G{d%+KDb;3V{X+Cw-r~2uMCP%;BH#bXGuVfv zj^D-jBp8O6eK+O&)&b*w@}Xcy5|AO352Cuph2Y&6&Z^Gf;axWh#k}_LmpKlkwlV>% z%j)EBME~m)Zqi9HC(5WS;AiLLX1|AZzB9ls9avi`)DUrA^FB>&tl$4Y_PLU~*#xOt zoOPH1lSBDZCODo)XXUDlKvq_#TWyDd)yKCM3HI9Cgwmg-Z`=cnHUqc2^PgNLQDjZZ z!Y%p+v9vK#_EU5%%;-NGlXs#zHk+nqJ|#WY&AoB!{~bpt#U*Jij0Nk<@C8|xJk88} zc6Y}a-h$1>Isi@j_*&O(4_`5emS59AWpwRWU<@+9k*`p-lh-6a^cQHn4JhGE6vIAV z7bgzaJ{~LOZaw>MofsTbU7zf$->X95IEzNsFp)H7TbtT+rR6Gzk(mFZA=Cw9h$mZj zQcLTn()dC90)m1&13`nS(H@*!+AHy3pdr3EQtcm&H%-h?*O~h6810f)h>J;+0obS} zoTfLDh2+WJs23M8h-O4=8{na0J@vF9fF-ib#+2K#q|IOOngKM0c_hm;ffshxU094Da)DD=ns4l!kqn|K zwn|{A&|2Tvxf+kwBH6JUjgD~&^G{h@LIW$UXQm^UD#(1Ou^p7lBv9CQW*A%MMI}J- z6W(iySW!{ipPhsEMsSS1Z1YE6m>L_L21HnZ*_%1%EJufN?herV#-o>KhYF3go3*95 zSo7~4QMO&%=uPAkv8t)fkGccX5pO9g^oQ0|y_(t-mZ~2n%ElV)A)5SEl!DeL*^0Lo zSlvRLpEJ`R%dxo{+Qcoz+hhIWz!m&%p6nf=km7J~79NQ=-l9Ex4Y)#7ASqn0|6sX9 zN+UKcruwozno(*Sg~TiMx5&oqanoXNB^=kvq|phCO(JY)8d_H>jAd0_k{B*;LS*7* z3avL1k%YnAiY71f27i*~?1kf+%QOAYU^fDiu)5TZ{s{FwxV};un>^FR7%NTvd|Q9Y z?*0^^QIw%*?K{kQaK-%~VlHD_B=BMvJb+38{SoHkoPTYk9&-*)V8;bF9b>e8Q}eB< z(Yc(Tf#35c(UT=XVyqT(!NDWtu0Mb4m=5fMLL(@h{TooGp7gXo+Vp zmu)Big;Z9k^+lN{&{c3S$VnV@hguJh!9q5Id(63*9R(>E7I}U7?l8f_ID(Zb8D8@#eoDRx+R@L;CpY0O#eC3p?yna>) z-NTd=%9`0Z1~i3ss^p!@0KsYKf#pifB@Xt}RaHVFg!JC^yM`3MLU%)3#e94qYv5u@F<0tC@9@iu&aFd$445K)L<=q2T*V&reB?*E0s5TOQFZ zcW|w)9eUZ?$i64P*!$MvyEWdT!rQJhV!+X|!p)|73V(+)8Mww$QA29dHk2tvJ37-K}(I=#`}ST4PsiK zRZKuKY2&fjL@CUrm_^^e>{+r0=ksfMrI~?(0V%P)DPbd_wTylm;thzxo>U&ctNE>X z5tyq2u2mb0|1RLp7M??hkwv~+Ou)!rwUk5ovfG4Vyn6a|(x$M5ly5jt4pwGoT) zr|Pb@sh+MFM}B+(?%wZf1hpzOw7>$n4@olb{Z$@P&47f@6h?Ml22lr)2VM9zTJ1i7 zy`c?GBnW%%wefz(*n@>O%1*}^PhTvis^#q+6m`ZgVH{rwSteZ88MFd&vj{up=Q>y| zNirWbUR`dc#hf*7_Tpt%K&rRkyK2{}1Uc2^ufc*$BV-nO2Z@27AuuQL@r{c38t4Qp z;8M@1LZMaMx$GTrd?!lUO^8!54OJ57mwY(B*sfjLhLN?nt)vT5d6|Fx$&rCwLCW(uIHw2CE zq-@5>x!a0Q=kq2XxaXU4Z>f7aL5^828kYJ*U_GFh!76g?w9H6cQ**58yLY5)mSl{S zN9rt7Aj%;Bv#0-+adVrpH3#v@jjDK%4^l2-K1Dzc3_{K3Wm>o3_Ky{orm&iMWt@_z zyRW92?ZFXRWrTpgqM0y#lOQnE#wXbNZhk1i<*xPBRCRb7hq-ZS!r4q-sst}o3viPX z@2%DMz@E^V_2_j$BI)WwoyJdfd(O2E&-z_j7KA`tuarn;RV)HwG+En!wl?s5o3B|E zk}#QT9z6fKH=e_?ZLoW&2!=|Y5m7KRlG=>Pmq#|CU#8(Cs>}q@W?&+OA{%<6W7iEB zR{}1U4F|z&=N+{h#7Q2d7fMu=e@ue{D^l4gf>IFDshIkZA}GZeG1Kgtvd6I%_6Oi8 z!vj?k5(Z*1>K~G`_u1a#1b|lpP{R~(x(l~MTbx4nOUhahDyQck>`wWdsQEdC>>qf! zqC)9=Uk;uYCoxu+m=q|uF-^(u5%6KaE9Stg@@E4ayzxuO=_pR-byd!(u@3=w#!VAq zqXrW)2&%l!6!s9p7x+1m-_+DgmDuVP(zj`%)nB=2krVhlX4r{E;>&{H4sW3w)Y$70 zH?ccIEv*EeSjeVRp!AW0Kz6nDVafAd!#c3+!K`Cp5Pwlb%XqG-YmdGy#m^I@^_v>= z^-pe2F26g!%fZHyy)maqMdgs>co^Zje7Ffy*AktdPRkyWt+V+WCV(XgSd-mkKk+U7 zfH5j~N5o@L2>yk|}7@5o- z6&BAKo>cbHsz$eF7P*SV5C+wnKIzfy5*g_jIbK(t#(Zf+uu_4?rc@@yDl*!Uw-WTzwGn z4tQWoi*&@a5-Oen=K)-{ykv@`&C@l5E-c;D3Gbi}gtP^~$0m}MV7^H>Tj zV15}A@9B1#sQz`c&ERX-jdFnuB8+G5^PyI!xY#@qdso;wI9|d%P(E5_m2PQjIy$gf zWeIy8`3pAK1?L9$2I822xd&S7i(v=nTgt3A zkMS&bj~oS20UnAMl@zxZBN8(fD%<6fIw(3TBP`fs)0~@pBrcv*F4H;!fN(iXwq4l8 zb-jQqW@H2-@tQdh|FWrNwmcUn0}Z)IGGj>@G<(lj=o1W`>PuoFDYG{#!wPXLh=$lT zDItxoP#gt*292!-WCV3Je?AqbMQC_BK_8IPxYiq(V*Us1GmzJfXKh z06$MfD?$Ir`72?A9=O~2MGFzflTV-0#3^C*`%TPUfllxTr}TN8)McI4m=m z|N5-4A7w@6ABEi@s?X0_0Q32?yp4-eJiM8AOGj;8!BdFK?T6_?b54h=?gVM3(zpgk zdOa+ckJ7rC_{Id1DH4kcD$D}{*G=(AiNp=f(NUl~iwNFXr%NQ4$QzoU=P|NFMcr;Z zMzVCN-eWW8U_LdEauWxn#1lpc81CBkUHTr!c^-t+i!t9>QZ#U#T+YD=Zg!5%fAR0R zb#jG?=Y>L|R%KvdUi6VYbod=q?=O`48Ku4YA!om!z!MSM~#a-@_ zNrvRSiQ0FO@yib1;5B6`;f)h2U~=X=&KcOYK{h*o&plJB*rK&|& zl#SMDHm)5o7N{)t=65`@y5TFHH9p**x}V*0KNapW75$egwmrB6kvy`0c`eQ#F*rY3 zX*r|$*&f4{)5Wa6Gdi^kei=AA`{5b9yQ!3baI^UkyiR~D75YkBI;*`K@fn29H31!K zZ45VGZjY>k$Np-LhQFRRsEbV$B`1M&imZfU!1T6Do())>OM{K>J%e9Z44#ADRk68S zH$3QkIhQE7&*Wq{L>Q5U5J(t}WGaXe@!9g%hT=hI+>jm#iT^^PVAHq@L`DEVE+~1-3L5xcUxQeXj zTui|(g6n+!+H^o%W4mzAA$`n@Xc9Qgo|ugSY_=&C@SDr;5Pw~bH3&2& z12X9FA(IjK{kQswvN06zvRX60QgJ?Z?ChEVJK0or1JfZ12doXHIHWh#%*i#TGx#a@ zkKwW(V5!(+tMpvMJG6~rDn;EG+fRmomKeaFoziv$1W{?l{tysWKx36k+YBr{d^S(T zE(JN7?pdN)lpE>kdXw}32ORVK@?72zeGrS6h?Jd`0d8l4g-|-@bczx_0ak$awKkBf z@DReSWjh?Ju;(?gI_np+-~iMO_dABu8u?$V$A5btEkDwu{oX}Hwhjhc?f^T@V-uu} zoXOqUuhDQWJzplsb~5*r*NrJh7IIra{-i=A}b}Zahp*9uE;|P zY}l3MfxyPgqu!E5l}fn5)}lCxTOU!k6FWrCA{tgPoKu!zxjpO9BUdWyISXEa*Qna2 z^_OXeo3SD%eR*X$ns(2QOwyL@yvE!ISPB)&Amq#ogj2&Q1`VPHcd3?bMql+Wzij%v zmL9vV&(a~ZOYlMe9j!}6oe5Xd25gJ=SJ%EylxVKy-EbyOVOdf{iX4h`+Sh(QyA(>$ z&oMusb|+g*B!Kqfy$7}Cm!Fs6IT++Ne$xV3+)CSjc2^(wYxNS{s3^+zW*a@kEf1%! z6+ht^sajn3QiF7^&)V-WsX*8}DUuU183rT=+;2`b%Ti0jVD@D^3*EO$=Ehj$dJ>6@SW%(TuN2(BAT zPQI$dpI!9))s6tIWDn}-=9Oe_fQm|#YI6Bi(g1|i2=Cp9&XSS|8!Lm!E?cT-@E$+Y zckpBX4cHBRr!3EJZiO9*3o|kSBGlC-(pVE&dlHCAniUd-pM=yaZwf}b-<@qyijy06 zy4L{x@|X0_@hwUyHToZ>(3hKFzR}%+k>?aso2i3!QOe^zWE*Ry;^_lj4eHnoIFIGh z)5dJf`5ezpxqLD{IWWw&y=*VTXp{@(&E8Oai%||asiN_qPmHHUO5*;7uf6h_zI~N` z`)f0HG9U_0fs_tV@eLk*)V8Z;d5zH0*si01z3KZ^JyNc}W)BE_ujt1YmLIkCfd`5B zy3Uz2*7u3Gf9Ud;XOXLP_?pre$TQV^0o6rV`aJ4e>&p9q0qK<{Te4bkvt-Y4x}_($ z_xn1Pzx&!jlJEAtfW(YWoO;eGEI_#6)NN+|l;j98(KGoy#j+8Y+6oDZxWc{Y{ler{ zW23u6^y8<~3`{|RkTg1xu4u-0(z;BKsv`l=E$v;~um5p^?_Vx}$iRR|a_d}Hk?`H_ z+~n$v7SqY8L9);q^g}gz10zz9OZal!<+1ymcW+9>5%6oVW-d9CkUfM%=I)fo_z3>l84Iy>pO>`(UNd z24u~19uLT^#!e&rC*-o7HF8wveBINnx=i&u5*=8IncxJ$a#02=uUdDE(CbPL-kBX? zZBVTYaPmy})Iibli(Ej8&)jjYybQdqvNWb|52)M=F9xD@!EJqpH`lCIT<3$FizD{b z_AF}~f{}z(Q}brgn>p=B;x!xEbori2n8xe$f4N3iZPZYKa(u@~V!Ho*V|u zF3VAmplW3rzqon@=%=I`A^m0Ds=UnjS)>%B!=x+-wb=>gXSW&$wd!eI*+~IQb)vY4 zMK74Hq>6y2q_?dlkhGez&R46P*L~p`!aQBWm|2A`YxQMZZPslAGVLMml|1peb<@(8 zCzy)S*s0;LIQ?4kUqa|c;Y$|w@*HeCX(&mQnkh~GW%g786ygmg&td%2UKHJkgd}Ks zvXN|8UMfR9OM4&R+LTRhDfzDxzym9o-UJqsO)|%=l#>#W)QJ8v3{|Ifg3b`M{m@R0t^$k_>q}=%0Gt4% z*4OI#N(ZXFBiEU5qg1U{0nj;L7i+K0^%&LJh9zB&#;RuV&mY9}?Fb!ZT??SvijnZ4_ncs{(I~;1`w@mhwKu_+`&c^f&R61|OX7vro^rLups?$lZ zz?4gJ+QXR?K5$(sTN}6I;*s0wLl+mRtUxxdb?I%a*y`RI<@2%#nZpo-%xTC)>t=Yx9LWvrvyX4(DnOn~ z<){li#zDC}V{kvwG7#3vKc%lH^9KzH0BwcPwuYnwoq0#&qq~Fj6Qf6xgIEk)VyQZtS8%9?p;N=jj-nsFnem! z*bgh1`m(b&qb&oF7~kpFdWXkPfTw!Ll1G$drFfi5xwrDPS=z>_7#TNbcEsH%H!XX% zMPjJWwleSKip~ajSYx3uH}bh&iO@;2_>7{!{QQb_mm<~B&)>6q9DXBF83J%Fz~Z9n5G(;WbOmGr{g1i7ocRIKeGCQH4) z*Cg4gvi|+vx#Zrcl+ow$E%|+yU2tgn(YGzi3d-Z;JjWD3g6i(?ft{`&CAKX!Uf_S) z(v<&jQpp0W@h`!CN*@ICWl(fTfYR_QYev|J@)x#O;KnJlYz?VpF-7|DC0}6_1rhin zT;@YZ2Is%l%J?2Edk?7{dc#K>w_hfixZ_I|ZGZ-lu}H~_Q0$=qRBJwgtzO(Gxvu9F z6d$?lB4m`OG^GV%Knjc^6~2GJ+Ek0fuA};l&B#_Bg3XN%9Z3Pd4ihY62sjtc`vAw0 zk_ULR$EuL>(l3@&B{b@+EQ`dET)lg8w@ijTw!M&T-|(M1K#yc_gbBpnVA^6(gs3d7 ztaX^8{!-slJ)~7jI5$3Xj-S1(N=>k(xXGblvgV^N6knsV-K&TKt+s~(p9BNw0PLUp zKV7Z?efdbSB*QmBV0@;M#b)&Rnu)XhI+iXo(o`oo#t)Fo|IoGv-F9y6^g6dHudQVF|<3e>I`Mu5$nY#0c!(1kp)V( zoTSW$igE48Jf=mW)rBiKGdDZ-hH2?>y{@!nqW)O=&Uy^nL<|uDAULUDec>yQw=BvFiaRc|zARB42ktEL z-eIqcpTB~$aQ6*}SAFdEJvZq&CF=LLXjyCcs}nn$uADduyuI*?tbiC~Ok3>U?>qgq z{#&q`g2pz%%N)8FT&4k%GGpkbcTlcZzm+`cS=m^*#OznIccW5WHb|HCOMG(DR{f6~ zv))a1JH*S+%_Obj!A<;V=@}RTAHafTBRWTP`a?^M z`+Hip1~n!)vii=DT1`JN z%nu3e@w?z>z*5p*@=iDevfU$}6(6Faw4yr~zVAj`C`j6o6y147X+$4^&EPG4&qZ_i zJeZgOUs^r_0PA(dRCn;nC9DG_82TGC>~JQy?J;>44=7HQ;ypbVSEJbt`+M4YY!;|5 zPy$h(^jzQ8l-(7k`%Oi9g6x{kr0=_c9R&sCOf;HXCO}^nDPJc_z-I}$|KGdkUlvR; z^?x*|t@1@5$4z{012^9#1%@z=o$pGMT zY`WwH7-#1)JNV~!3LS;S1r%wfozi{9kJQ~#bL-s(sP2nhUK}ein}jLQ@ePHIvGWHF zlzFLet%0*wnLLlKw3`dIJhrIs%!2-*p3^@Od{&?UxG4d^kBW3#MU;M>=C%U;VE}#@ zg-#J+Tc^U>L- zP{i}am12E*+z$Ss6zBFB^g#i9PhVhVf5a62G<`6tNlLGAk%CzOm-7^lth6M^lnrWk z89}kZJ+}Xw&u&=kyolLy_5o=^-9U?sFtGV3%+D8Q$a_$q?YW-5xj;^SVMA(A1+Wi5E9rmx zt&n7DDHwdW&m^URyB<*1Id}Q6*ZNK3)z84AnKP~WWnB8Inv#S$4~{l9R(m={KEa$% zu+Gbk8W0#LK7EjI&w98)Hd*8`?gfl9$ZFWAU$TkPnjQ42odYB0r#96)sI< z4EXw?+9hreUFrko9(NGGG!SFfmJl6+mA5L_%}EV6Js%2y5>EQpDK(wGQJO&P`E=al z%(fdQ8mX8^g^Me)9*N6HX;Cxt9r>&3Ot$IU~qHTKf$qS2GDvnMk^U7;R< zGW8>gm6VN6g;6^r388>&gxiQN6KAk~Btoi11isK;4}2UjHXKPvimWyp2u{dYNDN|B%yfLHC+_sUtL|+)MEdL&gSxGw<0Srkjx}QmV5cY|sUf~|@1;h_ zI6f@!D*s2LKKmtt>LHz9$Y#%SoNCHv9VV18qSac!?&6m>Lg?30-rq@>d#{bHmd%ZUXU8WgUv zE#NuN1Yr(mX4Kr?gR{xdZa&jqKbo7rXHu&9@$&k-X;P7jT)3DjLiejFsD|Up3pA6W zE;vf8WnjJj@7~74PO`~2TS<3JS=xG=oK%spppEs1x*-wA?*(myBP-GAH-Se7Pp8nj zox%BfR>Ztgh)_`+H+*L7)LnphW+8^8VavIZqs2-ram`I<{vUamLO^OR`MOP~K670M z{+=4u+8P(xkpd!Zf_}bo8Q(?y@p5a4nkS1+JLH!7Oh|#sM7q3`!_>YtJy4AD|7Lnr zxCxPD^5%5XUJphLbDe_msqQN;-}MY`n4e-gKg&Oh;=g&@s29rwg+fhwUmgR$>_VcV zOE(GJ33d_PT+MIPRUtwF z^6dlsv{BKq`gBg(@Ljaw_a7_XyMCBm)_d3d<}rK231O@7i!T?1$eGU{W?gFahQ&#L zv#&eO2kEtUyTpCO#KtA3x0d}m@{&$A%pcuXCHw4&3bF2sFhU5E5R-A~>*u}`#-mHv zYL^t)o|9K|Ow)q1=S$vO?A^bAe~^SOvB~K0d#4bt&uZ81Q(voLqP;#>l5h69-@%Oh z-tn5E7S)X-ehOso*Bu#8V;{8Hr`w9XE=bKMW$WZk?vdt#3qI|TXUAUU+ZE=$DQjo^HU>#%!t;^$fxnEHC~hZhYm4WFrB zvKcVt{cSY&&r;?89bz7C_#9E5c=niIEf;x?X@f?%%kQZY6_+9v*WrEe5E=U0Y4z6& zZ#=09XG|DSe{XQE;*bVar*i*vI@XZ9Y#SNzs-IP=bO0jLAJHJ-R)1o6fIQ3T^)%^8 zVpH3T!+`G|LP}CPYOgHEuV$aSF@2G1U^uY7wzlZ_awT-A$V`RCFz>Egn_8GAGx=r(mqZV%=-<=zG|A zFgdbHX$kpt_hPz(JLQFQhAosR} z{q!dBE8sQH9FMhg{j@a&3RK7ZW?Xcdk*^qZ%x~K#5f|c+u17zq)}Pxv?f!giG`Zo8 zH?GQmZl*{GK zVNW+6TOUo%I{Ae9{>mB!?^=rp(+m* z=4QX@qFdj8J+ddv`MyTO-}M+yiTo!&iQbkB-j&{c0Cj1dwtw~KJ%9CV*It~hl1t|k zi9;t`JgQWNR#l}(n~|z387dAKgejRj6NAurGxY7=$|{=GH-rCE+_TEVr;fd;JN7h7 zN%5AO!DQRX5oyuqfA!8ycVL5JZx(5N7HP}BWKYDaNB`L4e>dmSQ}DhMr30pdKMCdi zC5kx8`5t+pxjKA4BxPfFu#%;a5w%%oQ}DOIv3D3rlm~K{S>m$aA?Z?D+DJ)N>6Tvl z41MRiKD&_97u4;d&xN1W*ymxm#t@ONb$s@d!^X)c8kO|wfKxlLEjHBn0sc+4z#Q>qx|vH>boJ}maCUBM+tq>&q)Pw7 ztkO%WPa08&G3v)u9#fSA$>2T8qe11`Y)TyJfl>}53a_AkMnM)v?<&AgUKn8X>k9~X zma2R5FbX3a&-d(nty&~sr6?q^IU(zs{3ngr(;ii~YsS|1dsq8}j7iK6ekJA1!N`zS zA=kn;ZRO3~-j6Rs`YL#m2)QM*tYd2AE1W+G_qHDVTM7)mE)hAZ{_`H^f;Bhi>p9HW zenV+)eP!)A{RJ)6GaBwpJ9R;NwC_vSs!$t9xtr^ zNM4eefYd6OytGHqe=Wb&qV?1AZp*>#J3#&g4kfn#V%P3R-xoNDl9)T9>uO}&aQ4>q z;w(njBR0Mxs#CllkCA$UBTqiScgU$06spo>JRkGogoi}dhBrA4z=LeW$T?!J0R@t( zhIEWnc(_sH^v!Xx;d9+066^}Qj6#kdU{1?4hO}jIB%4(Vkl(#=Q$oyWgrCpS$aHP2 zIP~e+L!PuLsm9}~F+X*R_OW zPo0CsLmnXZMMjAD$r-rRb{^3^w<$S4bZ5F_Pw#E6(Qp#=~5Ggw6IFU@@>cc*d z`g0uSla3AqF6F$mUAG@dHpx*JzOeVW&9uCvI}1;=%cl%x#FF(9hhrV6BbY>M?3*J0 z68*px^YdSG^ZUYIAMCol{07!0b|#cTw(xRV$3_01mUH`D-WNLxw868=4~ajFCqOpT zKz$M4Hrvyn$ms$f-b;bx_AEC`6}(xaUeL(;D4R+Q$;>4=xrd3Z-B+;VIp@WQn`%U%_z@dFW#eSaq1Rmx0CXx zUNGQuu{Mss*Ts-rvmp3z`1`BuviZN@pQj)yFG#t(nUV;@#PX>zvYxiaEmE*OZf^Q} z#L{=MfKtE8_CnszQRQ`U|8fB!g_&zId(9oX?~MLzK(`K6G!HN|3r$j6FxYS}1#R_z zY-iSg9wNtm?UVY4?8su8kT(b?hB>`<40fksLjPRZ&ifme4!cC zb3m2~m4*Tis2(Kfgj`+OpsCR(kiM8Q3lh%L$*A*%>~q8|hj~-`KyKC5Jvh z++0}vO@WcQz#Qb4Uu;1t_%&LZ_t3QZFW1(`Z=Zyp;Q`baF*-KY=l7eB9DacBu2xNm zTDIYEDPD~_qI#gKRLkHz4y%*VuAB#%-RfYzM>uocZEN!ng-BO!;t=oqa{WpjOXzXehldYYA;M)J9{!qB=sn8$nm>Z`?&Y;7 zPIK9T&6gLRGzq;TpA9gTJWYS z-;ZJU^Jd(AX8-d2xO_12n<3A~$v*ySrcWt3)+bo&oY%URSwnzIZ24rFagq!y2Zr^l*ey=c zJ+bBIa)CN4`Lxj=Sw=Oy*K#$GJq!PFT?81 zPloF_C0vN+Q@Sa6D}zd(Z!=z(<_8YL&!0jWPCt;mciHi81F#F2`Dqh%xm4?}z{2wk?|cen?g}+%N(1K0kQ3;o&UbuG zTY!t7GUJMH-W5Rc{Hj(H5A?3pBSc=xfUoWBf$5}*YpV{&c>-jgB7GD~s_#}D&jVId z3BjguE1^-JDx}DdBN@q`mQarr?QUXWwVq5dN7lx=(GB|o)vj1kC6$Jw+lvcGHrZsf z_{e0f^vQUgtZ+D!bI?A=K`Gy^Zg1hfPJMR4Q9DNJ;tvQyAXNbons?sO8_Ug9%LNd@ zBF!n2DtaCR#|JBAiA?S^!-!Q@0A3$+W$AuORCZ4T0{B(^{sWid!LebAFdp^?a3Z@g z8BEEKC5bxs$$dFmlvY72SMk(!<*$;Z9-X%fOAp{)uq(NG;&1Sl6~o+8$Mm1A zA|0;9M8|48;N#hS^m+n-IVH3r@)V0=$P2b*()rLY=cr>8_?$}LyQy)HoHjpTb;r_r z&t_i~t0$bvep%A#({f_iQ^+E;;6~{DJc;jbVgvnKw&!OxRJhb9kB-Eu?~#>srzIE@ z!?De0R{9oC1^+*EeRWin>l&{hNJ@tYNJ|SSF?4sAbc?i z7o3g6&t6}*=Q)fNzP26VJQr%X;f`i^lBvsH6yE zRg*z$_iW%WDCozOWc$@1WZHuyh_qZ9ZkjJ9!G0L#z-rU29#&>ppYiAWI-#f@swc2y z#d>jI2YvG?g_s;u>t~{m(#_zYwmg-acz!Wteu$K=*G%*4b;Sq%pTrZgBOb{s*#LRy zylmFE;}0{Do%p^pSwgSaJxX^k>G*~zvGwto&1dh2nl$DtzGp_Vl;udz`Z8@NCM5&EAok{=AyLjjpH$2w5qa%o$6C z?Qd*+4%U*3kFH8`#|?Ad*(gnCrDfi-Pkd9F3VYY?vQei6nh8+*1)=zqI%kP99>nnnEDzrH{$8M! zPeJ9cWfl=3G!wvtT`xmt5cvlqKEc6?^)^lrE7V;+!!F!kp`#10{T#8yn0a4DD93Idil)!aHf<%!f6s5Krf2IWONLVSk})L8`M3!X)Z7)X*eKWk5pdoQKh7GSW~ zIqCWp?4Ktm0bgp|o&DeMF;%&=^Vrk6$GxaWkE9z7L73ehqa07li>J>Ak*?HSR&%+q zU94TBlcIqE+O5@W@|`Q@vsN#pT)Ey&XN|!C^=`3sb*0ArP`6UPg=Hvyr`{<#(`-(S z))B46I~~^^Wg$1W)BaDmGKCj8e4LMtVS&wDf|8La0e>bT^nUk=>Y2;UMebG^MOV`c ztG84p6sM7aK|wj@pP|=@g!&6Dk+x*bM}xCSl#^e+d@-N)=_M?opkq}^o@I9Y2&tzD zjpvg~Vt1Z{fFwYV)A(FG#F{8NPlSH!ypQQ{Lvi5UsQLkNbc3i{rdsG#^y6Rdu*=CB z0)kPN-AEGb-0TK|U!2Zk{*9x}C?L;vwYpLUH#Ht2d;EZsXIU{Hq0La$zIQHtXiUF= z0dB7v9+ZP5Qx>+h9A|RrEP}OrgbHFq4&A5etD=q?h6g{fqHB)}i2AOqgu90u$|KeZ zpsODgdg!6-oR6fMwQPbE(zf^&gY znVzs_uhYNS&HmuT-~2npbGg(P2P|JlEBPJb$30mr>ds2Z1Wja$Yp_Ul{J0xwI-^u| zOyDU?qQRl{fdwQi&b&Vmm=z^R@bmMqi)tW23ui@%rRP(M^;Ud*kEp3#2Pz4LP%`7J za%GDPQ*)t=kU@OH>mn5|GPqi>=6)bgvp&en*~uGu&>h{s$xU}*8KrzUZWr{T-95&2l_nQ|sZ3-p3|zVOb)?9;)|flV|0tq0&dNb~0{KUknoOZWJ5 zzc>(dY1kkqN$r{H?{!1kUso#1iG3Ebvttdo*Oo0v$B%z*#(6SRPOZ(#-}n(tCqS|L zc&9eY^e&Od;@SBq7G*1zLuX|rv5U#-m#FhJX0tG{yMoqkwKuw4U};fdx$!|9#h=Sd zfXvtIFh($1HBExs_}ts-ik&k>5Eqt|6v!Fw`T6Ut`6~t+yny_I?lV@KGoKGq#40_s zlY|ywQT(eHrIeA{oMs};HDLg;hvaK^5$89)q3`wF1Q~n|G6=Smt`7w9Hh#s7K7Nru zhj%R*n1!|DafL*e4zS5b>hDon#yk)FHYVB0eB!MZ5jd`$P#h25a_sxiCX~pY_t#j3 zfp^_7ESQ*(4l-Zlo~8!xx!PDiJpm6#4p;a*ip2hO2wfpO>h(y3#CwwRZSj}fDb$A- zD^3INaDIDa-ev|zzlIi+|FEITTmD(Vyd0pgl&WbdnF{%!(&fPF$#FYOc6YILK(;)p zKmQ?U>3&9z{1|qb{__*`9A4-7knrzzH&%M`6#~PC zt>PZisxCO+vG>4Vgh5h@k29# zYz+vD{Hg>?hfV4#Pcs{G&PzG2T~iAciZad= zzMsY@L6#%j@{R4+;djayhy@x#X~NI!92_~^UVPSX>WN@`Wq-SbQrTOR>jlsr5s>)F z^*bvGx%Q217TH`K52Dj$UDX!?#+N+r8!3NYD_I%0>4Iml4h4~Uc82Ax?0+>bhLW&V zl3XDPSPm02`kX)g3K4LE` zj|xJk`5W7&8|gE$UbE4Offw?lM4iLi&l@5G-6oE?eVTtlSuH}>belE>L=0~tsB>nq zd%A-i2RX9s4?el9y5$@$kancg`u(^LV;rtyp&Jii$tFj#G3mshouGZ<8wF5*aJ&4fr&NleCUsfQ?6BwbH7y5T} zft4zX0V`EFNAO(yzg7wh7x@X}MSRcO)DFf^k~}05^T^oh?HIegs(3!cFEY!OA^rnS zI4m?rE>!!gxE`C~ia}Ffeb7}-ZROttpsg^3D7I_(2Af@2Lc|i57}pngj2ZYeY{%W+ zne>K+3f(_IK(g}FFXkYb#cbvLnz2d5HU4eR$ChZgJ252ipR6wg{|G_MQC|;ElL`w> zSW}g`=oUA{45hcv%*=db`(poCT-(i;&0V?3NIuj~bHOx9Kh9>GMC-@9b_8naSe3ZT z$#XJr`Of@8(tb_)0959Yg@dW8slF^Ce%$v=%gdhj*o<7f9V>Q^2VLBK%hS=9g+~W# zm%sPq{Estt8n`p&kk%XnA()z)mGq*@UvnFC;`=_pl71>!Fy2MO7c9UOU%T@_V%(C3 z#d&l~?;^)FIv=;2NSMZ1TY`~pgdepmmMu} zSP4OwwodsC0z2cdidYN22eqY~O^2t@h1N3j`N=Q|#{d*F{R@w?OoH#oAQRegK&#pj zW7ndIE1V5!_9$!#WS$o$zhMSYg)X-v%$@lp=uVzCgO5et}@Zww#2G3-oe>-FPZBC1IM zofry(+L;+SMKu~UyP&!dkGF?y7p!R4`?D~tvNGnFmRSrZ!@e&E-v0$VC&Zyv^c03i=Y zI49^1NA|hdN7Py}dmtVKgwB`FAD&-_GT@A$s#q=CW0R3bFyW8(H-Dee>eHoeW#9eT zKRCr{*>F+`5K{BC`ls&pV{569s6S8H_7RynUVItLXiABC0zU}1%x7vP#mu5z1FB^+ zyoUIj$Nxe8M8eN!sr7yznBDpuQOeJU)nAbp=$ZHc-0=GyNl-%V!T0Yr{AO}~#^)tR zmG;)b>wE^v_WW1B1^7WZY|;_i$q^%T0`OO2{yAKt*h_qs}G?#0yGE*A|Il`V-CX@#7?xD#%LN#Te#VqtiB5!Zy>; zz7O)zx)l+Kn;uEG2D&Rc&L_ITA&WflS!QW|)K1oZ-)vce^zD|GN#5%?+6%m?>wa() zxnmivE4hCqs=)X)wxrDg6aB>_BqWoI((1#(SxFgfsB-c7{;wc>*&9X^4_xC?*V0T5 ztILk`OO2-7w8Dj!ij_68V`{~a!sAV`AD%7u=$&53ic_HkHzR6`vP9p5zb`2kGlCpGG+h35{?hf+#jwZB zmw6&0;;SGKv1+9(HD=Bl>dt!V_7@AC{x)Z`@dM3wx3tD#co9#>r;8d0z!lQoYg7^j zybW8L{pR?PXE}sZ1qw_OW1L4FIdwHrZOMNGCJyGw;+;+AP(smfK z$QX*`oK5?ILeS8)$V6Yz--!v;hCr~5MXS;jkR>lUj1niiZl_{C^QdI)Vbx?WU2oo~ z4_FX5=!Sl+8T@S}tZt|$=nDV65k1C4V|#%huCZ3#^o14XN00B%f*ixDU%MH)e6kp0 zovR8YEDZ-;kL-CjckjwqtYYQE>a+Q`9@K`7;9kz`FR(ch)0Dki!z&`ebeF5_(1n0+}j^@|?=6Q}|Dw865NPQ6LhZ`A9ThZ@oeK-9kX#M>f_JXO?8 zns}__78R(iIxRN`S~D3l6f|5L97(+?+_(EZ$Su#(Q+}XQj6>D~Ci%$K|Nt+$hM!4ED&v zHAyI+?x6P0xMh@b%aA^{9tX#0|H-R|fU}8FsyCI1Y`NAb46xBk@UF8z%)WVMx)dEQ z1xo$u%Od`={cFvUaPjx1D8mFUo1wG4&Dpaw$>ZX;%bwp#04?U8mqdm#^#TO*nnss_ zISCZ>(iuF$bJDnqyd|rwl)kFJ!&sXftg=cGy1${#u_zM77Y854H$weIUGUlyG&Ikw zZG1{Mwu`5Dj0 ze&kGk2AzUWg&{X?pMq_yJ|`7Bz^^Q({D|wGu_}*#fT6-%e!(SmukOfS z!UQAUjh zP$93A%JuUH`7r=Ip*G}$qd2n^GaV#M?ZAz3Ds4@xC;Il*va5MrH88_4Jfugl$PmVy zJ<%_U-<@_|fUK1$$+SzY>Y*=YZF-ChT$rD+tuzi3qBCpj>C1^7%yuQvcPB9T6FL9L zSh6A;eyAY~KOqI92=+sKQhj`VDTZuLXKDy*71FvlxDJ*G02UW3B7l03&Tt&)bbYae0^QeExKrw^pRvd#a#3&`Wz zmzqq$*a^?=ya$sX7AdreKF`$Q9;7#m845jEpX2d<&s{0)k;l2$;TJ%f^BE@du<>Te zp4{nGFuC2dsB_t`ppJ>R&_!~euvq6}Z(rMuaECM=KX~Vs-nmhGa5T7qmZ}@u#^Hpz zMz4WGv#l<=;6OvEXExjscX&AJ^sV$LO5a?dqV%M4$;tKdQR+ei(m{HQ*LfqR)aEDT z{7N(7jQ(FrSynpK(pv-!cb^FK?BAcpOKqgR|48UTuTQNaD2ikev<^~IbyPq}$#l;hR1BA6Yb8sxazF9!)m6OJiKC`11S{|%zY5*MGY9DnCh@ql$@p%$I^d->%G zE4~$gpXnIZI7T;RevK@05}walYKj?zspcQ-JcL~>^Ru{%;J%c7`Am81KFLq{Fg#xo zYf>J58TZ1QoF7h81AXF-NzC}@fES!oa!Z7m;W=CE_VYbo+C;VDoK)-9hgQ*iCNp1Y z$cD^wBo)5Ctj9-6({3aMa2|{4laZvJ1|Qq?%*zqeL8cGtAVRtNCIR#d0wNS=o%is& zh3*sQX1nu&ZsbbE&0RkXRmrwyy)o9?pE%I_D+Bd8K~M4IN{_`7bN+Yak2I`q#-*i{%j{fg#x5~V za5UQ}HhDbJF5=SFoI^MoaUNBY?!y=^A?5ZL#(&yZJ9#}9E8zNcv5e})K0nT~$0tiA z+-8koVPKY|Jb86~Cvg?^9cK>3iWJ?Sd=KQ%;0DeJF z7hB%JD%zx-eXj>!iz_KmW-Z515>>?0h24*rVt`h9kXya3e7)wdt+O&A=Ng-|Tey9a za<(0&#YBe*9?B&})Y35WeKllE#^E?xA5m?t z_M^E#Rkoiy*vnxsF6O3@4cWbCM5g%Y*6PlpjvR_=UQDBy@H7jNTU(m-qw#X zP(f;coTpag+oF}B=J?x~3ntgRZ|OuwxU@0Gt?s{dStONB`LBD}sO8gCT09Jop3Vul z!wDP+t_(O2CYg4;IA}QjM+<;jmoSc-PK+#lL!Dg+`8C zU7J=R8R5>u!`0)uW#O3ShDVMxc!r+?e=5NFcunhsMOCt;>Ex0|`pM*PM|;^vwP9OJ z_w$OzrWeo#{mSiIC)Bv)NX4e1Se?erpF#6?M&qzyiz#v`Cq=wy3eR4$)r zv^vLbPsaRe7;AhpoOux$06+1ol0R`2tEn^D${>{*sq=-^eFbi%%a71{lL7Qp&600aloY8xrQ15~DB!ep0A_nK z;29c)x%03ATq&8kfE})g-m&tnQof!lwaf~W9D5XQ1^(v_4C?{ZiR2TypWm1fzU|g5oIZ7sEb<6YvUTPMp&Sg zS@wz58$)EliH15yQZGH7DPxegv$$v5sxW`(KD$E+U2qr566RML%koXFt-D{@7nNRW zTE%x**IRAp&uM03SH5Io_)`7$+bgJl-z>cjN1buz9!0$$1fj8hAF(ygnl4R^qSnox4 zhqZFv@k|u!Le()n$~7XPwShADI3Rc8E+CmMKp*HlfarHWz|m)wMQO>jbcGBV!@XOg^~rw!vXjU}8D2hWKD#Re3rAJ1lKV z=@4(#BxIA3!ObNs4P|6O+p2gYOj!T?PzTVPZwY^wLDU$aL~5YJ+gPnAeJcB#>* z%{6uQ#x`3vexpA^*+Ww8dXyJrKZ0^r_?BrWZK?R+)Ka1# zjP!*u|kVUpzflZcvtrXowA}bmx6b|6GH}Y#;&cRjH)_(^xf7 zdhl}{^jth5U3&MES*I=k}rpKvLiRGScU1)?67l1<=m;XmQa_cQ5*NY$4{^6p{pd%IGh!snG z$s0Zhsh2Jz4-mm-;mm2``an?8brB-J#veh-@`8_ZP;%R#Lc(IPlh}G{RPzGA*x)f} z0>wwG^3{@F@%W;8Yallp&o>ZgF>b&}FQ9e0Sl^?1EStj1`|+Jl5uvY-?fZSE4bbYb zQj-rM6LcIf-n13oGx&86AYm!u|a}# zv1lYSS~Q^73TOc3$x($a2R8N*j0S!%fnHFWK*=b+8FDSA>l0(h* zTJue@clD}&856==qa?Jo_LJ{V+chWACt*Ozi54%H$b!jsP24O;Xu)#00a?IRyxx1% z7TO8h-e`PciY|*Iv%ZqJ(W}l^?dp6~nKspBB5~i1x>}qv<~nhpX7iAMllqR*J8U!N zbEdTyy_S60gvpV+g@ihTx7A&XS~`iKk7;NG-%+n6OaXpEtSud3aX{0%_eYS7{gT&E zU#QUq{x_^erasUgvoc^qF$eW1$eNepxgTEb>zKy#2QdYi$I)u9TMWVkh}xWp^p&O| z)?cO16`5w~g18?mvPLv zwkXro^Qr|k2BWl*w`a;}cFF-kvlWB&9qHM$;m%YdxT{`iIA5Mv=MfWkCWyCdG$R>m z&%>aS5_aL0H_{XlZr^~0fp0k{4XG^mobK}6fcU3SXL&~Bi)2R8|A3d40Ff$uq>gW_ z&$}Hg{L3?e>Rg)*_m>W5kX^1$-q7+|0IAe&GQ!Ze7#aLeB^Dwr^tSZvlO{)ab+uMc zjY5O6piz$y6*4AN?9pY8`51UK*^Ik^6UkF1 z(6J@9b98m|vVX6-@NNW0Z{2@4=Sk7}U2;dqvtF3^K;vKC(p2nHp$!r9?JOoOwFJop z)H>s)~bVqM5pM|;qBE;eRjX~AIaR*Q@D`!ni`V<4O!4M@(g$Mnz67c4-L4mNZ@X+e=+xd0w~0u3J(gi zPUbq#r}-5Udpc(zDktzYK3ShGZJ0tA@08g~$+*t^h8;tym4!HT?mA!K0iYRh0Tk~)+N);NmL66N2`=${81DZGxh24?D!kQRil?JX1=d>ud6Kj(&&bC* z>sg8AXS3LGa{|q-%+)(?u4fKv9aCMJ%4s@gN-o*KU#KF6XU{dyHiY;ZoptnMzg7^~ zpssdB5?ZENU5E8_?_KBYtjzu5bnKl*Kzl9?Ln35Ql+a(xgm{d=APb(K2X1;@H?Jvr zzlTE_(E!yOn7lhNGNw67pIzY6RX;DaxsolTf(KP^@Bacm{1$+VlXB$a7_V|nxk&VK zxP2#qSs~^2nIwadM0_j_!lK`hg62lCMI&}JQAogEUYJmtei|jo*b8@~CeJ&W-}Fl5 z=n|xA6E#c_I^@SVZzb9=2kYM(Rr^ffL;cMeyJq{W?=!~}$B%5MZH9_*r4nAHEU;SP zKyO>1aYGs&_U9SzpCw-Kv$9IDEUsGBEKL`?jdCbEHE)*Z;@6ZA?dxg6f7INa$z}Az zWYL$c?Po9X71&wds?V=)jovers|PIAd|K{*WDSOjKDM~#Et{rA#Q?$*g#n-Rz~|Kp z^<``2_*Cz#^$IO1bX}usnnVGJUqyq0G|r!mqtO<)%W@XdR%=h#tJt)nE0Ft~tO=;6PxhYxFUs!Mr$Kw#g6Whx^!#osLx`{p156 z3XJQibFm2r0yrH@i_}0E_MVycpnJ)D(dWr$nAGH%Hwx40o#M&Aiy)VkM}p%I5R&w>P|UoHms~ABNPhGg*dFoV?o6W z-;BKEe)$UTarcM%mASc~B4Ho7!}Duwtxc(eMu5mf(x{%^yhmIt@;{a~!;*YkLwT_P z+4nELAL#aPmc)93g*9EVb}fUr*v=cjI;kB;6;7PARJeX8k*teu4`SxN#DD46FxoXz zOLx39aRSH@sFqsezaK5pWsNkKRKaW50Hlz^FAlk-!?wvy73z8=@>KP2J=-2LD!wP6 z7a)9syT`u%K}q%IaM|CIAG4qe+ZSVN8vo6;0N?GC+tkdGrwUTW#0lI&=IVFn}KknIjESTCy7B*-?z_;c<(R zJ9$6{xU__anH_IjTRq1;B%g5wpQF8W*jChBjD4Sca;-zf z?K+>quUz2oksx93I2I)hsr1NO+gOW77ge-Tr=@sMbg2HA`5{p4Bzl9-y%MSt3u?)+ zT&>B=ZFu>i;U|_&OqM0skxIP&Pzyp#vE+h`C0^I-mp9tHH!{({GV_&;MKs$!4)W=y z`O%fFcJ@XA@%-r{#7CL$cHjT5(3^{)kjJ<^c8Gg_E(ntNhCO+Op_yJW7S( zqNT|RQ+3C$YMptuh7E{v3-D^EZ@b(AsnA{vtNk4PNdv2m7@TZ5U;&M&;6{kF44D9{wnMl3ek~ zs^swWem}5g3$63Klh&esCFQ>Jyhs>^l0yA}woTp5Gwb(xPkN6Es6V*=tv@tX4y(Hw z6jwPcjR+aYNjbk1u$wXspgL~r(*@Df6+@U|`ZyUxgXPA84OZRD^PqvcZ(YK4DjL&C z-$J;0qFf@~P9jmF;9$8+VqAtC&13D3s3t00|STR3O}7;~B-3VTH9){-}_)=M2S$ zDc!b;p{f=(OO6=@j6o^6?1fde`1cX@1?vCG@xg3!-WptyCG9qRYfH% z+8JV2k&Fqdka!XnMl_mnjIYHP9pWFua?}gH00^vp%lfbNYh2oS=m`;R4V84gS?I*P zEPGUX^!S~W7neCp8eS1T)KgfcE09Wm3C*t*^6COkn}YdMGfU1=A%$(&5@XjmN?h`` zO%mk0M(URA7#5_$?(tn3yW-U}hn^)mq-kM)q{;mP4{i3e2e?nysvBG^{2BOpr*3EJ zh5p=Wb@)YWy5NpX|0+z6?Hd%<3%xnCHpTQ8)~|Hr+cj>BXI`1YVGQfwuZv}dX1IFl zHc8uz;{y3EkFf%f0bn75jwtKFaExfJT(YmJyW}@j1%XDS>3a=U8Tu+|9b__tmUv^j z;wVzJ3^)Lc(u4;CX|L|BGo;xm@>6K66;9Ee9it52d!$(y^R{Bmw8N#Xzw#69I=b4f z1^Gj;)i zZ*)5re>6?*MBF3>ytETy(mHGo$n6V#Q|BE?=T(g?#@dsCa7DF7QXKRg$LHYW6J|7} zySDfxa^3=OLI+J;it+uXo!Sn%!Jc;0#9rHa#{DL9F(~f7a(vNw&osHc9%kWl095Sd zqbA5VP>%TsKhqbhCn6DlntWfB3DnMBA8T~R(3)?~C6-o_*R1>*TK$rAaL>?OLEFnGZ z`tqBCnO@8(_v>g_U%GCiKijFukkt;WDa50gbo6d-*g$5vdp=Ml2-+Igl}JT_-(}Q& zd$h-^ojX8Vs~iC~>)20AbHOt#wSZg9&W05nbPe<;q4KL{{YCMu4L;fV>}J3H&3Y%S z+t=19%(}F+57iw#nQzY%j{kNH3c3Ebo4PxyVTo>ir6Ii)ZN-?eAd7EQdQx27);6_^ za_*A{X246MGCWSvpl{t#IC&#V1^f89#fRglEi2kKyFChgG3$I`4I#e?eGaDeFGoK1 zvx?uK--T7aET{NXPIX!i;z#)ePO{87#TTEs-qxy&2q$cGq;c-I|3OA+MA0w;QZ>iREjLRInx2rzijIj27v#nJY&m&xwba*1JQ;+7_dYZKJ-j$bi*C|>K% zU1++Y&VD8A#BC+}g^Is*k>*U~sYu{F0O!_Si0KxC-T|H^c0*-$ap?;=ecqz>O+@SK z0QZ*EeamMC&A~)__ae~+zW^nNxW=T6P)g`qSqQ$3_f8wc^(f zsnU5a%LywKah$}x3cdZp6vG`S-;tv0h0^UdZuhSd`BBw7c90@X$^OdGxy_X&Ne*`v zPZl}#D4?zx`K&Bsbr@GgV^zyzu%5_t3H>jX5UisxELv)OcK!q5x+8TS#r_DP*dD|7 zu5kO7@*0#UV@CA)ON`I6*zZK7xRS~c7K!S7oZR=2X7WEIs8d z`w--jQ(8v`+)sF4m9c>x#~;fZ7s5+FgXw19(6obvKy0M&?%NM&zfz;7_R_FWzUguA zMycJ0bMS~)ls_8)@frp?C6(RkP|^*`Kbhh;f>>>Q)Y&N9MFe@!#2AIAhzB8lZ^nUD zN${&MlL{@FLwBbQxZIzp9~S4$hGl^1RvG`K!Kd`XL928xR6VJ8!e{7@sg*_6BEe$* zK{e6`zj_3~t=CizBp~eif~!kB(>pHu+z?Qd4n5(4CnCqu?wz{cSl>SqIP@kcE{xu$ z(%c6I=K)EuxsAuU@Dx8|cG^x<8slMWa$HB)`R)Y&3B5AzqB|6uq{spbciyM8&**&` zC!|sII3o|M@Y+_NsX7m1Sj=rDLp^zAKPfaOR41TH^RSKalU+$XNDyx$;qiZ+%qS9h z^EC5_U($!k9pV?4iif@_u1;coa(W%0cCh`NoS~kU<5qPgnPQm5_2X(p(;{)JfFFcV zbQ17v<8zC256vF@rJ2BC#f39LG;p!*q~Md(g=BJ}W|Ge>`A;SW7hVLDuSvet?MC8m zl(XxB-URgbeW6>eOZ0t!V8maLiCyu{q~xAZwJMTe;|z7y>)Jf5S>?rl+st~VEI zt0#T}WWfE8FN7k^Nz5t#>r3^&6g|UBJBG7*(-_G(#0Rl2ez))7fGp3aS?+fhF(Z2ZzrHZ8~5{=k{Y%>+ZnNImWC95 z5&SjyANujeboPEd>}9QTz`fLt`Sk9>>X#gz9Sftz)z$TF+qcu%^0fnO;N&J!zc&x& zcTA8qDG~EAeH!N<#dP>58wN<3WuXM2@` zVH(GmOdXOJ%eHtO)PAYgv$(XZq#A2Xq}Z}NzAo$`RM;zYLkoy#+0H-El;KFDcsuNm z?MOXW=)`!phLz3`IYGsj4d$tIySB0z*h9A-rE1m)ACPEt6U$4cJdbJ=p;tRI53H)M zoIT-5?hea{AE-#s9g{{>;ZzTfy2+HkVW5)x@Xhw^Y%vJnDs1v)--SF+cnlG zBXCBNzrMg%&$XQTu5->>t>DJ}euvv6YLb7=QH*1~>MXH`b^4|COCZ~Q!Ax&;B(m9L z+|a~V^SdXp4$7`c&nzK zfIAY1_<>y?sr>vL!8*O*aq_>(e|8y zYL|+txTwuDpYGHl_oJniYAF{rwc45|^O(TYG%Tm(tI|H{c>GSze2VQ8D~m(^NOiF# z@cSWsv}D92(W#^nk;v@0KHzZ7E-<0ky;HA}Nz`>gu<9~WJy*yF@?h5ghcZCJE&dNj zo5nflc7!+ng}a67fgTny#`EGYyb&e@B^_|()a~akq{>=cUuqgObdQDLAn zmDm%Oh$o)6y4|1)*e;}0-IKi0Ls;pG4E)JmL9XC)F%kEq@;?(#eo*~5PjL9X0kuSH z0fbrS9Z@pX6$uF`>-LI%m-<$7$CZbPy~mFJhvJ8k)?OEs+H&mnsr_}R;cF)9U4%z7 z11PQLX3nuCt~ZMtKXY_Agwon6%x+ZYzX<*2>V{9A>GFoBj7= z5`oqaEY&;msa-@wzt_cJB}=~hD+rD3)2+G8$0zMMJLE$j@XZE7WTyNSf}@!9o~|(( zpvLjC`ymJ6l`WVVqQ^G+BP`Q&GSoV? zqxX|Cd}B}z_MR-e*?rTV<93uT@Nl-Xi(+W-q<{V7SMsFf$oAEu$j!<2V}e@_l7utT z=yWzvCPmd++n?wPh@x6-zy6VB^p6%`fr#oNhKhL<#T5jZ zz^UNdlfDs_fJjg7cM=oZlU*OFC5u)?v;?pBc~gh111zIG8^Ay2RGVUd3(x?jKyAng zACCuo+3rE~9HJriFw1a-ji^8&$86?odnw}427^3>oTl^n8aI>mq)rRR(&5Lt zTv_IOh4x9y+T>s`V*nUVt&Vm25dYgiGsOU>inv(Qm!qNXM)(;Bqo~nWl_>Ed?&ys1 zC`Tqfur@6{zGv;Fk%Y>L(FgH`v4NZglr-TVEI0qlU@{@!HtKUwSy;=O)lT;ElSuX4 zi1lwJb@JfXJ;40v2Sy8Vd+Z56qZ@1RW;oW;Q4%fZ0%juVUHMo>x4Qfn2Ru(EF-a2k zX{BRvd?VidJkD9NvS}QEO0{{wR4<>K*JS<vDhy5 z{+!ucn*~brK)1<>kATF;G7{ycLFvK*&Av&WgkuuysQvRZA=#FUXux3(On^!NmFOAk zPW;cGQDgBVfH^^oicAbP;@!nF&xa<{v}^gn%qAJtZfPts{@NEJAxuPSNi$`m>T;A_ z3!p5M7O8ATZWY;Vw%?>a8`h*uGb*wQ@5S`OYUr%=I`BxGE_>C*{astYH^N4wNetyQ z0G;JEnt|X4*~#t4JN_|)JNXr6=m0RsItFVT{=sbsALg(8=SLF-RIiI4>fWiWr$uXw zKv*_Czh;a_n9yE@R`Q$(GkQ{E7oV7wt@1o_Jjz-6<3`wT8LauQYSkTJ9 z3>v)5_LEK>F**{I`plBYumn@f1GT_*wabJ8wKhp(uDm~JHuGQB&Ik*(xH6+O8HXEb zy)iC*LNzr9aaDPy51b!r7g_%LbxTWzC*LoLy9&$V$0W%;tAAUvL>>Vpt}!w|1litX z)yw@|eE-?+9V*aM6`r9Q8^uej(%BFJoW?i7r&KzU2!-deHo zRvvApVX9+|)x~eezb?gcY>(+Xqw1XHeWp-6BIf!rn_K}5dTNP2m_Qq!v8~K@p;ngpaVa2h51n6MrlX-H?))W z0bOdrf)ndV0Q=>~gqj~Q4b^g3yA}1n8NpIRZU$@#iXbmG59@9Mh^VBvl7SGWGP5f!WK+odHk~GJ?GWP z@;}WC?2K8$A8VhsJuH<~iOBS+xzBJ4!WGo7T7w>(AX*b~5&=1SWc;PcO!l`|Iifiw zHcDUPd5yUtevLQHs)Wlw=J0>t3b<)dh{vO|Jtmw4x#0^XxRVSWrsl9KS@sr$#PNC3 zf2SRsJ-@i3!eX>TDhUd_>SM@i@pHL&C~1dbOH)2cy2Xa}E9&u!kXoR*c!ZB=&>e|R z`nTX7RtG;vhRG)@Q~cDd2#PiE!)ejOCg#ZW>OxWi6_$H4R6m*xNLZ;jzpR&);aV%v zM6K_~mn`{BL!}pIe#_S=t#NaL83jdCV~HdflMv&Hz<`}^Lm0)<^COc5b`GboVGP5& z=YZ|{cVr%>T+CMo=xoc{SQBrZJOwR_S;;1T>H^@CbP6=Ll93U^Ae_qSEyFEY!4ySLgFb3NC`GTky7qCuks-W5h+p( zn1uu$wHA+4cDy-hIc)rE7>*Rpp5!B@&R0-jn(SWvpAxKI+f%`}t|6mR;kXxiBP}4M z8fGpPZrW$y{u4#O9+G%(Odc329PcAv?9*bF(Ej#*OwTzE`oUHc21(6M(Z2n&nr~r)sCK1J;Q^)d_mu*VIEjyTgd$i*%ArJ@ zL^FW7>|3Nsaoa@ZL_MN0^=MAgWLMmwtC#n^QWXtM-2h_xN8SIfK{=(D01K%3GXt~5 z&5CEmoY~-41)Xj!>hFex@^4N_R2FW8&_#Za05qNR<=vjNkLt}ndVgCp91Y)~!$Fs`4XUa*$J9P7GX`#eB5=})bV;1Lwo7LN*mn5rXNBOv!0;823`1I z&|@ToFQNaxE!To4OK)krnP@)T>b6SJdx*=0>8)9AoS}W7V7+SnEHw-`$FbnRU4in! z!Vq}?V229#d;TTB!7_0Ptgj%!A3Z3}uKeil)T2Dm>x36T{NhV_n0}RGi4SQIrX;lY zb4ZOJxazow2I7%uY5x{`ZMi5nU=$~8(9RLf&LNm~CSU6REk#18>bPXI^5N+E&^zr1 zFou*IjtUm5;R*C$aiT39{PI8S8(57LM8-p80nLyQb6?$ykOx6lwnwD=$`4erM?K!L z4;dj3k>jQwAs6G>pnw4R9JM9n86i)!mo!3G(gy%5=3q{ATN$<~#;({!eL#V9Ig5#y z(RR5gFg5o`V=Xq}vi=eDXtKeLR_R5P|S z$F5tu{(0ywJotmpO>H}Fm`D5Vst6a?U|i1ZDNk&!g0~vzebvtfZd79R4%i7L;V0z5 zWpz5hto$?RY#jE$kBjjV|CRKBaZ0pDsHSDycndyK5uxTjnh*Aua2<@RcPr62lpiMj z@9GL=BkZTOcs&FIJiu(o=&RB8k0?PhUuE=ks5CBPCQ|-Sdv5~NR2GE^w+OO{fGjG= zVk@E|g3^M3EQ(6oifE&PtkN#1EJ2Yqfe>X;5omXjO+*o835pOPBw(VVA_PPTdx8i- z0wfp`0wKxVhq5R=RWtKf{eRUz>8h?yle~A&J^MNLd+)3=`uT-wdXOQ$H@Wn6GR`@J zH{R+!U2&>kVU26G1~}WwR!TVl#GiX5QUO6}H_Cf3@P4>qO`%XpApJZ|zSN55f$l*{!4P(J()`% zeIl>@E_2E0%`%-&FYEWOmx{`lnkPZnKhhexU*dYZ7c5G>HMnW)d2K6wfMrf1c7HfN z$i~x0H~60vq=j!-$dJj2eoYtR$KxqG3ClbW-&G2d_Kso^n(A5EVictCj%k-ZBg}Th zC^;ges({=4D3fgRjCmsmrj`cpZRz_cMme=kR=WIYo49Slzkli$TIv0_j4gkzyBao);^XJRS}~@ zybwq=e=6`}2!%dc8{}MKdx)K$sfOQ9AdNq5ds-RXih{{t!+WwH)S9Dfq!6@2bu97E z5*w_#%bDG1M7NH7Zb_#zI|oHhDmmih^Oal$J9*-mnElp?Q{2H%9x>`!uAD2dQx)Ca z*ce~SVWb+}&U0o22_Fo$8mxNqHEC)%!F?66M+@*cf(qBtfUb_mm3eY}3oCQI(&Z@T zTviwPj@#Jhjd#Mk&v>?7v{dUXIdVjpkz`EDSmK5CYSr)hth7&7zTKGrdN3zx-+2GV z2+3zlsGR8mou?jw5hJ&b1+JN*02Kjdb#jO|%|`pw@u~5-+J**VBuoCNfA5fF%rcV> z&S&E`t!J?2E)s*8ycoGwY>(x(+qNgd>ltpnj@p#_`n@{A}KWY4ogJ{Ij+KWgv! z?(8wTg=339?l|0IRBK7BR>XLm!4PI3YS@#+h}gWor0@54XPPffZ8*}}1&pBZP0bCM zp6Z|sMhodj>^LANgUGzQ{&&OmDAR!6r~u1|kdp5A9*v~LG$g*D`dzx5w{OvK0Y`nv zM!sVh>rcF?6^lhHAbwewOE_`LSWY6v(er=2gVePcvIeU>^eiw6nDku6a?Ssuv9Sa z9GuTmp0EtzF$iDH8R`PTs~hagot&4WF&dWe{lv!(GXu%2TfkfJpVKnUr-h{o-lX5Q z(G>+V@9k6Wk!}|zf9=X)2>asV2Zz~8ged*av`6**;GK?J2Ds#fVN1gKi#;!&Jw{wy zy+Nr7sOQqcPuDF5>1A53%l+`j&$xA`@&*+Tw;b(AYlQdLR}sQ7oti_~F-(_$(yo}s z;~AlyywstqaySx!^`50LZggshx5;&`{SNA_y}bwBJDYj+z%QQ%MOV2@ws2^j^Ao!Ffg z=IFSmj>hTF=z^{%Nr|?wBJQR=u_|N_^W2f%BH~|kw8opfqOhf=XAX|AQdI@yJ9y3f ztt>42`R*H5jphttQ| zdd0Bh@i=B%y5K=X54$}bGf?2${56Ug+tJ%di+6I}R^nFMs!2O`jL- zM3)@R<1n&tG@5kbn5uO00REU0oNh-5H|bD4*^Y4Grn|u8kx9eWRhz2uXNw9(*6Bq( z>vmiueDUUKmt0Q1!fp4^=mZk3^+Ko|B0XZ_GIQiZ711HlLNg6<{A4!X!lFBi5(P&K z14F*mC)sdbjK5Kj+HBmiru=L}JVE`i+wf-cVRVJy-IoA@MT1}H*_!7{Z($}SDIv}i^94hLio*%Dwo{{0_U8gYH`kwUyjzLU z+Yl#xUO77g%jW6_%RoL57sNnX}ghHW_!OY@-PDu0)aB^n4v6TBE%j^49G z2PSB@-QH~``F)5B7_2}6<4<^g$I-1!aQYj+TzDvr)lBB^oL8~;r*}8V4)OaPoDiCxzWVItNpx738R-L3_ArzG^2&Aqa^s@-3fNJE|(|QKNn$C3t9baFqy#6US;v&~RnBpj8BN=ImC&4@1V*1rT$lD3S zal*IPRuTtV3U7S62fs0<>Z-l|kCXNLao5YjqFLQY_(MT=5vBCB)0x*j1iGVB@uJ`y zN4wE}htf2Bb%a3-p2)YO!1F6Mr{G!mz~pWUht!oRm~VtrOA4Q6|F{$2eigC7Y?}K> z;MsWah%#MkZCquFX#n9dIeBSXX#ZEkbD!Qa$C4wKo8g8++_78y;xvdvdBL;Jlegr^ zvhWC64y&x^UlJ*8v)*zu&$uuM=Pp`p^ zRacne+D=!+6k%E)=8PA5)htRsf=ouXUp~;)?1Egpi)7^iUg$V85$gURFzRCa=CSEH zKv%%X4^?xuct!2He=9wP;D#wBY!-UJZ7`1>n;6dfk`}aSlu@%`qo2z70CP4L8{jhH&uKAWko!vuJ^N-@N<=C zQcqRU*rnQCk(E~BSpp`(|KrPa&D&L(i8Tuu;oNkB3C(9?E{!*skx6)A7&?q4Tt~;r zBPzlNd%D=iD0MK~MuT}`L}hNR<32fI=$j+#hS&(UY}a6$&*l%QF%biolMIuhGm{w~ikHdN8&7 zg;y%oJnM69H8y(HrkEblTek~}CuoI|FAw4f^LQ3Q=gsLOVvhXJG|$qWJN6aNG^7>Q z?4wR-2@IE?W9r5>l5f~ssNCl5k!m=JJnBRmZL?vhh3+o#e5XseyHoYDAHUxlEnR(8 zLmemhgbvpa%ZnD5x~c15gN{(~E9r_Ud*+MjFwQl$6u8{)Na;<(G8Wx&4?E3&8zrqo zIP6kYaR#4khAs}`477AbBM<98`*Pj$j$7DhYyVRLQaFl?#SWDh`kkms4U(x|U-&_< z?VgdYE4*g2=S4Y_6mmDNmz8M2aoWNtXZ2fooO$wykYGNv)Q$d9QfuK7_YhB9M9pUM z!ekge^k)W3q$V=Hh`>TC@A8yBMY4N-~ro zY+oW!71)QkIo*GFjQ#M=PFsY<`l5kNo+Ewr^}Jwp?!KiJVIiCrugp=*zrUfLi|e4__p3|&2}&>$yml`EFpM@)*h<5-R9hAF^cE2&`Z`HG9UI(T{O7ER#uA_g`C^I zW&K2eN19dfS0f^fctEy&sp>N9@qv|WGZf6xRaL1Ej&j{Lu&4hIg$s+$P|eTa>pi0? zF$|$);BQk-0d-E|iZr4MUH(_5@N~mD+lNNrn}zxXgF$W4?;fYB)vRL1XQ?%9M==V( zBU1MbBziY9!+Tr22wGa>$GE=S{Y$kzBioA83k1q(GTv9Y`<%FPd!nLMT?=xWBqp=h z`wWS568Heg#6}aJ03`hoRlOf(Tvf)4fl-8cgJ7iM4^2-3v!0Uf--51a5>!8!;zz)e)F-pV) zb~{Nt#-I-9Kuu0`Eb{psOVex=!@uH)KGQCcHDEK9jnzRj^4fF<5MU0WJD7>qbV&k# zqQ=HVJZ$a1zcce}D6v}7aaNYP2ro`km#?RfflF=iXkM3r=f}5Cx)Normb@v)^9nF$ z4pNhSU1b#4Y`3N+M=aFg$Dk`s_=v%o8OBHbz_dXg@MS1VkP+VAY>k2)Vb#f@++`lh zAaXRd;1k14E=5z0vFzD7Zr{LWVy~y`(q+3wp7YZN_|?oSR<1X*mR_eN8!15yz)xey2+=w<)p>wKBaW-4lX+n z(*(E2O?*rH6q0A>RdY{eHJ+8q)?gYtph>AA?wrTMOG6`<{N3H2mKupyuq$lO8c_O ze)!j_T|_N`|EB=e>B?AP=^v=!9JJycPf_GPK=Z3e)}wYZWh!Ow{ad8x&^oBxLWx-<3>lYL;bts$*nKOY2(g9DKkg6 zz()VCC+@Ic2wqBRC~qj`elB~16!h78rUo{BJ&nsS7PfwQmoc6*j^LHE2r=ru%8k`U zWOwzT^go`sW4rg6M<25sEzPE_2QrVCo zs4t4#4!4SGhf~%$>tEDefP#xwU4ywX>g8f4siCtL{_ORes1t7z27MK=O4|Fc0!`zu z5yyYEo2B}ZU@EJ|lwM9Ls5_`Ak_FCEh=%0WYg4-c+d`quXLk2}n^K626ee38FW5Ho z&3zAv@{gq+x{qN~KJ0tGS7$Si!n8{St)O2>fN{%aC5e;nrZNYNd2aBKMZv-x%xCfp zXe#HgLo89-#VFP2@=aIOO*XV`1%o72n(i59 zSz^CphOWziRMU;wV1DpyCRnSBp9?1jGjJT4JNBuqfy}#vkbmb>ru3&~OAkSo7=;w4 zq`IPUoYn%~!`{?zJD`*K--bZD|&as zhV97y+MArUcCQ4UB#CcelBA-~=}2jO7Vi`?LGJ^r!oPAkQ}e?CC6N zy){c!frLkjDlsGrljXq!&)CZ>1HN4Iq`3usZ3%s9b_myhgH=>}aVZz%YeqgrJ-0K) z$^AxyG3tbW;`CK5+V*U~Z&{A0+r}Qpjkf3xU?~yxBapvHUz0#a_l~_eK{8=ShwXYz?SrDwWZC?0$Bqgum5gNOWaZDdo&T3SlL zzAeMtZtriI36^FErj3@`h6>s=SEUsGT&2yl6F&_m{LcELcHL?eJs)R0V0`-T@P`_~ z?HiY~#z>JOSai0d)$`p45ktU`rIl8%LWhoa z1jkzOzuI>VS82-fh6?R*!oT0}&wHrIIILkiWo&01wrF-9&6+T6chi#g|KVQ}*8Wt9OA{vd&huv{Z9KNCr02E^0S&`# zZVw^KWsDocK6t&;xwDX-5BMoZ-l=+I6^NAEJ-ecpD+Ps z`%Y_c1)s1$-N*2F%ewRV7s&nSDoyzMgXo?4LORH7S0-Aj`SEIC1P6PI&0jPRp_6^e zPB#OW(XX(j*MVO$TwWee*=*gHpE`$deDEoaj>IhuGrr;QHNarDBm0SmPR%vf@Jz_Zs&XlM3#6`sZqH(wGyyEuff{yO~fRDh{ z`(oPsoZz7|haisN+G$ZKEK^+rrs4%vjn zR~tx>$N6kKL@Th7musY_6RAW@;b^n_}AD8 z8NH|@B#R|MAwr%FTaE^N`iB7TM!iQ?g8Ia!3jGNJO%M3dVip$1^6{QO6aR3~G2iya zv>8tU#i{#`#H@HNBm#=Z&`Lvmdp8~xx1sD5-}j@NuHAdi7255O#u2&wDz!oY&xyTZ zZ?<;pcwc6qmF)Tg>n+2w9#U;SSl@2`>FEuF{K^p&gJsJmm(h;$AGu~5H0VFFvFbd3 zFS~NYd`Rk!+qj3D6`cA~G7$RHTHVy;nh{)>n}tib%@;d*ep{oF!TQ?MrXUYv<`t5L zo{|o%w2dY$4?pNgDlaG*M@9;|Ueb_-2AsksGw;~oeJM+^6FT&B&W9`HLOu^y1$WT= zg_b4#SM-R79Nk(D;SM>v*}wK6-6uKgKrCM4L`^5d z146)VADHJxUcm1R$ZTgfDF z3AV})8=Ed1@TzC;y1G;`BA8)OPp7#%N#N;woeFcjbp5b)Ti7EF*ze2nu32#U`dcy+ z#&W?C&Bi!j8FenGev0{OFeb2Tps+Sje_NLm)p*zq9M#rs$N9b; zIv~~vGo%EJc65QzD>vF6U=JE->I8ig%JQd_fmB{0tJXZ0zi5m0dOY{@0iN@$eAYSu zIELPVLy+a6E`TU&pb=9!+Gya#mIDLAg&0My>WKWtJV+O}p?D`hNZD!y9xMTg5?``J z&ByJlqoNa%&n9k6=eauhPJ~#_(%+HGz^LsPJhFpC(3clk=}1)%Ac7SRE#|&ySMvr! zGTb6Ywog{g2MwtG{5LRm&4F}*q7x|4iCM|Ms>T!qi)o+^YqyH0-<+~pK&CTjum3(N zYLvnS=&mf2$^Qh{=R(GfQV=lfY`Tiu{AA^~GOa_X0v;V1{_V-*I%Vww>IK;t5Kf0) zS2VeL=M_wRt6ox2HqHEO`uA_w zYBOt|g7tB+GsGw8U=HGmsRZaa-G%@2 ziyN9Ohf;ueQd-YI*`)O|ki(*2A9|FzGKgbCmp9Mi^%P;}z!`YJnVg-_W?qBOfcQHO zBH|(Wia0M)8^{xh3|8cAAa5*km7*X8#duMK73DUf^gxtV{>cAD>47Lc5TytI8#Qd@ z!_?rRG7JnkigmMcurTCV7{}#!h55|9;ci?S27$!$36{au855? z0T?={U$o_M&(&o{glp;J2OYx`v?{{5AL?xb*&k%%awfKn_Dda>x26M~uBKt=t3lK6i;SwxkRqwjB$5hKvCV3!}g zbgx+N9qBU36Ph7Zls}P8=JC*y#l^q$q4U|F<-te>`1P}AiW+3KoavEl`R3-Sa}DheU4YK7 zbw2^|bIn0OX5Z1@+W@S1yGqGksta}hi&-7=ANH`n9Ne0#c=})H|IYy<3W$50r^~dX zCj|f%*ymd`S8ZB<2dh-CO1%hOavi9{jRVHduT^3cIjeR`;CCffAGM+NzX1E}Rke4qrzSTU(fpTdUorg9c#4t*IGsB`$|CaDLw$ z7SyGH9hkyzP0DjWAT#6QWgmb?l|DoTctVs-{o-GE1}uLV-1@Wa!)*{V-|8E-SB_qf zGpOz8w{C>fUS0MSjL{e&Cs8ol2mdSq-cKX`&1{~3=cf!{g6h`gd6S)XBQc^Jf;9fd zga}X=ZF?K$?`LzcL(1G@M6DR*wtVyO-0Q=Dum`1c>?X-h2iksOpFP#3*Y)op9j4ur z(*{4w8REw_pzMp@KTN#=@%aI`qW<8KB{GP@b0&Z91uBny@RMdtQW?GhEW(<1X7b5^ zk3b0DI1^tRq|D9Q zzaB1+g0-;fHRfKE1jM$9_COEf&8huBiM0g^j{qFDR_BDH80F?Y&RnOmR2i82{k^TG z5TCWdNszkTt-y>*6TRS-uf_541$uwYRVW%*#!~A(XYvvph+nwVS2QH>Yn7`zZKy6B z#QEt*rM{~IWJXy)2|twfU4dky25=0Gv z+Ri1QPP-gVxUFH!zOjtBR&S+w7+apZvfF=TL)`mai!g^@cK0up1cnbxat~K(^RF^`i_oP4mEJg|a48eAPxvDY}sHEh1W`Z3=02(|g zHOOdN0Vp05dAR>I4+lh}pH`e!X_Dtv+aZoOEoz)=DW~FqH1%(sUo@#(ARn{a)$(?i z7-d)U4P_PXYR?za{~;J4O-UbW!X8L4slX+r#{cEMf~g;BW;42aMx}mIg8QaGtpYgf zpeSpd0ZeVXq*BXmfd774c|wdL7W-iG2>xfS`3!FTI`PkokYfDn0uJh3w)$G2V9ulz ztn~ExZI1=q&9UdFuBo)+4Bo5*Jpl z96Ijx`w@6*Dt7AhwYfoY79>{#vX!MUito;{r@N({@(T^aBN;sic6= zGB2S_!orFosaWH`1lyT*_}Wpw3ye}s;asF^WlAK~+zU1dKa7%*!e_*`xb9(gM9EC- zWy)>6a%=7y0AfJlDjk`G>y?4ee#5Py7hri_H17+r$HhlxmvY~!!bnNsF|Hqx5WvMc zDU#~4%k|7{??>vCzE=R22~9UGF@k@bAcDopwx% z(IDfwNWHsYN|(l?Y@huHvaLLls*e0!b`lPViKMpa zyPMlH^VkCjJLcdgL)chy3d-KT4*u}&;{UWN*&QBUx(|rT_R#NcY)^Xzviwn3<#OHynYhU+5tXeLI$_K z#55JMHowF;w5|WCKL9Be3Sf;XE*rjDLF?WJeAdrg9{ML!!_#2dI__=5|G@BD6I0-L#>j zs(|>a77YbMoH`0zVSfDe3I)UsGz*tZg%1t-%muF+>S}XqTaqUs>={5q`aF%vixDOn zVpd9s`HBDh2NWsx?krS6>{)6t7gNl<8%gCgzvNG1@pFNq7aahz+F{=U@xe+65-zm{ z+TN^fgZ%>}KE)J%V-hfV(3&Y{@j(L&m`b5Vl?JE*MU}??KPrufM~^oB_M3#$?j73>idt2oR@GF^ENWGOPK2mc^?zHd z3RS`HL06c6qX_x-qh`JQZ72$sl8781jst@7%W|fBVr3{{#N?2R8r! literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_after_stop_line.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_after_stop_line.png new file mode 100644 index 0000000000000000000000000000000000000000..1e2b0ea95d3b9cf83ae5996408f5cfef1af1c484 GIT binary patch literal 118102 zcmeFZ2S8KVwm+;W_Kt#uVi{x50TP-G z5epzHs0b(sMCk(3;amG8C?zwacjlJw{k`wa3^_Sx@3mL?t$MO&v!2%M8B1qOm@r|s z_C|Gs2@|GLCrp^UbJ`TR^7KaBIrz^+Zv!pW3CV@LA0|vN%Asm(p}PAyI=eYc5X7r7 z{}RNBIZ?c+f_Qa79L~nWL)6~chU8`A?k!4opu#2i-koCa?C9)Z&%6gGhLaExlM)e^ zF%pvz#H)zQ!oTp6qBvPeGv@s^BnL8UK>{Vf+0D&H5T_|ADh5mayhU7G5U&b<={l2r z{NTTSGE&x35^LZu6%P+L2U7=I9cS2AQxY#NikCu<=xj71=nCT0;BPl)R|oiymV=!u z1wEqXimAY@=>PF*EY`vYvJH@pJt?Sx7nH#Z%BrybP*ubJzzM3#uoiV@F<#S5 z&DPCEQw*o4>*uUvsw1K1;Xihd;ho(5w7hIQoCp+q2RGQx-jBH%9w&p51y}r8go}yc zWtha1yoPsTZHz7$ItL6Nk@Y0W$JyS&oAosFNh*cnMs@ZWebJ6WCOg=%^nkUZjh7dN zHu^S4iW}>Etb05_eMYU0E*OquHM(l*Y)^G!-YbKXX3~PLZ**`bISubDE+xzS#@%N4 zX4Xl(oowtWH0JZzrIFHNa&nlTUK9$fH$s>rzaGBH-A~QI4Y7NekF0$_6~F)4FWm6@ zVoZN$InYAaNA7rcBV27$d*E- zQry9c-Ov}RHg>KgFNzP@UX9{LLAr16;ArFH2JHH>f{L3n37H<1;sIA}ygitD;pps# zKt&bXP-XZk7z*A@%H|bc!IyAubsP{FTq8HMo^Otuy?m}*4}95VYbCy%@$9R)pk)K5!6)t z^juthi0b+zf{~rLu8W4awzH~-nYx&>k(Q>U*_KU?1ZQp7bF-F#n;Dsa{@SP~=3wgQ zw%J+I#dafsN&rZ;G4=B%x=Z@nx*JQ|;SKz4aa1>=Gr^w_py>|#f4Qb>D(+#gW#VtE z+^;}3k1S1k~#no@Kp|&5vMc;?u zuT64L*8uKpl>lx?05@E0wKM||hqvPV0(6ZuoOJ{Kd|fz|pRS854xW`H7@>W&#dKYO zj~hwMebhC4h(=qTwYBuTw{Fo3*lf6o$w@5wOwV5ePjGf6*}2P#F~4)A=@@F0Y_v=~%y3R(h&DK*KkSXS zF*Ojg0gWLT5qt6Y*NZN6&~2ZO+)4zlk=YnuNcevx*qOUqW0@ z?VqI0*hepbjXb`cHc5iBgqWV1N&wMNB0$gZpQH_}(@1~3OuwBrai9(8Q}Nd`as~Y! zNt=cQLCqD`c5<^ZwWru485*K{wMq6kH&=Ttgc2G7x-Qy&NSB#5Lh=E`K>CPmL{is< zg!Fujjc8*wV&`t+Vy~tuX6LTyV}~;XG!m25CNuR9Y)Z_`kmLt;0PAU!2$-JRd1!Ck zPEKN2xthFM>Ns~i7_!0lcK+bKLM=S0YfJZw3Zk=BY_YGX)+PM z`&-n3UTENfI)7c4t^WTcb$ZScID~(HhdQLu1aWOZJ6#ujv44;{&{zpT=)XxFUf0D~ z45$OCXyg7#>X7gF6TQ>&^8o)1I-!kph6d;@j_HUx_8AAr2HxR|=Na)m=862+=nS9+ zrqQETwxj8~*de>bd@#WX!w{r>n6K0ePysAP+RE~kMhKt&(oaf&zrrEha$rj>33$4d zxhGTOC1JlYxWM%5EX?{2>rnx1GDcAovK~KzIsvSW4b3C*`rGjqa0mPe7Ly?ViuMAl zA4mHry!~d{iAE^47{+o9&<%uhe@}b0LAu6xZ8b4}@Ya5RFM@D|cvKtzg|kL>pc#MR z3BQB0Ox^xBa8-RP#M77tV|MgyT>bXAii9wA7_I+leZzy)#Pl#b`sX-02_W9cVPf zcYn`+gO7!Z2%-*r?^cO_kUA`WWP_pK!#g9Sa|Eb6=>L;wfP=Ug#|D$XgEG(y34);t zRFHsw0U9H-SnBuYV|qq_dtWnbblN}6ut!$6^a4P$)KR4f^I>@KSu}(q%xab~AUp|S z0Nbc{VQhpCyVi%|5TFks2(s3Hj5d%biVgo3-z0~# zw||f>RKxZEoAQ(dzGD%>Kg%<1=-_~!{5@S8RZIBi_@+&R8U^id$`i|DA!=jghA5`S za@;ZAidpB-#o3`cDYK^qe?h;D)!c)Iodc`W%cgyZUHbDL=GRW9mIE}_sb0`v7Gtd_ zB`bj!m1OS3Y934A@uD~h<|W$KUaYt{PC|6J>*_SB7b__(Dh*A2)QYrW^?^xWc0yOb zrB@2~uv)Euei}65Fs38R>iPTrA8mtrNT5*0=Fi%pMy_B8vdsHXVNFZi+m?)q@J?d( z8&#xq{biwnYUg7gK=6UmJ6SgXj89#~*A8z+hVThzV`_recb7%3j;5^+EmR{72;{;2 zsq53=`|oX?f`YrzbhoHN>7FEIzh#rRj+!2J%?_F%HfpZp+oP;D>zB5vGtCE*C1_0Q zeQmRjX_x9U8w>#sI5Q7hEt-^efOY`EbSpGCMz>O79S=KAj231i6`r%%qDq4XAO$s3 z#}`MjGmmHhYM>S}lpwGYjL)AWv1+o|DUH!7)&HuAJAPl(Wc@~m(E9K0^M`z4Hta?gkpG&`Aa4|Yvq?Ombj2+H+l?=GA#Ku<^>#3|_qBCarP<=# zeC#)Z6{4X8kQ~ua1+0sJigF~B$UyrNN!cGlLP&Dp8nl4n9zO_HfuoR4kNq3~ZAEn` z&lsu%Ko|p(Q}KiKppXQE4$#s=*D&i1fTA+G?~4@^K)U*HuLihrR0>rAS7Z#0wqd%) zmF|X5sU}O_>_YQ3gW&*OJd9=pNT9(Qyefthu3)ehLSVOM>kFYi^3=Q~$5JsegG|M-2MWSmzd-b8+=^axgXV z-vTNKb0e;1re*=~-{Hv^mRr!2Hgk9LwpI7=vBgQc5%GG^NtX38GorXawE|`Ww8g(% zGZcrZ90NBycjyF~x``2?3rNI^A$4X>{2=w#GI6&96^F?q%+(pQrhT^H++1LNZ03dq z*Z!!x42A}sAZ?Nz8JibC^=9bjjhHuZQ5gv_Fn0nj8J_!d7$4QE`?h`1yv+!gfzA2A zJ_u}B?uzL;*jF`}E>H`)>F#2F05;$bXnp|gk_1y4%FV@eVQxZC3#(1}!QTPkDgZc0 z;_x?|3A;xU`x{3B5OQ(>P=lT&ji!r04nhrr%T{lcvjIJLqA3l)Zfk%p26o`izMUp` zPDRpI9ranzEQA5t2f%LxJudoqUF>_P;i}tHP>#11Dn~?hJ8yy-+Se`s=!7{N8n|+Z z!wpB!W5lX3v8QMB+!Bkg*xVJUpQ zw8vl51+v1z12jwJk8&!e9$;M_)MWr2!TQc$z8h1A9`3G;>S${WKZ#aF(;}?d3bZP6 z_+Pr&U%vZ;Raq_sg_@hOkzCAy{AV17Bu*3$aE}oG%Vg~Etn3JPAr4c?;w*F?=`o~O zvzh;uq=uE0{qPoJW;!OMuTJkqAGi3+=UP$L>7TLzN0TE@&Qf7q{)wYA(($Zo`>%*4^gRL>VuH{|k=-)DZGP}eKf#6Pnd!P$zq)#1n z4@^>G&mrnHNXX*^=;2`27OI6rNJ4bcq?@`O`V8_F15|@#1-oVsNe6fo7eIcP!2mBJ z$y^^24m6vDd7>}(+5i{ER9MD))?p4ZJvc_!Xb+CO0z@DqyzAH5GAt}-RuG}f{AXMp zji_)US1gTWVm?$MSu?swmduU@B(Z-${m5>{D7?pF3xvujvB2hDkWcdelPn6AD|nBsDkg*QI85e&HRKiIP8<3 zGxf`3@b`$P;M3QK(1+n?n6h)QAM+BTH^s-xj`ijo%jJ96e0??VU+t}p&=E|L*`bz`sAj zDLXeCZ*ONi4CVm7Shpc?V&c{ih!&fifL|4ZDQpj|Mx&q3XE24w2PM=TkiWez@Q{bOh<1k zBQd7R_&*MJY>x1SbN?8^Nr{gcN|6~B&i8HczYA$BB^Uu|dRk1+;r;dHeHi>fZ`_ZF z$ZS|I-P=J-glv1<+xYIz_V(!Ae^r{3Gu6S+!v>3QXz;rcaBXxvH@1oE2u)qqFGJvD z;BM?Qix`A@=<^87)6^6blTyQ0{Su_3_>6f9^g9FpzOf}~X^6eWB)*h*SRR(;17&2T zzWfl#h*%7j`G*_8BjYg%8PTy3(0_D%Nt^`$BXmK_Ktn?hA{Ikv|ER#vq@W;dgkF4= zBa#a{NsmyOkzz&i87Ec<(?^K)O9Ve6_xg{CRZ@q_v$ADr<_OsuXh59y-;gXjgZ&R?)l%YrVzT05V4TChS@XXwQI^_`kmxx3 z9RAT2J1>ei3`G8wg^sW^2^87EZ#j*$$S-mm9d@$P_5Tdq;$%c2n8j?11+ubuR;DvT zT9PbnA8CHW*Zw=^_YI?=-(3M=2bQDbet@Boalfe8mpp(O`s0}a{htN@=)18oJc{eF zL_$;y+S;(gmyAGCQkM0Zef{G*GJ^kevA&e73@Yb|!S9-l)L*RVAc2GIo#jzjsxqvn z|Ay#aLRNBYT@g{iBx`uze>wdB59Z^;!xGx&6G%zpN2N8a7-~dVCH`L@R=|AAAN*Y6u;2Om)089YyV$qG zKat7&g7pAIxlpG-zrOgHShj1zgyj=pAl=B%sOApQA5Gh&rHd*el#F_;cHhpaL{(Lc^^kMZRy{7D<_SpVT^UfEz_1PUII`1^L zO_<0rd8w#JUsHPi%LDz-RK?HL){Y9w?jk(}H3voq|$=(C}?v$hu&nT%1%| z)r`@!QMs5f*|J0`oUDCi&+$dDUHMMLm669#jz7c^PF|J&@jSX3Z>e1Tr0*nb6B`#F z-PIoxJN|yNi7M%4p_yE;r}D~)D$?_*+U3*eg11+jnZS1L%f_s~Z9Bpc_YN3;zYFK&3YUQ1$arKWp;zu6wBcU6aK>e_Y9~SY$B7RuJi{jau-pXJ|PT>$?yXEyI`NX~3F4s^R(d)$+8X4n19GV_%BzTC?2@aBf; zJwxM9Gnsq+az=n0A}4-5P?ME!Q5N6#EUy2jNSXfD?nl;x*CzN4be0_m?kZoORvyx~ z#lQBLaM)18^`iR(>57H*#Axm$($KM#vyqB&_nT5pOT4GkwKLo`$90H{#ei2flYHb6 z5m%g$IE2oURl0iW;|{dt^YK*Wz76NRLJ93FuW6quz$+iYZ}~96BZ?ZHbfqtei@1Lm ze}L2N1@b`*HF2Bjds{s77DZ8CC07bDeDi8;N4Vc%Etold8l8XI2-%mdVdOwByzL}0 zRE|t7yru0rR$*A>UWbIfqJcjrl?`;e8I4Ipj2BZZ;4@o=!6QpB89V^uKS}b zeP6w zl#AUT;x|Xd2i7h!y|==8@DoSrfzWC$PlnAdhrIr5?;?>9%Z~ms(>V$fifskN;{kKS z$rrP@$M?sfnIB)?Ix$lLv8g+H8<9~r@YC}Z48^v4T;eX#?$xhIaUx<$S9_d5Gj$U!osmII4^Jv<-dGn|Wvk=pY zdEgwCcFAhR1HENA+&m#eeVp&*t9lB%-#J9(?G;WwA?Vg1@6*LEEn4^Zq+v|x^9%ao z{tu6qG;0)#M3mn7%J|`Jf|oC6e7=3KVkI)K?qA8xManN!Xw7djt`1z#e>&q#QdzC3 z#r%ep+>p}C2NXYTbjz*qZR>9@;^}%iBT}oYuv2Y?hC*; zsyKsGL1W`T#>;#5cgxhrc+a@kM0>eHFIr*^r8tT>6k&HDqCJ5iJm{YA^lZ)Vl;Fgp zeG8~MHmN_4xBIwh)9ArCr*v)TLWf{u3>=r{&{w5b%9+JExd&G@b|j`m`jlBpV=H&p z9LV=ACoc;fXt1`cJ!TqN?)YSH?Q!$u`mWWC&oR%#*)ZiNV9L`g6>DMd-mRdNfxX64 zDy9kqiTPIe*K>F=XUC#IeCtRtZqhv>|DO(`L6Tx2ITU*QbgO_Nz?IlT;dT z_AJ;+isLhP%WxAxDB$aPy3op z?9P}pXZNJJa!z~1%-eiRAD$K~XG z1xJLm8sZ#s%xt>0O`7vF2SqxiYN$LnZ%#SII?LhiZ0Y?vqS-g1(`nSC`11Kj_6;lA z2rjQPP%iHL1);XGHHgyxK*q!P%>0*EJ@aE^Ip3x@7VbATwMcF=Ypl=o?^5btVb+jlHTO+u=!SugXDMcxi>Pyzs&_}0xrwyK0^;&m z2Z@(j1vZ`VygQq(!djYVI=#Xv! zyZ#vGSv6_y!l9sSQ{n1JrRJM{A1@|wTgW*T$1lF#*PJKhWS+Y=gD0glA;dg4C!;fA zAk#0Ocw%#7S%K@mC(;L$6bAh+gXb0Ri?HL-=?)pX8-!mmGG!G3CF|x#w+7PS2B@{aQ+9t#RgYQ(`wbJaml> z>=L)D&IxQ0Nj@nV=zC)&b-i^sdA(#3bCPQ0{>2o4iCn^)0R$67G;K3APOaE|$e!H5 zm7&G!Z!g%IL~KY4scr8sYX~+lEl#r6l@c6lLI91(h*S>C2k$fqb;N@VAO#cgYyVXIsLJ>nRn28!IkWxs0op&@>^UW1vguCtr#;{#uw z*(KUt__~x<7dt3dWf~o@AZ3HKa9!GO5Y1NS`>74~-@1n_Ow@N#oWu(OPO0Cio?LOLkAf&(M;64_nxfsY}U32e+DiJYNiz1!LSI6*19 z_*IZ<`th?~KeIur6r{8ZM<{LK3I;j5v$X9rzVL!zhq#siACEQlP`vr04>AkK5C9~F zm2t!KD@Ht@>|G4ur9({~kM;gVCRtHU@tXU1b)TvXZROb#hocKg+aLU|riK!bVJ(gTXU zPHoq%Gb|FtWoNM=F%PC3`RAasvr?}zSw`~pW_nv@)nM8Lerd7=ug_!g)H{lHAD?$a zu)K&AFyt7WmlD$RsG6jbZer)Pm<{9h!N{lr@92Y9*fWZ6wnxfWpNq2ED_LfN5Akh( zl6t4oyYb}-JW0><{MEq5`8<|>XX4Ehr?aJ%9Xt6TaqBPgF3Pi{RTwWXy7_MBmcXV| z*NKB~;97BnbR=X8XLdgs>UetK{(J2slPk=0^H;C|73%8c4BxuJNKY6)$LO~l#G>-)UV>;#dq`{?H)QR;5Lm46?jDz2LsHt>gVJw2?%sS~qT@O- zC@ntPMc>OMz(|l)y4B$O;Mq}?y1kO zi+1NGZfH|qm)rlzv%Z4HGjzGPbMW2WngXG?{Se}cHs{pGc7Hy)<~vz2IK9H8SfO>> zq-wfrib!P8I}M(^)oQy;_6{;u9k}-(DP6R%wX!QmI;8ck0JnI0XF{hO<@Jrlini)) z?ag-g?*(^Nn)h#T{oJ@%!f7+HNYS(ZR~he*&oz=+Q_zeLA>3@Hpo@P3hpGLHx*loh zl`Y7J?^*@$PGz|f{vLoQ4<0Myk@*EXf>E*3gyKZ{s6)0uZM0$Q&lVG%0aqwnMbzpt0 zdCa@tj}RkI`@YsLPNJ@q8lU?uzhci3-h4R2p9hmR?BOVNC9S4z9#tT;zwM=0`;&b~ za_bdZ_B;~J1$v1??MnHO@f*dwD|sZkFO(Oj{@n{(2esw-740H_O2X7AL^zFr4gw{k{g#=(a{g~dpI>f>;>UmsOx!4jX-GWU{KL#v+Jf+n44R1KP z;encTrOe=`sNCms0zdQ7?rjoI0%t|W%~2l*;L2}1!FtN1y*SaiB~Y9cxI1HVg}Y|t zeyzH~q(z@`kJfQ@DRuwidA{Jt>P4YuDedP8``)e6T&UEd=&1XK){>o9bltHiQf2#; z&JO<7k#X}#dZ+0RBuRxQ`6f-8q)<_0%ZB(JlcTA`vp|%C7S8I zZ>QGG7QVcBN&o&O_`TUxS@)NEK1xdGR+>pa7IF7Jo5hZA0Z!P;QGP<+AO<)QbH4NA z^|}RArM9*M`RlDB6Ur>RkJsJ%tesJykD2Q)ZJTckGz__IFv-AvCHkJ>t_bwu|>SVdmC*eMX)@pN&| z?YZ3LbCyZ1J8$Ws(sn%_qQTE>Oyf!iXj{oLGb~8JK|KJ!xWtuL9Euo?Wx4!3S-ixe z4GouHdL<^U4GV3(J=L!4G)?q#B{{Rnw&X(s4`RjsyXVJ}3kNv930SdKk+K@G!U9-f zu{xFE4Xhw4)E-69kw=ILdbkFG>gCCUh4Rh2uL|^Sx!OerGyioD*Sb|-qotV7m&7G3CckXPf4XL`qORf&`I8pVCxV7bgDZmvkBobIg< z-}ADI@2?mE2MpT$@rdj1QAmTks1ava+(d@af0|V?I=~o#Y=&Gqz3`c*6rzrC5~4Qz z!%f@^sF`*=)Xa7-$uYMh4#)x4`ou!7GhaXy(KUByp0(opgLi84qpbN&32|2aK_vx3`FiqAMtjPHw>LY2R}mO`FSO6w z!ar|O9>mvK&d+SSchAo&$~>@ytE(cA($;?Y)pfh#cohYOu6u1<)sHV4@?_LKmc4HG z%P;W>eOvdBp$0+k5#Z)(!n15-F}G|{q9+gu*;QUasUSnNISA@np+f9l5ebFo22ZBS zL(Zpc4dU@XV2y;H(*J8R$mBFznLsL%RIVPg3z4yD{yeB75z?GaZ*M;3n!KdE<%*h( zXZ>l~{gjrR%zTQE7ZXmK^si%>;O0b+FAe^IvYpf^R`~c}Rn1`? z(KY01zJ|+O!UGjm#vDURMM?sw=wsU=lJ*8yDA(7B(t*RCFOQD5$Xf;gBszKZPY@0r z+y^8-`kgzt5ctP4M^PrktMdh<0Vq3Y{cRrv=!86*G2RYA3sn>XbaL$`bnFM)q^Qx6{L$xriI)Ctkj`>5Y`@@p$uBKe_3SMbqWVzkC1~I@jJ##ty0u z2esdPa%x3{^y{AoA@QB5@%++zngD)vb7ohiZJ&HIUD(9JGw;L(XM?tp(XnvK>0#B% z|68hcSBNTbQeHZ3iR`s){E%$v$`AE#dYbF?V1;Mifl!N>chv&@%cWlX*{P(L?0Ff( zM*4>lkLv0yF&=?)jDB_Nb!0Sj;@WmDtH#F-QawK@!r{4sy_9zu&c$&}B}Al%M{EWoq#g(;5~Wq@8=nqry!sk0?_C>S*= z^5&aW9V_oGw5U2`UaQ{7#uxum0AdyNZWqPG3U2a=+b{0r ztf!`%9MuVWV*A?aBujUjle1H~-wF&o(1PA$i)i7eBd*DN63-LY|3+?j(R+{Fa3nLS zj7>VF^f%I}v&|}9*W>yuf`Y1oXTC>0gJ%i47dgA7BNe0yUsI{>ec&8U8m7gPwZD?$F=eGP24oP zaMBHfH`JO4&QCp6Lm_VT59d=SgxWX1dFlB6LG?P+l-mEAEdPCpbJx47{?&C)qIn*P zq+2}BXfMRtm&;na<_ho=6?^R0Wj0=GD;oN=zU?$6G*c$Jr8w!yZr)$n7?3Nf(aghS z&TNmDHJOU0=j`(>k5cOCt%P!5W(z%W0zb}vV}I+lM=m>p-%gx*&!^1FJjS_?&v&vSlX8EcmxdUaPA|aK5alzFOQbJNq zUe*V7Wr};=`L$ZtH6`1(|J~fspF;+p9th=K=5|GeU1Hv1Q{6q?v+nuDeHPwzF|WkM z#EPE{tQ+5ZR*u((i1o<%4_3$l{BjjORL<3caB5j)>(1`Dp`JL7ZdST{(c~rV@ky@0 z{d{o97cWfq3DrLl4heaCW*2viAsqDq+oO(ad_es(v+0`72JncnM7=$q-3z zC|xRjhBA~Ttuo`STV})(F0R#j3!#81!nS~UWm|m19u#kf6Gwri=`kP(~ zSbl!pX5kuXrt-BwUTqP<=iPFt%;Xver;IEIK5E+rCB)lY}(oZ za8ALh>78bw1D!Ql?M2q_A$`BJ+TI#*atu#WVEiK|=a4Y^B7P#W3$@FE#qPlieAA&} zq-8buliLgZbf4H&bL7`KK0cv8E5tL`#edLn1(Ywk?y`BQ|C9)nIRbNA(Z zd+73r`gzo4ZL{9bqw?_hbV1onBZT6C5Z zH#b7pX3ch|9dEQD-fdJE>I92M&Sy=|GiX-+;egF0F8Gy$>*-k5|I^(TE5>>% z={|i)#0UH#FKs*r9#z@&Z91%fRx_`4{wnTYOKtA%q6wDvz9=l(FhHG8Az9EYAIHdg z-xl(!U;o_f`XX=h+|L7Lj;xrPimowQjpo3`XZcpH$=;4Y0;y8!RUCQZxHDz95g zt*;t{YE`vXlqGl4t-g+D#IB9Cp;51VpI>ka{?yf(BTVyLHj}O(u!oaP&4HQEpWA_{ z9kZIy-b;FtHeSr+0+Swh1L(jw}k z({b_U$tf?`?6fWd9+3#B)IpEDg67$){Vs>5e(xg?CjMd+PUd8!p%NYzcYU?Y;xnM~ zD~>)w+*wXRRpg$YU&$HmT+~OMsd8g(MnHZJa`-6CqCiCM@@4Qqw7$rv`0($1_lwLnO4)xu7G}Krdp*Q@aAUcIHc=;()rUYc1 zPGzHr5>T3Re=bvj^@rB!L2TOh>cS^3`dQlRHT;85C^K$ZR|QfoU%4~G-%hl;BRXR7 z{Pwyh`;M7f$&%yn3H4n<-!*PA-lXSJ%%@-GU+ z`a`s=8ost?t|?7D1JmgWLaEEgaZ_0U)F4>GEgc4e!a@*$#fBVH>C&<8x3!QA4w&dy za4zcp&Sm5i(vIaHpeR0sPpfoEtj--Sfflt8i<@LGveEipu%4!~Hkrntq#aP*itg%2 zoJA+a`Iy9b^tW-o)z9bUs<|J55nX2GP2i=z4a*CyAXNp|0H8H~FU9Y62}C}H%E5#= z%M>@9KOGuUdBQzmsQUKQ{1>Lymi=Wdv4P~Ex03`I-??zQU|H|6dr8)WtjD-V_nxG` zS%3y8vsA1V2hh}}-%#tjr@i&jCKlq3MJKsXkXqD2_zsrLq34GTGAR3*|^Fwk{C zE$7oQY<1cC7%r~-1M3Ifp&+$SJ0Z^MVeoYNxhrPlO9NP^S8>UWazg~&I@hyJFzQ}(Wykq-Hs&?~xxrl#Tk$0B zdI3onBi&fsxf_A=sXAv<#n|W}8WIz;PsgxnK6qxL3SW3Lnum46d)cEt9%o(YDy{pd zE>j)o;~mK7+5OJ*)ww9{d~$GgHyyw^i4th;oW6o_T+`JCA>&twL8ze!?zHch2joKt zedh-IJD=H zb@j}+p`iXol9IVc&Kb2`_x9AnOa<(;0ww7fuhiNGusXw2>R(bn)BRd?E_sFA#Z`;_lG!1y|<<+ zLQoycE1Z($b=Z3bUHgQ)>Uh-O4294$+kMQDpsqla9^J*I52Fg!?U(UI>uf&=Tek$1 zW!lDp20?(34?~xR)B6PmTX&s+6rlg@RHfbWb&t0)X7x3vTl0q8o3C9Y$XH#QwuFs< zK-xQJKW{?%aO*dWd;1|2KK?Pg>kU^vZ!i@~R0=7oR_>`UY-!f|y$q*dIq6Oq2NEGGjaR+Z zfU$&A=L6ACJcXfA0e>Z4pE-1qS0+XSZM9MP(}iN@5&J(7Q}3W4Jm~YbNpSAZd(hD1 z;p@;Jyi(4_=2t-Ysy5|=6w>pzso1d&!pukyy=X(bu5Rw9hc`P*&1<4^yESeMX74RS z2&FkofIpgYRbzjpe?5$eU8r6>^YcQgaBaHmc&^pK@^zD_LFhCL)Q@<4G1;_s0kwRf z*=3-&MrmM8Y;Sv9&BcURGyAs#1+B)_ALl3f>JGg-85+q)3G_PCU~1-k4$U{Uk$&lX zQ4~qao z+K_kkYDj)r**jI0^f`teQ^v1j0i3W9s(*vjs`wZv^di$HQLubkLwvjnv09oX=%J+GF$E;QoO}0zb!yvlEAx9bRow}ZMUvh9=C%ZOU2hk0SM+0d??Rp#^fgD>k&yzA zNttx@g4Iu|2r%EuU=I%`os=X7LLi9WnAFcX|f2_xYNwT$& z^)i3VlAGnxnyO21C2F zPN7wEYDLAaJb~O)Q&@xg>ayP>o}!lTJPh!({Cr!!;pb*QIggNx0 zMw|q{yn9vT)El1`UAKF(y|CfC>5vaN;^+1$gm11>?FZVuQ&VHgk(w-|8vb0qeQc_t z9B&OO5pp`K4@%z3aiG`!bF-eR(DEZ{uC5Vi@lzJI4klghdF3saqnHQ4FvB5mbQFRV zxg!x!Ddh;Q3Lz`Blcih2q-7a{UAv_A4)qrb$?+F&Qpy${EK11z7bxkQU87X=GPh=8 z616F%W~je?E1z{-wW^Brj%y0zajqB8p{cAOlY+=XJ%z4Y5TGSMbxCBtWAYNu#?~k~ z#q!qtm64}1bU{n#9`Mr8df&u7HA44J!s{NNhKiUekpbT`#qs(#`5IIMt}i<|3E}9i z!w})={ALo@)v=OMT2JOyEHG}{vOlt1PO(z&s-y0K`Tr6mcL}xSzZ4I7akXbxjfkgD zR&Gs0g9i-1?OG!XR|DQGjxHl>ruZyZkxulKT{oT^Phj&?v+sGLmE(B{f6~aQ%A547#9_?eXz3>+;R!KzG_%Pch_p z80WyWbe?p;P*pg&H=!_+jZS`qVrZ$|96b#C1tD1yoD`Ln6)(&<-oJb6_@BJortA(T z|2p#iZH!A%K+$^1XDNa}(T6xWc{VNJ3%h_V2V`ZiiL0Yfkvcxh;?pNMviYY~j{b%O~kOTpVAyLG);83~S zvqw#rU)Y5$qujK)Dm-WD1{tXe>NEb96XcBOYN9wU%K-|0&3~uKo$zk~60~6v?&0sgw z6bD}g%lW0VTFcMX-qyFN2Z@oJy2Z@%KDJ$d98&9*FI}(7#!4q!0m=saJZ!y-X1rN2 zw8;Fv2w&VU`xftxw%Zq(LR&E&&?a*Dqk_zrp9Btj%o(zzy?TGYGtinie+k9d6Kga^XVB2MxFA-gU8 zSv5Y=5yo~VZZFz8McHt1xb`Zmz&ymkj9Ywd^^2D(HFS$g?J>613%XL%V95rKwkcPF zJ%0T)-{sz6nKc(*{!ISZEn2y3drk67`ZqrqSpDIp7`d@qbmzVJZlC>)-2pso5O(>& zbQG(6`Gw*K7H(-wu6@R@Xa$Y35y zwf8T})G}=e&X=#8pP(1}9NoDAz3^9ZF~O&^@@nAz2!;C*4IdTS*DH2B+I8>j0mYIR zfkefo8(V@qUt|Upg};he#zV~Z+1%fKk54{iDB!BshQ;O7pn?9Gp)ePVI>gD9>5q~# z?+YoVhMKmV3~fu-+aMm|Ygk`3`%OTVC)fRar8!HksrUJFjaR?0QF%2dM^b#|-3v|h z1wHo$<18-0s~q}TKB-kpNO7q~D(Qa#lp_a(nqAkhWAI z;9_`lf>LLZWfQGYI`^uPN>_=%;FZJya&&Otf~gh9YqMTdEgTxWUKkfe%iGiz%}^Xn zk3F<$mKe()2-0;;cw6$QmCYZBrJ3=*DdSZR|CLc-@IA zro~MiJ(pH86f+*qXzMf2E&VXRX6XLjwmwEPSA9|*XGP>5%kH69nR6Kz_U0X^$vs#s ze`fb`-@V&@nWVmX{ycrR3!xfU_Hi~C##!DDUnm^@a?#PQ_ph!`xFZ-1Q-CK{If!spmg<#f%R$AbgoUWi`0c!@zd?UWI8VR=}xJ8tdrZRpl9|9U%P zB8R1^?xfS$1|A06l%tf(KK5?XjL*z4;}jVfoS0~7WM}+z6Nlv^tA*-gsK7qnY5-EK z;#7JMp!Me&qa~z2t}Ix85Qyz-!M-_u5Tpl}_`>5_n(2c#EIK|2)v3Zi3fKl$?fcuN-i}W_dn~M{5 zLPH*Sh2o918>okCKb;AmOiwGgFy{2kkK2SH8nzUlP31t0zNI~pqhg~aM@5OLIgX=3 zDIoD-j$qwshtYpWQw?6PtO40HG zEkxDswTO;oK8N1(Y}^!|X_v{p-tVyskFoZm8*0Hwto^--C+QxyCYX0N-)s=Ilxp=t z@(~DpKR<%6{b&-sC8RaSEZx~Ian6qU?3mY@3CFG?ooHKuh}o?y?KR)t-rlM54ySn1 z{>DbPRFQK#4h+u%P@a{VR2cSlJiQ=(7D+r7=YK7Eso#zy`rKK;n+JNk(v5|TWZV8CjB4P_BvyuNYg=BzkyOc2**~zvepw@@zlj-MD z(te*zH@}|hRPZyXf%9Q6pHu$|@7IKpebcx_Qu!IDuD+koFgtDV5IgHQlk^A17ZF!X z!U){G8e_bB#IIID#SurVm(Wd2=hU(x9yCX9n{t_~xtS)WMthi$aBd@}KS`VCusd>? z`t*5>)tgTBVMP2yV48pRs$#+7RJzH}yVxMcHs#+yx3~nK1Y<-T2KpLWl%?0NCvJW9 z>fxmm38&4|g=wylN28){bV93c-h+*%nonFV8C*T=vR3WIC6kDs`B>F^4&10*0 z+mufL>5niG-Rc4%49=#e+moDw3r#-UlzN!`d*<_tJ8sYvE~=htDN7ZadebiI#xLhO zdfbc`w;x(dF3{iJvG$V1MT1{tCeveMjO8NO9OCU2(6+m`BrwQ27z7LtokDj_C+qt< zO4jC3Pe0Fa_{6hR;mZ2f=UOG5Mb0UYr(Cj1S{jxdtl~0OUPxbmhZ;S3hAvJGA*6vN z$RRYWx%cvu*Cm&(dL=0SY^+P{6l`v43sp4#D7huDjB=sqyl&kC2TIZEY|OsKD5D3& zU}Y1HPGNxS5e3BNa#XmNr@Q*R)~hWP5Pp$dmz<|bvE@1;qqbyw?2Gl!a#t5e5DuD+ z19+fLk$ZV@XWM(61k(Aic;;fc>Fy*riJWY278retc7WTsPTjc?8z`;d9GuWO&EwGXu@?N&$Ci}#nJQiGb~(h?2W8=BJ0 zd5m6v-zCeCp(&%YDup$l7l}@N*I)Q>nKx%*`7RFQrIx?-DD_`@_z&Raypc7|_aUzFg=Ip2Dw8+gxu?k5hXL!-Q<5VJt z2Y58F5U-5k0*B?$WV*2TwHv{W$`@Onu5%NZ@m$94_xsj}Z_%mAp~x)h@c5dlvOtn4b7Fr6BVJ2Yz& zn^P}O2F`od{w|KKCOu;wV*%rSmgvwHQH6o49ksm9ua-LZ>0Q+4bFSKX+b(XsjMXJ; z;cGqZ{Kp5oj0@5)pAeP2yvoN}u!6et`MbAwyxNcJBqd)hec_$Ck!y%=U1pg^$w$J| zhLa&FO9j^PROSyX-PC@6(=lPqH1U3s50R$fN`0i58>SVEuAfQMIV!w34EWekc`FL2 z%!x6XvIFsYo~UyCvJ8G44ktl*7k+|U+t)Ykb-J@_V)L5dUZ>|Lo~C{Lbq4X|hOMTv zvwn*wtHzz_D_&NjFm%YPeN#(d4ZWnCw(+#t!sBa%i)T~TWQR+Wb2)hQS0@zY4y3T)>V{njxHHqwQDNx zcFics%RWBvURcTYNt;?OOg~)SBoL%dXc%hS`>%7pjc(Jj04{3t@kKM8+h{Fb)IJtAw^GOFs;MbB*x2%ggy$=`Xj32F!bN zMGqbO^y&A8xVijEK^CqbK3^B)x^qf+!@2=S`}fTin}ttPj^v!=>2KaQb-Rjd_Z&+u z{!rY#*A%^cc91-T3H!>Gc8Q%@M@3t%u9rD)yD_9ZZ3? zZ3{)rs6P(OFw6a*@u96Ne1}zrK0Q7<+d9%IEV;)z#8xMuzGWKqcbPg>h`Ql61>@2om@m&O?ExJfNOcAKvtfp<-?2l2{m4$HuH zJ!kgk2V3@;cH9v=|C?3l{59W*dmHVJ z=sNf4l-xb?yLmpRb#zef^Rs+mWC@}bJ0GFETm?*QdU%}_rql&Usc%4xaE*I?kZORB z%a!8iXAZxby^P*Ch3-&ssi*RG>+=oyr4|LV0JIOA%{hEL`OusSVsFoM=lA6$d?}Or zJ{QS2r_dvZ7L<(uyYB3p6WKzh)qH@=hq_ORh+|s|o=QmCga19`z~qKpkE9#o<~Z)UmBp!boBlvYA^-E4aBMYGMuJF2 z0!T*n=GHo^FG!Z{*`*zKeE#LMT>V}j?GIti(yPwtiG;h0Y!yk((0iSxcFA;AcjKE@ z%anpSRDys!SXndiqNnAD^UtPJD>_XyDeRo0ff1OehES}{Dp2B!KcP*_VN;Xb=@wnt z7G~*!TZ$Wh&%S2bwkdZ=kT2BqiiNX0_3k9gXLruFY)sGMb!+H|ERm;ir#0+Urqu}; zM3rw3cF9cXD8Kf$tg)DIE?xKjUN(UC76&*HMVMBBp~!CJn15drmb^pq^QZcfb3|_L z4YeCT+?Zofv9v^K*}0<7V~YLyua7KS_pHn5LsI{832MyM9{;DxWk;nme+ji%d|CS4 z>Wf33w^Qzd)yz4{&%4=IEAYk$;jnGYj8M-89=(N02Xr_mZ=(P_*U4 zcRaA8hT43#783*7;dB3(2__8-j4?|l)46%-LAm9v*35F(x#SpYE`K3iqJQN@1I;Vy zTf>t5D|nv&>tj2!ms}?K4(0@!zMo?$Y)M@UerB+2UkO*sqR-*V zWe@jn#xko>Ac^!t3%263Ij4{DL>hu?&B7^R$9)dx@vePugeLt|+*zQGo5kjtu$$oj?;ksIA5+dZKci%!;l7V{++GN= zuB~OKvh#ihXZ+|A7IC&_V_8BAPX=+y#`uOKd+ZluU^3=ko{IomgoProeC4J-Mp#6{ zVZ}v=Tw^xj)U@TBE#NNWFr>S013_6iEUVUg#mzdXTqeX-AjXcaYDh7cnd&W7LrnEJ zixIZ0OfY!uS8~Th$;$CJ;jTnx+Kw^>h&Zg@D=t|cmP}lI*oGZl_nog5>v6C+F$ zBTPD3r`PB!xnp%n*%R(E;lwnl1yBwmv)l*4IAspYINhJ_jwJ~ZzdI4^(L&aF7K)2* zMPP&-FZ=&!d(W^Yv$YL$jGz=j6cwciii%Q|Dm{uwlio`}L}~;C5_&NxSP-z$rAa4{ zfCP|4ilTrN>4X-F3^nxLIV-5M_l)lIo%wP83f41FEGb^*W1+q%=KQ);Awf7xQ^TA&G5g=~~D? zr1ATopH#p}YCIGDPJo#M(x#^5RFi;puK(HDcjUKJ@N2_2 zFULk6>pj%tJJYfk#+-iAiVQymQ8!j@(A`BzE^OHs3o;VGhVhpZ*hxZ4nnU8OuRnv~#_NX4e@1L-%C(KmgyBl`^!utp*e~o<;+f zD48Pv3=<%?`b~^SEd@(6T_r%~6`*l+DO?<_z1h&Esp_~QP!b_q@__@Vh}BB+K{}7e zd9?_s1zwr&y`(ezHZ&j5Xt82q!BiK0SW%|L~oe*;uZPQ_VtTIBseCH^>cLs?6flFG=tp%hcq7_ksT z{tGmu_v+cLLPi}A@3{3)KczWwpfc187>rRO2DBf9%iqKb4;Wl@3fQVW5}+=sd-tOwl6hj6!DoIDMxl z@dD3->NQ9TD=)vw8?YkY>ZPd8F1-lUTIlV)kEJW?%gtR>+}5s6J_b-w=@N2I;|5+q zDn)m8G#OgF(9rN-p*+h&}{7uV-7JCpqv_PS0$F7)}<;Ano$hMT%M%$`j;n zOn56>a?&7PuI&39|GU#uSP+{pu*s-&+(wTS7fawk3ynXL?huH_b$I^6fv)iu!3Za~( z76l4uWJY)8ZhX;f+1hz|>`!@?m7;>wL6%7NvDneJj%l9ZVHI`Zv|%B|zS$XM%Si5r zM8CN>gu=F)PhEF1yw+UIz)io2 zXGce3@D}0cWoaCJN=0pr^KvfO);wx+!>B|laG{FjtrN&ghP*sg|mFe@TVFQky z7>i}{Do3?gz*BaLg8IXu5_p!gzn8BU;H+K@lnCs~*EfoMGe$#sRSOXx?+;yx})*!q>W+r@l`?~HZCPn=(5~=!pPT5&mTS!Z?@qS9Wc?wpQEtY|>cVkhCl zK&#n77#GRKef-K;2m5$tT$=oRUEH(P`2?Mwt<-oz;FU?TNSZY~a7rI@-cQU-YCdUT z#RqmKx9`l7yhiL@UCW2+Ts@n-_G{}O6N5NQWbQs){P^bpygcj$BMG~DlR!GF9>=Yp zbwtL!i;6ginm)8&^&sQyK1r zdz(gQ|6%Aw&y3KP1&e*foQ`+UP44C}-o8Sm*o*4kR_Tiix9qnf2MU~5FgzTss#3WM zvtI9PSnjUs8zjLKUitvQtr-$1b`^!`g57aH5l8MQYk3r+dUEW^Qj1)aN;*eD&vM9q zT7*~1@6$h@!R`qru;X_j6%!{Vd!hs(t>*BVJTCu38ZqRo`dbIyM`7Hy*@Yn#tAGL{ z-~f8teBlXppUAdwP3U*V?J#gvaYoM5yH9#X1uzSs>CnZt7koSe#$QaU7^(EO*rQ@e z!DG47N}0Be2^#%RmVfs{OtVh`3u>GGBy5*~{sfRGIT7m78rjf&*WY$HwB&ThFjSU> zUe6x!cw}d`AXW@M^3A+OY}bJO^W(Rxl6IeNs$GQDZf$%%lXJ#tJoCS3(XhVYs^70F z7OaYB^K^T6Rh<;tRx=5HeSW1#y<2kKb-Wi-M1&me<)}TJJx%6*MsJR{oSTR6g&1~+U=zyqyuvF2qw2!m_6LC-~4vK`hd4V`HdZu+#a0E z$VuGqBF=mFlmIl4m2yF_?V?)zE{zNmiCr>|D@@b38rJaB%8qvOyQJ0P2T5#<^k(Sj zTVk6ixbPB0&k_oYG?Z`s6CHg4t5Qk$!)cd>A9xRbat8tvc~fXwd|tXB*3|;9G11$y z7W9eZ+uw=!*uJd+KOkd#t*0sW@*e^6y=uxzk2}iU>=IpC4FOlsP ze6=}oQBfH=lXtB3>s!C(_CyfGlxpij#{KnNjkvgBC&bWMs-IP}vkvH^O~k$hQ{fpm zT4jFsraY84m2^a~?w&~)@FA&@{SeX{_#i6zV7A51wtJ-Vm98GAwcA1|2|+5*dQc5|Iyo% zzuQJ93RO^dqv_zTgj56HM~lc66x>Z&!h`+?K2!zLt=-bQfA@&(cdds33+HYYyzr{z zud)V2?=awm;?CPo??w#IM0aC9bV&Ga#@pn7}-Nwa@e`u{tp zb`wHc>GL8kZ|xxK8j8r#bUR+iz>XYqN3;{6vYY&1nnXF2lddzRMP!DO9seHWjUbRD zmEEZ?C?Z!mNLtU|-dZN#F7Nzp|!b;OkP?)hd4{R5YG|KOrvY*8K6q?0_-__q`;a_NyyhzQGt`=$QO(WEgOG zz!$`2i!{FbVWBI;APP$v(;YH(TP3>t;h84Jf|^%;D_%^q7_dH%(Xa#x7YNpLPm}7p zU9uC=tS+TQf4}_$#(cAcz~8QwYXAnMapo(B>`$UMkwzw65pP^>da|J$k#tfQUN?N< z(Le0mk3atouc?@3A6L9I$zc<%p0~raZhPxE3Pfda{q|jHJPpAf5!{p-f4(da#Hvt_ zXje4cY?ijQh+{1LS1ZO^O-7mc^|EvZ0+os)Ua)l)&@`tCF$2tTu7XKeV^Y^c|(Ji&|*QH1r zs*7qX8U346?rT$xPvH~@Psg&71vsorWT=1Z-k}u)peKFt(%xY|j!y27ry&{dQZoka1$U5EKVEG?D7X10165*3dQbvEs-T*VI5qG_G zF?YCmQE#tbddj~N5DU9_JQ-e>GM>J^el`AIeN_Z!UhR-R+>FqcZO~%*SMOTfotYw5 zId3PGjVaSN{8wM)cWikc>*OW+5M5+5e)(U0^^T*qw0eO|Y*BVvmsFpt*Y7K3?%neM z&aPD2W09TWjlhoko}PX97V#+EWv;; zV!F{ubrJn`;U(O^5&s;$u-Gw?x)l2yUXv{5e|4T&WC82J5yoV=x~9!HUmXR9p}2?ErVw(y0*5jz=xmxZ?epJ zK(gV6Pv?PPL!Ux;5}IHkEJ9)V;_bDE$9y`BS=Yw6xlRojqjI}bSl63echDDLrj)`d ze?CvMD2z$IZ%Kdf@RPaMK7C%SQohl{WinfBM!9DB00(_PYAR~~I9XG-k$TkMGVwC} zO>eB#{8k??sk08B;6*ukEoO!Qo$drFs6v!=!Fd!${o)gX#?1^@ePd3eX+uT*CXJ)jx2C#6`F-8#BNZUeNnMD!JA1zs!*I8&c<06xgNUD3S7l8Fv4R3Y$7$9Fc6R zN~O3cUejOKbmXX~-KV=#gqboFr~KNd^Y{KcaH+6@Y>2|s2f3Bbq!R6A6eLc4?WF=5 z4>B+01eLQ*$VRiKmz~th&9){O_BsZBT}?4veIUttAoEeug<~6=?y}m7zB}rzUI*SA zSdNy~*3urYzg)uZX3zp|Mg6##1fb)~DGAV>KOT0S%!EHVRAEb#ETZ=Zq2 zHc^5kB%dnYFe$C9$=BL+dSGTET|uwa)l2>;kS8Z`Ah!i+*1rNDE&~+q{d*Y*$!IB) zQZDun70?;bQg3zczE$E}K6bfK*YU5N_#Z<02g(T8QmcrRlRzVlIy7ajVI3NM~_ ze!>LBEe0#VeR16>Bj!t~BKiL>A)vZN$y@1%c~f>;9R-FqH`_2g={a4MtxGNFi8A-!X0`vu zZ$EO&e%rx*NZfuyFzdRtJs{^d(sdF$T4JVBpNxy|hr0Z7&a)vvKrC!txNr?{qk4OL zqp#~GUk!?$(5BF)ckfp$n56S9qK7d!1N8=NiJz-cr9-GQ@01!%7}m3>M61UGb#S>H~ zE}5*`hI|hDlSNJKWrDOO{(V8I_p4tcjYg0;_4cPb@dsoZsNquoYvI!%r6+jN(AXh2 ztC>DHB05=c;*EFFgx2vrRQzmfDDX!Pa5}i)exd$hiqXe;;W_3 zLa@&80sGH3;|21mh5=u>Ibr9HEr^ljB4{%Uog8HMf zihrP1X>Z#XJB)LiGK94!<4rcYvK1_;nDWkRi8eXv>6*kJ%`q!{BRX?3%a~MC^@bYn zQ6|K&k&_o@Kf0urCg-R+-PX^R)|&9r-`ITByWhRVG|H5n>hnJy4a_&_vB&#ID^}gR z*GSoZ@#F&_z~-l)%=luGJ{4J)n0?(_ljA!$=wv$2I>sog&$^k6la}bLDS4>IEcEzJ zUJle_^kmkDsg}ssAEm6mKF3HFO=<`j@x^bwL2O=WQF*9b&B=b?Rmm?8=duQm)V0Yz zaURk~DJ}VG)~pLQ9t$<}OT*$m7^KXgQ`R$|e?MV*2uRG0uB#LnDqE$q7$mr)v<+8$ zoT;NjWC*4a6_wikpql5a%K79B}gy7_P4&OxFshyIdhcnz;v(8ypP4Y-@A*AZEXHE%vo;wR+ z&&&y(-T~(y|IPMN#QFk-wS24FSaIksmg3V!gA-2OyH^0=dzB&{o2}k$O};+aQutZX zk}8Mx2m^vsP63}r5M5UrUzeco@hnS3c#RIMfLxl#dme^FGozV=m#G_?`5i3(iGzPS zP^c;p-S35ly@0AGfAvZ>q~UsY9EBD$ZM4hEjmuXf9%BhQly^=G5Y`FFJxjo~%0F@|uv^ZkmeGJR-hYW!=&> zb-$lQHhXPRACREiW?kiTXLHrpI zn$zudY|H~6%!}+>4Y)b|KHZnisH1tsKN}cnpX6WI&}z!C^jxY7Gg?UZK2b`->LG{w zyI@AnkzR)PZLT=zN~4%g+{09uPhg6$5?8;+Tg0cDkJ`ce@%=(CrGmGLv)%RWKi}6` zQf<~ZUo~M}HL;Y0kj89Y{oPameN_VbDi?brIPjhY)h6p$g6CBa0rU5rLal#hyDZ9* z`9W_-15Nw|EHu&`oty3uQ`F-$aagQXt+xM=9id2qmz|h~HsH6I4*lw#6E&LPaT4WZ z_Z8TW^xlS-snuoYUk}?hzQnvXTJ`fxg1dLc+74kF1bzK#zO)SVH5<~RoDkfSb}l;+oFzP`R<&NX%dt78xtAFtk7FDW^$FbS>Tft#$U#kD&W6~jTagR zS$8IrdxiG=0(=Ipf<>@s(7~>9wF3#&^`q|Oln3S8A`YGk14a#P2Xe!+3M?j$bD-;^ zC-9|*0U#B*mc(WQKieesIWhhM>}V06gs(Tyep8Qq;jrzk#2S^!E*;jpuiEhWdbw|K z_5@MqLQ$*di_6#-v|$Q{Cb5gd3_8TU@uoDt0k#-Q{a`zy=>!!M=sCvc?4>XP?w`-k z97P>0H1S)6)sq@p?Jp6LZi*CC`w%Ko-{Fu157UwJO%?S~oO^tMbu9KUJyBJ*O1VzF zGqEN%BF%+G*{`PytH$t87s51~1MG}#Mpzj4fCbowov*pN+}uq_)kt>|*WCykvavvD z37>AeaW&e%eu-oRLW&aOQ%wv7h2SB)x-7~(GRD5QD84&u$u#W>R?T^ve|SVOvB@DK zwJto;X6(KZ_8L8ZvpBNZ&?M`1 zw6p9r0Z}7?TbP-mCzNP_2IUl;8xJMwkv9TG$B8vxE(kO+M8uX~_nxXAXs!*wJQu(7 zvOcVTT`cvwSQ>Yn3Mo!)M0o_?{yNU{d$Yse^uiDrLAUpdx|&Z{D6^DNZ^^ZAD7cog3dsM6NoXk9AvQGo5>PjAKPjx*&adYp z3ges+i3*}!Y?Fw6Q#dRhlT_Jmp*_b_cMHuv&r%(B5_--6h|>)9B=T#4Uo;1Jtb9sM z8LyHoKz26(0>5O^FMcD5+>>Q}^DIq{o(5N2JZ8yduFIkwf%MNa)ji>2-#UIBs4?@o z-$$PR4eBqS8yJOptR#@aO43{_l}>uSx-Pe_%*%Xn`3SR7M!b|ofv6;7V;e(rp;l;x z6O4JILbI>5=n2Cm^(E?8M<@LtU zL(n8js-gotkn5)AfW}s`rO8d~i_b0Ns;x0=A24fXpNFe2nX*SZKVfM04Q;ta%G`^% z&j<>d+34I9S{~CN6)c^`5+2~oj7JZENcC^H3#A8ASn5khD^?HPO$KsC&l4mFzzLbU zubr2aCcj8{%T6Y5XCLd#hX<0Z^cwRwn(~k+_3pGSQN_4IKBf`;=}rOGk#ncpz~|u! z6N_uFeoYb+DGKTTWQ+@v#RC-5+wJS4Lr^X`2pXqgQ#@U_&L_tZ*<3qU%imejqets2 zmp#P2(8o|ONZJrBPa0BTa95*uQz&)2mEmMhd6UVurM@@m)xT^R6KIvI3k0TsNC}yp zRL7VgG@dsGj0M``V>1}K$2}Y2yb3(%=VAIb11X^nQvRAwOc$8S)Fd_|9_%MHf9%y7 z{dQvFI(XK~nYLl#ul1cW`~Xu8en}zItb!^+B37jC9Y}ONhseX-253gY3(q|-ZnwIXN!tHW$sR z68Ld>w=c@z$JZbu=le1W_0WafgYj9IMd&-9H>?x4#q`|Tl|4CihJ(|lTGW;Eq#aRh zQz{#6!(CZ$iF$@5r@PMfHD8uDRDbmiP_DE!8o&sec|p&$xT4Ui}WP z8yW%m;IzN}!m62O#2p;8`R*P*@U*&W*-rIqnQGB>Z+>P*{@OUykt0BMKd9K&(7dB` zTuq5w+X1>xhAc$Dm?lTg6ZI=4mD~63nbEeqBGfooD5q%PF)np%QtHIS;Sm!Hn%_vO z1qH%7NS!zU*#=DBQnidQ9k7Ar73_|*?3H)Itol-9i0-R*+YR9DI%@4SzPOs5*BDXa zvZOIb0YQ!U{3h|SR@6laW3?w6zqGd9qX!BNyGV-wEm5ZdBr!e&Bp7;&+P}l5G_zb( zWydbf^{~%^Yj4Bk2*W{7(`*~ANiikKjQOK=f~0r*33CUKv~Idyk|OSZ?Z8iEes(RX zPWbPFpZcic*c9Uf{Kyb2cYZQcL_g~$3zpU|E;~CmTlK?ew(81cXAa`M3;{93I$6ct zcDBAyc=*+?Jt>Jmch`LbPn?99ADM+GZEU=jG=I(5xL5+(_Y%hWI20@BA?18%uHG$` zxY8!;I=`H_xa3lIL%ku{k-m)XXrJr9@rrraY6Y8NQ{Uh!UO4@3K0_f#sCpd5DV%>tEixHz9*tGIqAPJKMC zVKi5+Y$4|?o%kKve%+KPib3-Y z96Jfg0;`I9Qea+o2_THd@NOETqej^HHG;dLeQbw)+_F(_?BU^-qM7=GJ|Pdwj=pu% zv)s^#5gtkTxD5M%b)zc>VA?P#XMVnRxM;AduiJA-W!NDlwe}J<0T^ytw;?&A=&xzN zX-cODONMo3_V7bR0!+@ zrcnPPaCdWouYhL+hn;$c2i7D@dL=*XHB`bta^e(|JSwO=`+^BN3-!#S)F7>6=L=|Z8{tmJCGe)&vyX77`6rwLxae6E{;q^yaY-64M&F?vaD_n;l=bB*o zzFv=uYtgTgVH*-n7@MU+f(mTPNk?ebi`X|p#&@?S8Jxz~$j(!r4m4XR@SLm{$gb0X zb?i2f{zVf|((bFEaF{sCTtCY+3yKLaEVcqAe&?FhG4dWtpo|#MD9!7)ApOuLHX2W| zy&>14SpWX}77Nd#KDc~sW=|8R&5v}?Md+f8r_sudY&91_f0yym`*+b>vinkyW-d-OQd&v)PfH6v5ViUL9!Xv+o z(XAk$N#G{%+WLAuFm)H%IrxwqZ55^sQbX+TnAQJsINKERtkF#PFu)WP3@pL?3A%gW zPiXJ72|6}uP|H6IDAn!iPMPXXaa`jZw1`WLSnPHh_EIfr<03x&_}D5^t<^FElhMHt zPZ>V(gf7P@|LXmjQbUV|=sg-wXhj{`ls)>8QQqLPm?xpH2mg9>2ThVimw$Aqw3?f51)VI52#G1_Fm|-$u@nPXK*K0cytfu@$HXYbNyX2QpuDU zokE)lGI@@FW)XA!M8mT9K=6$2z*tInM@qOn#(QbvYyn&EZW$U_-Foi|&(B(bp9=ec z5!8sF1mWK`5;aeMpxKv{u{P|S`QX@_eI@A{ULSkyC6tlbsw|pZZOGgE?2mxGzZ-S0 zD`KM@TzH4fc4*I*!oj4)oO&sDnnr=f)!ufOhdv9FB8_%L3=Bm;%rq_7Kd@boiq1spz0 zeCR0)<^OT@LE>;~8}KLfqn_rGfo5)%o)1cr!vU0rcVvVmjQTg7wd zjSAdz4Yn4-4KQX|p==TkD;QX|X)z{tx*#0yK9#LtQoNi-egA4j2!zPUntDMu{TgB` zGbOA=ptvvFeX85bMcIYCFgVo%?gyGNrE&h$Yp4#uFE48w8$fJwh7z0XHplz{8D@U8GHq6O1vBn0Q`yV3 zH`!_J*n?_^(UB2{(Xa8{WqyRW1qFrnt>p_iQ}g==9&Xr{a9iY)bKGWQi#OBU5f#ogv|BE!})5& zVD6{u8MK)us>;rrX}PUTle+V*9u~#GaK^?cSOHrH_TXfa*r}rIB;Wx;YS~z z_I5*ZRlpYC;L30?fFurdYY{BiV9 zbGZC+XCQ2OM0pY1@CjXF6IITx!`Zhk4&&@mDhWG(%C;#(a=y3PPVqm z2DjHwv=qVzYBo#?9TZDjr;17G9_Q3~&wI=ae2_|n^=OmMQ>-&Zv9~F8tt*?tQdBa) z*OR~4r?l?=cR{A}Gt<4%fo3Ap*B+FdvbYMXHt0@}^?@jH#EpvCSX)zne7Zy?!rQa; zQSmswNFn0KAo@bzwfPDWIJ1jB)?D^y+_<^(jAOtUbrn! zc6qO*MJ>)LaVj48fZOPQ%v{(gw{hl{UGHAht78`%)i^fVbgB34_-r8y;r((K&W-p@ z=PPkWbX|I#xl)vRpzW+gsqX+32CPB0PN74L?1WF%3F>O0xPY96;io4APwXN61pr=v zST2s;V;W#lYvAtQ%6#{?kJPz3NF|r{m!!w-rsZ(`gYN376gyPAec$OZLpAFJd>AfO9kuOw=Z|3ahC0vd-VHxRB$0;NVm_mi6w%(OT~#j1(oHx z4;iVYEi@-crkYP#hwB^O;MRK!8XYD(^J}}xWG}2}w#UT=Ko>fP!pWJ89I9tm*U4BU zu*fX$<-F^UFUib((mQL_`_m-c0|5;c@O|Lw1sGACmgBns--GfK-0F`0865X?L-3s% zaY8@gq6Fd~A$eMnBh6)R&T>=Xu&bNfUV>eNc6C=*7itLFP+(_>HHYPexX-;fi+a}b zJ|Po5*XOg}qrL;ndD*^S%@DCSkI(qcUKvpCyJkL8>Na2L z_I|hQ`;sS;Q_0QMoWu(muXP;QY*(gC@9J%j+rCad1SZeBvD*EWEX zOBD+^umf(zf`C11u0B_<{z*Uo*5`_a+X{PfyDq^4yJu$1KQ;ajm6zmV4_S#aK)@;rRel<)Lyar zjrvzYWqI0!O~nSE@v|(j)U#@l*F!Ht8~wenO-5Pt3e zplU*oO`JPbFIN3HHYKc~;CO?eF|$-G3Z$lfl*^0&HC9kOP*jsO7Bnt?hBNF{g>}Ra0@9LJ*N0Uly zqA(?b@5fG)yofMbwzq5hg}1&+Ym$k%eD7=JkyGyphFj{Q)cS)9<#HD=w}0 zm(@Fw$e8l7`kNl)j$Bq@&%C~XnNpf3EMUW6cz1!S0=wqZ@ht?84~_Dht5zJI11Nu+ z+jo9yAv6of6+bBS_z}45;vf)!m~nMan^oWMy_?u_6~^1p!%%`#>uVW_kSm&F-kXnk+BW`d^B#GdMw`Y289s73Un#ue%ia<1n`2t> z;9||;JIy9YH@c6;ATZ4rA+qPoEstk#NY{2!mAvfp?=ji$r&BxG>1PL+nOgbCl2pr> zoer7pPAlP^KWfd+=>@=B&WHhlFq%^^DdJy!s3{cAi3KC|x_NZ|GhihTP?PY+kQR_H z1p}N(R9tQ#x&{`#pXODev_$e1r+0SETEs8FeD%Lcb~<1=U6gCOG@2N&FHB;4C|n+Q z^8+M?bOm15Ny|DDbQ_|?TyadsLtI2;w$y9+&Z>yRN|$Y-XTJ%60IhisPtxJw?z8?& zOT@E%m6PWg58A0S5x%nfuy?D(adyW3LENmL^hZ`&vvYb)<_lNe+cTPo1=TB;nn)>9 zh$b}i9T~Q6hWn`pX*{7xNVEZUV^HYwfp$+u+opCyCH7o@^KySy*M7gb_lj3cM>sR0 zQ+gYwduQP@=hWN4oemX;KHDh4(FVEfCFQN5u{+meM|S`zad!5Q6p0IAA%dC1mYLXO zZUC%Hb(Pd)9caSbd8{-{W^*>s_G7s3s%5d7y@1o?`kr31d=5HLXH*G z#AHY}?#{ zX7TJpcgeybZTlElKW%hG_J~y9ESsxhV@=>3OHWH14`y>dAVY4FN$l`_;NBdY^6aI{ ziNwIWJx0M(%HoanVvSp3)nai;mS3IA?ZJIx!b7~?uz*SiRz!o?S;oP5kG|%q;y#nv z?$;%55zn7Le>&)@N#)De^ww)3FkkkP!z&FsX&qwLl{na2o8miT!qxfmlHNGo;?|gq z#FL&vbTFI!6N)Sr?3ZuhbK=oq$eO|626-A*5pP`m;{(Zcs+m5OOGI+3rrd?h1%OD9 z;4Vs~#pSUuj=emR(deAfDJhw2v40VtFF-$7+~S3#y@0vZtH7eBAM+p%POc6-{6v9vvLO)?>G`YX=v`Hs2O?^mPg=2?3g+e)T7MZ zjq|-E8i!?z)S?0t!L$h*Cjecz{2`AS5e+VD)to+e24tJf_H!Vf_4#f%#@ISayBw9Z z>6)zd0~jWA##m$V>~qIhB}Oy1rS@0}XY&t^4I4|*`BrLE!D|n%lEUQWW_!KdmL!+- zWar0H4h@6GN6C=hpU%3M!u5}IB|FokW&*n9iH5IauzHdyqfGYcfh)j1d{pVVYvt_t zelFE@e@XJOp_5~HPrsP>*L#J^&FHr`3yg#sIQzl8u8hcBlcUqw4f6Ay?;~^SHb3-G zg`q|pW39r7x%5;=P~71S#ANPpA_y^Tgq65?=2bN{4N2Zhdc_(X`WUc%4n%_>x}y*! zbnLSZsv3g(jKSxpPb;)L2Bk}Gjb}(=7V%^(@q}%Hu?=!a1O&^aE7Jt(M!4wF1fM}_ z4xh>V&l9mF2dR6VHDgmjU>KI>0|-qpbm}n2n4GM8&h?=9>A9~yGg;Pkkzw`WlK!jR zSMJkwi?4WDf26XQt`(qdVi)rpytn62@^m2)#P{HXlayxKKw z2uvxGH}nS$aBn}QB;>L^;>4bE3VZAqJR~m%nziCuPD7jk_GkDS))fJVkfemvL%fun zn!Pk4pv1}36a83=0nffB>yOpoY8Atg@(UoI3DEJU-d-E!+!FV3ACN4w@yPZPboBHj z$kGz*(0aMq>oGAX`L~8xZSK66?qm?n0%@|Xixi-z!bwWIzd9bq18JFT1D;_vlhALz zF%y97e|Cx*CQLxfudiCQV_?#6;s%w{I}zl|@8y_7O=S!>kha_3tw8*G<~>F3Ee zx%z77a1CF+XoC<*Y$-&D&dCCV*$6i$puA2FAM6jXI30eXn!}?n zOQiBD>II#gq{FK!xh1_1YO+4dZDV;e4fIhK?#4Ie>c#%t-avx8UnFJE;=-Y-v}c5y zwzdf~h(T%=D&K|+kVN&E(*=b7$LKLP?}rSWCzoWuJobN=+;G>UHPMcMkoK6+o9$;? z*jz?ex=S*T;VrL^?@qS@NbenJQ6w@HKskY8Uj>0VwI!t=1#^7(&}eu> zXv9~n*eFeHdM!YdZpOx!CzGs(%ko3_)oX~kJt!=>5#0iU+CZ$r;1e%Wt;j?59re4y z{=M&RRg0U_YSm9q8W-3cT`U{RuPr8dqx<|u<15I9W?pGd_%$0g?ldr1<{Go|ZAt^} zb|Nh^1SXZP#!|Z4qSlOOSs)J*HX7zOEpEiKx|#ZCdVaXKhkA#m`h8=7d9c!|eCoKz z_8Kd@dn_n9;5684^&@UXd4gE6O5wRU*p2Ta-fldu0;MarVo#ibPy=B1RbXHFe*C#> z9KJK9)b~b|mE3Svr?E&laRQX}wAN$Gco&LBj^AXiinT)RO(eI|PjZP9Y$_{F7XW3} zu6BnUuksR-oYB=a@yR-Y!MMO67ussW;y5<(tenvCe&kQ>lyd+?jcHNv@Tb`~LHP6p zNk&lw3^Df^MJi3MlW|^2+eEs|f8inL=h-?-4Jyacq{c$Qq%FZ}cJ75TI3|FEc!_yG z!K?HR2nI)(%-bZ#g@jvuraEi9>oS%gMN%X!waMACIM%FSRTUz7rlIT`gFhCw?{AkgiA`=r%T1!-0mje^9$^^TE zBc!ZJtxwNN1l;gS^A*RA4oC5=ceRD*7#bC=!aw*JJM(qAQ>T4-EupnqlA3r_K(~8^ z4rh@3$vve|+eo7A`q;wjW^C5>SReb7{}38?kjOvaJt!nK>nVy8a{>uecZW2Db5S zp;2sX0!{C~*(y|CLq#5;v*4qQnGx}DI;>=~)p3rAgput|*zqzQAU7$^7S<$E*Ts6f zf9&{px9DP$zyaHko%#paW;74zZ-;I3pF&Ls%I~yg`K=%6T@Nkp(*blQN6gbpDN1#| z(RHEK0y8yVw1+Qmc~mjpT+OeumQ{*^62o|{e~Ozv5Gq~d$O#FEAaF~_xj*0G;GmT~ z{y0A9o&wk&#t*9VZb?4VlA~ipivWfJF+h9kmT&4D<&E~U{c3TpzI0>)T?pFD1LKgB zZ5Q%Ha-B$c7cx}E64Ql*Z$I+4=`V{+&}1wAdM5dl+vYsqP&G?$Nlr>sL)er;rTf)# zK&{>waKwzaW{{uM2?^QR_9X^H!bMFBmAblfn`{>fX$|Nr+qIb34p`im58pJN9sL|& zQybKM>aqY)R9g}Sc}#~0Sl#xCfnGwW$H`H+sVHu4hJ%O(pT}OBD$7fKgqd3QQs;yd zWmeUUF)5qUoNiA+2)3=Muo;JjrLVN!L>8!b1;Gc6_S!gZdBos2Bnpa552! z55LC=wrT4!`fJ!@DACx$M5)4&Vv8Ccf$YcY*X)Jzi%pPsJu~kVSS(y0yFIfM5Hi6j zXB?5#XzT4+Je5G)De&MN(AKAAtL_(7h3vWd@?7cp%uFh?Lrfon8S?V^3@QQ#@OZjM z)-Za-$s-;}0j@wo;!V?|*Yb09av#w>I_|AWbN1OY-^P-c2VT~ein#Ge#O(Mb$h^F* zu@xWpt}f0EBWdGRaW?8mcMN=cuJ=K#jgph7nT?_Aj+$U|dMI1&c;wNO(JMX)F2O~P zJvI@gwv$FMuc>x}*>zGlpQvvImwcBMTCTNkQ>){>vs{1Fj>#&#-=}PLxn^`yGc=eG zE-7{BkzSJN;_*MVb}pynNQRvhtEJOy(CwsG3ovscvr{HrBJMC21n7uoKxyl8#HobS#i=HlXG_aPRRmk;``_p+SO8@11amT9r z(4b>rA2tRz*H|TQJ?NjPPW0C?GkeYFj*`}{lWyV=zx_xK+#ZzjwKaF=B(?h;k5OT1 zL^$5;$Y0DT$j^dX6d(zdGOgYhp8ilUqSxZ|zDH0>*GFZoab|uk>)7^eQ?Awu4j@mMOt+|zbKrA39IxxewyNx!y!Cq-JfhC`oFr{IH4 zOUladkKHYOA_U95*axA6w(ONdAp%2Ky{d|~!wqqa8&NOhw!U~fYwiek%QP4BNt_$a z>*feJgV)qe+T>`%TJ%e~mIIoELR^UYEKgpI zFBi57#v{oi-GKgtrKDN@$T&O##iyk6W{C8s_lVTI@Fap|j+^p;7Efm0C$yr9z;Rdrjme!Q_D5yvL%C0Va8we6WlMD5)jIST*Lm+5v0d9`8hWH zy=_?(w+AD)lgk`)_WHuPIjyE+njGdgAW z=U|DYZW)Y4&PSG!DOaf8P^z6uBW6HH9q;N+ykk#cYaRCe8}Q=m(q`{H^PS#JOYMk| zgx<|wmEHctj9~z-M$CluM`s1)@F7PHj0(I91?zX5n(^(P%`d0cs{drr!cx1zGyh;&Zd0xjKp$`-Xh>+{#S`lZe@5N%D zE$x21Dip;)CZe4a<+h*iymyE|7t}N~=qL7-7J4n%pcCc%HXLf(K!KMRd3JE!?gIqv zSRlPJ6jXMv#jLBg^_aCin$aO->3PJ?#D+J#f~XiS=x&{N$N|?^uwV`0cH@u%6MRdN zN{?kT-mhj&ga=f63uRn+>%aBQKcK`48=F0$Ml`W-_TSX(cGF(1T%~boV%XI}q^(NX z>Nk3Z(!qTJL;b!h@!5cV&jC5OjT;h-91}Zbv7Grpxm3Ot)n!+aXVwyWefzR`=>H6Zhd)UCYP83JC_N=@;f%|anys~1h@4YFbN|wDLAOac!<7(ccuK+a0kDi@hja?)=+DZ3fEGaM$3Xl;;SAx}1f1f3VB?@hmQkh+Uq8GJZ>Kp7Ol z!*QZNyE3&w2A?e`vn6m z-PYo_WaW2NYSJ{<;wV0n&!1FCbZ9nIOz>X$SqosXCVgDqGI0Ii@qwN7@r;BP+&!f~ zdOe3i@k7`Eq$BV=nC6zBb4;#*;#a35f>OHIzu#tIajNS3?0azDmoa`m!^3OtMRHs9 zB2p{w7e0zVeq%WmGHRAlN)|Vs8a4NcY^gFopJACB|DlWY*dZfVt4_3JO|gB|Gp#&k z@*EOZ?jt??`P2Dvbi1l@&v<}y|B0!>!Oxb-?#2#&1nH=u;wf#i$o8}|kK@Q)4rNDc zKS%e`SQvhUcik68+^11Va}7-M$N1307T4aTXLLAr8z~84K_1$Xgm3RJk+fO6zqX(z z6DeuNeWr;a>de$%d6dH_K@Tv!*OO9#8Vl4|VC`F@v3D4-TKt1>4EC z%hD=w33z;yUVVW>g9w~nuwbZt(icf~=%20$E6@pl^R-TQW7%WvVcvKQ{FPV2jGfcM zrr82JDG-gbiX*YgPo36^0j{3}BVBmOL+-LokaXY~+#X7QA$6unc0yR|dj$tblIIBk zem?F=ARtXH0Pm`-(t7ZFs;HU!Zfl<9`eLhQE^WWmtq0fp+~We~eO|rf?3|{jx%2-p z_T5oUF5TBx6hRSC5m2fP6%dfFbV21xla7=CiqsI07CIOeP!zCG1f=(pASD3;p@@Rg zTM}9Tm6}jg2)%q06}|6!zu#K#{lf(=?>zI&GjryYz4wXQQ(-DM!w!V?(w3T@{1AZzl)wzZqK+`?ZTQab&ZB?B6>eQ7UGIvbgSkb?7q3IeT5J16d35z@Rt}dFSv?8=k>rn0mI{x;Q zd7nZ6E-8t8@%c9tEPOwYadM-=M(S|#Rsz+yML9WVjG^e;d<7{_?bcQ3LRhV!%cNyN z8*F)rI0tQKgs#&^urqrSab968e8j$(nr5fPS9+yJ&^d{M4>f#X16m32=M1fMNE$9| z&KJ7-ufw|=^N5u)1Y;b(-rGi!@w&Wvat80I4#DE0*hy`}81!IxOhJiDm07Z6y;YbB z5uKI(>Br^Xnr?sR&eZ1eaL@8cV2)yZe7;p}4RvEBh_hn3N$RTowN&nSbT;RXcf*;_8l{Fb)DvHPtYT-?y z-?H@U?@>`k+uxQ8I~MWE6aX zfv~0s*F;nTe}HSmsfE{UWscv`TjFT>py=D~0Zp)N8P{kQbm9DfkK<8KhD}nTCLasMGIVe$iz>OO&EXBKa|Ao?e zzfiJx>JyCC(L3coj-iXGydJOYOsXoHUp9aB-q}s*!Y|R<7r3~;Y+H^Nw@xH-TVnOr zvE?3}PfF7fo3rx+W)v%2*1Nr2N*C49_Cby~@6p~^jYO}4S_?`tt6-33DAj9#a>{e` zj`#iJ_L3P=bnI5g^$~L*A&f6jXI1WNH7)fd=jCAOR+?MHphFo^YlD_0&hal^zJyE{ zoRl6wYjV!^e_2=Kqa%fvxj$tGACngGRD&Co^4{o{)<0hR%5#?}|lzpd4u%v<&;Bn?HyfBt;dkUFVt zygtr8l~A)g%0R|yQtEF^q?NJ7)5Dyb`46e`n|s%9Kr^U4uJE>ZQWo?5s}gC?LF+0{ ziq4iUH96isM!q+_1}t#1GHPOXiawg1yRfM35NRUUMHGOEA>g%9#~j1p>RWfmhS%qM zMhl8q0_gb<-b~ovMdj-%Pwfnz^soSM$7}p_F@ykW7u?Qu-Py9Xm8eHUqxMb_JccnJX^% zUN?icw^wTn?%SUC`Qf+kSh5|-5F$Xobucx*7c_PY*Q>t0AGbHCqkWQ|IvXv5)UxI- z4u9V7?_y~qKq;sr)-5N+dYIK@Zh5qIO*X$QH4!A{kB>>O1np(zn+a~D(x6}q?aCwQ z!R^mXV!ioB1%*o;AOR}2L9s$ny^QCF2gq8$+M zf=Q(3G`RltMqBw58n5g&5>sRKiV!+a49%Ub{j) zTMb1g^}LA<+T2hwSrd=g3tA4$Uh#tcwTt;|=4_|<@>a@WPNZOQ)q^H!LTs3r31MHG z1%D(-rF>$8zt`uT@Yc6Idp8kHGF6-B$8=S+7;hT6fr9Y67Kg^XH2h1R%Q^4s1=XSUDmCTFkX3yhdR z|6B&<{c@e8oCafS^MgYP2ba}t_bPJ83hh;LU0S{rY;1hi`~Lf}^4NkdNa=>bifxR4 zu;(4w3eSepG8t&ic9K&-g{qMW%vj4MnFZ~Xio->jG-l-;;tqwxk*$h)iXQ~rimKFF zaZ&a0zz5INYWN1FQGF*aoppHWEBdBQ__|wu+R8>$xAG0cfWI#n?z`K@U;<*DR?p?- zjQ&H@c;OcamoA&&reXggRLumJiG$Xo{_W3CjNV|*v`VMBNLii=WhLIHXWB5>cKDvTWJXhd z|KUB&PXHIH18CTMO;@R)BP}W(lY3TU^71>D!eO*wZ&Op4;$`2;sqZe0&*L3xH#m!! zJDf!+78@qytjjvOu7}EXR--sw<5X?-AMlh_P`-k|}tA_X^ZmKLj zb^bzyl)N>~MVcg@IK2D75X79&KJFweoA0}Qc2jNO`^E*qO6+HrJHpem;~K9^-}#A^ z2bGjCEbGr8)WQdYKlmxP1NhNF=II=JVmt>})nmCF`iyYI8{my@jjA1J%BzwMDyjGdK;ce7lwS zWRMx{*d;M0di%@gBi!C&tlHn*J-jNO_T0FA+lHOj+YLs*P|AI~|< z4eacaG6gf}%Ido@j#s%j(*m98i;Js%sJK+m_-eZ`VVhvw3!RuTCBp|C+1*$A;zmkD z%&~@`m-^e7U7k~&muX$vgkhYpXcgI$t)4WT>`J7CT^LH<8`P@gQDx!xOz7VpnwrzN zK@^X7TXUVGcgnj{q=WxffuY(6z?OOv^V-N=J98zPIjuYrwGn_2S+hjjVm1V*EaW z!SXz{KyZX-WXvp2#3Ms0W~z+-2zDch#zA=nA=I0wimm;G;h+{9=Ims{fz5F z66EFhz5v}YFZ~(k*?hKwF|PK=q4SKM!Nj1zG{~Ap75YjQ+HiXOQq~)4;7m+M{+ev9 z`7CUkLOapNu*?1X`3YJXFetXU>%wf*$d^?jH3&D`*bfk*K zz;Nx6qKd`MaFWga{ud4XFX+q{aIe%tw!3QoN^|hBfrrNbm6IuaM&_E^Hz1XAb=bqr zBt=-3A>tZf_PBh@l2x9Zn8b|=L38ZS$wu~zd(Q7(rX;fVipiP~V7;G;YwKz`RORjw zh;Y7qA+cuu1M%3z`YtPmy%opSA>8Sgu#y)H&q2L!c9HHNY@h6HP#?6N7s87*YvlwPZ|QpNxiRNe~4_RE&HfZ)Ld`_;O8(Ym^ zZVf1?QshiYZ+p2lW=4eR&zo2TIaE>+yEJO^tDu4OO58qQdMRb)u6H{g%2Zi?f!hgz z;Pd?~OP^w*+v#W#p3b>)INopC-LK4P6otF39@zNzw|(l#Bp_Cm6=QeacAt-8r(&u7 z4M1pkpYV1{+y=DRA#x@}f`*jSsZ)^w3%D2XhoSD??0c};5h+1yd3`#h`G-Tj8bTR8yu`(byowlk+?9^Ug4|}bPo5S4z-A}g9chiFKqLMNTdj_WNtxgfHg`KQ?Ao=>`{$iw=>v_Dm zjb*u6KM|KCQ|)Q%0_n!Wxp%+^0O`op^|7^vV0OFbxe*KVu^AHSOyFS1-AhUFs z;^A@HZ76c%9ymPow~*WZyXI#f=wxFYUBkvf{Evh{a@rJoYRIgK9|> z$N9TnF5`HgFO3l(Yic$jdB3!zq%2_7J#d-i9TI9eF0jnwl*kzpUW&`gaMpfug}>T+g?QB2hSl;;%7HN&&Gt=J~lxXAGtI*{Kr23bsl@ zpF;vykqP@eCj-ACpu3Oyj|8I7ynS~MbaX~Ml1u^~tNpsg`ShUdo~T%-7*qbeY&}9bT$*#sKKli zGQ-%H%7!@m3Da47*@6Nzf5asxs|X|QHbaQ^f>mIOiHW39OEA*%Ha8Q;`OZh58aC%6 zxRrr3yOy|uOR z$xjbZ)+YiDA^|#2m2G9dYM$IK9}ui-ql)dQT~VcyiL6MyF!YH3ydp_Y^{Z2YV-E)D zw=^TT;Ge0TC?i*6qaKEgvmDxJ7f(a2;%tNL**92(kfHljm~>bi`txJR_ySH$@x$(C zt6w-5ct+1?C*M3w6QGk>*!@@GL(oyZ|$Nc9S%ARaJb+60JJOSh5mPbnFF=s z9Dy5M>I7YbDmebBi50VLU+>kOtff$yN^50chv@1jHg-R=12oaNyH=z9f(E@9i1{FI zl7}%rWxLfqgw_~lBfIR;y*PT+eV#qt1Yt$jSBKf>#|1-S&PIo~(qsiKwa zTSw1HOBLLs03$MY2q4AmHCsUF3NqJQ`3I*sFyWdbMKX~2waZ81}<&J_ExsmIC|`3 z(J7|9?L6xw$!`~D-bI1|ba<~i6K5>f1o*FcW@YWpCsk!_N2pCC!)(Ck$6M|m6Yb0t z9b9vnOe_7a9J=xdp1jqCfSjX-1;*M;N^9pnS9vluZhSnO;sCNk&3mdX=9tO=F1|eS zXd07fwQg~7aTeSGuA7+DOHZ8KUQZ#b`96L?L6N^P$m^gDUKeV!2&>_0Ec>(tX3 ztIlR*AS{pX zj{(P=>GA0vO=oyl`c>>)0(4_O5R}qRD4R<@vd!907o%VI+QRczZIDFpom--%YQr=4 zi}bTL_zqb|%F0x2wedeGJT=5j2_(L`rABeE^N6O#^N+si>wTw<^0H_9i5_Dmk{AsmY+zOG+GJ@^qsYJr z5>54De{c4wP%M*5Urvue`XaNty${9gy`zdS-<=FwUwL_he4k15Zd;E+!JF;(oa<4H zGQ3{11Z|tS$|gU;t<$Lckg{yC1>brPSX*CfSfz|h-{`gikB!q%=HqLTJf>ui2ePgM znT|c#(<4Q-mbq01I+w0)`%McNiH%ougz*LFO4_%Vk!hS+rrq~P?>+^6j~~Gi{*6z& zUds-Dm3%!?l#(1k7VLQAOu`xgG!$XJ2%>O~fS;=A0M&8rUOb*+X_7V0uI@{Z-o$FnqQRHsea@2&{C$3T8axIsvQ;aBn< z+tr234c*R0Kf!Lf%DL!s&={0C1s=n+qRxP#q=GM(zBdA9u{w&5PBhp-&DyMO3G8U zA3;@}N|`Fn%UuT09y##2fvhBXxI@lrz@!eWzuGiW#+9&Lvyy)EQD#beVZ`5(v=x$%($PAV9xB*KRpUyUzzMJATER z@Z;(aYE;YFgz^PVod^a<*`P{3zp>{B%@q9bfMH|MGt(!1+2Q4eiqu_Bn4R6kb6)hV z;j8|Odi;W2HEIk{qO%ShL+gefa*P3lhqH2Cg?AOiWQl&HVvij5F+K&KPWXbGn;Vye zXYRG9Jf;&}sNmqQmvOPR^0H^nTwCBguUl%@=De(S85G9OzVX8gL4x{iw;;LM#(@4< zXdh`6^qyTpxwI?bs%C1H6JALB^@Yn;0b9Ol<2AQF93&|^8A^@Nwf%rwq ztj`mT9xzl56zy|rbL&8K^m?HiB)E!9OS1u(B?t5-5WWKIe3QoBdFJ%#a~(Wwub-zq z2xBqr=q3TKEzrPiQ0nE9cA9#zwJEX;m;y2VHNJDjzFThfUhiW}$n(3>0{R%#A2432 ztdq40Mkcycch#=f-pjDuTqB560o+sXWwtg_`O0HV0f3l*>|A%OhxiyL5wvKxzF8({fmz( zTVoVaQ>?}TU-da$cyT$5A3hY?vwwmgxt`>myxpf|5ZpV}g$3}h*D~W38$*{o7H3L3 z)}plFLn?yottxQW4>U5)BSwPOwTV{#NcQh;SIh5R zVy~ZRj(8V*D#JXXe3vKx(oBjee2FBQIc2=< z&L3S0&FWCINnwuTse1dlW)`durgCcH>rW9GUke=o^` zNqOt0_lTEC+9d0ZfEjT}z()a{gtYT?jC%y%c+XqnHo7$vwwi_C!zp|FPveDNsmud9 zOi!-wxg9LP2Y`?M*2HgBf35xQ@8wvg)tzOt|6v)UXxbEaPMn68BgLu}50A>|;xkyj zR_66cIevbZ5zBP`0%fFVeK%=!VUmK`_~I#_5>R4SyM@ibs0vnlPU|ysOJw$yo}@WA zQeV3@)f}? zd-s+gPQdCX&s0m>4pq?D{Y_`II!&wq$Jf_Gq4W}8B5;6D3R_1$4W6&v#sjmHS5&i6 z(#dan1%7&wV;_R;hJv1=-%>AtD-|rw4yvbXuF-7Wk7|@qCOFd}7BYMPG=Mw^x*)k+ za7x2p*L6$e>WF&V$~T*6)q}UQ<`{Xvq(c&OGjD@2Lfh0mv}%0Kv5d! zKK>FZuM-Dx3(=9AKJ7*B&1;A#*> z>yNSaMhd=s_39>{S}(Z5?j#Rhnt#9w0M;o-xEqX2AX)2tKB*Rs*KzlZ4j@WkOx8HwnX7jS4I}Ez4q#$d8~8xY>eu@rGJpx=BRx92W6uAgivgmc#LW;X zb%AAlh?gD=x(rjtAAsh7oE!)Vy8)SSn!o3BmZp&~ojM=G$ybol^6k|QvuX#uJQ-## zsW*{|GTWU={wr_bub#mtb>dH5Z=ukt_<&60!V9yg4GIK@*UyV$*2J9%7@Zvye36xC zL(9jH#ZOy7#(1cGB*NmLr}+r$ilt+kER!tvWS(zgot z-PZoAM)7!|2&27sVn)Wo1D6Ho5nZuTdB35D`+yFHQLeV$k4{QEI|bk8eGr%tYfTNU26|4f+LI-$WXZt=q%o+yVjlzszP7zCIMT$&c%ghwB0=eRH zLnxu$bYa6(IJGU91u1C1ELUnG20V&>p&%m38~UL$4PL+@92Xz&J9eyQ^%jzSfMe!0 z3EeUPG5`8{BvsyBw-}I}C2* zcgjO&a!Jw!CeZQb7_%xM;8A3W1YDbQXU;UraSS{}6Bg{-LoeP&?3ov$vwV; zz?0}4sVj40ZaV*zM`1}E3cQnJ?KaAzU1?AmS#M&6^q;Tl(Cj%MS3EX8Zra4npcDot zk9{-)NM-3{AU$DP?@+(~JRsRsRrNj)<~UiJvD7!whV0hS@|iop})*oe9WzrYB&4#(;#BPF!^G zkSgm3R1kvu?~Xz{U;7>aDnn@J^UB}W(=P-Lkp<^X? zcX!cEZ&GV{5i4z>E-I^dH0PycLGD7b5TRgI?(6rp`JTJ<*y-tMLaArl^Tr7Yb+L}u z(tu|fT%8k4D~ko(a^5Pn-yJ0DGf{Dhv}BuM4@T?+c+TaKE}SX-sc@f@_T9w9L~bqF z%f#!~uj>^MkofegOe3NL;NYYN1;)>NU!1E*9nAV2OYN9z#tNELW27*WR)c>J%mk@Q z5d86Tme#VJZAeqnemB;|DQnz>l(wE~OiN7iY|^Q?CTJz>vylc-bM2#03NRmJqlozI z?6w3UU;&I*9S(Rhw`Ml+^)PiPTeaqb(kb~xLcRf@*qrsAD_nWF2Wg4c00fuPWW~hi z&(mP$xVA*&p z+t!vTas#CZ&hs~|d26fBo@&q=bYa)g(lP{>Y9XX-BG<;F)eS@;(fZ{mfQ^F97LNbM zue`;5ep~a@a9Vd^f+^ zd6gJNor(+8g2Siw-cPWJ0fZmqe9fk@uyHi*+U!7ic`|yi&{Puas*VipJcA~1P^+&p znNzNu_)pVD^TSflgO{D7HM%=alSG@lyp!g-I;w8#^c+qRp6xCisUd8|Qtxvm5a~#% zXFjC@TrO*iW2$+y&-^g18K94Ge)S}8me{B1|MiOCR~4E>u?tYG{I3T@$EjG~TaST5 zvm_cMqQm*7w(<|)vW>7e@-PZOvsnu`MVL2&5C64lj1@H9xx?q%Xq){i&10@Q`)jkG z6gYTvGzbMT%fg{NA%}L8X5~_Yp%IpNF|$mOSk2^Xecw-XQpFEV4PYVX{yj1utt;@< z+Y9GG-5`Lr7Dzz=aRpsr?wQlk@0#Nr$h(0ysCBG0hp;=9r-O1#Oh$Q`u_Rh!Av&99 zoFjn&F?U6MnF)b9CA$Bgn4%xAaF3>itcW>IYhNJrLv;D4Ojt`3NVjB(0gBbfj zm1L$=DiYwmk#W084b44tNTSwedZk$bu31#7{K|VufHYABO-Si&Csg;RQEX0jqP?ng z|J}z@fz~~=E9BNq;IppM%z?Q9*wD_7#}L-^TK6bSuHI9Uv%MU=2QYbW2n)AUtF#6I zV9g$i#>AEwtX`*fYLj!x;of7HQz>77%%JBWt*^w+N%{4Y!Wr<4V)|Pb!83g6x2PLT zG2ZTculk?eQd7LJKlGl;;{Nj{*qTmJ;cDs2b2_}=PhUHSnA4aoxlepQkPnkfbqY6N z6PVVL#`EKinPaAW+GnZx#)3FqoLzoeOYb$4+z0@8EgfFhh?|z;{Zg?>cH8b`yP=#V zWR%~BqEJV2I<%9rud{&y{?dK@f9oy^f!>`iAy%qqejCXv#-rS}ANEwV#H860pxEyx z4~#kA2`1!)?R}Vs#rN~bZsoGKYjVcoW+-92Db=~Hs@SsIZdTY3lcDcfIdGGomzqH3 z1H`F=w4;Om{~Vo|ziFf~kuwIrrAcS@7nZ#>AL;rCVmM;~CRfdpyIfO|z4i%(^Xx@8 z12ebCd5r>xgLA3m9Pj813sRv@LbfDKBxD~#x!aG@U+sZ5_K$(w#&LSaqI%rIJv>uO z-#u?pYB${ug5*J}2F%#@|I0`Ei_Vfp;~EIRz_+tqkGIm*I=BWo_>aYxuX|l=#Th=G zc)b^E=Z)&m@<$IqvF)NBFB%q$Eju;PCcK-41w0RCOd^N7&4h=Nim1jHd3^9DUXa_0 z_T>@nJ;j)Tv;Uj@_~}5_J+3=3?u1?%51ygcCfK}O7HYa~5Q8o3Q7Ol4XPenisGkP{_d$)tztr+bWLg z0qYtidf<;_X!!oI>t@LNZ{R7$^Z{E{OS|pV>KuVw{6~qo`RS8MMH9A5UlHA&HN%+Z zK4uHp0aIvnTKw8oV8#k!=5oQaQh=6xl6-{3zn^6Uo>hc8@a5O-iO6NYS+E&$fAIc6 z?}(+V$mPJH1vq}ZYn7?Ue9b|f4IRE|We)jUk zUO2Gh9tf4!`SG4}S17q8>RV*&n8IT2uUa{DkWr=+XW5jO

XcbssGVvXxBP&7|;q2H@_)i0mxpQ~Rf0^ll|Z4acSRTC&b z)!ZR@rhI#?u=31H-xIfXWvC3a7wuP8W+3@vO6y?>4J&px6fd~ABd ziG0OX86Q67OGLG!>Sf%WH&k5YW7ZnyY+c(mB|ki?2Ep zpTvn|rg39iQ%QZTw_cRrP6%{&KZ3IJI!iq@t!VF$9V98gV`~u0dfL_oI^vV4b^;@D zQ3l*b_YYnwi;>kpT||{V+Ar5|@BEOj*4M4zuwNvpTV7+&gO?TI2kY+?$NR9$dK%~z zC(lQO_w_;~oqwllyMNYfou#MjP4V(mZfcAK#Kn+Pl%pmt#WIB3;h?g|^raa0jtqrW zeW~Lq^vedLQglTIrG=}|$vs~&-8I2lu>3 z?%pzEn^5wP&Q*NY12LI(3>_`|d+TD z>upT@w7~Lbxtts1b=;NjeX#H83?W7RK1jqKv6mI-?A<4rrVB&gk61w=ott+?YI&Yg zW14SyduD=g%hlMp1^#u3I(71%cGnWK7eA_+OFep2i4S_IC}`1@Ev(@*z@y=vE%1e_0(JAj&%Rk9E5FUss~J(jziYpUHivZ#mEt*3AM zMF(kPNFLCgcczA60tqDD)WXJu^!JsK6*_92hTS!0nFjD7_X>B8Q*Z@Fx8sbJf z33IZ!Fhu>h*gYrYpj5ELEX&*a2aZ~{fZefeiF+(9+BPEhLVERZDt4+*hcOn5XKh5( zZ3zc=Gu-uRDvXh_GCrJCkuPi{zHjD(tI#gIonO1~;hSLTo7I6mv4IVhf=zauJ^ zgv7)4#wWYbJ&*2csI9PU@>MQQ{IpzZed(-N>gbt~`G)CVOecr+w7rh;$uC&U?JbVj zzuUFfBgozlFz`IbjNI^g(NHx&wy+0EV{H|M zDmdVJCj=F_{!PI1%(RMRU-H?^246hIuP8C`xkg_xB4!@dXtmO=5qrlJ0U-)1VUZwG zQICc-`blIw!?)kL(o|A*?R8UV>5W#;#OK{PN*StIyFFlauo}GvHQ5t&!Dg?xih0SRdFBYSh(W0X@mIe5k93s6w33 zyglIju7>G-^MWmc>%#?GD(ejn9qX(5ZIo;co53nF*ss=8*7u?*w6OTM3)|jTW!86e z&J&!7#7hhXXb-CtM);&rxK=7;11p0{0j$a>S ztlXOv%xQ8HQD*30YdzS9@g=B@tx@hy3GR}Pu(-Yh?d>1cRgsKL)?)P zFm{|dY@T_1E*nX@Bs8CWbnNe3@TXn2=Ky+&7eNBDMY&&?&zwAkq?cfyW@lIu$i$D>ArVS2S1^2lNu z1u7T?$Kh$QqUTLpKs$>c(8~*b(})KfAIK%rt`#5>xJsj3N2+zn;-m*e;mEQjmN|Et zI{y?lH}1ErxFjCh5SBK6>0f5foGHVqwfG<(9;=RTCrB@%}>0QaP zNf$}oKxkq`PHINL&Poz?{#2(ck7|QQ%U`5(~8h|re#IZ3#XCTIbjpjY&M^# z5z(42N5X7LVO04D=31^#dv-Fv{tX;Z;aK;~2my||0BotiM%fHa_I#>qH)CD8( zIKw^8x5!wF4-ICky>q0YayAtz-K7ip6~~?S0E!+`Vf4QipbqAI%$4jDlc6gh%*Nn6 zKOuuGk62hCmUUy2VK$E3bB;2sxtJqVfwkBT6UG<1Z|>`JOwKB^#s?#;-yy1NZP= zdJ18IA4DtONN+}Krc(~_Yt@kf#d6PHs)BXgQ=xL>v(va@GZKvKgqUY&+F`2rGt|nD zYu9EY5!eEa(n(~YYVuN8bA3aYC%--jN8n5DtMf5vq>ve~=`#+y1ndXFDC}sJ!2+M5 zlY~5ndj=xC8knuneK`mGXJ`gWm*UsW!Tt`YSmfU_50S)%Ol9%dtzi;KFcxPy=P?ZVtf_O{hrOeH@{*tj*K4WMKp?ty#z}*4F?mer;@q$Gy;ro)1Z? zH=jzCLYo`19aon=`@~0`T_BTR=p#Fc$G%Q2W;H&^rj4sO(mG838L;B`xtb{6Fd^cw zf#TP#uzcsxp$DhXkcQVl`)VO&)k;1Ul`T-NNfM8gK4(IqVdRF*Xg%I%e$%Y*<$;&h5&!l&+ zD|+y7p)jScgTc?+7Cj6NM}xi+E2H_g$CDI*3o34UVI{o0yr(I6eMaf-p^WHPs&~NT zK_AJTKD%Sf(}S_)^1^Dl^QDwk=hadJ(x>rZ_^gL!;GKT?3i0Caue&}y_#|~Q>qPeT zSF)uq5684Gt8+LN9bVt4@#^(IbdBw zc;7x7V2w?fSOu|3Uf8B_10QQQ;Un@Hd7rmsP767ObEJB<+K6-9+c_1q1b^$IXxG3U zqE%r+YC-BG4!or&)pt)IwYLs6wbbT+*Yf&KDWkR{Q^@UbU0R3*6e)Lk=5y$Dl`3_y zgyimz<<}(KQZ|&_XqYM-?QfWdQ(dI7J|pPa?lomks-pbG#aSPIjVCSPHn3D53h==) zdnlhc-dIgUG1T4Ixg9O|qZLACHk<-NMsQ=qq$O0HH18+Ab%{CaRVgoW<-(pMu&!3r zo=CespQ;A$Ec&#*&R@!K(p%5H8?SnkTYgkuVOgG1`&#S3wl|7J(-pWu+#ZpAC<{dk zD1GCaAe>Yto4|X%>}KvA>p-7~L}GbzMMPr_?w~kX@s4tES5{)vOL0q|fQZ+LT6ME) zeFA!ZnWhFEx!D{#ZRxeXnuOjTgFe`_`vmIOj*nxeHcbjHDa)I}wu=jPRf+JWhh-X{3^({1k7t#A1^psPIuZQlY;^SEl*u)GeYkbaZNgJ8ymT z(@0xBCgd^r@Q=-QU`51@fFI&oq~c~98a|V~HtxV` z){iSEXl0$5HEZtVO>^)&CjM}GmgW!l58F<1EKPxT*H!c`*HqWUU+pbaTynBnsJGqQ zwK6S9jZ!f8gmZDhWqsn7dVAC6+x3r)*7dFau0V=qGJRdrD)w!HmcWEr>SM+Z|I2E* zIyqPam5z-hKP?XDq^Wv80)@@BR_*F1?-) zMUzDjQ^$_uT%e4dh+X|*!%lU1i&Jx1DP=U>Y1A&83voqJ6e=^I9%z}gj)-YCZ&XB|{8x*<4y zHorkW+<-jA33|jE?CQE{v$%7(7AfXG&F7LCms6ip>YNa-`>yV8FkJqmUSqo7yBnig zmyUQsfnES{b!KFX7;_Agst`>` zIcTr--XPzeD()OYj`qHNG2ica@Vw60E1k2s7Hz*Q8!q0M$ZuaD%5MGGV5o$y?sOPC z&U&2nTKQ=qB>mM_yj#DYlJ z(2vuWA$`)Ef{DbZBckjT?Au<^>`5bZ1EYQFEbhv!ktx`SKdn?}Zf3f^uUtO5XKMS@ z>6Gm4^`$q>v>qQb-K$S}KuxGGy=`f<(%?=(()J#P%d;C7<5bUO2aER^JvlCJl6^$> z*s}|l-b-0rP7B}aha?orRae9!leRUO-P&e&HZV`|c(IP$)4a!p9SNDL7bwqqUjKOI z`yY*1w+<{2TimJ`VHLjrv_3!VPzCI0{WR&OGPXHPkffHg9`v$|nu4x7C&>}`@d7nr zvlEJIlx&}C%DR-iGL7C+5q~z-=}~!>UmGXUHAap^atgju{#dn9!6C^-^w^q3FRZAW zcHZ3+_oKA?{u`_Ej7~kCZ*tLT&3uXN%92tcTdQm~Kh9|c8ra7=$8)m9wzE8d4#r-!_)77>oO{w@n<86+O$%QAxt3O#=sj%AF zAUP|}Pp#A(36TIuw-F$57Ejf{2#o!_gL#BC9n3xsTn?t;YE83((ZLikC3BOwLhnKn_TfZ=3DmT zp%d#uY;9sYZ_d5dQ1t%M)t!EPan9o+5VJOE_b=Gca-2DyX#iHlTsHP0U zLWxJ?vTDmNJBtKf@~MBbB4y4c9lonnfmJrVp7vuu>}~-rs)aNhXbF4M*CTqxAyA-k z;U4`x>Th;6*7SZ)ka2o@*IqCG3_l5*oD7&6J0->P51; z7T7AwPYzHtTb16jE2x9&ThP^B13JCgMIk2I3+Kd^HjvTL@QKekX+E=`(Tk%E6)HUDav_es-r z+sgO2Tpr6uYR8N<13Y8d39ZIt`mQquOfij8*%7-ymzK<0#8=iSz}%o>!@^z2WFH17 z5)UCiRa?Bd@A&pl7N=PoEmF3>IlHXj@(%?G;?}-Dy}Y^0`1XdD4=2>b0$Tzbj21}z zXp->5**8|K)YO-44|mlc?-7&D%(b|3;_Q!szLe|kxvm#z)f3xsw1mL5uf%U;Pb#?R zpmFi1tn)d(AC0O*l6I9@;$qHx!U2zxAwI(aGt-9nV1=QO}*%;O2^{rjA`eKbeTdg zR5q{TyKCjJYeEKu>Wv z(%q*;Q%vr^tvWZCRoT**-1m-?bLMWnZ_7E^(~ZXKmiNf%T{Ugm5j@U%n*3A(rfS3g z@-PLFH@DHoRLf&OqEmYocYz0yT)d(n6Thi!kz2>J^ye32wCRuYjyL#ka7&XTxb zr*$#f=J06|1w%b%ZIq3jap(xo6omT*i29n;)^$r@$2N+AQ^@UE$rgLto7qLHPVu~_ zO=&;E@VV7K-U!yD-yY==(UPeaS|J{!yZ$Pf%JdH)R_~8(j!M#avSSQzMn^ojK%!AK zZt;?U3tsQ0aH6A*E-qW5e5B-)Z}q{wyNI*6Z;I&_%lQ}r(YFv;#*e@J-F`&nTUA7f z$}*s2X?l%$b^4Wi+C~DpF-Z!qY@cna<|@q)zMGcs(|h=Bd$a%EhDzb*IxjAI-rVJG zpt9+7ujYrcBN0~O+#IJTUH94>Pp_TFUGS3hbo|zKpJ%d#@!$9K>}hFPSe_o2l`3~CH#ss><&9hlH(MlbUwul;1p6k|PL8;zzbB2%Py(&uI zlJ3s(d(S0eFQ(~pD`g8>&t9-izfdl)G}7&j)+AQdts~j(Nj@+3>T{2;6R%(75NE)h z=gIv?e0A$@)at%op*po+l5RQdwO{vCi|Lws%#^RGcwi1@Kacs{UTlx_(H;e&JyPvy z5qLD=cIEoiFqvi1J8siNobN^Z39xX{KfRHi9^P8D{>uCM=ke*!ZQqAB=7lM@o~~0b zdiknhdv%V@MT=t>Q&VSiSG^iOfro@oL? zKC0Vm-k4ss(zm#&)#($`^4`ih*z|ht?p3_UjydmE=1)2)fWY~>z#QrVPS(R(yFnkb}Ouy#|5ikITc7iaY4Vt!sO zflzEZe-zu735@9`ESinPT<7*bJDx`v?#gKkO5yN9Fa z`#ujh&b`lb&mZR*d}rQw@3mL_)^Dx7Ur{xm9}ESu#ik*<1klxLZ`swAO~suJ1t}j9 zzOHi3uW_3>N*2^7(7M~9-jLZbo&(5cM7idwvF7A{5G%;Ux^pOxbXU#*n}&&T5FX;X zDh>R?=#jeFkK{BI#u@J`CDy9r<75(tP7#Y>5qAp4V0KUgu65O?@i76kcl)hpHoH9W zPC`sWngp%iZLHD@RbsT|VvTY9vrw^n#4uzmW5&OE?xsWhdIm}ekp4n#mkWNRuvdtqax3MuK^e9oaO5mMT9oSNzWby=$rs?i9N3U>=4pA zrQs0=a%WMAQ&bit)JaEylw&Zk5!|hs<1n^qf&@MuB7D`s4aFM`!On>(?j1ESDgcH= z16v{wuPp+VzS`xEgWiz?`D>2Wi|cY{ra^9Bzg)Dp}3 zQJ(o0D2U7*{SZ=>tP#@2i0s+-!*1m6SG31&_tl4uNuXsd%jytvP z$0g$Ecej&;dbakvwJhc-!UcVD1(q7Ua+DRzIhE~`6!kn`b=;cl`e9?tTBJ zn|hmRXmVt~=ZUvw?@&)kMm6tBPhPf~C6N?YG~3=fTDztt!=Az**rM^az?Cj;A|~ij z=zo_J3>ceY0X-DH1`tcP@cU7}9k|{S;ic?$UyH6rn2-7Uxe6bZ*8&=048j!{_P#3H zDIS9oFX!>r(9n}bJh3^26HVp}h(^`H!JeyXchdGF1A2FOUY#(Zv5PS|wcTt`F#N6O zYr_xbrCitSc!#)`XC(%BfGfnMte3f&#Y{Vsle<+eMB5m#E_}WDEzV<+%zuBHuBR!U z@%nYEbYB;K>yP8p?~L#vWb#OM{IaL$Ea6DANu|n zY%z=Z&fXaHh9g#c+cHqQ-fhhbxG&W@6B~7?=)o=PMmiEHYGQPlE#t|jQuS)+@2`UF zfeNYDv(j0SzOe_65e0WJR2nK{#`D8?kCRm`Vn9q(wGL8e1Akw_vxWqz>AgP z2}C%8IqGafBpzaZv7b`r9itTwOTxwKof=xxoxuh?mI&~d7Df9nX3ck!r>3`iKP4D7 z?2NJGiJ3e&e=<70_Dbw^Cc6}nGW*16FPTJpvoE&_D`P#Q;U?VnIPTGasI~W)ZvHdV zKYVG9FjbHq0mzAVF}y~OzsfR(*UC&HwD-vU0Ax(!I=Q6Tpb__+^4VmTgl5LHzPoVE z{jTt8;tWI2JF)w`1N~3l1iWAFz^SMEx+{F%omo?Ks{Q0SK6!RpQbHc>n5}(9W!oxS zJ1g1^Q`+OJmE(iSrbEdEV~Efz`{hkuM=IQVJhi|Rdh!shj^jbkG~?y2_Nj12VX>{T z!LZ@X3kfmkW`RiLEhxa$+DPr?)se^Qt79Xqj%5C0D-UOC2qQ$P!n{^YXL^~bxXli6 z-`k~Nf>Ewv<)txhcYp2e*#OO)k{-vVY&hKysf^)S)tM=}x6RyY{^GZC^$jZt4^lUt zxD9EL*s^rF@1SnZ9&!nPP?w4tU~IIbUU6YyL9-L_Iu}keO}|X@Mofl5OgZs}+P43T zwdSE|s`gn$*Hp4+Xdt*&tWuZ*)rK`rGtq@bmNM*&a(c~!ShqIDXm459rH;4F(o^oY zJy%RLTZe;66Pme`jtv=2es^9^jTVu9)GN}nY)pccOHZ^N2@#@fA z)o78(B(~2!(;bnGqpCf-i935o%{aw3-F8gNaOEI--mbudZe~e1lijFX zV+hT^RkuX1x+2erO%Tugf+yf!>M-M|941;X??q4p=3oj#Af>EQzw~W5o^mRef z55tstcu|UUt+K)b5ynC=c=he2+;%QfKbx|(rOL(NTFq>>(kMA*N9>|PLVW!kiErT#zYYlSIc< zj(XE>fHUQ%(+#`!CDFR40vQ1}PPH#RKmentY|cs3`z~c1;?rYWDJK;tf`VW}*ESx^ zBwiwEK1q!B%t%VSLxPW!W3w#bM2(j zOb-cXf%oA41L*`V0Rj6pe7Jt<5VYWjg(D$C|J*g2{~S5?`bt>pRc@n8_G6dm?odeb zRJ+T}^l0TEL>1*ih)6i5H9jQlonVQ`GNlEH`CqB`QOQPvC-WRgWte z|0G6FN>n%FSohWx-Y5WN$qQ-cFn1mG%n;a0965^y{(I9T`h0V8#hwETjHiL~C=7AR z2~YVb3qLD46z*3pK({OaLI$@J(*5;HBiZOJX}*(3O)m|&g}t(*LgGU=uZBlhP=9f8 zJcfd)WXc|)fG}CWC$SkM|2%wBGyt@7F%V&XEkww?PCpzQ=EU=v&oR+3&#C4?H!u9dcTyUCs9XA za``ooWV2AH%i&csfQ8r9(v#}#5f#a!n)=LVwm)q2j`tYXY`_)E5$nV6K8S)-(2NYO z{6)6?sX&ovU|go-i^M06;3*``iwzs7uv8_ z`zh+ndD^3z{)Izbj058YTvloHf|%z+^BDn)_Ma#aQHy+GA9-lK0^l#l zMDOZ()Tukxt%g%jWM4UAEsqmLvjg-b?rV8S-YbGK0^r1xR#2pL=Z$xko0=wPZ{ttgpS3?4OG2^@J_aZoy%TcON;ba>Sk4{#{l+Fw@K zQsj=5S(m--aqNq4&PW9&g1s=wBG4RQ4-s|kt2x8>cMa}yRlkWSlD(h zj#g~ba~T_5Rido~0QwfcYZ@OvAAyNwEVs37s0*hJqRzV3s?*qF0q0m}VvyMKio?Fn zPqx+WPL1cHXxS3l&H9THoeEdx%fS!Y#gBeE0n*@g{>+mjQ0KTS(CjqF8?A@vfE28n zJdVtBa{*yo=NK}xaZbP~eeB!{x~QIpO+`EFW0?Iqnc(73bx7QGW4nT-vCukBC_0pB zt5YU!Xv(h4qLrSKY3)f-{er6Gol)PlH(>NzJJ!AHAEwes>WvQ8=qf&X$rRa_3x@?$ zGQ#NskZ(p%4?agT+*rQZy1;tD(!yfqZ2&Gn5qDYcWxni-Gn~eS1DDcHPk)qEIg+hS z!xu9i1?e*#>MW=r2yd${+os#<>K7RZwkPw8)^M%Du^DSW!rS-S|PZ-vb#}7qtF2R{M2Ou=^lq zeuVnKXhG7a5*22dfVUYqp1#H%Cqh>r$bwHbr>1ka9aZ}yj*>fQRE7%A69^t!;Vqzp z_&OikzpV59zo`xW|MMGDg3)T%siDMxciAsE^^nQIV zvRrCiz|ghaZcwvHq1F;X9d@*9tpWZ8=lOd57n>KzPShjNp_@`ngsxyqzj;J_0*hRQ z4-9m}kkh|BLF6p3_X2;CH~vSc&T%3az&%ZL{Ef(s@R97XN;=VzUpBf1uD(;r`0X1N zC4jf?8+O$VJwm$z|0kEkKj9+%wcO5flfgKv&wa$4xdN>V)<-6x#|Xw~K^U2=*AVZJuFm$V~~`E}=Uept)4!Awh8EnG!ZEx4d+Vng7_O6jrVj`&F9IuoHM z_`4SXm(TDkCOu+Phkh%UJ|Cx7t~!;ERx)r>AIjsfOX}BPEnUW9Muyy+`_%a-#l|RFLV4yI-iFMVE+W4Fg ze^rv^VZmpE!UZ5Dbw-Tl1oyvLrvAiC;vq|Koz*_$BAxDk^Uzz;y#jhOae9J=d2>WM zCI3dPRD0aod+1vc+tPV6S9B`=)lYjjw~dpyQ8sYZ?isjQwZzfwJdnmDV7p@@!tg`5 z0Zb^3EIET&K>q?aYSu8NkY5|~ujZ=2zaA!Z&luxX-YWuk_%}~=>yFsgoV$*ibxq0V zf#3f(KV9px3&R++A{dHj`ee%gmGvnL>ZMIH0|_fO&uKFLs{tDoq^;HOSJc8i-3yW0 zjQ_^dj2pD~8X8!5>o~&0kUG$R^;3E7F47|4FZ3`~dMSrioz1$e0?XLIgw3&i2?`-qmUwZhp&l?XW~aZmdASn0TxGU%vem?Wc~8es<=7 z!bBl|oY`T)>vz?1k!E@%Cxk)JV?Q8^6%goSTBiv}x3qy59t;D7dVhR(%2_Xn@_M#^ zsdzVwAeKBCjhO?IpK%shwB_a&H038*)|xLq=#N`#IpFtbrizd&;# z#psIZJ0qG|gE}Tn8cJ<`M7tj*987Tm%mYmEACbRN3J=f+m30BTBS{C4JNDz5X|%0W z{>S=8(>>%)`FodUU(7wVnQMn@3+^=f|Kd)r+cKWE#S`IvZckFRl>finsdZbcuDr{o z+1Mr>=EH!6vyY_XZ+xPVNhKlq?_5nBG?&d4Q)U@~ zqB#H)P|pPs7_w#~$Y!3RHa8Z1hvK?tt@QeOqJjSJ1<4(SY<{Dba;acB>^gXK-3c5p z`_s$)I^}=g_v_Wjey}+6;6Jah=3Dq-v;Z;!ZHoX!r*dX(a}(2S-5JsL(vcM#493vL zyt*!p0Svh&$%7DTg}8r&MjeBd9gkRJZJ&_DV;M7AuLqETR*8ml!m56YRlUFw4}mnR zd`ixCldKknL2DkA8VyXqi>Td_|0$C{)F}`O69}Igx|$^cg5jwoz<}C0==y>#!Pv|c zLt^r77UAd_xLjbk%jQLL&$KO!!kgu2rz-EZR^Lh*lO8-^7 zakGGz)K`?lDMj^kbl&MQGaSjo1O`?DTB5GpL_6d+cA?LQuMB0MY~>P&FcOL|o;+;Z z`CmcerFj5^x$Wtwf1V(fZlKyVk7)sm^VkbI*eP3(JZuUcx#CotI}@N(Y1Ff7Qy}K{ zLQdGZSYs5;>8V<3bLklLX~$1)xdm z@gBCNd<1)l{HjEF@(=d_#|smYP?E%-E~1&?R#ftbfp2(tcJ>+~cWF$9Xil{qnzAJpT3xw6R>69af?fxWm3W=44o- z{Ac3c0KCz*1-m{8fh4|Hv)i(Smgv-*tIM@2pqmPl%|Zjnfm+vcZTKEhkhnko`=4S(H8s2!e?FRM5%d&!z5(1_(3ly2%F)hAO=k z&u?HuUF&9N#C52}>qTVr4RRTM^a5I+G(=&^;MvxqIyo-MfqM{y`_uiin2Kjgv$}#^ z*6=f=dMbh93Ns8yI@k&;Y8a!=J3XDhG;z``P2ClmBMK8rXz7=?c!=x~)I% zX163}YH2@?L6cRRBoO_#D+VnU|LL)W;hO+P$U!+DPLNg3=Jc+k17o6sQBzrP%ity; zy>e$|xT7l|wgSXX*Ib;UR`>Ec- zi(V<&mYnf(O1Lf)vvDAyLGnsmhM!IT9ax~Co4cl9SU*{HJ*#J031LJO zQ%0KRInFE)@H6bHSMN4V?dvEiQx0;8|)7d){pu)hT`4I z9JpALcU8pPizoAg;Il?LdL%kgWRGRA1om3CDr5mrS?g_$yqT@%rvxkMaHy*cg}5eW z9lbk6{exc=u1q~L3ly2CQD@ZF_^?Veg0f3Np5MOom9bug@SzwCnQ+Z2rCdh|;pTx{ zno{ZL;N$v}9_RqXkf>wZNm3S5e4@*CuKhHmQI7y?Z9J}#<-wymGt`~Q4MzMrSH%W( z{>x{TK(vw--S)~`wOL__^qeow?cb7`3+!Pb0ue6AEXOjguTm^Gm%a-vO$zCCXf<@^ zKV1yJ^)?AhG@1Qo<^sB<;I+`4Q9`p^60n6DodkH1W9Gh0Jn?M0xpqdQV9!4i(W5Pb zdpWkhpwzz%6QPB!sCpO*(IiU6FryVhnp{ngL)(yMI&|D(Vo_(Aka&kWBaK&cQ7j_H zzpHZSoWpjZ!8DRE!~UutH%;y{`COU4k@| zC*w`DxJJ{riTiI8{s|{{@vMD($^%ByEkz(Yg{04#Ahxo>DiU)=lqxatzlQdXxQ)ZW zHBrb-qL9r;yPX``{5cVsFm#4#>aS$2r>d@8op-L&X?UmaUXc5%wr?5AvmyC6H)aUv z%D2+ZSEsi=3^6Sp#17%@^%0|TdQxdeGscK|R#DkD8(`!AO{4um+s%3tPss_QM|c!f zN@*bi*4A*`8i2&I_qtN9N?0Nhkc8_>fj|Z^BXYpruA@DjDp`=V<|run;79oo!XPoy zQ6p_m)?FhEl9VN=A9DF!ufC`XJCm24i!@j3PyZpqJ_u_1oW15VxXq&~Uk$X*@uJ8Ji1=_s_Dc#f# zQ|+dvyIprg4Kdff*LpgAz2w-dcsoZu(obx(8S|wT& z`1}}PNZ*PerLQbbDU;UOx`RwJMmkumja5xryy$DlW_|spPr(B>bH$GqHL zfmqoMaTj4s-@S5)2e}|dZzrBx-`i`UdQzCd_2bFn)kK8GHv8@%zfDFBbuCF{x&@vO z5c$f8=AApYF1oxwYQumEYayjxkt)X)lZ*u=;i@K`+v(O~H#oUQ?21Ka^9h%5Ah~M) zd2eRZtq`f6@;I(}>JP;t-2(Mxtgzwd+ozTzKynzc!577KsY@kW$o1;&ajqgQtG#o* z+VO}A$u8%c>+84K@euL_1bZGgIFv~vC?W18M~AgZDJtPK7=OZArYUSAT?KuRE+*UR z9#8*N$`-{5Vg>m{*APA(L)=5p_c6!(HGRuPP7Qfr?fi1fzc_Cf6tvZ#DbOEn>pFT1 zol2XuZ_l}_Ztc~05RPJovQ8wPqkDLOs@Rk5&%KD&!r&-94ChF*L%Qu_J1ymDK3FMP>R-ER4$<{r|5Ln*$G=1N z{VxN5bsg|<0YGkX;kJnL>3cb&FsJvmTEcO*uT;C_;B?A*dYhL(2JB1fma@v2ja!S1 zd&Yh(SD-FKXf~nqTaf3&G>0AnzjVwOf6z$XF3j71(GM>8r4v!`q+U~u5v5ekGihJc zv!2LH!xxOiVhped<1O3OPv2Pu?i@T++wx`4kFM7iOIUF=wk#YoIJeH6L92I~Tbo2s zr`pL?47OOhEwlO1xlj8q)9ZRZ0^ZN>ag3*DI=?Q-rwv6x8 z*aNeCnxRzTY{7FNlW{rDou6*5U|C0}T2xME0&m1DOt;RmyI(V!Xmzch; zv6@x@Pt1?8_!wR*i3O?8e1303td3D#pSo4P4a>kN(l0T~jS{QG-Cm4Tz}%%q-06EQ zLO9CaC;nyw?E2a%gA70L-;}GzVITR|+e|B`Oplzn$@ixx=E0}wGauFI2@0-*`d~{9 z^Ue_96)Lmxc8Fb4>q`w+>}~P^02p;Z+N*)&81(Xs&h6BAz+?O)$?h*0Pw3ob#mJwX zbot?r7Ainka!Fj?E$7>R0WVy!$y4G?wOySmHv;K;+qYK>M#2b~are#OC+|fFp$PLt zQTF_lwwmC7Y85y`U{rh9xj!V31R!3CH+OihM?tVplWyN}rrEk<=#H+B7a2V}XYnpl z&8>D8?p7#MmCFp+4nyhmxkA)=zZkwgWhvWN{rAX~+6zW6Xq)(9uHn+YNR??#rj&}P zRZLc7p5e@t6unK@cQ;4-3QjJGrf$-?g)Nk4nlI0TWbPXD?8?^UCrOY{yY>w1DsW6* zakQr6e&{3lXWwRHJOG9DBf9iY11s^ga9zM>cq&9#|3_QWHCQqz@L7yyD)l~0Nk_uZ zD|=$s@aoS6)PFtf;@;T>(%K8yWaOTXSh@ar*yfO~4jD%MbEBA3r?y~%0$-8>qhXz; zb%-QJDlxZxTe+r8KLHj~g3;z%zBi=`r}uJ1B{a=i%x>ScT`%vq%@wjO+Bm^PZ2$Pn z5ND1MJih~;p-gBp!FcK{?R4TXY+?CNm?%mEidlUd@Z1cO;PI#H{0>5Ks~_lCMdFLD zqj6rDECf(BI~qB9&2i0k4EuIoWY#sO%S%xgm&&iNrITF*o>t!uI8eXyNA#}00gVZ^ zdZ8Pju2BV?+PC-h$>96(!!4OEr=RQP`@(Fd=>@xf!oP@Efm>9zIl>kn*<*AUdTH&& ziI72Xc;?H3a!%2Z7CaI22k8L01k{28rl1FQnBe{WdA)`RrS!Q?MoYgaf)#T2_Sa_% zbXf)jBTUy@Ks(;Ns<%WJGy@89Ljk!Y7fR>V9{w*5BsvIhwKOhN0x@*>Mk znHqJLu?(dCR}B2ZtzzG3&Kjo=Z=<*TX6O6+5PE6=G`M+0-wJnlJhHzn2lAy_loBU$ z-v%z`E?XOHdAL#Vk30syz1D&glr$ijM7s>rY%LMq00)*6C6l^`jZ?x=Ai=fQ;V6el zR2a~h38|lt&|yq-X}>cvCm_Yc?m_|olsw?4%Kd<;we7HX@qbt33fRFX-2Jr;P^83w zD4%K?r6ms5V*LG@0$dNmPTiPL&s3W4>{3@VKjzXQ*nV_eK7rmIl1}ZdCRf zKWGmc0IBV-qBYC)8+tQ7iprn@aSLw7BxS2QpD4wxJ=R@)uGSRXuQG$}>4j~<0Tn&V zae)%=K9>^SRsI|L>@>4%zO1kRY>)o0lDF3#FcIY%xgwxt^046YyM*hux0U8{6Je%U z@xR&u(hRRh9L+2Z$q(m#83aUig8~Mx^Rv+DP$YLdG_eB zVSY{^p-r+!8Sb!Nw3Myk?U!5`mqnpE1OcM?FIBZ-pR~1Jk%lGbxv@fbPtCLK+-&t8 zwVGUMoy_JrLN?>sK!ak?p`hw@6TcMi=4q&H4(C8%tWKG$p^5H=>6~ZN+qj;udAaZx5IA_2aSb}wUJu{6j zv3}=V&gr*)vfp#B=uV=#p-xXV{4}Yjn)XCC=F8NJRk554)egMGHIshT_5zsoVN2DS z#9p+~KYd0Z4G@ZIJ|7zaDXkLNzN7xg4PTo2LAxb?fgsOas$1%g4kyaY2GPQI$#HtA z$@{>;Xd^pa3mp~Xb!otT*w=M+=!*HzJkbvp)aU+>3*r6r=AjC9M1>6L{q(YcZ+TC??6$g__}qYSRDE*hbX#C-<2#N<-`9Jm)~ zYsdQf%6}l;G6tVE4ciDn?t7Jhzf8o*3`=C?P-~F?Xp3m67!Ig}JaW#-kD5@Om=rCv z1C_@Go9Md`#t1~_OGG(memN&R`Xv`MfiJ=}6=gpJZ}Yl)`W!a7M=-$k2y3g&y6y2CKVXySQUSu>s=Jwv1MJL04s0l1-MaPG#4(8-I9q{GX@r zlH3C(|0@pRC7J!a(Pp9hToKvsPt^+&<+GZcE-c@<0~7}g*@&4(FV1m5D~W3C1q7WQ z3-z}qe_|{U`gx*Sq**B9@)A3|AuFM>4J~b#3l$)Q`PO?NPCOV>mE0hba39w;x|=@!;k6 z^la}ZurD1J9Pv*bY8LQpqv<)^mGeJr!6ROf?(T3~!brW;8d0#tv)?{i4{$ZrR$gK% z@ESlg>E!W5RIh#V(8vuY+TakoI3M0^u+Z&Kt>akNcSej~+p?D@cCgmaLTE{Irm-Q& zBz~kq@2cm#&I`u#ob_UoONQmf`t#gYqeH5#!@{9{ffprc)~`(-+TOKXbo=KK4$*3L z7@W-A(AK7n-F>H^U>jk5cfFVFzrqE|W~lmiFTgK4;gbs3T(JYTpct`_PeCd>89mV* z!@R^Q36fzDEN{|hQ6nzX$H;Nk1gwqE#WCU8p{J921N+zMRB$<$XKJ+F<~qi48K_=Q z_^19)D9?gV{V88MY3j!O+^Kq7mUce)8RP{)U2kvj7ljop-n6lu1FlHLjHzKnL+ZVD zkhkL!ZOR!f6VZRH-Z6q|;EG&KfMU)8C52XAO}+LUf~6UjjgmYAfFj}2;GXIQf`BER zxCq^;Hq9OntNc%kcZv7MVoq;~*?Z=`B-*Fi=O~$KoFb8=*!Zk&knSftyr+ z|72fIDT1Dk(Y_H+-LOCez=zN}2_!eDpp_fS+~;6rZe6rb0-=3fi>l&I>G=!6yU9&t_rEE%uBG=D4b3wH9$UF+|KG#L*)4~X*pDlovh|G2Wh zfnaVrWO{8;z`n;Qr&S!D(265?O6FlML3d%PnLF6yT7NUork2*ao>qXP0OB9*@~|gh zt=K{nUjSD1SKU?)fCU#RmT^khbqkWmqt!z`<4bPbeL{}3YOxhWW@H{ab7v{Lcq=Av zh5_IjrhQ>}k9_u&tppL8`122ue~fzou$tvra)zKF2X-tu+c@0ux|`cF~!;+hY!!LY^J=M{jZ$%FaDi{7x;rkN`N*}K-`Drm&tps9ayr<@Qx~aJPJ-E9)xci0d)t^n=d^pW>oa?Pa;c=To79?!vv3XH2 z4cZw;e&WyG8_R%+yW_2x8{;=C(|>5)@*6PbVBv_K)4$Hp=pS@H z{Z~=5>W(QOq0p$MI*qFd5MkQIXOGAH1UYR?+F!QtK;NlMsWzr&A(%45e9KL}|>7H#FfW{6Er}92b*zcsNNnl=Cc+R_oFVm4>+lx82LM z!kATw7Z-a8j_AAO0J%j{iDBov(@vX%)aOS%_PeXKlfB!kv4~YsQNi2fK@gf{{swbOWM4Sz7 z#feVi&k68?n(k~Y7;LR}4!yY_B;+`Def5CL#oHwPUa^_z{F^4Xd$F8wJydFJkxQad5SH;u5w;!>ceZ5wJ&DeV4HU_5zAUSo`}aZYjjmtnbGRpX@48|z72!co*Ta4s0kh4nd!wWMJbf|tj}uaDSlp0 zimAaK%$dw$5b;W}lh)TbylLJ%{3WkXpa>A3M2L?@Aey4NGguBUM3B=?7QZFt78wKj zRR6A40UN6ES{>UqD&s0(Vn|`&pPJUGwR4-e<)+$Q1@Mc;Zv=Zg>%GCuk0R$dIkgM( z69sMZ&2p5OOmgaeV3AOSPQV`Bw07o$JLNW*ma$_z_I05Du?Si!Z`)t^x%~F(xycMv zZRSS>rkNf(K%o4BZvWK>P77KRTe<(*a}W7KOujlWzH8~p`6(>9v^@7Atl~qc>22uh z)&#I9?~~sw-WjbvpTCFN<}9KU~OZ{z+e|tOFJz%ls8d=l?q_^-}6R+_G9TH;M&mpyHQ*4(%QQEgF7WKF%>P@H2 zro(5mSo^rsOtG~ntoY<05&CJ}*L5n~yME~ayfnE8d^Z;{6Y<9I9Od|D%E)`gncLLo zAd&1GbOfVaA5lN2m?fMJ_7Vkcb^8`}`iC7!Zu|Y!eFA>Xg26k)Ju1^Z(kgs-Y5rK9a8b=!Q^)-D0`R!*IAHuKX9hgG2-gu zxFLC%z61)wYIfGT^-TQe9E>U*pmjH0vfFS*1$5JidmSw;J?0UTaO$xDsoFiZaps*t zE4cgCmyt8S7BLW_1ZqyXYa69rL?iev!w$a;&OI|C=7BId5 zLuKZgGvTGMN`O;M%pUexCr35a3a@9WNoq{A#KzQD5U)4@ z8(+Bj&L!YK&58c_hSP7z5;mg$X~l0*A6b!x6R^y5Rsm8A@l2qic zV_r|C`66`-@15SVtah1Lo0;y0{v=7;nSiEBx*vihMgDz9G z8`eE*>=xA_vN`ey(GJ?9+J(pRt$TBy4%cnIC8@Z5Ki*aSu$deWQ+Y5<>F&1Ok)K9J#AWwT7uSLcbPR} zx&?tO=@;oJnrurgI!<_EdK2d#vij*{d_1JaV_|K&5yqESvWo8M?Zp)P`7VqxKH9t8 z8pkbYv-VK^H^B~j1$a)C!6K_Kq*Z!gRCT^G7Kcl{NdJ7o4S4}bY2sIgx-4!ph{tCD zQklV8dFr$$i$6}nbr5m&2?BRMgs^Wgejl!Iz{pTbWWT^YipkS%PZT7KILTvJVW%nZ z+ikqAk^LMETD5gFXP;a5%-h)yypgt~^p+?AZxu_^j-cRebKN?d8elAA;xDrM(<&_h znXBSmCw+HE`gfl`eg`XZsxp$8Wn2nGhl2$UuEX98#n8Z%-f9PG7uF9*jCfs+&I{?X zo63iXqr5vP_i$2pLo6;bv_070J03dhv)RAkITEG*8t1>KBRuLB)4#i_)>n&v@o#{55 z!$Wrl92mQj2N>7B$H3JyZl_*V-CqG`1HhNiDIJF3Bj!xx7ck zC}sm*gXsVj{p*x8JSh|oP_<}F>o~}yL%{H_+pHaKiB`0L?W#`sNPKFqMt%0*E%9#q zp;-Rqfdl73W3dO(scWwqo0v~N3O9pAe_r!JR06$WBGYO17}xRS-UuB ztjxZ^?HGc%*PRL1D9tUBeBmH|Si!sMW3Z0TP*}>JeFqWk-?)Ua*onwF0_fx5b7j4s#m&5* z8^D7y)hGwg2UQ$er1Wu`-KXywK89VG3qjSpBu|E6O|V))B*9Z68w2L+9llEi54$tN z+Zcb2>G8uvqITYozy0|vDV#RCQCj7V?{HD2e9C~}eI%Lts@MxVrUrYaCVQSz=5Gx@ z<=t8LWkxs0eAOZ-&z;(;b(v^MocXqSiruN^_2DjaFmrMIhK#o=Sr3SI@jJ*i89glh zKsl|7kCVUw&pnON(M%?)SH1yQP8&sp&hSyNiQTqM(6#X#am2plWV#hKtf27T&+ag{ z($rz;hB;VT=Bi4qYugW&T!k0|Hr-FiAsOJh=}+`0eRiGe_WBLK6sx@6*{E6a*=JV_;02^L)0l zjpo3QF%92{f2Ev07af*lQ52=l?&9i@fF&4J-(wqK%#`}-Vunrr zw2&o_))jA&Ixf|77o^r4Y?0FtVZKuWeKIEAa#qRSxvaC3uVxb%#hx{*=G+iI(??Vm zwbbvolj2FRbh2X(4c^&TZo0qQ*vwvLkMJDx6CQa5!A2RzO8*LRjY0T9jR+{oH!gus z{fsNXM;VSF6C-~H`^oD;9G*f?!)i~{x1)^VR&DV8^a9%i>S9=;q^^+P#ZMj(O z9nJl{`&#h{SmMjC5UbH9p56X!CG(Z6>@O zvkFHDSZ&NVZi(Os=LWKQn78%=4h+qkL&>xUYrR(+IYvj2?sNSGd)9eRrMAbLs4!I=wcXfo5;XNlK*PsS zCdO+^q5PeFU3$jFhVY4v_Cx`)$_2lj1-^j&w7Q*Rj&PfiWBVS*a-PQ3wM1(?BW<~6 zSn>F}w5)dSWo7j!%CC6=g9Mo;&vW`-BQ1Gw@7cB6hR-gS-fiuPt8jzN>`P6(dRC^A zlq4WreP?V(d{5M6a%tr2=Jy2=>>%%b-hP&E=yPYxBCmWMlMrz1zq>g!KiIvswP! zG<>eLp96ernnHH^o&H{=kgI9Z>G3gz=%#U<*%e~(j!|8SE=E4D8{rp4E{__|U?_Um z!(}T3a{a-{n1EprcCee_x$CgB#Ba3>-n7jsAV9n5;E=yK6)a>wJR8n0R4q-zMMQie zGoZmAZ6LxZ(+wAQ)b=!hCTROA*QU0q~32w zXsF!UyzeR>-x;u)-LZz1_X!y!H@;IrbsY4Cl#Y|D2NKYx2Qrf1=qhiL`xePDJ`IM( z==T(pzzoJ_G{{L@cC8VjH>z_#9f9OE1k<~y1|cfDTu7H;Ke@bdJUVjLi>9J6G}Y%m z{SRDKo=^I4k@DFm;*yh|05xryu05m(mGq_2_sksP>!PHlXaX;0cbfPyVKg;VY_4#9 zYnDq#eC>ixiEDzGn~uo|53pi?4T%sevwNW2ciL;?5Aj2?mn-6DK7sCcw&bPldJH7$ zt_Oo5(e-vI1hj9|jynsue54v)TNd)GEZVxBs?ypj0OPdJWyLLAJAuwE=HQh0G3t4G zxs?|*rxs|Dym;{f?IiZ?gT_)_u%|+}b|13(>AC4du4bR#YNpOo3LY|c8c1i7=%Pqh zozHsWWG$lw1hwWvJi(>y^lHY5i8dX=LvXoE!gJ$dnD&`-e0JBA;yJQ3=j`I}Qr#ey z_3|ayJRQ1&?le2g!`n)xZNDGjL>+NI-Bv_%uxG`*`G!;DF(`uDpsex0Z{vK+&+V2p zViMx}KeF#sd9UW~j*HZLO_O+0>Nf#M)fm&ftjmYFCb}9!13WJFX|)bh0d(ev9T-0+0;5p_6Jn z!3Iks1k0rR!aVzz-XE%yAK4XF?%|GMis$91JGVYPL`Vq}BdN~-+w_vy*_hi^b_6bSZ26_w~!2J?46dFGYA}QeBX|$Q;U4q-0{I zS2)0!P(Z85^@}T%phpXz?~Ei1i6~ojQ;yx<1g@Tfb!4{oSU|B zxO0o;zh!(+XZ&2|8)DDz3fFql)<3u2BznY@o!;h3^Zh}Uj9!Z1Xqhvs2k1`?q>h-cQJT>7yWcnfWuS`xD>|Kw+~~U8KpyxKdOG1amW4M z-&TM4^saCS(V1dm&lT3i@v~2CtxPYzkRyKCd?ib^=|zdk2{e69d*8iJIm-8HJh;K@ zU|4>voNlAz(tWR-B4*xY==ip|S)s0D-M}*4md?`S_HTuv!H?mw+$1eNa2~qhzpdJU z?$#6Et<#aYh0u_Dc~z!sQCA==JkPPN}!mURsa4cyvpMT{YC~h>~+QS>r2M! zhD-0LtQs#Raj7pFUnUn$x{g3FPE(y1Kc^6WG0LxQB#Q)O;r5Gf!uqvJXfO|1sdQPc z-8hBktlMWBGh~+6*V~0!pZjih)#~$)c4Co+!Seh2KYUN1sXVltM1SkZYi{5K?L>9| z+Xwyc~)Ykf4Z3U zj|V5u-BK^FpU?Rc7U^?+tSnKYusz(@e(z)0!>)ALZYn5` zO*o8$O!F_%e?lB19IYiUkvv3d|EocRL}rnpjw=x-T{|zu-4>!>4&)O5^6arw>w2kw z!Xu~Rt$ad4Lgyl!z#wu6wzvqbxiQ&9?e02I?kfz}K{>35yf~qUGI$E!ZZbVYCF)Et zHZ}%dv)~PTIW_fiYWgMOAn^EW@v9P_I(?vZK6EMI==(jdDI^piHueUqbX#6TyYp|? zosLIjx)OgG{hFuVz&WH~5V$=OePN!{?(hk0BaAp8)L9sYeoz)VVnVIP% zCCX61!2vIGoRNn@p%Y0TK7^dDyw{7`SPbj2Xt`G?AtZa8{8n0HfMTO3X{_|3j<}QL zu~&VmRj0nn7}=1Z zi;IgNeqD-q)qDWeTfO$3;w(?P!seoAcvP0W^rKsI<@R&BcN1@E2=B=$$EEx2Y@84w zh+u9G+~0FYF;bkA?aq{&*gOgH7^<&e3;(ah;cSG&ZxZ2`hKuYuWHV@UtWwjl1Ka)u z7Y^*c-eM{=MH@nd{?;5`Ixrs-9dnwQCin@-ij%Udw8&ZBDj6*fxnn`a8K>NAG4fOxCG6T7S|-_);5AMYjFm#!U&;(9kS z?DfFFg8h05Gt!GZHUIhJ2${h(Cta!Zc2c_!og>-<+_n@RwkObL{(IXSa!%@z$u_Z^ zI&bEt(k|_@D1|9E@UD>P9Vej{o!}XL{rcQ_2dnvx_Jt~oVk#~@?(ra^9KuI~GjATG`%1AfL}_f^Jkfdo zluf44OKWTR%Vrni?t2l+uV-AyjmMsEzQpkNWwhyv2x2-4C>cS%TxbbV_-kHPzVXPhz4pYvzC-7whq zTK8Ntu6bSaE;}!EX>&{3S$MYuf{4hj)$NO!)|!|vJdv&N_#EQY`Ie%HqDwE9T+x;? z!jf+DQZ!n=s(ykW^+;xK?JoF7!m*(!=CT-XBv(rfY2m>0;5*fs zjn@{__MHEI{bpAz)2dfuC+K?M;w4?p*|W2=59h0@@rUm2It0%uUYoMIySoqP>9Ke0 z70i`$_M28|AjFkcjhsBSXZ8#@D(9D-?-eadQd8n~-8}uA-LPes=^loyRdBF9W7v*P zVW?hk`8h z#sUjJ&TYDMuNF@2MU?a0y-%O#)_BJM^toC#P%`Zdmfbh+OZ=$oA7`T-9O;QU1f7}T z+6s82pdcx4H_OK6(7#%k6zZ`lZ6%+(?XAVHRb4A`D*5VrYx1>NM=Y80GjD}j?MzmM zaXr&y!9#KHsUJhBM=Pk|*L{&<>7^Zcj&JU{U4~(lSIt1ju6z0SItInmNt#}NR4Bk( z^J{ceOJw3U%7g`vWJtPu+8BQS>%c-2rZO}zLNw|{EQ3)zd>oj7y*(#epsjq7IyuCK z`5d!0Z^I7JQzpZ~aVW?NxwhTq6jY5bb;l82WeU-F88J8UUTUjbRPWEA$_6@Dy}G_& z#TU3QYS+R#ee&s6WwCL3lFm%q2!Y+UvV=G;apb(p3+p!bxy5cIbcek~Y3PAT_V#*( zHLw4LlYykPF-!ho(KNiaDx38!mS#g-cnf_Dmyv1(*13C<(%nf+wy%!lKe8D1rEZZh z>0bG%Oww+}%IkbimPD)_VG@hYy7qs|(%(u5b36iBknDJa=4SdR0%cIX{O>Y7FBv4Y2!G9&RfiKgk+cZkr{ntmWsmgfcK45qwP z$*z~|hay&<_RozXRnfM(`o1*ccdkr=RC&2>PBsX=$s6Z<@`IxGeNeu!sk{@~x5sIl zh!w+&k*3rQzCHtu_J-kf3EXUZiZfRT$VT6DRO8mW7Pk_}*32<`xRK*{lY1W+?Ir7% zct2Q@S5T6acUqYlTJ-Fo{TZu8`ZBru6ZH{!VS=^&UQ$yJ@>BbJ$w;|_v+&{Oe8&Ap z7zDlgF6io+4M;e>HqU_a&LLk0c;6;mkfT~z6Oe!x5dl)P9LASpkYjOe{H)fo7P(;! z=L9}`ZxIQOd)J)!OxBam@FZ)KK0gF*p;-McC42!mdjY7PSB5`tcSUeKgut3?lfAMs4))^q;zKbLQ^-HwCIKj0t*GO_M1b{ z6L^dzvQlbE@NDNki&%~3B9%C6AvWmN_)V80iP_D*w-jJAasM2pkhK(h$V`gvyg-{8 zk%YbI+-{Z=eT4-z?ckqsu5N~C4ccbQ(@f?y=K`@6v&rL+IFiyD+627v-qMP>_$KLj zXv}0EK>}n%1u~S1ibt>)N^(r3Vf;>@T1!lfOyakv!ID(Hr5tUb?p$AKQjFc=lZ=9#g)uZH5`C784wrP%k!E>$tVpqVog=Xcg>m9Ii_np}n zoSCxSG*J|ZL~PJ59v@zWnS3D$=?AgD#V}XjU6v?lBvyuM#S{N z<00`HQ zf$a6Q-$jCz?dpgkVkN@a@fdHJ^B9}@@xhR9k$F1v16(16ndvn017^Q_&zjX85uNR5 zJ~T&cpwyCRz{A6Hn4Y;z*ZArgGrMUkBGxc|l8Gtda}h2(2@+bcU%MmAWr5hZ7;ZyC zxaz<;UOM9|={=c5*F;gflB1J_1&+5s;t<+auWFeh1@2nv<$1mtY4^9Td_m`3i4G!- zr+SU5M52;fuBNccMIh&&&0zVT&5-G6Pq$DPWKpm#Si#{PI=ZGIHaydp7^IcPkNG+b z;ooe$#;+=H`_jDRC-bEu`?(vQP!;#$xu``sIl4;IJEZ9EG3~1%c61DBe9g*gW6ffp zI1=v>%H&B=@hA`Xy{gn%Rn2vIs+Mhjyxit&mUMDXM^7)3K*sMUJWDA&o_p}X{fH&B z{s4=XmX_=AeABr<16t>1Ir|>TYOK(9k2AuEAEfw;Wpu%H%RasfJ3BE)6b~TebSYC6 z)~k>5b!+Ze^qc$9RXDHqB^26|LI>=kyxSJ};mCgH-vRLE05#*qiynd5 z1;@b1s0aYc^ftZ>sz8(i>k(^@P2UfS<=$Dz3`vw6R-AHnKuhyZ3sY7-gopMjYGOQD zyJvK&x+JMPibDKt+CwldJpd0aT=MaCSkwsyjT`T|{H_!;ems?}Dtv54U!PW;#Ne*c z`QcWcP-r!1_l%d>8)hxJ7jXXczrG}rM8=kplj}S7ddFp^lJDW@;pzE_@56XP0{K+* z^XF39+6g`)hM#?MbSrYLmN-5dE3>m#*D(6KgrE*kiTWfIME!yjm&Yqm17Ocp^1l4H z{^2#tVNv)ue*^)GT&8LH=O?uq;o)ZEm9G)71YboOa)DI!&3Y`F;$*(zIF`^t5D!3~ ziKy+1_{FAh$hBQWF@bhiniwvzb5bln)ZxXeWA+5X3}1PUz1PI;`hoyeA%&{S_^p_U z!RrLohC~r&w4k$(KY=IXw`uxT)Y$G%`oOXI9**XwdhiKVG)WMVLC>jWGr&j6ZD&Xq z78abID2p7v#klfR{R7Nc5I8(6YekSq)`&UCf;l1>UWixR!_Wm8!{E`(2uK0VMsDrJEt}RU_LSjf4gsY&eEv$){w1h}Uo}~MPpz*Dz%zz4H6u+~( zF&kvJ!Bfq232&xb6D2Ek3~2`%hKnA^#E|8AV9+bXL4I(V;m41ui&NI*e_Eb5+LSdS zWHY_PX6e-gRV9T|?z9pJIeShtHk}=A>`i2+t>63h-b{hTumrxau#hip`iEM!!}7XD z@YMmfgrp=*v}k1;eRRlY5>lqRKEw1|pr2|HWt=dQos`E6y6oZWettPRW%o!=&zbF3 z=K~Qu+*?s+%AE7mKRuiAKGMF_wrfK$7yq4iGZ-O(g=#{~iGEkhz-T6M61Xj}XhkQV zO+0*2!ATt}O9MX>KB&a$eWf4k{Y~xw!-cmLhdi_a^)9W(b{90zpGWZfC;yho#OAC2ZdsnPM7)KTZ`XY=2!q6l5UJ3RY+d6t@>P%w`VMacYnvx>`s z{U}6P<%=NKlIr1L$#%oXLV8A^>zs0E(OX`iNhmYZl~K)kipv-7uOyipWAYeMhrUs%)iq%VJRA@tn>K zIXY6WqX&nCEEEJHI06oYVoHQX!ROIzY|xYXa7E2C8N?0zQ*+DSkg}L~5AVj{sPk&? zoBru#=|4xE;TCAKK!IobUB%DyfM`zP^ND2b!3n&xR~(M^Gcw``Zn-ikQ$ov3!N?!a z^!cl`)1~>0W8gvcN_^HQB;dNPUbzr|a2QflR3!3i^TAY)ibekz9_i6`%aGnE4L;WS~yKTzE?W4iCHN9S`5JKFBkGqD$$nfn&^tht3#bb^sAX~0F4i2nj=G;13myU1Kb^v^&H1m)b79) zqB=>ZcSpg8A_5;!>^Jj(T-c#$ep@M5Fcq?Qhkl^YR_~|h66SCrbZYNjC&^#;gbrY~ zid(cvzfoiuW`zwFcvSMJU4{{ixNU82gRsMEMOl79E9!1oVCgALfqmo|`ThVZj{m$lR4^%vh&}0$d^=!>To~v zfq}%+q!)n{YJa@!KR2h?9d_ZLpOK5*FjN!pS>z`k=*z&utoX2?q3|X}{q`sN#S@mo z^O0Y7-xwE?>D%yOx&216f1R{{vg8NNOioz84q<4kwlp2)K&#C~fbPWMKiIR0nh_$mMa()xto{nr%H#v8zmuQQYo1h*`@ zBsy7o7V+`RdqMhpd#H?_);&Fw6sl+nszkBX%wvk;n*X`NbXa?Y>wesOu#qn<0--`~ z^HH7$2h&(&94y6NGrDh!R04$oa*l^;GgFEbMa0Hsot43F|9%RSsz<@vPSaOUi))pn zw!3RiVwp*qk@75bhd;yR9am)c)O%_Ks9sK)GVATlc7LwUON3W^WN`u}o{Z~XDA@SO z5QJcH{jW(g%(H;KN-_H=s0^yD6#$@Lf@H*26ib$(>0fwjxNW(f;idGy_!f8fvY#T) znXE>$PdP{4=K|(;pfca~r4*HpVxT-5TjnbG*Ut(y9c3I$a! zc$~nLtsv`rwzF0Z9=|$LRF{~mE1|4MDUm`|_GCrwoFHbm;I>j%1rk$u(Nnu`9ok_@PBR^1kM5<*zxncK0&Zee7L|Zu?hWZiI;;@ z%J0hydWLKR&^mL>EajxQC0m0G38c478fb-fcDiR8Dy}SyjEn-V`(L*m8%cTRmzFZE z(nhU>0fS(=!JBArZx6Z7=c5+8Vj5?QZVTtQGU_5FN)10vv`*#W2%@xEf*y9XBlh^@ zo6G;)B@Wm@{$#?U3?fF8BDhQD&5Zf&5G@+~DAgt~tCn>D8d+vu(8V##sT%_xd<*$d zCFwppU87y%cS7SeRG|65Rn`@-@=Qcg$`Uk5aji3=9mc*j}tmxrIWs{Bfmn z*qePX6@<0ix9dGMb@FZncjLH=*y(%}`1j0;Scsp{i5fdp1ln}XA5QlXmsHxTt4D6CgU$@!e6`?Vck2qjkgO}?0Kc%t8ijcPOydc*pH|c zV?}#xhcVf-!!0<-V|#6%9o}>UFpmJ9d<8n2;a{_0KlpwRT;$Ao&|j-=hwzi{oxo`o zW5qj=Uw19fbG!8VhuZBg8d%mDqcu0D23s1k>W32<_zY%Md4crbZ=#V3u#SUH9-LkI zwzjwZkg%}E>YGi=&>Lt$Xp1C@?-wQPFpr{p+tASP;*LR$4@uF{dhCzW+H?O?Bm!m) zE?upMftGhoiLOSFYIFrPb^JF+7U)~1iB#pkzSR!>-O>DgL-S!Rb+pdSXW$0`py`~q z?F*IwHLQFD$9h{pA^jZZ>v*)ab_~v@B*W`hpWpB-nWS6$rF)nABh~wElBFzns%BD) z+PFqoRD;$9o`0&SZ61w)bR&S0JF54V_L67I0x^{?I$zPjQZzXQg*WW(+tVZmpHG@? z=msOlLzvx`A~}u??``O7xA%+kR$t2;6qniRc-PjmS%m&X^tN zO|(Le5u3j|b|pEGTrXsZZ?g~Fk=)}!YliMQff8Tw(D9S=$(PkQAIGm_hMBf?Zjnl? z8V;KYoZ}VF7SX)~jE@mPD@eA)r0o{b28zuQc;sj1iO2M3U$R%PULn7betA8UtHGd_ z_591&&TK=}k?oX(K=?-QXJ5|4r5IKbE;n6aP zax?gIGZ-s7`C>AN5}O=O-l}DTKc~9KmOG+CIh?OshWybPwMH>DS)Rb^d<0_h{#2ID z0~xvv??#-O$hwFt45iLR~jRG<$Way{&CQ%7Ft=9>Z+)s>~CeKw@3&)k~_L zXMS>Q3Ot2?&q;BuqraB@_BIgppx{#3e%buc-o+%$78}X)yo2fl-e1DUcJ0o>HaSm++%WHtrpH7d zu1l18PtwU!o0)SWvl#NM>6Tob5q{UPZ&vaSo8!=2yc^D#vXs*7Dt^p1`cqw=A4$u} z$z_RpHy)9;N0Y^yGQ5k2i==j6c}_CX+*4ovsjYUAr1KI5qjQ8~_ry^#Spe64XL?Xc zd~;x?(pN|-J@s(1+89Cf@;lzCDG?D-vWP$BCp)&EPS^Cj+SbIXGOk`JA`kG_99u@r{g~kB7 zhALT`%OS~{d3L#a`gx?de81}*(!O%?4C{L?LvpQSS{4n%``_%VaHh>(3I+CeRUq@9-!xWW zw??WU5rNhHH>_Bf5GE=>{Q8U6TskZAd%|f&fdL(1$#`&ZS9?4{x6fXX4W^4DNN>E2mk_(yMG(DO zql4ltCd`4Ag?NPKk&bFDneLpU%9MHWx5zK+%|7BxmeFo)Cx^g2$!tX@Ot!_;QOr2xsi-Y2EjYh|&ajvEi^7Xmnc8e^dEQ zSSo*sHGlEDa}6qp+X;A}Gg@O3Zznd~MC#J1u|YxJ$}bQ@$`BdlG4y02Os?Hc|INa- z-}Kvs;wz0iNP|#Oiz?Cw@81s|k*ty4D+R#$vlhMr-37ooa^g5WSnW7Y;?D$kS7xj~ z8Qw&za6Bc?zc-l|UBv5%CtI-YQ|6OdV>t-Ub~j)U5p5fWMZfPHSgsY6!LW_;HZ}O> zyYu=rTBGig>)f1yFpeX|`uK|o;v9D2?}gLG#d9fbZb*G!{+j1MPF&?7@Z9pn|BwTJ z`5}lm{0eZI#pHu>tybku+ow~%xd5{M!#%E#=a#t6jHrYcqEU$B?gu!uN|xVmo`GD% z7ZmV3=b02mfVN1DVz{jKrbH2Rrv-_(c>$ZZAQ>OvAcG-ElAT`g|sd`kg zJD$v$t8<^4`qrC!iVz!{{LQR%cbfWYH$uB%CN{}wGLM9UbNPnP&pO_zoF2TTO|8E3 z)4!JMh2St@1aH^2e8I!nkorPu#>oNcsg2q+`N4!$Y-LUiXh& zkU$4-$2z5S8U(+`bL-@ihu8YZq=ob1usZk<^^4iG)--G#&7){8rY0r>XQ!)syT)EG z$7@}!Sw_&^V+$LzGnM&R^xbM#U!x%#ozrtwm4 zb&Z=xbg-yikgECOaqU>q4oO&R?#JchBjPo}0A}RO*BH)e%X?k&{;t~5|A_@F07tO$ zix7bPSpfu20cLcyMz1#guxm*~Rj zr0FRlXhva4u%2Yd6>9z}BDI~u3Tw~-L%KM*0)FOr&KvvuXgfBD!SJ&%JQgL7JL8Md zjll*XHhsCqW57RMoX?Py*|7Z7#M-(4vm)|X4Wv%cfvhfrMJoY;#=O86Pt&g`jIdI%xqYrB9FVlRTYxHktp$Hd1(e+A02uZAN|PS+&n% z897j)oF~6h?S8-u+lbLeJ|PXa3NJ!z51*+ny3|s?ygdE?gNdlp{Uyw@}Wng5V+sn z?vfW%=REh)(3*3A6&?H3N8hpBNgBWW9^?7{m4}mo3ci9ywC;uzEiMcY4BUR4%xnF! zMMYK>fYy--Tm-pWS_pvlJi+uRDknCZN}q9Gn1m+2;cV zV<8Ih^NWk`yS8{7n-MR{ZIf*30{!WF438-Q<;?Of4e8f#&kG$N`?b|qwds7gdvYb6 z#0N8xQVR_h^NvS^`c(I*KiS|4+vsAJP;BUY@TGsDzIM(l98}o#9=Hz8uy_myLvcYK zuKf!;dP)|_zh3TN^F3k)6`S8!G~EqAl|!{D8FEbf{s}vQ3aUY8ymicboA&5gB+I9Z zYo$bu5dwe?n)M zn9vhK)hyNgTmD)Xcoa=B!$vGo6L1|_J**u(KAjo z@OjmMlmE;vnUnImMS1Kgrr?lazwqkjA@}i{gN-w8?^2a_b8Fq6`JTR+kNx#SXLEQi z50jxR{&OVWY8qdCpMK(Zi2eC7We!f#UN@<9wB}MY^a_t@)|&66-Lst{b*Uk4xk1>p zaig?B|E%lcs9`n%|Aq4PT*^;Br!$d0AEFx~}Su+nhQC*U3li|{kd0(MXBRvH)?~CLs*OfH0YlF8zg^#?T)O(K9=MI1^S++ylNKtOsp`WS9AV1^i*kJf zw6(hMTc<0v3&=@B&9AymPzuK*m?iW}xZ^?F^0)8)oyr(CtpskfqjoT(_T6z9=aXAz z{Y@+ezcHTcZ`J-!k!gzdDpvJsbLI`cf^@Ye9ZKJNG9Y=?IX#9hh=- zDV~WA2~&xv!7)k;tImIeR)@8%87MGm;g20FL3H8V^QtX52MGF`3E&Dn_zFE_*#0k! zARY1uJ`vT$u!*w}=jQT;i3S|f>!>n_gE9rqPXucgjh>0_wkYyQ)8q4XhXxiJ^8tWx z=8+7u$cQ7>z9IUX<;M-^i+%O{yXhLN(1yp{Zs}{ebhSGz_uQn1^$MO>THC>~ZV&ik ziCVr`v<$gp8M4S=@}1ZnP!9gePk!Z5^V%R8rmz+fB>Nlw!5A1G;z1?>9T0u0R~0dMqJFSdb(qn-RQoS8D!%2I+e_K?**=Ka+@ z%ruF$P??!n6tG2G?}zYT})9KGg#^k;HjUZoHYT*eQFFs=0W-K zadQ+j78WEnnQQBFDpp=+j?14ygdI+YdET5q*8QRxXvgc3!7ZPOAm0V84oROa`6kc$ z-+b*B(xx6rB7BReWMLTXugx-w3_wPJ60v;ig^-seXE}(T^>6onLIc?)&^i#zKDmc~ zFhTm93vVbbEeTNP;+09UtbF-U-uJxiE!Ecz^g%uK&br-@pgEivXeabm%HnNv6hp|Q zIpr(6$xZFVKMVf#b;+=Fp1Xi=^|y=)5c;5yrNBbQ?iL7t-RSQV`W!Uy?!41)Iv6KV zCoWdkQYQb%60P3n6-&{GJ1ds*R_sxZ0W!Z^3~vqlM}lEAmznuz<_w|c3`}B;0k3xh zlD-+=>;V0~A5Y+tP-;2* znrPuczhEar|sTp#9O}{jv_=uf9VA0_|ooC*c2HM?eGWxN5pL)$Iv&k$JmsgN2~mGM4}Z zPiG-YN|GPP2%DFRR5B@omDeIWtMo`%hXvA#SD7Bh8{G;4XT6&k&__lOo#|9d_UEZFR{JA$slA$CwyItj z2jJ!`wy7JrTW#iGnD?Z*2}TPdDWDCPpc_yGpg@zGHf5u)r6xxxF5y8 zYae{LF-n#XcsU6ShBwluf1wXOShMpGt=RvDac|t#W*oqjAtn`{C=+L=MRP5|eJB?~ zv`<4SIgd;PO`js-RUxOuvAqhc`?ikgl^OU9R{wvl$j4nfv%!*j$C$Ky>oL0b{QlRc zxihP0LaLeGJgtpo=Q*SCqojoq5;|@(XX$s)x{QxDrii|Xi|=p1NTLAFK@KaTT5|(^ zHW*c68HjtV^LqDwd!Aph(7^z9D#IMGZ9Tu29?S+N|Lu1bX9c_q+(x*&pl}fa`po37 zRVYM>LmyZM^$20&y?myOi-`N--V#)rn=D3bSMbpnq$cdOaD$wC8)lmWmt;kmSdnyS zw{wC=!lh~3GelR?-~GZhWYYB*=E;3z^M^61zfaqISa#;FHDAGJ;5NqdsZ4pPL3O6p z*6Z5R`&8zQ>wXJC>_S8r1A~|tedCc7ug6zvt@_lVk5p^Xn=N(o`;!Nm`2GLI(U+QGsm(SlGIl|X>Qpx9{G7NG-8%+%}2-l z-{Tg545P~!;R+z$upZ{y3Ak&0?Tm^&3sNMwGAUm+#shGA+8=(PR(kY-0gd|34nv|k zqfeAWt0~E(5o+q_2xFlA_p!z$f?+Au(?hi6794Vkhxk&&vwXkM7gU#nndgvLH*Qyi z>WT|nVM}QDTH-skCJSqjl3W;Q9ZqI^mD^`Ef22lOv~-)Fq$@J!`Aa_2_=1zqi%Uzd zSZDS?XJa7K`|Kd64F+()gvZ5XmlUN>+!NnFE09KvRr+E zWGLITcYUO^1~8H7PQHI7Puf0jClhd_z3g1)KR;?4juDG9efz8#U15N9X7}wwN|XDAsG*Gz1)l(~n$eV~A>y!1 z1~}|s)8autVi+VSpN^is8Md*|uu)DfWfJ?i`m=leATM_nWZCXOb$*dT2fEouQ0LOy zfYt)7%Bv(tTlY=*Jj8bi`q|rMghilzQEop)xL8&_Sz#a3rV#gCV3^3z1MYgdn#S-N zD4#LNQm-&fKxwNFjs6e15a5hv2}W>0$jDtE`S#sNEt+cK%@J!!`b%d5`_^)aMz@*F_U_SLH9>jANysIO$Ty;vk~d88`l#W1RW&KwY&Jo*r43N2 z!sEUnkZm>C;bd&cQh!z@Fzp71N+$+-L_C7|QMLiz{(BIrWdoJ}2mciI?&BX~-3(f{ z3e8`LGspgPUybBkcAIvxv0+I(Iq%-p)E~-HmMzjUj0Lx6q$~2lw!pKXXE-Dz5o-y= zt?jLV?l$Xq-`awkSv?1*zM)}ZYbgjOEPH2>T2e;hP<^A`kG^Mg06Er@N(T{0wysEk z>d%c%R|*tHto0tiq)=7mFZ!2>1M?yi2bUOMPKX0bue@`@YAo4e)JGdBsc%a<5^p#@ zyz(GTG(saK-BLrWrHWyDQGROw!%as};P+dipDtCQsyw|LCnO=!AJy--Z1py38U96ovkx#ObDs5*X zAL89#mze`lx%F5d5Vl_22Tw>zznL0OP zAbqWcekY~m3Omwn8XF@@sdEtry=T>#{us6!+lXIW3tE^6-$Q3xxqc$Q$+22fVrel; ztAA)VyP-V0!o?RiZP5m%;`|Zi!_;Jgs-g&aDpRNd7 zTzbGRJFLWO1p*V0})~*cj?hRKY`Nx)AuZ z$iltk*q_LTAc6SGT_>XG={1|hXQIRFx;K~Z0msi?&v{#4@=xv`KRdmiQM;OJD_ZGk z35uySdGy${?YcwAG^`MSrUHwq6xO&eqy)1{cO~wtOVH!XFnx1C8ayH4#|c3^_2TrH z=Q``^Z)d|@llevVVz$yM8av7hY;AR6zqHnsg8q!~zEiu(^XWOHYNNe|VJsbM`c`!_ zlAVL+h2Z7+&$J)@tbWMQn$4o@cu?O!Z=D}>VQN1(h`9b{);&%@FUCT_bWqC#lc+rB5DSxc&V4 zLlv-8%d4?C@b@|p&_AER1Hr0$z=Xgtek)a^VuAp!>-w;x9co|d-(cF53(tq`^5#{j z$A<(Q2UM!V*_`rRQK1{Gs^Z+HWI<<~y+OjBQI&M&TdjM&4aF$8<;0G7vlTYirUTh5 z!}cSmf%`J=LUkFlpAJXHBxNY&sT#;#>Bj&Bm{lX(X~Y@B*WL*hXxT#F*a5`HI2VN(e}+wCx@)_g`u!7IeDXY9U+OTKELl$gtXh zW~dyDPz?C0mi1j=M0RhFSiph$O4wId%iJGwi%GMmzNIc}b}%<8o<$rmj42{woKug87@ZY2_{`A zxOG(CjNmX@Ae%kfANL1=%fjCJ zODyhMuIGj0XzFTzQrL2L+z&sNXgGr!D*`6X+z&2-N=*0N@*<&mI_!h?=U5cf(R76U zkpvxFQ$w!jN4C?ouIP(psLpMx`SB$wHMeiyCgyvB8ciXTm3MYD|Am;}&nGJj$R-Br zpQ_FDj}{un$h;t(z$5Cgq6_q1SRfYha>=sL1!hi#cTY(I48*YEVREy+4OilQygF02 zyf?vbKRe9J=yn3*Yn<*cmr3#41pT%C0Qd=58ku!7jU_xv;ZS4#Rhq z;^Ojnu9jAL>{HMo8DCQi-GTEbc4%!dkP@$VZOt@N#WHJEF5^#BQJ{vWBp3bMjPSRc zewpd&?EI!CLoR+LUueES8#Zhwr*9mGQZ<*pJ+Be{VuI0}P`0pB=$_H(~k!deB?aef-Au1}bW) z`!77)lc=VIuc2;F_=t%qzG6U%*#C$bq{ZbVu(ncGVg=4U^*jBhWW&*<1WO@ezZrDJ=sWM^FU&6dN~k`d~{nOWY)x31aj&1v8u`H)}4#c z!;O+vnD&+-P|Gdw`5Uy>MiNg<_r|&M+e4z~ilOa`qa?_Lr2Q@k@P6Q#Yt(k412ZFgZKntiLBpzfZjK6wx8sDiozR@x z2CIbJx0+*;_?Nn3ncs!#0$-i4-#`k+L~;v+V2hpH61%=A^HB;G1)Z7FHuZ^YirYR% zKeDwO{Tj#}GbBQGmqrV6p0q({786|eP{3e`*!5a}3asxm6HL76tO$mrzaE{YvqyGl4JWH3?ptfeP z%v*hL?weJZA?|&ClCC?F>)`Cp|KPp?5snb1a*9u>_jHjAW;osZtz|EKD)zJ@=4fp` zmk6BWq@B+}sE3$PS{(1s(&)loKjl6PuN72r0HT5SJJF7(2!TyY9h~X@{u5;a=AI+# zBbMKH>| zcQNY3YC$6En8vR|IYpH9I_2zecfsa9)tWnlo4nZhW|>nV@CRYUhWCi3PKHg(qhaM;@1r-HFoVO2#!p^jB{x1ypvqG zjn(?~RT%%A&(NJ-Qd`N*+B9KDlPqYBSyx<0QeNI*fEJHI_9F@&%W<5=-~g+UyzYM5 zmp$DdWzw15rcjVjmimXXL4+h;?N94>4Szw(+k8-h$O={=^g;_j9D_$YBu( zN1Yi)jHbW205i2K22}OepSOR8e7-ze$o!<%Ya97LyvG~iMDq?#;5N!mgZ;&Q+o8c|I2+Q7af=xoWNU>Os#)) zy{u)p&=yTWK&Dfh?$Ngld?`%$1f_oRLo~Ue0mwk`@E$)B6aK;_4F-2*ALBXsLz6wT&lz(M1SPWkV72(F&9odQ~m2ZuX zrl)1q)dC~|sSjMy?klIZzH7Xa@bRf1EQw{+!WzlbkaQIjtLauptlw`L!b1`fp8v6o zq(u}@K6M)tvrQK4*qC%NQz~xiRBUqc^Yg*M@D~xUzPNxI=6z=7^4Q|iWQBFL_v)iU zTYOes^{Z$=*3rGnh!)tN9H)N<-Amq_Pp5_sQi^z+fPQj&E~(Gummm};i^dZcx2HSj z%S3P44QKN!wg0D%(*cfsKNWWPjp$)iZiyRIZql_ZT1-wkDcmQbSNj$hL355MNb{jY zs<=u`0=1!xuEl@s#H#1qaHtd#`ZJz&oEJ59JJx^Xo^_O_}Tg~ zywG3ohwp#|_Mxw&FPR?5+TdV&!Uq3`&^;d>xb3Fj!Eg~drb3aHS@Zo7!T@%okqDdF zVp=eALSR;8TriMbD0ZLCI~+=3Q1M|reJVlf;OYv42HIhqv(C{$^oSH+%#E=zC1)7h z(X2ZTOT@M$$PrKho!pJu54SsC$+#0e;6b}@p$;KOnttzj);L8kAJ@7A9!FpBW(;0D zFmP?ID6Q~ay!X$h{E4z&D?VCUiS6kIr)9KODjt12!1et)14PlnXoRiYuIrsM{fj!) zi`XoYMC^8h3uc&|(gJMHplU^6kV3hSkJ!oC*&>iiX7PR5zYzxTIl$Dkcz$FU&ddx# zf(B9IU$$vEgrC^hGL%(LhRG`(t&;ZAvx*Go8Gp$f^<~jo#HwoFS}DgsZ=j_Pm64pY z&v`HZiBDg$Vo0s)PBb7dNsg)rO=`vMlj%Nh)LZsGxOoW@C-Pq1<2?HIyMU3BWezw6IOwLDY?K5zU5ZlBN zIss!pSoxIpY&Pz+MRhL?w5fLM@!7}O0{J2ZNctYvw}=)YbdjzX>eOkv`&2O69&Zjx zu2ukfvZo90|1{LT0}8#J0g_G{h>iggz!K0hdRW>aV~PTrnPA?WfNuJfmOat7Ud{{q zLCr#Wy^CPUY9#yb9r2bCV8V#x1zU{Sb{MI45SEMXl+(`j%p%uujEi4BmYIi_#h)n|Kz3=S80{9)t0U=R2mYbvwGQSet))Vk%9Xz&AWt zsddr>%SQ(9bL$wu4246p4g7)E0hvg(8YReMI6=oM%E(oVUg1yh+tBXPA~_FWEWPym zxuuxg`h;B46<-|njPzgf{12qs_pKl!+w)KJOU$$Y!;@5U)fua6Ye;zA-@+eVVa!aA z(%jHJL>>Ap6Z9kq4yneyK2Xs~k7#V%e%I}vDu@8oA|qbIVpcU^+Wo$Op=p0lMXOOV z;{bsHyZc6H6cKyYwforf%y^i_W7cnjRi_b*m(ebN5ozL693(*ph~a?0|B?fypIS`5=}oZ4J zO&posKy!xjo&}^r1RfUxD?RUmoGtoEUCrP+@WFsd7MbVd5n#sr2oNF8?5AAYIvAaq=Pl=A%> zOsTWMZ&%*VRf2sZHANu;T+(^;o*y7PpM)t;wspaA{VT|+H7yZ-bjpXEL0*6NkR`eG zF1h4Wk43`|JNvj}s?*Zw7pVNz)FkaO4o}jPT2id32YMMi0mTl~$sHwPS1_7goSkp9 zG<~3XZ&K!v0y}4?#@De|NiTpZyR1W&<^1&2xT6r7t8@%d(fx^srjp1rECO2B!{k8+M0#`xPbmmkwmQ*d4Lbt7{ZVRgxVZ&ZBOp z^M7+cU}-%dj;P(=;JKAjjBt*_6l92di>!`#ZH4*+$j?{0VX5dUVKw=kXCSkaL##-P zWpZ1M6yv}htK6DW1(S{Q7KFfMI#{2bJ~VZX9(!p%O%XW)@y6M*2!28WOF>ohH-ndLrm)KV)h*vW4 zAutCAYrqPDVK->RM8%rvWO#T8V5;YGKr3L8VN-C43ZTb1j6#mVBn#^31){OU3hRZr z>Jk$Tn9@@F<==~eWPoECqQU|jJ3?IqcI$vC!Q1z*E@u#aM*Hr28b1i?wuMP*=)Htz zKlyie7U8;#KVH-d2s=>PzsE=W<#a%6&uga`mfq+$0nARti2Ce!<37spzn~`fuWNE2 zY!1PpTI4!R0JED2>*4-~*9SU^-DEJ1Vn8h7_Dr3{$JFGiq&xKT0z2OYozVndHC5zk z^`>s^6EMGguybqWE^9})go@^*eq!Fshq8ZfF?W%|d#lQW zfxBivp-zUErKqlMfWN=LFY$w`Yf@`ECj@=;ABeEkrrC|BhK;Fw%ktwA(}kAiYE3-5%gwbu$4i5$Y)L$Do&){z{mH ztR>uJ=KjbNR|OhF=gR(UwhF0z=;t5AI)x@;TJ%~ zHwOBQ(gipKlrD?0$@Q-8vM4Zl#%g4o{ZE73K_C3N=(@^el0P4%LkMA?IVu3{;B(jS zEDT0Fz|L43!Kzv9yZ#yb^J~Y*VVh{0PiJwH84LlR!QT~PXoieo5k^RU0P;}K=DnZ= zJ5$f7_jkMoK9DwouK}V|q`zMs01rMxd%2m8iU1YTzKit={t-+swI9_3Ub1X%j6ZGS z1Sj#|1^-P@(ZFX+kkTMpaD$9q2}q#{1cKwz&CUg0l1im->|zJtH2=Q1{zuSlJa0mS4QRzVPy}!5Q78nlg z9XMIef-d6MkC9F-t0a!{cqfA|&33Rl1)Ym;y~06X=AmBe?Abi@WkL?dX-^W`l#ctlhjYDhp6-EGv`ZRFqoh48~a+rB4iCGL(#RXj$=p$Bh@ zG=t7wUwk=v`+iTuMbZCh@7trAy0-NNK@n8&foSDrRnUTF4EApm-6ec+qy9pM?$Jbl+fRuq8!b zp!wYn0x#hY!$BW9KvHz$!zj06;b% z@FL%BqYY8&b5yU_qWJ!px8f)CHN@HauCg1F4H` z3a}hg;nU2pQ18}b{D&S0ar^)$$yxZ#@W_qmU98M|5$k6Xclui|6^JN@w>Zl(BDdZV zt`jIdofe)UXh`1)7>B^fbt%$TQYX$_{B z%EXA9_+&RMh%%y{43H4P@@sGEI9tpDT^z&RumJ}xZIB=2SZHl6n2qcQkD1q7unEcX zpZUZ?InxbGt#r+-vY)XzUL^I+4@+0b;KJ^Zn-G1!O{H-@6R&H4KKV3;+id0Li1zysx z45*DmLvQttZ?~R{wiWkfrmJ%O%epQ|m7|G5(Rh%B8 z^dRjx%8z!uzPL2{FQ$L#$Z=Hd)#b(&1Bwtf6+AuaY|=B)lM1glA4hxAAY;VC>QthI zt0FMo?~J@V07h4N#(eR$YYGr(?UxTi-xgx3_Xp2*y-apaJLP6h#=2;_yd`!>1tqZUbG_X$Va~FN_{cV%9LgY6BuOuuV7LF1#R8^8XRQ^hm z6TgFrf)zL0D`If}?6=@NR}Jrd!AdcpZo1>*5jTbCWF~4Nqzouu_$W)_twyhliW#eD z_)5Aych(g=k+%(h+9XTf)6c&0Pns%f*_fI9F~>4wcRz z-Z0tsBUwfl6Byi4F{QMq*@B%EMq@t4t!i4L#LBih---&Cyi1jSTPEL8s4SQ~A>-U7T zQ~fE=QbzxYB7W1r1Fu8Q)iZqrYIOz^ehvlU6p1 zMkE%(k`U=Bai|>|gSvFm68DZor{3DamXB9 z4#!!aMM4f$IfIsMP@NboiEAXqBPo~3ykP>-DA zTtenm9oFa8`u)D2R?5Z7e#6MHz9qM>i<)K!(mZhoICoJ^$^njddALkK%Rkx8-YFDG zMwatJNhh02P?Wac;KvhD?Bn36r&#H#P9`wJ`-HyK1%>r{nkpo9$svwZWx--aPjZix zi|NbbaRiZ;(1Kg7*91;;@~ES~mA9-PxhSKPilpr-3wcStKL@-Ihj|&*_dult&zs`- z`r=D=O0wiPk)IpxD_~|h%m;` zDip)i?ymBxr`&?-11kmZCQ1J_j_mB0V2Tb7vGm#$bW``zB6KrpKnchdE2dLW61t2- zl{I@Q{E(NrijLN{d56DLwH!m;&n-QbKHXh3y0#uBaA4EytEb0`>~j6_jn#;^ZcSD*vS+et2G9wpibR#qrp?GG;T zFuDL@A!lj*KiIKNeGjeyfnTMBawKtE0DJ~jCZdHq_mUIXMzdYZpkWWVJ_8SmWk=MQ zH`-)%t186BjqKg|(Jv|xA%*Qfdze4Vqf6N3B@BfKOCcdf1^OUT@xfaGYLDL+RO`x& z&9WjyI08ArD^C-EN0k}TbR)qRFN!x}r}NOS+xhVI2w)EQfGnF``-8r4qZHO0CehI> z|InEvhyrwUVX+;Hg?AFIT&0&=>tVbK|H1Q)#kQ_}7pLy6w!E?Vk0XJKcNi%b%Zz0K znVrq9*{W{FG)nsG970kq;GVomrPMjlLT{(TF?Fjrc{C9l!$VO@yTfQDa7kMciowO8 z`U81q>Q?cU0g_sR%gFVf+lm`{_1jxA+JcI7)*|B=GSQnA?X6$ewcZ5X-xwsUb#@?da(k(?RRRKyn1#FeiC8#lIfrWf0i z(9hdy#1tN0xYO2)@B4#IQ?ozTUse;6chWZ?>KJXLE8VK^XH3hX#PaY(kZKs?j`vG5 zck1?ZF0M2hSvzuE5|RWjjUA~A%<^-c(Lqqa2y4G(1^yA0yJSrCUsqZSnljRTz>Wh z7A|8nOIlonkQ9_N)8tPFY7l)FCBFwFoCj|#_}KdJAsx5o%t@W;8Q8~HC3L(jJXXhc z_S$%lKALu9!K;)+!sBH>Av2!75tk(u}bg`W9@0?o_{d@X_kkj96uFWUd-*rd)EQo_I8e zpcLHZfTL6HN{=i#ydb3tCj`#6%o~4w_#pus`e*i5HkyN?aC@<@!{|dzDAm;2`+9j- zWRJk*v6Z&wgcy*4VF!~_@CsCT2&4Z#W8-s9>-S?zD;cKaMxk891%6n!#(obvrJKU= zIosb@V};;n%)-eZd&@V=>V3RUPPaVQ{+DFvVWSy%!2t@Sda0tEK`@QH^OmTS*_qxV z#xrs3`*;!mE@6uE*ia47cGd!nbF`z^gz3~X*x}huh<)cHyv7^NO^lH*K@6-FURatO zI^Fy<5-0DlLgePgioP_8QFI5AWVDM2Nid-a&=7SNsgjG~l&nPzW=rIJ1mOyHFybSQ zmS0&5sB=Dkf4|ZYR~pFc5UNNV569yuCE+T`AyOsS%#?s9byF-bE!il>quHqbqAF#l z(eHkgJZ=;}bFp&h1z|J?Q)7X3=?P-=UShPoM8CfH&lu$&8Dm3XosT1Po}|&2O)|8f zmiIn!#1|+;Cv!@=^BJz)1`_{eM8)3UPl#ihX>4d1+em^V?}dZzeeWq;fflBTYQKb7 z3qvsaf6g!VtQ@?9sa>909FkW_-KnhfCmi<+s#`?~m01D69vTI#mgZX#-uVQ}s=UAo z@Lr+^+YJq<>7D!N^CwBTx?304c6t+JvYdL=XueRw2`3G8U?M8P;}c6Qux$mxih%}H zsz2tW_x{R?OH#?zaZrm^SqmB@F&U5>JpSY455y#}<4Z~uzZh3~jj@4S(om33$L~N- zzI{T=XnUYSE;0F&RcHcORiQ=()FQZ5&eDkpPHdTc1ZaK7D;#*0_vhsKfc|kmBrDTL zclo2STma$7dW#7nP3RinU;#R}Fy`I=NGy{k66$U>2l&;Y%$m1<(>3s$_aRxrbHf3d ze+zHx0uyvF&h_I|e{R&s8W0Src_e-JcY`%}S_+&k&OpS*zr|!D=+N1+(%1HL9gT?^ zR0?LjH7mJs&S!={ej}>@m`z_VeItN0dR~h(3emckppqp7;*#OgP(sAZ@&pp0H=#N2 zV5^ej$iM`I1V;U}TZmFAgaZePl&=~Qz0-w{2>rGL2V{NTv4uiK8^0l>el(FFdGLs{ z6UP1KoDjo7H7mtD6}O#lC2zkBd)X4u_dK;eM98#?Ma$~3SzqU`>$Xz#+Ob6bLWQMvHppUg@j28znv zuj(~(pqA15W`(CUvnh-YLh+F#I1t%o$Cwe0j~ndp0En6vhk)d40r3;p!LJRdh*83N8y?FP zt!muL8e(kzjA?fQzA0B?ASEHr(bw~L!~Su09@^@+WrEq|>$1jI`H$MM8V(pBy43Xs zB*gI@NYHxX!R>CoEQ>SVE}O!h&Cf>W<&)s@t7wNR1c$gnPZ{Gv;vw zEaXSFbJY9Q=kJHRd_G#AyF~hU?PqMRdaen&=4z=i)bTHXF+jVXD+GqrO`?mzpW%cb zms<;xmZPkoj<yWJm$o8|ygYd2M z_2O8lV{8BSz`JXKhvr5LyjJ5u@JUNGTB^~})pERcaWyc}F0NXy21L`f?j-QHweF8?7X~d6O9pcgbSQR` zRLXN-6%ML#Fhk$@*2^-CxZ!irzWD+0d2FHsl7pomL0e5v`bPkxC7af8?fuHWCr&vqe^ ztW~R*d5j-fk8gcH`9Sst5k6))E<{6;PrB1H1nE5b-*;Y^EbXV)7z~252+0O)_|A{< z1dUKh98w4LSM`(m70rKr{DtTW;$p6RQSN6#CLcqID?p%S!NRLc=YBFAjjmZaAb7@a zqpzDF>c>Xj->VPe7`mIzZ2nsiM(3NLWf?RI$do}!b!+6$9pSegwvvW7OI?d*_ih`I z71+8K#I_GM1}ldBNn(&%5+*(;;}Cv%_=7?k9`4fjI4`!sMN2XFz=m{?Yy> zkx}dq&Vh|_(qOo(RVZgFj-}fC958wV*VDQ;KS1$dDdY7YOZB*mtU8woEc+WBhp*(g z^sNeCfDVqqCymFl$HQo=D?#9*vfKi~GH4nY=%R)0?FR8-Qyio2k<(qKa5RbDLCQZFx4m9-Yk;oI!&@KRL-2Jd^C_XHYa1`qXyA`}jW0sN0 zz^;>hqzzD0?Y60xc)$)sQ}q88eA*XNYo{87ISQuf%u6+*UK}nRPu3b&{T0CYuA8TC zf+iEW2g$l@*p+97j#MlKNoI54A)1C14YV1TLB*<@LX;nr&o-c*oxVcQl$n{LsS%xk z05*s)5YEJ-Iy}}+OXO*s8_XcB>>z9BV~VDAA-99^b+(wRr}7pU`<~TUIyt@Ds@0!$ zS+L(z(@<{%L+$vBz7~RRxc1F!ERvP$j07O{WMpXQgS7{eRUbjIgDzfXGz?yiFeRR2 zM0Klr{3br^%gWCX$G2dTme+K#ApA{0n#}F^@@{?ZLDe6k_^{2)1DYyo31-+bN0bRc zSLN+s#+Vu(#?>*To(<-AYU;xVFvKL9KXkG6{wf$cWx7dQ0Be@6je{9_ULQ)66L`YjrEL(_P})CGlY7IBMjG(q)!#5D5>iokXQM4PZ8Bs_h zFMd{ZU1JK!9$VFc*^XUllg)ZK>5x|&!qZnHKgF2a;tu1vk{1vU*YO=FJzTyP5~UuFx-pl3~6s1 z>7WCCI$)ov^U>W64Yiv3e+JN+IhF?Dj4Z5jXJpH+s7794YEvt(#f?q(ow7SdPvdsG4@B9q&$h=}Lx}A$0jE@v--1)GhGT2ImkS*3-erENaf`qWP}`wD zU#gc-OB-;y*mVcG&*4(kS8muf>tYvZqHhc)*Vspr1c?Y%&2pg2SKRcIRtl!|+JA;T zfo=-V^aQAlH)a#o2~4eXdgT76J~OD7?!7GnjZBg%8c2>yE5t&+1~CzY`HP}ff}^dB zy2DxDvix`KByG_&_yl0^kFL>|Led&gw}^oH9Nk4cVo23-@zk6zDo_WSIW1MqS3Fi` zJs|Xku7e8(_QZ=0pBlA?6l;Q1L`yKkmUny93t#&o=qxe7&<*RvFHFmsi#GFV4Awk# z8wB7;Rv#0qb8-PhppONM_Oz#g)sp!S%^n;8ML5)m?m*H4n-3lU99py?^@+>RWLnxy z*Grlw;0#-fdOZECO5&U&Pikp#ypSU=V0)$B)R zz_`5sB?gNB4>L4*2DQYI2nY!OFA>s6=?mKQg-`VX`0D?c(igN|(4@%)2h`edv^E?)$t%!q#Qq1u(Kx$}*eO%y4{qP= zw&#-rBeFK3Q=8EFi9To#=(Pv*6AzSibhQWc+MM!FC?ZaqQ?AV^pP&!_#*{^EnxZ_5rw!po3m*rEm_oVCl zvImyI3iM*EpSo;hLGSr6^Qy9dY-io?I}EudJav-%ryMecn4)XQO)1!*u65X}b6)gS zOM@L6JhhtUj(xUPvreh^R-C)^$zSlXI;9RV_#PH#$fdQGYt|`|=j;+ViAvQ~Cid+{ z-1Tu0ba$-Y%odRG^oJ{Cp{Yo+mz9{`R)Oe8TE`(6j*A9 zHiH*wHtz@o4&1?A`=K<+RXKYFT0HGn7Ck+)P80Vpbk2u$gsE%W9_v=JE>B(9Y=`!! zI(;yE@oPWLO0v`cKxX5~hsn4(#z+5QVKhohlM zP~*h!kl8fD(g8zm6QMPa-}anP)4JE1q9 zdYP6B0c>J4><*h9bTFS~q4Ox>eAtC>%_79A?Z6yrTg=s%-H&s}nuhXCsky2`|7@Dz zhGyNeOQ1j3<*rC=b&cMsFrB7L<5vuOEmx2iAFA0b}-ChMkMPh z8%C4$I;B@we1(kRE@kHPlq%Qo%?_GHp~FXY2|5I`Umt8;vNL81_}jk4Yjd7^Q2hS` DTZt-j literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_current_pos.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_current_pos.png new file mode 100644 index 0000000000000000000000000000000000000000..bcc1298670ebadd57fefbaa361b61e96f04eb964 GIT binary patch literal 119341 zcmeFZ2_Tef`#;{IQ%?K72rZ{o*0Co0mKc&{LWsfG$1)6KOPfliT_sDYoEB7y8e0om zglVHN6k*Dike&Z^KQqcQ=bU=a`M&S_d;guKW_#}Yy07JPt{rVq#2m<8lw~;eWfBtB?(QPCj@BekYgaE3H#-V^1mC-oZ5{0$?QGef z7MC>=lU;^W5tD#Fq+~@T#U#zxzqcmYxp5Z6lWC4FF4oH=G^IquV5yax#l@H5RN}+%#VP8!toQw!g8eO8Z-UzR|OhOG_yEr=A!CzW- zL}xO(M9smI>apLSxY{;Ir zcAo5yfE3`2#xgM#_$m4ir^aC|ym7Mzvau_dY2cR0;+Dy&a9*gYVJ{?>smgK|b>uMK zfk^NsXyDzPBnhfsb|f8=ois3Z=pF+*x%z5(TDv>o$+mVbu$`?hdo!GbEJhZ5;>RIe zObjQ>CZ6OuuoGuv^nsxxZQzKUD@optwsu~etJzml$Yd9aqx;YgiDWl7J0eF9I4fFv zdXlL_e`Zg1;hc~28+TBjA*-Vg3`ejUeM)e&r8uyED=Q(xrUiYz-p-NaFtD?@v>f{z zSL=Zvb57#rU~NmLvaiQJ8Z0d~CkOcHNhZU3gM>Nw>wzD+`l{KvAa)P%k+Tn|;*VeZ zl^dR4jp^?!2l|ScfwhbGfa0-rnBq5}!@v$q%N<=Y38;d}P#l5py4E&!E*r^Sjuf^5 z*^ns|vMX4z3;IIUn&?dOBzwErs*zpDNcU~+?5(|BfL&i#P;qf2A=9If-QiPfFL$Zj+yl1jR+)5$}hmX}ZGxUq90&h`ZZr znfTdgxlpV(8%X1gRAlT8IqSG_*5P*DW?Of&^_$50PO4Npb&A|Zbe{DtUS>v;vbqvq zDbpg7tO*8k+AbS>ObMH4+D?+Pu#>l$p{f+#Nz8H32_?~cJtvYk-iQQTarWJ4sO^h) zGVsRxX_M^KHGn&&lE4i~;D(cpmL?5x*i^!orfa0(s7w3vb>URLx=zj#aIF;H2<@va zrt1WJTu)-}qpsntZ)EDIt)=H>x>=95(QpHslZM(p8=ZW;tO-&sK$9P$Nsnd>G#aC8 z(R)cfLrJP0qR|M^sNtulCP{;RB+)+l>hN22kTUmm{mck@V%qCB`I!==XlAZ*el~E8 z?fMN4Hg1THO)fg>8j`Rctgj-b=O>B7J35nyu5x1R@0_VRhT0@+EfaS$2?sGm8=TP( z_QqKgHi=n-#^81Xao9G{Pc{R zLB9vnrXh(}bB47YT&xMUWLqRdL-bp1lC6Y`v#l0F2@RUAleRC?Wwwowya6$gJ|Y{D z(sd#sJs)Nx+L(MGv)AX7Z(vHm|PQySn7*f8LU0}+Rp z({|PKBKnB|tq_O+zHV?a#Tk$|mg#DP+du(?;Be8`!B)$d444Y1bC%Lp*OmYY`05y{ z`q|(%Vc+Q+skpH|zC)hG2R6M%o}THilwS^po_%gEiY>=%j(x5`$|b5yBu% z)`#!@7ImN(8aSZNPuI!R@1LYj&rwnW;osk(4rw%ATpQ3%*U3QaAEXX6RuT~UZ&HWT zbutzM>Od;m68|K1$anmS-f8)|gZ~Dd&_+5#1@sojbVMC{F9FB~-r=j~8T38oiF~=} z44?+4(L+`yQgxk($SyG-j5oqC1Zf}UEA?n9fW=5#Ilj^e;nQFGNlEZm5(u~KxKc|3 zo|>}vWNW+>>^BS-*nXXZSwCPsDxgiqC~891F&xJtR}9;z5EVfbHNrB6;~R!O zrhqlXZ+K<|F@!p3EgR3kcS+(9iVpK%TvsB22QWp^JsTN^u7o0W2`*?pu+n!#5qj#{ zAP*8`ex?YMaf5x0uF;Ri`^Ml+wFkHlaX&kb9CpqhiE&Vrr0xvV8AFU?EcH)P2lC}6 zg&(30;k*W-4(!ojNCfsbc_#@mj`&|k5#MhY2B1d}QE=irEP@)Tfj@F~s2J$c@Njkm zBy-w7C>a!eV*c)L=#3L(b4JF9Iykq=kofLzN(P}Lw>amAc&FiwrZ`43Wu#gAMt^hbDSgmexMbq9lg5)C9EE|%be$v;3D=!GQS zPz5STz(1PC;4GH%qxqPg5#Zjp3>%&H4>Rn+)h#_5XqGyv6k$FL2R@66P=sC0G6sYv zAq?Oe^$uPKqD-(G?6;WT8T1~jGU*NYq3?^z*%ctHT7{x;cAklPwFZ8*R*alIk++aIp=p*RHSLkNPb^&g`R{r;vrrGW2Pgz(SuOdC2lpeKJ%*M`&*{yDyBQ=vvd{hRW{@>q!4IJqH; zsj(b)n73lrIdmn6s7}i6X~8S#mvNeV(6F=Pbb7h853!H_yodR%lc{9~jdhBrA9OQ0 zD@w}B$%sIw8fzPJy2p~@GMuI)^;;`eTwFp@WT5HlFr*bLB_kpOJ$=-PwC1#dNnbZY zpMFoP6n?|$wEp>F(1gRVhAfAApa0P=sJkSJWUT+J8*1bXb|A<89jdEoiF?_&p&Gn{ znC*HMXd-+o(ttP~ zyq~%O6~6z`&MD}(3srZsDpc-C(zcs7c9T(9nmSUwAy#%OAF1x=#vy(7$x6z_XYtyu8c!DYPH->gnVI6m(CPoXpj|$gWZ&sy3|BsA% zsUvHn*qI0Q|1?ks87dH11;+bNa#%Gv?3BjnlM?%pW}x~jih5DC4P?Q= z5XhlNM!R@+Ukc-`sxx#|DD3Fg*$X-<-g*QQ1$??6ezPeBPe9SCwy&*|rnQZs80uw; z;SH%&Yc(#1va;kEv=`}`qa*!{Y}_2a+hGsqi7-(2!es9dqD|HP5iE~HIba$a@>TOS)oRjQ4I zi?{81utGGG0Fu);Q~~S4qnaEE+8k{Oj0a2_S-LRo3G}-a*@Kn-b;<6%A;&NaA zks9i>q{XF0WHJcIwb{czNY%AWT#2CWFocA;J!8(`&t?f1 zCs-dFzu`c)A8Is%(Lqy4n?!WOMh8&o8CrXTMh~1+2Ez@Epn!XZ>;4?lhqUd!Zyz*z zGst~lBR{YY0v?X*V!ILU1rD}5)PlyktC%kU54Z-ZFTlJMo z;M%^QCb&*T%0?ZvT+mp=CbSO#;UIdP3~;*G_fXDNw`$#7+N(5UrCY(^YzsouoeW~ z6%W6GmaLHhWyo(}tP;BpQLjNlK8L0!0fVG;{sT0wAkgpiv8l*1RXSR@n zfKPD(?1zC2@FP;}^&$O0gG!h$`ubaI;KHzS%Shikz(KYT$LJdB!;xQr7-W!t{WfTZ z1?lW^BD9?UjH^R26;9-gC6#Q{hms^`U>C`f-QIwd_7A8Z+}ap|_*is-a2cf;*bofz zN`8ORQrFURCqhaLOce zOAcfK12``u1NVh+5PdMvOX5T%B_ue|It1!*A~+e&=l>D7=Ty^v!u_zh{-5c=plSUd zN<)682kdm^XL^8Afd7}$15Yx=nsbkmu-w0^*d!$>DJ>$)sU{8h5u6lMm^jcp*pK`- zCJdZZ=g&L{(c9ApyZsa0yJ_cUtAcLhgZiEu*$r+cQ+1%g9a%Va^d)v981_@de=mwB z+4<{TdeGe&_-No(v1JlCF)>X|RnEGaaIYvV#QvSNCuP_^a3h?j-)7Daus5dYjffPi zi@jAxttxai`yG-7_RiOlf?XzpgQ}#e9lT{bxrHcy-b7<}1i$qKHPKY&zh^V!dk&6+o4289`?ab3=htw4 zjrDH->X##0yqsG7{{@@@^8FD)5nZgkyc~&uCSIUp6wc2Otg$hW8{iE^M{!UgHg5eb zgphuG;Nb?t9K5vLHwQm}1^+y(Nl8H?YxveuG9$PCZ^tz* z#~94PAH$wML^oiU)QAZcsX>zZv3)QY`me+|j;9-haeABwRd{{7ogYSl&^`Erf-`H* zZTLh8k5D`_;{JSBM_XI;GyqkqgCoVx(A^q~XsGZc3HWSiXg9pCYY%;1&a)yUWZ~D? zdk!%O2GRRLAgHM+CMKQ2i1HTv4MX$qf!GNQ5q*9BFo|MpjZnP z`v)4qgX1kpS&`xK&A)Y|Nu1-*2PuQrCJhZe2vQ884Wt53PC)_0AjSA5NF*3;q8_9( zgXM|@G(xTrvJaB$*JyrFF7|Jet0ZJy(ozFr6&og3Dcm>Q94yy?5Nohd2co0_X#e+0 zltcI+iEh$>koG?zPi}VlZ_KTwWd6)j|EOB~-zQN{^e{-GBdl`Z=_^D}vKNd-{*_%0 zvM)&#;lV?l2HW9RxeX0JISKo}2W4d?M1V95eZFF=wA|O6Y>*8~aWsCg2@ZVrpE1Gj z7!>{CItVwI9GU}w;ttLMM9`zP*g1hIDrJb^*ugz2gM2GkVDAuvzh3;EC5!*LNL^A+ z948|4b?QrQSV2HW{G0L(Xx0Bg%npy(f||!SDu!ABHzNM!=>6ZARu6Q=z6ZkofAs(< zcpT5qxq_c_1!!*J=Uf4Met`XOuK$|3f!H(YSAc|B{%Z5tY`Y& zw($1*)GNPe`{pIjFCTB!_^7;B-+VOw?&!r5ysLjZ9IL9T9Jq1%tZHGkbCVYH8qR;P z^-zkfa>&Y~+s3Y(kg`Gfx6O;s8Cxx$_1-{o)ka%d(k+1_%f;Wwb)UHv?A%+_cc!kg za+H5kMTTN~Wm3~E>TZSpo|eK;!7)4&rY&NOA4BHP2wc|{S<&-2D$^@Isxqc_%k%ML zI?F4Ady9i}q=UPu&gmhK#|tiuQR=%LKu(;xJd5<~+`O#9*HYylZhm+{?B6@SHDtT_ zZ_3+7jm8%J`a(=L#Cm(<+qdaq=$p?or%_r;-+bOXju}8D=!&pvGL&A-T=ezVoEI;J z7O{%znkZ<&$F!KF_FRmDI#qR`V zMnZAL2ekX4jmixC9*bs!?QS`-dqr2Umj6OsI7}jN+$%u4Ny3YKbU@`5aQ2E?HAX&_ zn)80UTX{E5VdNDVz}}2LJ+ynsPI#?azb||SMd%lNfSihq`0c6@yy7uiwuqJD6y>%X zoqa7YoIz1=yIW?O(DJ#ImhzYnyu-Q6^KtexN?jXuE!zFJS<@&pZ3qF!V$H=JD)V^h zd++gUjZiMeYLKCE9R-KZ&d^q7 z_18_W=&F&a>g#R_x6_Hp6+9s#+~4;!xzHqY&t#c0vEAew+LMCc#9pj_Ubp*bM$V%_=PYUX5 zQR>GD_}5?G{Q2z;kE#PQxd$q`OxAV2KYC?hYDG|Y&a;OCe4>FLbo`}q7bFR>mRI}C z8{9m>4yBw2z0VWEFB?#ve76J+7!Y&t;xEjk3U{>tw~sGFz$$l-D+4vZSJ`^W;2jZ*=l7ZC_4VGNLQ%0L{hH`xofT z5bri8qlWa+XW6mx4cRlRbRsP2W7^u1f&&-I+g%zp`{TeYz=rf*{w9Zot<@10b4XEs z_C0;=Sytkut@Cj<6}&T#JYCINZtXK+2Vs&8ELxHq0ErI?`{PAaKPFJ(~x(SiN z6_o3Ed%G#K`-!PlPvzW))f4Bm_S8j;W9BL?_+{jvfCH#k>D%gg2awuahEDL6HeJ74 z7kQZSb41oCRd>}V7oJGX>K5?NzLRW!;rzVMruyre)%Od^O9!=Gu{vH%%Mr4iPOuF0 z?rgX0oj}hx;%zZfpM$1NqjX#6H6BKrY(RbQ@n?Be+CRj{92A#tTG(IvOiSlcR&Qz6 z0Z|Jd)6P}JWkCV~pYF|5a@(?|_krM(Xa4*b$1%&Ir?t!&!6Zp&Kf6AceyWPPz6x*v z|0ks{!ekb+3L@oY>~&)-%WJLDD`z*~s!I%u$m*$9$Y`>(>`6>(+&6ZG-hNWF-}2p) z`Q}(;kGHE7mBzI^A7J4r+;fZTIx#%1k|a$DKC+iZDXv z=i|pKPQ;qaU79$OJ*|g9zFK)cS3sRu)X`RV&NR&gx)nYr#~i3jN=xKf_mLG>^+2$5 zedft4_@IszO7msPeTki9ec9&hj<=zTMx7bF^y5eAi$-!p5IXdMH(gTUOd&yYQS*Gv z$4T@;#cmfDB`2d>AMtf~eB|>2fDHfQ;*y~5hP?Kk{37#* zpWZ!43+jJDzFqV2N);>a;Oc(kq)Z=E2LJPY>8Fs!uu+loBDN5WPBC~?nIe49g=P<^ zrQW|VfyuR zpT)&>WR%9-Pnl4pal3r$j>(mYX-y*imet|0<`*tHkHq)ZNZ=!xkD7(}NJJ`JT|A#6 z8l|M9cUn3jJ5tPA^^7D@lW=GvIZHt=S`OEk)|8o8E^~5j6TL3cqyFV3ahvQtiRFFe z8DI9r^!LE3wayZgI@GUBzVXpMX7xCq`n8M0l1!pKpNe0n ze0V-PNq9-)`^QI##Y~^Nu9-KZrmVT&Y)r5;?Yrgj=EiJM;mjbvnpN?WSk5Q)W&1jA z*XLP@RLIx$v=CF7KIXLwJ}qNZQu&0FmW{ysMb|EGi>=#>U?C(E$ZE0hj#6p&GK|k9 z%vrOtS>%+wjL&Q9(1VA(YM<^sB@`&!vOLmdMks%fudX61Hd-Wh&%>NIwfU!SRi3Gw zdABwyxNohJhyS~AbF<}0F&3Fk?+x`<_3M_e4(4I5ma@QxsfMa!1^Bg~(%aoYnzGFR;`vc3b1KE8Y)14 zLJ*Ik-Wyjx*E=(TdSAW~XzHWtuSNnWEuPxN~v~27O{e!Cvm zIDM&RwsG;6>Iu zR8l*5>Jyu2#ru-XEDhHr9I|Fan8~f3E1r7Nt6ETn%D7p+emH$_###XO!oB<$>3Go1 z$QyebYaN^zQC^Rid3=6)s(SK)1qy3x@?$D`^OyN*O^<%qn5@69^?tExl0fu0CXbFg z&v5huEmwg!W5>=GX+-@aeZW65DQ|_F6N5jsP|+aZf=9F0E2-k_M~9d4g$2AiPRIpa zFf5?Heg9b8?&HhZ$-mMMSVZ0%qQh*`cgEH&9?Z^}I~tEH)3J#VCvJF|ueEA>AMgiEzluc>NCL+MKxLR3(+`F%`(J*m08J)M*jfG}fLFfXw06gT!A8?!xe zd2d8b; zP-e6#Bc)fafT*K0kq!(5LD)P#vP@{>)XvurE0eVZ-fVuaJ$~UdYMIBweVsmUyo+V~ zw@-W${N;GwA4s@kXCeucb(a>Ruox&bC*OLtI@a9vmhl#UruPALWGMAwG|IZ}`edOR zJ}DaIX{3@B!}WdcB#n_8{x+B=K(+V$F0JX{)cRB_xdLaa?vjoi z(I5k)b#`hsBf)AB!xSXCbFf4|sI(`L1DylqQ0Tlnw(5&uPwbi6j+uIUX6nnH{lQhM30tmLIv=2dFTHKsSf;sEslCkWdP8LS zEPaJGqghrHEdppAZ+A?YLE*d3uf_$h=beN+R%}HQO4&l@Agva;4m_x6%8*Iv?9K{D zk+^h;L)_=WXBOm)HmC7c>AoKOnf^_l2VGN3MHE|36=sJVUCv9tMb72sTYeE)#F|p} zL&ia@proUS?0V?7NPtJh>@~9dGBg zBvR4BIouYe!|Zfg%V#GHZ#N^u@ss0W&VLdAFnw;OlV3^ehwG38znT*C^qJPfR|E^= z0*^0%LiUla%UMO4v&VAb1xrtv(NK_g1*4T6Ojb{$BxNJWV zW%&pXzDUe>vDH!lPn|NT)KqtB33}-+?0Gj8;uqHk_l7b71HWHHLC4AqeBf^`9Q(Wqs^ACFx;PcHQ0DuSX`UEx|Ycg!!*@ zZ{Y`bxbSQDBH-8PLUW8?qQI}Dz=Uq>slF}tym-}n$2AM{$XPVb&X~E z?RB(w{M77E5gEFS1mg69ktK^oV(Oqbd$yHhy4s1Lq~57b8}vpAgjcltm69M0IrKU0B9>eF0^c>HJ_IN^j^l)1R((Ow>fd9CfJP9IVRp--9g z7p0b8>C7fQMnm~ic`osrqyZE{DovhZN~ZwfrvLrZ@6T;_Ykvy=+m~Y*aoT+X5%UNKR+FFv_ns$JQH}h+$~2JQOlSK;IrbY zw#aIhPvIJt54nba=pir@I}JChNP7s`W6mWSG(y1|?`Z(21(h`pat*@?2Ix@gUUTu8 z=<`-}z++zLBVph%g6gXTMfroeODnJpGPoizT%oeeH2Fx!)encNRoXQ~X$ArB;{=7R zJ~Py&<`gGpr1S*7WIYon_w{^k53?^k2nE`>p1`jC^RGAU2y%CLxrdozL~AL0Mp-LbWccnM^q&c?n{Y{PzCw zM@Je&YXmH1)$NlC%d(u2cW;{r#^BaT5P`o-{l*VFATpcf;8E};yG@aH#m0lG>-+iB zJb)#ZKc*C5bvW20lKUo*jp57oox(Ojl|22;N4FR;8lp}A`|Q*KkTnKVn$ohOp0^q?j6X9 z4D+XxETK-39z{iEPi1>xzWqdV$1-rI!l`951eM+&%2g3fZz-6k7;rnb^mhKdJs2rN z*11auu<_>e8;21IIFL_0e20e#rBRWCJ@q8M@qsPEso7U#Dz^NfM@PMchl12CyuD8d znG({aF3BZ~h&84&@=gc~6=pSd)m62TeRsr~mr5_x9d;}raO)>%)4Xj+KZ+=p0Gq;@ zzur& zPW5|Ibf8cDtzyetXOq_D$<;>l`KNa?eI^_3YY4vm@I@M?r!B+ay%cfV7^Gh zuESmv=wWk&_f6G3xlymDfSQRDp?6f4+)FLBkMynFyP^_uMUS$UrhXAf5T8s|xUBgAvv%yQxUPQ+#T<;fyv%4NIg+HanVD|42+@ID+zp}9ZqjS=Mgw%5S;B;-D z{^X{cFZ8y%HJFQ!wB}JEjS!PGrl+6A>;?)0Ef$uL6K7TUlU-Wcg9QuMwdlIsez&_h zP9w|)pydjG02D>VeVQ`z~&O0{gNV;~$R9|%5$i=Y0wP@#Q`OZP>Y97BDD*~rm7&19WB8Splw+NEz2Q}gPh zX(M%?r)bq8R^rh|6ER;R40~lpy3iQCJsuBpv|n62em6$8mC*qOf5~6EW5-V2FWB>T zeD%5)dTUo5?Cz<}tAG~Y)kllCth*NUQeYaA0gDg0PGcEyR;KgQlc*mvqYbqXt<5Tc2F8PZau=as{YpUobI7pxmz5qN-=2$jbiSk#6AO*V~f+6*q8t z9%Tjo%slFvEt}7|UC)`*TxZo!@97Oy>M}@gy&&p3>B|6|dqz{!tN5EUngWx0dapg0 zD%!s~hzCxc$L-X80OoBQkwy;`(LSh9@6@AW&Fy!56%MmntHPB8$mKqzo)`0_OV7zc8N#z<(B0h5VY!(hk8@l6Rrv2E~w#HBN!a$UqIpYjE>0Oqojf@ONjcG^^f3u<*j~UnsYUkuc`96c=J!;eOaQw@`cAn!9Au&qkW-d@jiYm_De~czZU)*S&=eW7H|+0^`Loo77ny(j@JRG*ldQ%ja*eOA9*2_8Ax4vIJoOYOs-;+f5pBx zxd-{?LW=xxU+^3X-yLZ+E@AM>aXc1N#~^pydH|u#<;Vq;!gW>qKNrRb2lah^m2}WN zvzw{81Qno~sr_}qImv~J<^|Mp=-EJ9mu_RCl6u$~Hw&#W6wg97fe0537U3lo>WAkS zs;8Rfhz-mF6pM(Or(DgBk|$g4FAwU@RY~fp?LEk@(`P-|4{5oHJ+~^P5D$<&b|~2s zpS9TMuLdR6Jh*T^l384A7%ROlt$cP)MOciK21zB=KnRE3d_0U&W3(EEjRQ&pgV6rRkj*w+k>Ccmw-B^oiQ)jXD6r<- z(2x}#^YL@cgDFbu_GNwSSfzN%AKD#4Hg0kiQpLxtcrz{vs-zwimcyc(p+dTQ7qm4* z&Tls2w?UKLySVkzYfD!mRKz`ApAAjyI9&}LJfYYy z)1og+Szny^5_Lu*_*ND~RgB3NSeae|Qe>Rz%LTblm$Bx=6`m1aT2pW;xl%-P|Gep; z!5#3xk3}{QT66s??11h{3TF_}eZ!SF7ub&h1sP_wACI?x3WqY-f#?vVI z;6Ae~dp|pCfa-o3-H{bJMi69gz4AVxX#Y>!k&(n5GG_>%Z-Sn)>=#xXYV-wXC6ZND`GTHopT95Eq^q@_Az9Sdxa7S+P{+IK_>i>D>6El* zpUp;C;OH@q5N_Wr*Fz6r2w4EH7c__ZQVLY4oe33`7kG~s2V_oIg>MOD&}M8j?qaIB#oo1c%cQ0^K|?DIhv! z95bZC?=<08y5pHBE(Q6mVxVAKU#5qmC2v5Mlf1=T?q+OhDU+9;(dO;Vg&}I7hN0(b zGZ2Fh!9yq_U(rqGn=l$08hM!IU3BcJ48y?TEF4koS&JoF?GZq6zLUjvxBK3_@R$pJ zE?t^f9Z(k?F;VOx5&^*T0BY?_dImEpw$$8;z%8hq1wrjfS~+Gxroaf(1n1+{Ax-v37pEhqF)T?GGG@%B4$W;)>)uLA?W95lmttVxuZgPe7qCw(5C64g{i;E>X z(MXro?N9eVXGQycd2_wk(%+aC-oD0cR#p4_v|MMsNJWJ&F}}(dYVVAkBO4VW4FtKC zT=d7Jjhs*B)b&v@jHupSqS>aTXw%Ak7)_f8<2bbw@0@t7B;)NAV0Ul(=d1$Mi9aA< z@j>BN`f*SC$fcEIVCBFR_f$A{NDzu0nL$x1)O*{MDBdd)ln}y)U${WSKnqV1q@*iC)yT=Mp!^>ILJ`ZEX5p+ z7G$ANS8+5@tm=BdyFyT@uQ^=jZeG&uCFM8sr8{jBr8|`@0zA$Hl{i*sDX`w|s5(gu zPx!I5$1_p9c_y&PblKaE_ADj)=m5{mlS25uGOxlMfwYD>FaxOENv_S05d_rwLBhu~ zwFCnt%Wt(5G`GIcf7n%*Bxu#2D`OK@oW9(OF?V^^*U6&~w~_)OGXKXjLo^jsM9+FGcl@4m*|Hc7pS^fwAiei_-!aX17R z8EZFh7g8k}JV)qDQECK%ynzu2DR$M4?uNNay&v@RN&}g7mUAOSH%|-xLJBU*D@|%G zQA+FYdriK-b7kX&4!{1)?%e&Sa6$^iwlH40LbbOCLb)O46mkOeQP}EQDdt4_0Y6&; z7o46!nRu_ig%v06Q~&yNQ%<3?Wy|S~TJWkcm?A0AQPI~>QE3>;KW7)IIXOS2G`B}b z^uXKfFv0z<3po-0Ta+`B?LnB9`g0Q#u%-mC#2MH3-eB zxAW+O;PZEbxCLSBs0C+E$`Nz-b*7Yg=H0frx83uLWj_o?&hZHxc@k+jiEDYHKXwv` z`Ji>M2PPd=KhMqT(CBFj5BTlG8q-bp6Jfd&n;VYlYK^a|77g|zUJH}cUkej@FsYhl za}ma6A9mKp#Qat>Clm%e{1$TQ79T>7-Ff$XKj!3jKuKwQZP8Au6a?)eI{lwQWl?iX zzA4>n+zS-B3-&$Is&s{hg$qnz-TI`^oIUfp`@8!c1*uv5ge^gxt8r+4N)|%L^U!$F zzQeCMBHUs~fZws3=q--~h{o7tD&pfH;=aR*5Xq1%P^dlA(c2WNS@XWEkba-X^ck5bpvoOZV~VFADQhrMqoig$U}1>`>weeL@$ zm=e&-mr}CY2ZlA!EcyP_^lIVj_kQ7{c=ukmTEj9C{zx0H=cC8;LNNK|MG8|0xed_9 z{Pxk0Rmh(S)ZrB91u@wo_Xm|FA?YqT z&e7o+X|zD5=p0I2`L>pkl~_;kmR{x2Z_qcfLcn;TM9qxN3=41m?QU@b`VWR0FtVp< zEC?)14K3$lQ3<T(#TxMJ^M##n8H}?)T3F1bi^8)TeDsw3!Za*$Ukch9XU9wDkEkvLwwp@J zVMGtbAvXYix14nB8D}?O@;KSTqGM;{<+PaqNGI?k<96j(b6}0RcoKGI7r5GmK+tAH zwTSl50OS>2uve_%yn#i&cUf%{>tow0%YdiXALi;vm-`;jVkSEn?5`lzFX%7j)a%aA zdp3Wh%5b92$g`L<+2QEv=IGUmXU%z-NA=DW?dLOd-PhmoO3os`jV`Rjd{t+d-tn-# zPo04u-7sk+L}da}bh}l%odj|80GUdvZ zdZCCw)l_QXHhtEYf}-Oi^{2}m>J?4BY5uT(D++>}=z*%ROXp5_>er3OBQKah0aAQ~ zYT6J74#Ad@4IcwkskdJJ2wgKN@Hjj{OD^rEY4f0KDX*?f#v~PhfZ69(*ZE9OKjY~! zKcEj$`mDs1wV-mOH{4W?4oZ_Yy9Ilc*&`FMZy)dNiE#J_&YmL#F?x&|Lgh5J_5HIr9gk(Zb7oWwHXAi)$j!3^OrMZ{<`FS*ndC_6WB(klnvY)MLyB zh4$s9&|CKaTud9CfjwyNGxEf5UVS`j(tJEGd|i(_adh8j(YZcSr4OctHzIvr7try^ z_i-*?QuFWrP#EDh8)`6IbEB^M z?X&i9B~&R0`cvDw=m4Wd8KY}QI`a2xKyA|%k};Jeza0O2Zd>jo|iN-{8_{hfD07TC@YY3u1!JCPD>qQ9E~gE z98e{qCp{8vECK7|%!-`ieg*W))KB83@00Lw^wTj^>{2LKaN*DDEnKVpNiLZIxQPIFQAyVC%J7muOIBk8|K)Ah+$Uae?5o_A$m z$4}(>20{PNAWzqmYGaK6)gQoH#j|N8A5s2h$IT6}0F)a{p4MSH3(i}n6dVkyIB>U7 zn84v*5}S(Is3O>?VwzdtCaXK?m-p!Z0Nxg?pb*TXzzuw_U9VLkfIYmE;ufPU1{6@^ zY4t(Ee1yh+NrWrg2Tk3 zlje+u)_zNms=od@r(P}8su_D z%SwbkRl>DQ4Ms09T~r!|xw@5aLUhbS2tgDnFrM>;a{d^;9PehMbuw>P^~sm> z@#WIS24&3UkpA@=^x_aa{1l#qGEm9Ass8qYN8q~Yg;P4*1j5_1bFcSpvufHk!QKk5<|Qde&a*Lm{|T z(xt+cTP6VRnWl=E94pEb9ZHE49xq04K0F{+FJ%|P+Zs@%eI$M(z zzU=7^ruA~ga@WyY1ixRsU=p19Hr9=KhG8PdTHR1Z%lYt*xz>Bx90eR z@c{>xUH5kp;G5jhmS=UFS&_Bsgowr3x9zTJOrPs-pCnD`XcNl%R36jw+n1n1|1?_D z3PnGMg`HFT8L#})QNTV-r<6;<-=&aW_hOB^Rg5pO-JPop(@I)*&CQ=fDPCm4!|d;U z7f!MByMNPB?N_?h9UGON;0h)2Xur0LV-?$rubcNMH6H;Ubxs_|OnjVl0^+z*FuP#+!4IXDmU@E9i{*H+wG0p_GXN%KWVoYH4wk15wd12nusjRuiszngS>P#5?*CMzX-XoOt`}x~r zLHuYawQO%x7C2D?<3TZD@u>khXa%p}`WfUs5x~hjE7nZ9#Zf>vS$_O#5_W zR7he3A^iGMSYyKLIg1#}7`Kv5XUt(`Dw;&@ZoPraR?eSWq942|v7u}0;uVyo%i~6m z!FC+>2k+cP41C87u~CT55ML;3>=yD;P3^OY_+6Qr)0%h7BSJByf0p8_%n~)flsaC@ z(u?P~uar1_5yLxwlh`!u#4E;4pzu-}>XUYkqbF^-ctEYYWWG(Teae?-mQJKJ#m$d+ znR^~PAnFkthWw#?AFiF5$ukLK-Xei9JoI-@&M*>!iU*YVby&6wy>Ow&B9N zk6Zr^O<$HAZ&0`kH2Ih4ES*4c^*7iv>`d6(Z4q#=jC9(5exwz5Q`q$69|3y8<3%@q z$Sf^I^jI`p+VSd{PvEsfGwIWhJ{ze*NK!i|PGc<(;GKspth^2${{7&%+*$MfM4bww zw77v;fX%Vp*`2HT6&XNVX^C3g%f~;)FE>vfy7}tWk`4@I3ooX(fonWDt5Y+z!pB_Q zwQ!+=*?2+E_3EzMbEYbF#M%da3i+I*xPgz_;G7n&z2LmUaU^KjuKhS;Gc%hsi~iAL zCEwLVx)z7d5iw2QT)f5GI3Z=#1|7Vyrlw{_pr!k>T?^#hwiva?O&_Wd99{;^Uc_jt zdmmNzt>@0il#>U1er57$-xCGH+N}bxo ze6wT6Uj7;`bmjc3U6)s{HqI+bcquJqXew;x;;I?TH(TleH|q`n>#l1VXHUa4`oyRZ zw+_8eIc&@oq3hLB?ehFpw)$nZ_GoRm)3)rEUY^mz6DFhdW9xS1 z5cdzU2F~G|!Nw1y%C@T^by&X#%)fsOv*(=Z>|1%8s#^#f(x$&({(kC}J2Jw|^Dl8t zhPh7#UoB0W9OCAs;26$XWAM6fbw-b|uo4kEs)`o;T^PttQck^gdwtzn+bf@wOE09G zxcG)oJb$Kp+YM4c0xvPClAkVMrL&vcV$=LV7_TFrFGX_OHW9SEcP8s}dznaY;4aB_ zOGkI|+(zl$vkoYKEQqM<7_HWJKTK5f#Tn_r1bsz;4wG%l#i=@Z*%*IS*^4EvTD9pJ zYwY<_J>t=B?YF&6FTb>oH~Lg67<78JmkKu%iG2gcpTGP(8-+yy*t%9QEYfSH8W*Hl zm0V1on<7Bmue``PKCi8*`=TQ}CT04~bF)UkH6kJyY^}>b@Dx8fp7Jf=z0w#aK2oNx zea`I5Th<-VXiy7z*{tuRT593laI3h>-A9*~+d?5MFw;1%xY-z+9>Sa6>8umSPB^t4 za=YBqgcm3cnN)n@F0tu@X!69i`!`p(9yi>{MRwbiCEz&AAFRe{VOTqz)wPtt+_>qS zlz*FXb={e_t<^DYUdfbf^SsvFWYI29n(nV$>2W~x7{pD+=&6M_ycC60$D zpy^4>37x5Z=3Srs9X~i-a!GzENBGFpUhAX(;pMwcq0;Y|F}|U#_aC-ZNG!#FJSNnD z+eoi0e15G@%DW{(XRPQAnU`6OOBIv~E;o46Z(ff5;A3AVbfrR{Z*8t()cH=s^K<6E z3oQGxkCJa#)YRvz`te9{tHNnRmDtjS3MEUv>e@Ho(_sW!7e6uYCZ=`B13gd>IMa1a zQy{?IsPz5Q7kb57$@XvDB2S;b9249NsL^mgq<8%9>FMh})!oigYcGm8Ul((H^_2wz z!Nu!7ymCITkaFdc;~K`~hE>AGw3=T(WCtcxEMLu#YLBMSCHr1~@|(fZ%pf~*^%Tli zK^Vkk+De#(B!cZvwh|a)!B^`2r1ZJQRP$Y{Ry`N@Umse(q&nqTkhzdT|KZkGOX|G5 zRNHIEgXtC(o(*YK($Xny|NV}2(Dl}j@kL5rr}|9RiB#X5FqIPe<*1wDg?AyR7x}HX zs%v@6YvI*J&Gnv~D!#&f>bxz~{WUVKUgvjB)#fiPy19aJ>$<^8t~Pep6huo3{J{2S z@WdMWyNST!?A$f0kJDm=XCK?VOLYIyz8m_!ahF$rc&>F-OQ;5SC1~nmC5J{7X%iy>@U~-fD@a$AQ%! zyZBCOiN_noyq%nIZ6?dI<4~KMrB_B!0_EkkY#zFN>yasC+Vp<>Dg}I3qoU*1w!JoE zEZTdt_8(H|9(l6E_xU9zLM^VU)m;3rBF*vPWzfYXy?z2n|=4RQ0w75a(~=AX|=AG>o&=? z?rfClKbE3Uxb|>BhuibWV)MXhEX|ZgBP{s)Mg#lRTbTVw9Q!+EFJjAEc*Y3xlhk5{ zt4(;cXKHJGsL8X?)D7JY8(+NbzVQ65PMy!za*}+lKwbNR3^gkAmk+zb&(F8oe5-rX z5yjIEfr4F+sxS8KFH$091Q&0)r<{68`bE;=zI3gQd1F#lCJUfLUsYH`~7rZNZei}Cublt+i8GhLGKpJsV{ z+L`Fs)}!@Yn`+h|n6cR`OGRQ%%@W3~+6~+_R2+G8@s-TQ2#IbRB6YEt0O}H-6tLt} zY|)nSO-nLL*I%Qz*gY@HnLM5zQ!dhQJ?d3)rSbEF5$i8Rp7%-kt);PyVVJac3MGGD z`@9u_eaSDS^y!rjV=SnBD-IZ7D-Y9+-wuNiW(Z3gY9J*wMZ30vl6E+Yg*Z1QU$~`V za#l{;zkIPbU+*>D1wjeM#lQlFa&fDBvGeoe;pTz-8ELI070zAWYO(U&D;#64B#2LL z6wWty3M}Mh+V<(M^g`-CJT6)v3)_xqz9WUnz6X%)K>{zuwLarv|B5JYEBw26Y1&$o zkA61O4!#=ECqtms30*q({IVSQg5w_-Np{E*Te?d^5--WbZ_P5Zz2y&B`o1@zNo_3i zZ14F<@skffe{ufp(un-3NYa*K-$;vY?WmFsZ3>=pub-dMla4>8CJN{oxqHS4 z;!xsXgA~Hwkfx4^cRvf%cAT5WDk(cp)s0B>yS)5nLeeQea>K4T2tOhuUL@?x9b?gQ z$4|Y*jd($L_PcP)DU&G;lRSF8Ho4`URxZ|y{7}3;xIC^|xjo|e^Scu-eBO6j0CFML zrX3@o3I!BT!5WBq8$vO-a+`(VYW5iB1fLJvXFnfH))9Pq^hDwb>Ek;5CF@JQBQzV= zMA5drj0^M)#gC(3>}t~2nQ4_$a_VSSk`-T&YH`7|s9!1h8KN=EnYcLnSv+(flbs8= z9~)v-KCew{*~gAU$G$v`MfZr1Sgs(Wqm_P3m%Off$vlj#5r1rih%wIuOS{(p3SM9g z^ZaX;Wz26OiN%CN&D@Yl7RqCFqgGpBHh5cqn{tG5abVh!>8}8w?F@&hD*NsK$Jtvz zMY(l$btW*0>?@%>cSClP$=(i5L18{m6p;^{Ylpx z0WE<(sfGNxrnI9BYuEKEQvnm0Zq6UG#PkU8zmgzWy`^V6!a&jYv%Gws;~fQ4%eQ+;{W6ke31@u1!K0%a@x{Cdq|L)Q1?N-{_*ypw*vn?$Yoqc1! zhZW}l&8xR%N)eP4vM)_sp5~4}ZTw*0yOj$iED$novrbW1sw*DbSiH`v3F{K=K?u>&PS$C?`-t>qpTaZrDGolgw?`udDql~RYu63mAe z8n;xPpP#?8jW)4Gqq!~*`1!Ye`gE#k>^~40EjwzGMOavnO=cf&yq&#v&_c(dA~afH zeGPBl90A+lL=k_YT3H#9%KkW`aLJkvc>a>@B}+H?dSbkl+j4u<#^&dFLZDbii^frDSmXQ@dO3+z2LzYO%`$Qb@1L zN-6G-$uE5{)YgkrI=2#^-%oi&(^Whvfey--DvhGpzqg652;}w5c1i5tSbHxymrtDi zJiLE~?10(m5S<9`BZ6Uuj1xuKyeEKTh-_d9Z!}R6}l>tUCKL?iaddX9QzS@ zDeK5OelrGn(5O3_ZSau!DVXz>T&y=hlFjn3x;gf&qrwkgih27cZ=ikNoMmac+OQd0 zsX{rI9EeES<-a_u>VA8t#aU-pv^x60Il5O!_*D}wN48H%+z#wH5jFehMonU8Abh#n z2r4;A*`ma}VN-_wSfa)#sb1?3U0B@QkRtyk4_e;K3)mm0SeHNzsRjEN%X*#8uI2nYcsNOl= z{90w?&MoUN){|~my29W4+035$!=z5YUx57ZLvjq!k;0C!0IS3io^5}3+USJqe3sf)xU z$Kk_w)4f_?)_Y_cHcvKo$uwpR=VIy+mf|sD|rkkK0=dIkWtyKuTQy)FdZeF1l%`RT-@fF_U**y-n`A$(d(bt#Lbv)sN3(X z5fe8p+wk4YiU<^?6<6^57L5#i;Tyg&BU&_m=G163CO)-JQph`CV+*ZeuVg(b1+um9 zv@V((vOD&VH*3EU+n4X~ItwFrcJ;^*K4 zYR(L>>TtYWobj%*C&plIiVk6-6CyCs7`pMzNGH$0gk)zyF@M}cCu!d;#zH4F@3nCz zKFn`VWoS<0qe$lVm$$_&w*_F5m{4;7mF~LTj5OdsSy}h_<$=#dW zK-YgbFhu{!5>`_ITEz4}B|VB_(hOifBLL$w$$TT%WqeyUaW$Z_Y^R}Cmxg83Rev8| z;-O|Y9GzXjp6}&ly=^uruxD4Sb@%@M^1cV^#XM$<-&GRbn<_5j`NIgCOC0!GFPfnY zOcX#YpH|DSYw1%{h&HzNe(q769jm68FsDNUw+~7Rc=*Sd{RPO2n$B|hh|!EP#Yzm9 zzRT``6h*A!f`EL3a381sOZ|DTh)u6`)loHOzRN*Gjaoat`P$HVWgnk-L45De(hJc! zkkP(iRP~Gk^L74}t#*5ch96Gu=}^h9Vl(oe`g!+tDLnzjk<*a(XY~T?JrZAHChllU z*Rbj(z|vK0No+sBy5v|+9^~2)OCiEq)sD~28)?iBFQ^Mx$+2U_YuMMGD_|)e0>(f$ zV%vb>-x$(hFcMQq+>6^B&Vd+dI)73^xpdy$4D?c3j|(}2r1Rw_Z0g?`5wY3sot(t* zMn=iX>N8@8DooR- zBU)q#7gQW-tdDul$a$AxbRS9Xow(4iiGW5p+`{7=WZkze+R$`qz<=CH%SO1&WXDw# zFhFUkq@-)GU)35V)~GUMXRt8Cm8(=pkbPtonHJ5=Q8bQ?l_E{kZW)n=VwNvAX8npg zr^h&!dUKZ_5ZCG?Za2ilT8p|4;-En;(dCP3&*j|<^=meTzAA4_O+qk@>E{Tf`tbCN z_R#$yT%UlXVmZ)76p!OkkeA0|=_))J^?)dp06~g2xCb>u`wGjij9KAkhNsx_MOumN zP|Vd|4ad|-anC&qdqekWcYy^jGYyzDvrsG zz8%}4t0=uQ!JS$8;w9s>(VmqK1?=BD0sAkIbp&F53v>P}K)^mt@03Zf4zd{=;a0E? z=YWgfK91H)&2#gn_1Jmq(bH^v?>!B_claQh7MW6R7%D1N30cppzyC&#x_J{3Z=p1P z!2XR=Z>4dmUvQCD+xZUeTBGJR z)nGD>z0Q>nc6f5_#+wo(;t#d{#PQHiXaE!z&vowY5$X8|o3q!l!0l}@lnw9Y{mGC# z0ol}lGCOg6Kmc0vC7i|Xi9{gKelY?VX0fpC68h!vKI`gYsL=N%^2D{pb>Czf=c9-J zZaDPpz*h4Htd97+2|h3nKO7{2`cq|ru7S3%Qz*KceyWOTweymYgF-be65}h}*Lw`E zVWoZqgcZs^Dpmg|o6W#42Y9gdYrY(uUDI;h&m*X&%Z*wcsmTXw^{kgvyI;yQ6&TdmoBk=S z{K<)O8JzqNga+&{MZ9g-&{$o;-h4^+K)u4vk4YxI5e}SPuhg296WMO6|4Ga^i$HOP z)H6>XDbYH1PWZ5P<+ylq>z)B7#9E7|ufvU#3Kf3OLre+_OD`5aj%L1nn zja=d2K#Zf=%=?K^VHL5l&+>_^Ib#x@U3x(PFPYJaIr*o|>)maT>Jzn&{LFFIuyQ4Y zwSQ*k;Hb)|)H1i$w&`Y<8%4TB+Vt2Bl-=ftD}9t_H`9?4n-ov2o@Bb#CazOZR(405 z6Qw;?leHxFGA8H1#v0UiYON+EwY9W{?Bi2X5XKE&!zIL=BehOhaa?*-WBf9TY6{w0 z(~937SUM0s43q)1uX+#OAB5XH1EwTqVww|*Rd7>aY#}Q_XL7}go`E+<_if!;uk6|E zF4C(W&dJG{pE2<(H!`VrG(9}Y&dpsj>RZ}?L1}i1LF>gTR|7HQXhF;Hh`gn6GUnNs z9@X$Xm9ii6Yg3!w!?>;2tBp2>z0d>8X6gEKax_-h6)dPqX=!Oas2}C3UoMC@_5sAM z)nugjUV0XhIAdlt4wBSK9gB#6-?^wOV9p9JyOhbmg5+JXftUugM<1F?u zpa&0b^5r`F_2XeH!jOMc?gUBumfjo4sPR&jZ9k!F$i=+5!pr*wfwt%~XMqp?|5eLX zsuAJb|0+A|M<5zoY))lepDH16pPlOWbsbsK1Qqa4=xeyAj#ytujiX$><3RCl`fy!w zoUhpH4w6%RMzM%-@@?TL!3=293&}s)vmrn$3yBC*`XlkF0$TR`?9iaeV*(h5P-Xw~ zQu}I9r&f_Ox2YnkGNQW%K=zBLr;mvmJEbdzK!qojnok^&OJA^Dcr*R$#c zwm*SnAk7u9pPp_@7X|;ajvw;$+BdbxUwbR3Lj#Ps{-_Zot2JN)n$Yose?=01IUN02 z6+0coQn!6CsZEB~@aBa-#%_Oq0e~?Y>g=EX$_%}kyEGi~waBY2t8RxDB2czy%|8}X zPC&*0skS+dh)E6&ujtb{DhWzqE4V zCY;DqZhOeqO9u+e6JqUg6%GEQ!qQKu02^{Bq0W;1>#1q@u3k_DkpC~GaKI{s^XSDRvKOr7hq7tZ7+P(} z)JsQv_5`5@^#43}FyFFh3!Bs@ww*R5AyAg8e>LCwc`2Vl$>E9}#a(FL(9plx;88v$ zlf34wBC(#vAtTW9@-LR^;8Ubl*#SP+8khn5Fq%iP*n|cz~ z)C~n>!+)7N*~NUd&D8#Z)IPt;T-k!GfAi5>%4u`s`gUGA4%TioIUWCItrJ#08JF~} zy>v>gUqt9o{+n%eeAU>?vGaDT$QWfWWIXz>#H6sJ-w6#~(i6?i5K>_KHboxm+$40|JzKPxL2!aL{ zyfavW(VWaSV406M@m=eQG328>@R~39W_leI4K?8?lt%mRvT#~Qg!SJLf0PJB%5_W+ z{EJX~A%S+fZ;$m>cOlGODL1xH-nvZE+R@SfD$N&`Zi$qp_l4-r$&HrCR6DpQot|U2 zgVv9!1v7W~Jeb!KSNX{2Y&~3E+?XodvgJ;}ZCte8DTw~%OXHfSRgyM_9hzSMBV^H1 z{#e;P)Eu{~cJijcK}L`{V|zQA&x5uzdlpdfwN&a{Bdb*vpQGTc^m%*OvxQVWWsBa; zkCH&w^*v?oqVZ^kcMv{G{R6K|dG;M=7mf4URc$U;Q!C)m{h_!!cEf7%PcNBydE+3f z^BK8*q7$wQwF+lpSrh}bgM>q>0@lLAo4)KIx66NHI7{cs?vaYHTt}`qZjJJ*sw~nWu-q?l8bhoC_7w7m_(e zkAZssLy-CJ*W`Q#aN3(0gs4>9t6eUg`q!V&;x6}cQ{~dxx;X~#%yBK5Vx^9Q>?mdi zkE`A|4rLF>Kx`aOya6V*ngC+67e$N&S`_+PK9jOmt;yzTW6kL6_w$9jd;_ixX#`-A z1}YGv8QZzz%^`a%U?NR?=CVMAZi3*4xyA|}*B|gqntL@WZWiKWSs&=!XFv>nwB#vH zetuS{Cb1g_scR(IQFpTYCJ2QSW^hq(sc5{3ApiBZyUTSgEjP_={uW(-=uY(ZsOcIT zr%sV6PtqVGsIeNbntwFwxL>n=kz+1o;0)Fu;yLfMbpO}-EwX_Cm@N|PvV}*WMkN3#!cziJ9w%!g7Q$^6 ztlEpNZgCAj&dDrU{F?Fq+A%z74gi0PFE3&1Ja_;UG2w)z11=15P0@(sx{=@PT_0;N zZ@I!Sbr7P}c*y-K!m&*$r>-kqs)ikGn{)EqcFCF3h@M)X>7hHTiSl-Rl*zEJF zwu~+2jh%Nqidqsu5T$+vpF`3ys};NKNN$JPtc0_OQ_F?hdx&n-ny`RjlWEn)9vZc1 zg1{}z-b85V)%6wx_uf<+stbj^BSP^=Wk0RNW0Cj;g#VjU{g44l!_Dzgc~B+K&FFA1oNSoozkt| z+w)d6$wEK{rPDJ2hnAe;ml6}LS0f+{UykHJ1TM!Pus(UftD*RWcT;-Kb}WVF(&fH? z>?6<;cdQ}oLR-&~tfu(m!_;nV)jpbb86=Ni_yTSu$Rm6YKHxu$L)2y4uGP47Po-NG zDdF=o#*^alUYJefvcGtB6n1yCBar}hwku0n+^n%(5SH=16inHBpUw)K#)Mom34ikO_FwZKeV9O!ATF^OyZZCX00D`XqJVC$k z)P{m|O|7(#OWJ9<-jMq^BxMYDguC`<%2C$!O8XAa`?Z_UuIN-${8V=Dg~GQVAfxr; z@gG!6>((AiA^cMAnbF7m*JOS<&6n5)=UpPx1H9ThV7%b4H&LKKZx8t^5!wC5%IT=+ zCS3J$Gz5?jMAZpSQ;w)$bgtv4zAD$ zA#%zE>!7NupuU7b3Lp%|imlf%fe3?$BH8%gHg?u za{xSix#pPM*ju>6lv!_FdNMJ6iRtG88M^@Co=CG6wb4(kb0)zWg+VJ8KFRi3$)DRe za*77xXkV@MZefMe6iv4ig-;M;0zrq3nHo1(0s|>oV1vltZS_hlVB0k~1)^n|sUg0E zu(M~+Hk6;Br7<6_wi6Y47!odF1fQvtWLa2vWQB^&oTJKN>J`j%HNH08l-p54btqcA zWyjvN?@?7bRSeny`AYWaTeF=*(3~Z1c>cChIKUA z%!AT9f7TK8`S0W;Y`n{LRC5dvbuGQ1~7Y2ppjQCET4wT@8 zpVzh$-dE$Opql9Gz0Ru?WMS3|mF(k2M?LEmn@b60t>yE!75da-aS&=z$0 zow_J&gxuXv%nPRA5`2rMTO@}-Ttzu1UWS5XU=sIg{Z|DCH^EeFaF zNg1EdFrf{QRB4Ifmk%oGNw>U~7n7T>Cgy(Bzr03Rt*yk_`{>cINB&7HRFp}lz7J*T z;=C5Uqn3wnT{B0&kF3s#2K`%mTm6Uf=tlK*56^;)fsd&Cw^YWxgh|=XhgbJGzV?c- zz*2UZ(vKk{Lr}?Hcq4O99`8y$*t?f2{;e~BTC2OnIl{eKs94!#0rd#V1w^u|W=UhO z?{eCM7$yLc&v(e)gp8705r&tr`MFoad|UHJ?#v9q?LS&9lz$TM^_1IcT|#IcTv_VU zZu=NT(3ZVjm>uc+%s7Q3Vd9oMB3qs=;@Q@crI`%d@upL8;N^Gjktdvjh+%Q-V8Dla zLO)C0_@wT4m0*pHVe?~h1r-)nn7kom11S&;hcs3&0$qHO8e^NTbM@pdlsT^HPulEL~ z5d^0qjk!>9dG?})OPi@%8i^X2HY*=wv0$G7ZvV&*^kP}NE@q)N>L$Z_?tr!e{WAR> zv~GV^te-JwF-Pp@$KyoB*&W4*QBMV?)AG~LK6?muaEkmP+b9Il&8R`-91;90VA51N zTpT)zK;vMRoB=o9NQMkmDP0m@Z)8>EmQKCJ=49Ll>=bbRN51hl^xDh=bi2jMXP5_G z;t(JAI2iA8k=mw7v31e@cT+K)QjimgSHW27PTUI zUqeGSyW?t|aF-JvzfpgXS(>L6sRwihGAzW^zWD2$3#+i2Muee{|;;1 znLW3;5yJ-_@=503uagk(-Hl$pngQLVQ?HlDdq>Hp!3sIa{!dd9KZ7jPDS7yrb5J-H zHbe7KwRtaEnZ7@xWRg0A2yTjgWr=Q&$A_Vd4Q8epJUwmqFugsWS|*MIp-=#X#0<4^ zg8b3AdsLv^%;+L$H>*`^etZZ0`THFg6z+UhR_}YCXbb7F^X^}qp|30#X`7tVwx3q| z9sU@*>02?S`g_2jj|#$qyV_ahODAgp7(n_2Uj#+*T7~8yy#zTPy2276 zS))FKL7tT~q9ks|NMFLD{fl;4hUUCYZ|`oIzA+>#NnBXd{6bcixQi?G)qV74oW(}) zKO*B1=J-!53L1n4q`ksL5-^zI1U31*XFGcM;dJ@3pyDvqVxoWiCs7D4yDnWr?gfQ- zYibNmea1ces84hLe7v8-(W0Xj+4*oI3kGnuUTf#o|lB^a0->$10;l$)Gk%?>H zCpntFU2rGXOzKje4xFr>d4Q(Cuw_}QWeeB77gP;#;iso#?B4{A?z|b9fF%>SESz;t zY0TZfnt4SLOwK^s$gID7Sfe- z9pnxP@o?1ULd0B!@4dD+yJzpXS5D+Y4IYnVsV6;Nr+b8L5xrbq2U?m3fOS;ONMoCu zyQ2I-1xR&1k*t2Lc8FbSH{WMs+_4I6pF9$N#%n-S5{%$Wf;L5~zM#HrSR`pAe9yjU z$pwakK2NqV}=Uxp{gk&sV;Ov*x z{%~-b-)pht8lmnPLd}v8HttnEZRV|SHYF08xiG2SNRKjM%R1h@#veh*c6?{ch-VKg zl9W`uj!{h#^d&%kPT!_2Kou365=5Nm12UF?LDsb{;JMPFp3e$7ruTJ8)Ebbj5@|rs zEI+?&G$e?iW+&}26`;-Fx@Z5;_JPH(^3#8}2is?9iwAsc3Q*mJxS*2^{{FodHozX)rRdX7Qh-E)bk6!9J2!w6L*eeH)-VH$p)s2lsJ*EA}oUyx>2%4UUZ6$?(&fLZJ{OQLW zV3FG{1X^hgE!&OI8FrX`)5c{(is$9UD!ke$Qa!jcwqqlPS?EjFL}oCzd$!nL15-C_ zvR9uz?t(~xM#}ojU^7^`=2G}F8F<|rUGtTOPnRrHVzY08)aw?@YB<3u7T5MBI<3W# z@bkUS`mw!@MT$$GvRx7V=!wn@6Efac7NgZyq=fvmLKMwl@`CfGHG&z-s|Tph!Ow)x z0Y$yc^vyzUEbeD>;D0w6{B(45�F596tO3<=;^8a~}_y1ivFxyphG^(*tIB7Xo^I zBL;)&Wrm(>UCYNsC~~lB+uVD+>9Wu{jk(Gvo-|IWFP`MbMjngrqVG1yTHLhQ^&*0y z06QD|>@1eg;aX2UkE!sgKhTUb6ptAgqinIhp!!RD8aLd2opA2t$$Cf=)NJD2@?oV; zMa)V*W@#wJtY}^%On|+rOlX6XT~kr7PU90lhxwERA}*HWy|+oVUOx50ZsVH1uvw99 zbTOjhFr%%%Ts)u3sf;@EPW*LrM|Jv9v&lcas0bGKzLqg-#rt6djA(`9^6ob2?1!-! zTGBG6GWA$b6DZ_$$u=gxf7n`9GRsU~H|IaG1e=bNAMXLib^6QA7b#z44Cp3;k?F23pMf2bBV7?Ows zuJMPSGYiPqL0uI}_T*(T*0Y=jW!5r<*d48f4Lz4uXyeR#iHGLCBmL@m8K9wsEu!xVB{vWE&w7`LEwo39S<2+XY+mfIo%Su}6 z)2DZtd(G31Nm$}MFnQ+Jj5lR)USVncDsrVgcYGLG)9I(+Fg}6u&-9Yd@zeJ)8m+OK z=(d`v!8};V!-e3=Zxjz zi&Uea%M^vtbyad53Py71=N-pjAbmO5&BvQF%Xsv6BEg}GVMfqzH!A-=Pp)|w;tDYm zzBz)bv%A|2g^WKW+dC~eE}~uCQQbqxSA{cA_)sNW^Pc_cK@f6L=9pq1ar|nOan=kI z<|ms@Bh!3#^5f&*Z<>vpb&48^%VHbC%SnH93a@;~$zt{#OlBvy)XKjlHFRgcZ|@aD zR{6L=n)ZA1pk<^&;O&x2IXwWd1>8X!B?WXJXP&@oyI^K-e7 z?1enT1?>_ScHN9N?Sd!8hi#IL#0QOy!0P9BeGs3%e31L>56T9^EU*rqk!8c-hGGJOW(FHdTS^->TXN9e0*J8 zz(KlfLwH1Ro~wg(UD8bv{JAa-dWu|UCZdNa1kU&_W_5hCXOD&JV~+gu-VxD~e8FmY zZX_?jFc*w##8Pw4=NM4*|Ab9>8zs&W!yjN%-VfTA9Y=C5KmTY8X5V|;{?!{W=eu^K ze_Ag-uW*;BVp^dVIc*aETX5P=;OqrTO6Zu|IwRHnPUD8&3d_hxLsy_{p0Usu-+QI> z09T8O$<$)|>a{MsFw@mpEVR41SykmrIpp>h^SG#gJ`}q;c~`iV>I^?eE8hgJIcn7l zQOChJMTas<#BO3lQA&Plg&~!18i1yH2F{&=x^n#?zdBz2M&;7KhVbCS#=8n|)B=Zp zE}Y~XB8g0P`0R_G*i2glE~C=|H1Q?WXMA;~NPl5HQ7oXzj0RXcd>T*sp-|1>ZTndX zCPEjWo2OT(t@EhEy!b7htit}0?;M$xH1P7&S1-38Nu9(|l3wI1Az^s&>Mj1;58X*p zNN;7e18;6jS>`1qkaOFfHF5NgK-}vB?03w@j_kd?V-_?4t_U;g{@zkUC;-Ax# zNSCFTv$n~CRjJEvqKC$ZcZ+aYo(}5Z<(2o;IpIHC3PP%$E+h;_s*Xkb9Ca%GjFP{W z{SF%u`H_R$Feo>Nj5#^~tU~12PZ3qdN0JwAJofZ@65UzHo1Ni)aJ# z-bDcr9sl_>cSR7=G(WvJ{maWXv%z5qUZ#sBg61RobE<^Td<$`zM}^eK{ltkQZQ$C0 zLUT=Mn%X|5tV+XEhYb?Lhr5>MarO}db8|DPVYMm^gaIqPd~_XH@Yj+v{=pMJ1nD#M zekHY|^NH|pV}q38IhK9jK5e@5*Sts!;1}4KUzZ7re)bAkFrg-!6}#bLV@uibwqgHZ z?<)JSnE`?#K7Xl_ICghH89@;%!H+G{OD#|T+Rwj%I(RJ>uBRkZ|0l?=kzQZ9!*|<33SNruzpy*9 z#Dm?f^x-cppud zaP85|UB%_2W%mNb+z~1af73y+t&h^NNdTnaNa~bvKYvwku z3|HC}>J;m<33Di2N=Q&taN0c-eN)#UeY~Pf0dd!q-|}4+`rAH!RJX9m0k@|lx^Pn+_l(Yb%9B}(eTU(okr>9V^-&CXI$nSl5@OOZnVeUv3{_nJ;*`hRzGkOEg zBgkX)P0+f2gnNbsl>yI-O{Bz?*oH5EqlwPadwCiOMHh7sX30Sh_O>^)tqxWd1C= z{WZD@_VIZcf1A~hQ0c2)-~q@s9G@xW zzn1?)o!)#sZr-t`mU*_A$oo{r%KVq+8D<>SL5)d|fCp!>EMRW*!HzDc5fZjAl+Z$D z;@&MIH1+u=jaR9ixjCZ0)F5}yWx)nwLblhxGw5wEIXT_C4fTyOwsZCVRW*{FImR;Jlh z7#5?iHLc$Orq?NsF>Fs3bYAe>SniQi6WxbRbicPpJ_!pu73oHV(+KVF^=@*tOCfum z!=D-09T-hx?5ZoZ`nvN;UkDM{5U4I3xk8c%04J98e-B&&QX%~=O zzjl0Uvh%sQxg1xoUQLyn`g#8KzY_r+8X#U&DZOp}ufuw7MDOGC7=^yTVP;p3LfhWi z8JfWKnV=If2NWE3Z$G@alR&Zr9Q1uu{IIa#+&i+(C4q6A5bJ=q@g^QJ!i%+8!=W@i zYoK){KRun^@k>p{3HR6fBPln7tP(4hP6W2{UXz%FI zv9Mr{^sNq4Ji0OGSAYck0`^ug(K_36zgl>~WZ_is%ZU6i{k*W3y;VD)AYJ&-2i5lZpRbK?;- zLO8&_tw;4a4FI*+lzb4rfO5R~PZ$iphzB6uep>$r(~B@HNbSXY5lv5K|B8q4`Ba3s zDtPg>t+d_qD)$nCDhcXdbxy7Pf@bmcGMRMl>%Y6J1 zT1~fxtHRT3%2&|@0R|ima~&f3Je!lDE*K*>JDUAPH8J&FBAW9;Nrw%XRIvn6gEYT` zItotx-r2kQRW^vNrQyOX4=pF-)S)VeQX;U9#>6i4tEOsTV{oeVi&N8vZX>?+IifpO z>0$7|)7CrC(!pi>&G|l;u{ChctJJuP{Td0s%Ua{-dY@1tngW_L#QhVm1NlJrh`H+S z!{6icge=_R4AMUNf*G(3hqEtQ=u#aQok&%_yyW0QzmGSjQm1~hf7SHMh$)_(kKHYi z2<9Ln!Xklu4f6uLz2Uo^80u4LdVE`rH8$@8`6hn*eb0CvJa}+-(ms?3?vKW4e7$n&w&U)W z4v8TRK`sIj96ps;Sc2M^>p9hg?a<$xt+bAK+LJsxx-)CJjyF3`)->(YT&0E+9~UQd zBScCr92GnD0e5Wa)9;*ue-eoCqm@)oaZlnvuoOkm1M-2QHqTRELIS2%$CIjcT5aEa z-Dxc4_U51Dr37)f%MiXpiy4s`oJZJh79Aw!KAj$8wpel-a+0$fdnMR49xgDNO{ONq zX5llu)GD&IjXjj|E#73v?tDCw-);yjYIAOUWv0DnrRk8i7E^ZbE${UAPcm$Z-{09RD5^Yca^WVHU zKG0gIq%p^AJApT0NTVKsIL$nc1vqKudhwPc6x}I;Np>B!6JW9LGfh(yTa%u6)(N5x zK_O41hM40!yzq-WjH|SF*X6%07F}yk6E}I?LYd@`3W}=={PbnsZRvvxqsBx-)oVG? zr0Av;Ar}pM<5ZXP1Ic^EVwY^EpXYrFYMf4K`oKkkGcyC-{{C%eYuI7)EjZpIT-0ru zR_rv@!eY}pLir1W{gvOq!L4vc{5YU+gYAoQQF`M~@~BQCpIxhn6YeMTGrczQ$l^=B z5wZQfivfa9HkKZYjiqAkNc&MCyTO-N6NjZonXg`zsRMu^ zN?=31^WMqSG{Yk$$1b3gsKBn|y_^{+ zDM*5i!q?sbl!!27TD@yam2g;4@0E;*{!oMvA86$QIazo}BYD$a#*{1#ZEe2CyEWZ$ zZ?fT&yj{cXhZsN4>ABpuVhuB6UM{nF>Jj6IRdYQcjPCWQiSsRhGiewd@FrWx3YsrB z{1dniAtgHNOC}>Z1w}z+(Y008VQE9=UP6&E!LRC_0M~Q_E#r2E42cj7b?`y^uNiqy z1{;i*+Xj50H1X97JVRXFlYHzlmCM+QLr|Cmv9^TF8ZegA9V%H}dc z>G~UYm(Y9oe5gQt$3x%EzILLAOf(M)`-}T()aYUz1~Z>-zyM;$eKXb@6Vr@u3hwYS z(@XfAmG-Hvjd4k=V8?fVXRdZCl31jFD0$Uxap(IdZkPFwEDoGJx3``OjGqe{Jl0Wn z1#E`^>HG*d)ka0mdbdf8J!9n6tGuCZ?76+wfaVWTa!P0Dcp6lbs&tZKP4+u?8ejEy zCTVA|b1OgNVI-l1_pf;8+Q*BL*Xjwp`V3y~{8g~0TKZ8~UwXUhyUAuZa`fGfV z{>$AJmJ?q=##T}B5;Da-R(AU;HGf`uxuG+19S7ap@mX3K1*^}-r-U-^IW-g zPj$bc-&;bV?HJ9=MmL3izceNtTm)^jb^4dPoN$IiV$o!K`jZZ$5(5N}1e_QLX6hL| za^o>y<>q0Z7Ebzq2|Tla`Isvg+%1_uk64tI8t+#`i?1{q5Q}eg^?Mn@*4`t(qLi|b zxudeopBuoNxfWtfygy#0;OP1)%}??zs9N*4@w6{ zuJsp-Vm`ZAKn0I(!eZrDyKYNERr>L1rJK08`VF2g6T2XbNT!yLYt#PEAK=}5`O*qM|i>Gs2R=Yc< zWjBNC{HXYqYg7_1xH1apMDw#)&FD5I)#TN>FJL~!bI0R{w13-}8#jv()oHoxteleW zIr!2%aeb*KQPit?Y#TTvoL5qzM14#>IczK}xyBK4IjVg|Zew+u6~y8@@+rb@5#%)c z|IJi>{$y$Z90x!7-%ekJjYUWPabS_-XqDzcu;d zh7FPy`*Dj80`s2VoDFslr%Ix=VPCoKVHOICWYuH(kRS!Ra zsMQ$4$(s5i;RlRgV;ojDO1Eu63aL(rPL|+5oUg|QjiqimzHcWN_CLOc=BBu!rqsmp z<2Viatt}+y0*OQ%7gkp4Fvc`OHdVW&}%cfj7ndGxxtyj#ss>dwr=jmDsCcZXgE){?qU1h~HCCE9A% z(@W*|v3OSW>T*_vKkU^N9Lm|*?O*_0hqH<))vFPTX<4D|uAU}%i-d0455CD#LGsJq z7hqORr_K=dMyrVz14Pp6RqwGrJ@;n4b9_hDOcOS;)^din$#A@CTx=JIcG9-wW~YcI z_MNcVJ?Y1CHw(bG@FztPVPT#ZghRKaQdeGE3j$p1;{uv+5{Ze!L1E(AyaLX1hioxH z7w9wOS5$DanPeoR8I2?mI3(nAj}+D41zeE1V+|3rRws!alZj%-k&#H;IFS+jT$aGv zA?0R5l7f64xQTgF9NM1vuyfEWZN<=I{d?!w@B!Wk(ubPZh-|HyPaU)PJnEp~$H@B$ z&-qtZvIoX3E|m}BYZdQsMP=4g+WX!-p}qu77!BopksQF@sqC*5P;y~A5Pgbd%bulT z_j^#%1&{sygYaQ83XUzWNbgf*vJt_x%Xv&cT1ktH>M0h`#Y#2rlch%u1ROH`ntVwv z)$Wx4s9)*IlnGx&-dW|OveiV_#&P}?=qe|Pyf%avU`vVFuNa)7pd^0 z{LM&Th(akSJ}a3_cb2Fm@3p45Y@#B}`U1T=5DzfXO5-bJd!_`)}kYjwUTb3^QkaTC=j%Xa22)OasL!Fr?&6|tUm}Sm5tkXMsiKSjZNQjCtX$!o$ ztgX>&V-|kzZK&l(2CHw1*9@wa>%{DKV7#^i*GKmRou^qZAsak5-y}(ePPfLA$x9Hz zKgDxRcBBZea%Z+T-9CAGKdtYbnUZtFWieZ&$%`~fSs%i~jmKZ#t@ur`*4v2Xc#!o>~ zd2AYPD!ZPIyp0Hf76#b{menn6EU@Et!OIvgC%UJ63_*6!82Ht6opEC-E`q@dyl zIuW8PQV+6cTx(_D(RXg{wmL6~jocIo>wFfIY(QyYvJ%%KY7}RuA<3wrp=4`0{aMr@ zu{HI1azOUGcd(w3kzWMP z?NOE*mk$qo9P^YzW4`H{mS&dxm^vUX)YT(4<`Rwe;W{~eUvO{+V$2o){OA`C#KR%2 zM{P3l1@RG7H>t8dJXIGR?`P(>?jpH&?_Oe1l{01~jub{lMmDId9Lgui3w2?+1jnoN)ZJm;sTQ<&eeTfxmVp^MkrQbG> zUb^+=jfenkx@4jCLnzy_{VhL>9E;&=J0FEE5D2j@we)j_LJQ@rrVGE8Ay$W6^oJs? z?~As#X`}sC;4H_zcer4>HSBp0dE4i6}? z(UMimPKWZ|;G#cS&m3iN8{_oGENJXia8vggmk9^-wU-13ezyXh$hjH5d=Vh36W0`o zJ?tfnSz3!VOuaio84upG(x(-%p!ie|f2Ek^>#IE1&WY()&6m+HgkG2VE$=^Da&&kg ztf`VfRKub>2l0NTBwlW$ox!#kqZn7HcblDdlFz9o#atL#k ztz1?l+*Xw(#lRGTil__qq!GKEL6&7DY0w`WDvmQ#sfpVK`rl~YR}UT3CE{kG%33G* zKF?~m358u7?+Rrvejv)}!}je#f>Bc6_2i`F7eNmKuNl6DUaD|&rny2G=Q=^ zp+|sZzioZJJ#|piuzMopj`j0J?EsW1)gbhQHbUX0F1})*^#vH8e*x+Wu2F3It#BN9 zf1JzDfP)+s)W)ul;%N}hwcGRp0rvOrGcJ$43eSrXm^^KCNn4J_kNyI8-HOEP=Q7_Y zq6xed?g^AXB7XkFJ-302eQcM$JdgN!*bd`IjQN~tita>W!M zQb!77%F60qgmd@jz{;fabTE@E-^DMmPKJssTZ_t6oNYs+DRnhh}ZliImEcEXKBb`m0W4`|S++fm)c4ej3 zF=cv{>rz|H5;uF!6Cf=h)&W4?%o0=Qu~@Ibh5FbhWhKHem zc}$i@Dagi!uCuZi&(<=addQ!p+Plww zi`bg><^R>e|&T_sw~BDT5A{=@c%0n%gD^TeC6rR)Tyw?%s0;<_8% zefQmI>w-}Gl!pBXe*`P!Pg zsB*R0&sq6u{I1J`G_Q~xeR?m=kKcS#L@UPY%;c6&KDd{m@vSZIPDX&m)@FzidmN{w zgLo18G64)Vgqg|(4_ZQ+jUG@?#wX)70xcSC0`}SVs+}v?vEyEZ_Xqr*! zzS$&~a!!scR@rR3^Aq2&?MjK;6^zV37$*C=|;i2i{92%sZ^Jbc~hdg+V}XC^@>ZH4ATN_o{je- z!Pqn(x{}B*-!=?PUInz4Z1!^T*%*Jg(W>kEG?Z1a=sjztt@snw;q({Pap?w*n`x|D zlckE6?>9~ECowcWbo$!hekM48h+Q=JeRh3x{p7tv3w`=${1xY6H-%u~K2O`KSlH-T zxIE92L#VRO6P!p2DEAtf`JPx<$kCDfNw28iR*F~opI{O=jEP)xV&gS;$ z6Zm(ZU_qt4W>;SXCug)j=lS&ihq1qa%Cg(K$6-Z4y1PSZM7q1AL`u3ux*MdCPU&tz zlm_YUPNln~Q#$|q_VGD-&ifnR_{O-0qM}~A)|zY1x%QP=aHqU0KB7{Q6ZqnJ4;WU{ z7OUqfS|D}*7G0H+_ZO8#g@uKSJ7hky*W%&kIU879HYB;QOs^-j`L1ZA-TA|+a*TZL z=h6;S>XlxGm%N5jb{p z7Ry%}5$5UtZ`nZhFpvtwm8{5w6v~GfrB9(mM#96wzUF=)qKl6dkfOKTdPTTu1X4yi z85#8aRE=6pkHxL)qks(hZMLTgy1m!DD?G}=dm5F>Kg&0~eYdlZnWFw*^U&UJ;%uT`T{^?D=EI z?}(K)_WRxp28A&8s6i8)Jan8$Ap>yzbZ0`PO7Lh&Lk#Ok`Rba$=;lY2pThFNd3H~j z+?eVcW?iirL3P&MUm5=Jsp+DIZ*fl@+=;GzI zExo2$rkWgKss%r(ip1U-{)K(LZb+i3f^&WDnsRn|p~vaVM3S50`a9AVc4=w{NvEPf z5P^>ULO(6sJrqc}kIJCNe&!t-D9GWA7s6ken}3V5>wB*{yI$9Acx$^}4IdI-&fhF? z=T*{wo`ncYQ70!ixH33UNoci~;^$s8- zzJ^aGxgTB9J2{w?C&*X+jKN_&Z&p`E^xE^Pm->R7=EcyLvHWN6ic$^9F19-tx%gUE zwYpzb_VI=wn{?XTQsgjZOhgoJmjVoeC}TCDt`~51JA~m2&RM$0pf6d^Wx1#wBR( z+#nMC&xa@!#KmqN`F&6c{O1qJ2thhbJ3pJMbEID&VU>U~naW3hU8waLA4yc0lUFzL zgWrHO524YG1O@Xf7c$Izp)|31mBOQT*W!7}OO%ZEr{q$XY@LJH!SdMOgR^N((}H6f zk5~JuoDIG7ivsj%w>LTDDIHofWwqn*8Zj1TU-p<&JW_qTvMm`$u(}+bKO0#DU&n1r zk1DV1P2HFCpkwFjc{)vBQzQ5Cs^kBzMkzN08|}ZqLxbS{-yiSS5QHs0Vdo@T9H7^m z{Z*jQjBleq0rhErY}W>>gNF{VoCHnldgK~?ma<2JnGeCHf74%ONi~fgN<#54;SeqX zJ!bh5T?7qL6Wu|)Py`Pf%Je0r!>FFv#uq~ztHoZBXho^9Iuzb5&g*>0(Vdo@y7^iz-R@5n#^ zNl)Zjh)FoURy*;G;m0^!He^~_+Gw#Fu(i7PcNcocZ*wg0STF0J$~@l*Wm>~fRaH&B zIM-e4jp@e2{PKf}0*1XnS>*?Z#w9HUL0tFKjwKcna#+*p@-Ilq`q3LvGBn4XIBSBg zd+_FE$aG}8^Dl#nlqQhU%Q+Ru^$3pr1U|%+V>~ z;~O@0#FNb*(7JCA35-s*#TMBfa(y~&c=>;$fG1d)!QogO!0P;GcUi=O9Y@HIN7=@r zGScXDOK^5Dd1^z<>ckMxbQ+JY6Q1(!WK-efU{+QAq<^L|U%evFRzi8m>QxB|1TXHQ zQ%d#)dd`VxQ6)9j$u9B+scyA?HBE0#h`JYpo1=L1LAgif>{ED=<`A0!RUylORug{? zD#bgtp6}ARurbRx==3G?x23!!XXbReZa0{|EFM4T%u}UC2H`pTxi`duCjWj|$Wyo6 zfUT6ALCYBZpWOw@OBw)>INm*%@H709dEMRA2-j#U`tAzcZF90eKMPmVB^MqVDmu^O z_#riw0oMpiBfKL1cK7b~YT3l5H1&I(9N~a&sZgBjXtSzn-(^(vXuO<*jy1iAm%5;UQY8|%$>Y~k)wTXtjou6rq!FJll^a8~t?ug9c zbOOuYZk?d%sxH_pbw)IUO!HGz4?nfja9rYE@{}bqJ=>cs7OT#CZZW{s&pkWk^PK2^ z&Tu_BKrvPkAwGXk@mjn$KVsddqX+gjS`-&3Mao%to0X&we|AwkfBtIR-7WELNG31Y zb2P!?D~0KWkU09$QUyx6>U!gIs|I$5{1t=!23M2W;poS2LLb}>|#T5(Z`#PWL&?GX7ibD8B{m{=j+aq?^4-wb~~?&Y<7OgnP$J~3{h*g zr958iHTcrYFo_?p&0!p0OzT5M#{CUr=xS`p_6194p@KOA<7{O1H;x|m-i1rs<%7>j z#Z13Rj9RCoP3jlNr?Cg2p5-V2YWGbpGjX=2$-g7Oeng#;Aw*J>iNvRXL!!9Em_m0# z&@}Y;r*UhF7xmY_)7vlf)rFavY0k%5{C7GmRRU*x?_>$7jpM0k^}Y8)waRyKZ#pr2 zi*2e5e;S1W{=2iJClwq2>kpE8r@giy{dTMh%bBmO;I&x}gTyi~&#Wl+gTYXuhn&$f zzS*fvhDPclFFJbl)@J)1pJrCGXm8Y?(S*ofNI4I7!rb4U`?HjEB*q;syaV2Qw@;WP z4d|JDoYd+GLbhxD5+|oZ`fHU|-Y5Sj8c~6mYEHrR?C*45DhPS_g8>!^i;zruzwf$} zMdDh8#YBfE_^cz1lBl6AXd(q@TBoZ8CCw7RiZih9c2TN-G2aq7l`-{+Kb+BttSaaa;vx7+eW zT*h~oYHDWRQ4w?cT+qh*2@qXOHG)yg1^pM}agI2sDF1UrFiOQCY3@iF4-?dHq8Mt= zt(!#m`(JagTXfiH!u#8T^KK$b#(AG!e6?tY#JwLXr2LIb`ezDf?%Hv|r4yxm$vcy` zV$Eur_vhc0h0k|uE4Z9?6ZsNJ_}$*joNWCN{3y$?(CkG@JX0C-8rXcF@J>tJjg+h>DHbSRW6vKcC9h8ZN> z!=r2JJPTP$ezQoIcUQ+*L8gkmg&X1qRZ=Z5J#6ihr2`eza~7;F65@Xy5lHbi0s=12 z$&sBsI7d}tdS`{|J>hWrGHzv+YJ7ZrhX>QFRX8}Sf`dJ|J9`A@O_ z3EjaB)agxa%ZF#jik}YgKR7aCu?MeEt#P_-7ZF)qeO#yfS&>G){Nv4>PRC*}CY9d&Ol6;^zYD)t zt1rX3*GdQc$=0|`t-#xT<3rCZa*~lJq?F!R(G)?TMnSaooWXBMb`)f_p+uy)j0Ypqb(w8j9%d;r?oB7*(GC z6l7(xrj`QAoA9KU)$K`}i;Jslvp70MHEgd`46l#J^jdhHcXx{3 z&t4ZMnpJ~oX{fa?dvj?wZf=)MQ|{iV#Og-KVUaI8d2Vucd={V75>J$sm4)`k>M)8j zMAO>Z`liWPzDm6(hU#ULaQzynufA86Q1=|9t@EN3~b7IZ0ZUMX;f7{ zJ(txT5^h1t=tKAVD4iR=-UeF`at~@wcCi$WI6aZfi=Wcr`zg+dcajdG<7p^zh);($}D4mynj(|Dcq2IU2pOPcTc!ap-ihR7~vcZOtTmXu(*Vv-0-*hz=D zpE108pb!=1a(GA%;Kh4;<6#ZPm|XoFi9V8(>1Giuj)4noieegSVj`lj5kgL~a(m=J z0%p~LgWE9~F4yCaVkBi2QIOCUGF%(KB4! z#)ZCUvY{meg%5{kbed;)lQ(=f_*m8M*XgOJdVcy%9{sD`I;I=i9=q9iarg>&&KINE zHja+zUI*DZIb{}GivGPajqkEtj#ivJhA1v#W3evN?uPbexg4+9_805VJJQ8uVuthN z125drA47mI7XpYg5q8mY;8)&*0JRj%qXVGzoBFePBCKlOgyrDqhYX{AbT^VEipOW8 z$8)n1sYxjr9^GhB#4ILXz1kfqdh(9fV;jpVM92Dkf4TMjV;n@uw`?8V-IN?0udlGw zE5lRRTHjxvFE4Mw%cG*EHrqUOotr<}9Hk5eEEBXaTzR%}F`7>W;XxQ-;9v>|tx|He ziOPQPIM?;Zh0f^u_icymR3%`kR`z+^)9$ z^*pR~NozED7_K1G=0gM@WJdk|F>>3H*PRrns`8S{&p}Rw&vxrXmR#F@v(;8v>pzF- zXRl2M3BDIAbuU-Boo=hpYC#OY^9yvUpM4Gc6Z*|Keg*3#I7qf_qqRc?`_M@k>_ew+ zF=18Ss;{z8RWDkSV6@4961B*&Ny4j0iVCX+(&l8+3-nLPtD=6DO=2k*OX;y-RLJ%# zjx5R`^_wy+vc13a*d!IvYIHszArWw=Va4p&IIj3^9Cd0Q93|-Gnftwh=F#4dAFxpm zV^UMYx+6*ZErMpNtygW``R3RM?idxypGZUy(Yoasa<05FV0PSAzB&Fm+{Z?KXEj}g zEFOX-Rqb%~)l{v?BI%}3CgIt|TqaS))2R?79c^0UTYHUrov6!xVW;j~_W zfGA7>l$r;G-Ax8EH1kkYJ;-RKj{qvGs4^I7slkn${Uqbn1+heSzJV9Dkdn8qrhOtND>@~gby zmUqltf@(jeabAWpfAIFeytpbTDYa>ZGQ{i*!EV2geQMu6`DyHBB|#8 zQ?ZBN=foq6X0wWIdtyL(1Y1HZscAUxWoJqA&70W4RI1QI6>_~RT-t0*UsiN)|C+6h zgGhh~*51C1*`Y{zjnE8BaZrEIkaO`xAtzv$mAW|8H5=@efTb*B$_^d!>5W!NsJfuHeV+Pwj*+8*D&b7XXSBh zc5;Zx`_V#IdzHnMPW+SI1^)TS%MR2_0(L74CQaj1NPhW13&LFk^DnYO1d==+C;u_e zP$Jf$yM*c5q6;qZ-3ie|v!0AGAfP&k!!SsAf637gC`M6o@+~I$cwsO*!KhhkyDE{& zZx0(!r_FE!_%eBfdht-4xZJed#H1@U{1z5OfFyHoD!#OH>PPpiSf0(<_eqc1%btvk zqaJnlgh7?+bDMblD7j!@VHxv-lhvdUvnNkXJ`QTu1$Rf-{`P8)&6nM}yMg+>%M^#kN4M3gJtq%M3d|)@3Ivc1 zCH$Gn9QeA(D8C}OD2ja}EnzJxewOPTIvr8uY2L|1K{cQ)&9|CC&+qP^Dt&s{tD}`| zkw!D?c6;TRe9sVHX@-}PHC1qMR1nkxa2XN~l=16q!`E)u*IQ$?6?U$xKL+y^ zb3=OXkw6cGB<(@rFcePPB@h9|;(VLj&Wn2mzCSxTIq5h=r#zhbKtBBppWB_w^Lmey z`;%Q9-PBjt3JqK*ekOQY{Bk${!xXBEg?5Ab1=9DYa81k}|xk;`r~I%o8m3$eKv))FOlyn>?8J=bg!$Rt?!Z zY8f=^lxrIdXE~G$)kf`v$3QLm06sAZOcd**T<%{GKcuA>lNwG^6spo}a$4pPQo z_{`n7@fglQJ6!Xl0|(Mc{LsgLrnq7z=SJ$=(DQ|~iu z(NUwCV)rU&d>8Wlf-jVw-C{CjF^3Qm+j|W+=JS*}^F%$PrmVU}T3Y&i+8%hmG#tg=cv;R?b>@%e7{=Q> ziJlB%-`bz9ra3Qmewfr%-RqB{mLNZZZ#|d(vP93~X~1$x9zywZX<;|T8_mJLv;fy7 zG!LOsz46lni^Yw>P2!lAWOnnnnlQIhjmD_bYBk@>^R`;tnG1m~HDx;VdasjF}IL2#FTVLqbIzcF+Kg z63kx9BFg!%$iMBZTpRS`FvgPVMR;6WHgG%SGg@RY|JvqKAV?(pg@^tkWtrdTSN!V* z_)XL9Mzyr0myqf0@#jEmE1X^M6SWZ$d1XVFr~9Be3rZ@52{Gm%2!P_mx9nL+CN*6) zCtVJP`})S!4xkwSmEd4uXI5$-e#JO=$-Xv<&wU(lEH7Hic~z$|t6K^qJv zIeJ#_&l}>K+>%nBdRTT=Y#JI3l6Tlfof6(1l8XhDpuO|A@nm8^Vo&!Z0FHdIB8|$o zs0Qq!Q=8uk62{Es3TLZ4c>TzRqF8-+gN79ku?^Fe>^NHSpXgOU(>$2n9ew_sn(FZC z19`}YD~tI$z)n?)n+6@2S~uNYVXD`z1il6S;x2o+lx&3@32ub=E?CBLpZD+Im+e$9 zuANIr;(=aW$sG>MHPMD4iy+cF7*hTaOU)|1{&>c%JU9gx2$echsGesYh)M|CDu;A* zdzesZPW+G%;&NR22*Flct@aR%|NFBP1}%&3(7pV?Xtjn;D7Ku| zB9c|Wr?EKYyv*w-(vp}CDvJyc#F(B(wGud;7h{oF&()BN%SO493skS!*xHVsUbE92 zF|hiGH!psV9=Idm>750OITK_OpI4D$Z(W?nidMxp~(hpL= z`%Tf4IIT%KDkvlO`QPbv^hD7l$yJ>$G`bzNev~S=3-t^tT!lbcHl@kuDVpwH{Pz1q z9jw0)`4lBcQD-h@VM%|KfEO)Kpt=z1sBK9r%cQUR9&1y^aTp<6Em&y^o(Pjut=Q8acqL1oHzhk?*X&`=`DOZ~Mh>D|9?n{g$N(#5r zbedcDYYwZ0hG27Ya+Yh=pqAd=-mb*{Q>~+Jxpt&Q2M=#V+?SZXx3|kX1^urk-+lb} zQSbDNN+PQBdk-Bmujb2}XMdJZ9-oZ@KiR;lzjJ`$p^?=T%ae)NfSHeiS9Df)2|hkCd{yzTOz> z(d*m3Xz$pyx2NT zJcqt6fi}8wi!vI1hCcj7wA_pmoz8Wcgs^ROa}=Zf{r&PqOCzY#0XUq=lcd(WI~#j@ z)|tJeZ=a4@ACn645uzw;TLYYVSoR^`0=x;fhKwM%CP0mLKV-u^h}osYZ7_Q1rHcXA zWxPiguFFrd#=`>8euUT}f@j2}N8M~nWOBVyFOB&AxK8l)hShAcxabmPb!BB_CpW=n z`Np+V74-Bx-`FWp$P{{5aUB^J))BPa&N|qKy&gRK)ilPEs$lxjSj*CMg>f#88ynXJ z{0^wp+pL^c_m~Yz9d}+EN<;FRtMt{u&C28Oy_qVN9~M(z;Z+J=kLz)=NkPu)45V!2 zH+c7J$|0Ezg7(oN8@ z5>ClMXMG8@m#CGJO}7GEU&E~p<>krA?#Ik!Wn9i@3@@J3>xB9DiE{>3CB|q_DfDfX3 zLOffoT5P>g4iiVGI*~e6$kf#0EE7-TDfYUw2W8?795ZLBmls^?H=7{4jz>_Bi1+J5 zHXrltRSd`KRA2FLJlXE*?p}=(@K|%^y`6GidJuxc_@x2YQYzhiPR+IX&AK$3#rGGX z203z&c^gRu2w@QY+rvMq)Ccb(wCAr!7=t>4S_~K@36X>gV@r zdWJo*5Qg(?@tO)N2$EFf(R5u7aB0Zx6M)esrb4LuVud?MmBwW&l5p#`5m9{dv(mig z-6>tMPAyc_-kZJU?d=fI^t!xfyGmC6o|`DLMfAx>qtk7ccaHeYrX|*GSLa!)3L6nb zKHi%wNmMsRX}3Fpd^ACPXi4pLfxL5SI5X&04^!saL7VW%XVJ$`tK?ERa{$gt?xHLA z)vUA#?hu@hmrb!AU( z1F7{J^^k?n(`;8u zUB6L1O=WMs@daJUrglR835@M0rr)q;SL*vhGRXq_`vwuxd!$K5N_2S?oaY0Or$eSi zb=;62pB*GnnNJkbx@~PghS8R@QX&9+UnvI26t6+k&7YJh1Qk!MSD3lu>&nt&x#@dG z6Jyz;0aq7*VogRMxYU5!>ASd5fP}0|Z#C)x_Yx zVT*goNzQ>`_ur7M&(`n}kJPJ2_6zKg|W=4KQ$QKC1!7S_Y5 zS4cxI@g_oBuNd@E@fHo{eWG{XczAP^lCfec~3d^(`fO}YlU3_r#sAdjpwob*Qg|7Q5529Zh#&i z+i(ZRL=)oWikA;8i~38wO^gHW5Bp@wlGs=S9PvNlx)nFCv_21JvhVz0VU`e91?IWp z3Fl;wsmO>B--POF59ofHy$B(OXr!z2yn}VOM`dv0L>)vBIjJAL2XPW9sdb;`!I2HC z%S7W@-x@3PFnznbd`L$;ZwmvTy2gn1>1yP~MNZ^fwruwHp+(R4G(Lr$iJZ>QIz$Ci zYZnWc8N`BrfI-k_U(dPz9I4Xg4UY0H#&M>z1Prel#7$xz^+^|U=>PqMVm?N z>AP>H^?c%M>OBixfrccYl7fAUzs&l_02InbWkVX7Tk7`67ETV^_4G~29qZ^p09uLQlS_-4I*FC;uP?>$RO6ehkA4b+UNSFW~wYhYkzJOgnWyY zDtZKkMnFK9z+p0lM*rSdmU$J;Tr9qPDeK_VEKuI3CAkXF4{v^!YX{CY$a8t>d1x#BOyASiR!)Q0RdlX05&rnt&t7eYw;`fC1 zY#UmK{BFD4?R0o$hOtAFp6?3mWpFnt4J%`L$j@AXlM>cz*@0g0DlyBDDGNh2#SxE_ z&8UGJS?MtqwZz~04ZAS;yKbk08I>}A>sF{~lD4GoufqcEA?y85p-4$dq3=&sQnw}h4&NSf16)2BF8v@|~Z=|{TjoU`C zHs}NjqiTw0(hS%FjeS+aX@Vueq;4$93Ts2f(2h&q54r3vO6PQbCE`A;OF&uhr*Rp8 zS?dXY05hKocf|8|wrGcBi}81>fwsJwxcfGp>Uh z0R>JVxOMtFGPYe~>rPPDlbc}DLsCV>A{Albfe!mGdlhTtC`7Cd_8z=r5SrmVMv#z5 zT~pK5?gAS+7mmKmZf5;P6*vdGao)Mm^Wz1tmvg?$$_ok#63Oo67Qj^hHjc2RDK)Dx z-WVI%5AV-URXNhXOylvNno^6U(I;mv zN8~Id`-}u<*V_|N`UO6a%!~DC*o^^G#3a*szFUF+|h>VuJj-S zto<6cHSV(xRr?=3CTUV5>;q1N`}s{*SLR<2M#vLBCEeOp`aWZIVCRP=0CFM#r@$bv zMurCqR&e!~=z;&o?`$I`>`Yy(PlU3fY?h&g`+zA2Auk8MuWfb>z=ZuE zmJcIpv~V%nU8DGQ^Tg9@I4PrZx%Uus@=F`opnR`7823cH zd0O;p`DjkJcf1`$MX)g1MLlEBz=QBZY!{KAx)MQ@*^P!UY7yao7&S_Gh{5Mzg{+EP zOn9E?>EYAltcM{#2m}Gd69H0jQ=G{!>lnjJGN@qb*Cjfe*?_KyLxZG}L)-PF1FnYqkh%NU+8@+CPI2T<+neW=a zsN}1bEMN}7q7wLtK1S^uCgijVGXyu?V4?wxTr>6@OqvH|(lR!>@*$J<0WxVQ|2=6} zB#pimG!=z0PWB`Ljcyewa>A;TfxcEl=UB$S7@i!^aTr3ezb(G-b)#Eet3I+jBEs*Q z@?kx27pSJ>AZpZNC<)#w6EJCfr8y(!`tUjDX(;Y$zk0=5C9oWU3oCACpn(d+S`0DQ z>tz5MV`ih4*$hMtUQm6i){6oc+HW;>Dc`r4xsVo+^su-v+Bqh+EWhHmH@J5kMvweN zfcDJjDRjZDJ`OyX^fjPz&(9t8o1LNx3tybX$gdeH7`b|x;aGKDhBn>e*c%PUlLEz` z$ZL1@lbjIfeOi@<#NIP00F6D;33I5xMi>31xv>4wT!4oFlH|xqAW4o{6d((HNO|z` zAAcNB=-swD7E}F~#KtSR?eOsuV!Yo2qPJksXMeF8wFDJE8&9{+ojaM$^w_Tg*gnX) zxYRrszM3lCSZ^s>LS<(b;Hwfq{$qLYAMgE~!(#_)L=4ubU_R@QtXLY5new>UCQdxc z5uX?SMSRK6RypCf7qv4;8bz0iBjf0KnFXh564zif;FE`jcI(ATf6w5juW+n>??R?a z-E$5RXUnT%O z$uJ`LqaF*S%|+5y$%r1Al7=g~Jol3*_uIo|Q8v@>FVxE|IuY2c=F}=&OcNn-@GE3n z$<%$7gG>%AM8t6B1xNL_WLx?%Qh#czoNmauaF;ff7RRDNK#oi=fy=Nk|4i#O~# z-aR<4c@wh=C_9m~E1i)x{=v{(6h4wKqA5zAedA=D<>a+hdy5K$)glbNfZ{6ZpItj8 z28#=g+&t<5DQVDu|KnEZ(k0Kipt+}(Fr zI&>L*6`?H@cH0_*`N`tQkK_29a8Nl=9N^m!-{Nh}08H?2fdRe{!ayr}l0NVNC;Ko) zy#@V+7#9XvI^_rNCugufv_CRK!Wh&`S=o-Y^TqBu#~l_& zlP4hY0D`fvd6*=CimBHPNmB;bD7*_kmVr$Mlh#$lWH~@0eopw1e6x6XB@&UFyVjK! zI)ks!Ur4#%^h@s~irJ~k*UH)Rzfu2&X!+D=jQ-kgdl8 z6LBe5{f?s5j<(z7h@|X@p}Rub@czBs{)_KzswOC^H8j5a%`PzP%Yolqyl2#&vg&}; zN0pgQcm0Q}{*r8s8UvzSJ1w)sZv@>#>~peGl0{S455Okqa2zF@R1-1x-mEW5S%*MA)#dudp z+KoU!-tlFe@}nQyuyRl`%P-7yIA;PA zq9I(36;FW`39|aK<#&Y%W2#Nh_n3I$x8-xk$ViHg4*(aINVECnuK~Oudkke8vY7%M z1(RASBwMD|pVF)7yPqW*_}oQLV?C|CwUtJ#G?Pj*wmn{802qbji!$mQksfT{ zV$T81(g(m_+UtM_V)fQre0mV8KST5m>4+W3G5q(l8{u8%YeiVteNf}mVAIa^U6>fF zRe!EaD^-jlS^?3MD;OX*yTewBuVTEh3Y}C;IAjldFW~n^3FBhfKPg&<91mq%7vq`R zpnH^RcVR?UD^Gs{GCxR~<9lsV{{&U=mPZ9B0Yg8=B}cdBu!RH`4{Z zNVIj_6@vA*j@M1bJ_b{9O%!Q|0&5ygmDgg$=iR zGoHKpcLTuX)pC2F$yk2W8-wW(Y?HZ~vPLq!fAnC8m23g+KhFTZcqt0#;YrlR<%cVW zDCwQJCSPm_-rrsjP{*EI*+lW%e9C4(Ck#Sc(IeAJ%=jL&rjCWbMG0}d+c&(`LsJ#?D!Lyis_ z9}h3duuS~Ro~3Guh(JN08o2sqop-%MDu(SSj+s#90)0_G%~cjpkObVQ5d$Y3%Md*8 zcJ?+n$Kd*`#{IIqLBQ<91c^{Ut0^yYXTTZl{N?{IzKnAq!K>y9n|S0AHg($M#xgYjtd%hrh z1mXQWn10n9u!gb!kbYm&z4dJZ3#1Aq-;n-TexkKZ0W+Ttn_ZSA?BP^=VS#0~YR;y* z9tnvIFxo2Bh}3_$Bw&Op{hC?-+m!9!e~e8(@**d?5hQ4#6W{U3R595U!9p!)lPOHq z#9mOMo0!mOJcg!O@YJY)t=#z@bwIoMV+E}S;@S8C=~}6!)ED}Dk7=Nfh>Xa!!o{@n zhd<8uS7AY%g887{qOI`IaG6oCJ_zn6EOaW^d@PV=&mGo70R~3p^5g&G#5~da2@NPV zz%S=G7QC*(#i5!GIvyhAu<|P?FcsV!fLw-kYs1E+mc-%Fh2(HBO8LnU#nA&?`lt_X zRq9KZ_=P>pfK-hIY%d83{Cs>iyBD@KH9_~zp!+(@3TSN5FF@>Z#e_iRe?MHv4>d6z zU@qisu#{}X#_@v$nzA!WW`qH-26=pjH{j=gLdT1iDtI-G5p1^CB^v&bd9n&EVQw45 z4R>9H$=(>b0gq310`v1}Om$hDb?`$X?cCNJFhH^WY#rp2!mhP~lQ z=0hKZ{?1A#qTqD-h)4pO#JFyV^zw*1S)@aM0ARfwFhPm+0rtNk3y76~fKwA4k&~7d zxpvya8XXxNL>4U837@GnH-|Cfx0Pm&lO9m8O4iM7&0PBgvCsqdl`oG$MPZ=}`|2scmM$l^yK<2s| z7VLVq;ZBc9qg}_w(|AFlvptRo3`XU4Yz~0v`Gujk;1lUK3HnE4Sq7q9!We5pa%w{B zgW|MZLt8P!6^Mvm;iTJeav*`gMV^ysep1v9^Jly2#XyUIYikhqW@yVSe@j1n6FHKR z*;s9Uo8gMfUM@yyfhxvNz&xV!z7!7vB61uBcP6KK%90t1*#+UBGdc4wvs5 zigTQx1cQhZiwY=^+_FYXv4aMMpyNpqaP5$cSZ@lj?({@Y1yJfXxtEs&(IB_~+cGmj z1;G}KFO#s2Uwv1u+<$IWkepx}-7}-Y3ZgU(U^DHjZBYIk;i<89PWd7y)&e|ds#5}z=KX^3DtyFzBz!JwScnQw3^i!~& zpOTA`b!gl|4CNOVGheCEh+HZ+Q3Gr%tU>@c9i24h^#q4T_FF01wJOtZRI{%GOf+yeT`%6VXji+8QViT3%eW2>52FGT%(ofMTrWs=e-82V#EjbNTfqlm^k|UfDP?bL0|(4#tqiWw@(-NSxXBDITPWZ`?=Cawj(q_!mfm~Z^8+c+Y<;tEHJv}J za$N_QCo3I=cEHKw5M4T6@2Bc!@w_l;sNqKeMxb(J`)A)ZMu?YcQ7Z-ZBS8SjN2wR_ zNBFX#VesacuV;FUW)jOGysfkMue19N+Gr@zCwI|{$pFhsX0Fn$x^tBs3jsN8GGF1* zFuP?4m0WVBTG<<#-HpIDf5a3<0flU}px!IR&TNOW#^45#hVg_D94M=lD$5E+Vn!A_ zPOB+0%oideB4cIlK(#+Q6m6K0s zc zxIz?(e_{J98QGWiM&`Fc7-3JZHwiG%dXbc<h?Zuh18V!j7vrbwVMm5Ai`vSx;o-xyzQJo*2Kaqb7e~ZI&aCYwQIA4?moIYdS zd+h!M1BeNI1#q{g=JG=wC2O$Iu-U+2UW;(uakPrZ?9SEJ*7h+CRJ(7)Uwz~{1@$%eb=e!xm?WIrb<_x&rKA(U)Jc*mf z_{?Ii*=v!GnJY!fb|FV1T;!Y4VEO#jp?>?}b+NWxgvnO*LCeFSW>QGw)CccINR?Vb zZQN}eTBsG3RzSKqkVfyeu3=WFTa6;}3MZ*{Ivf_6(2QhEusfo6K!w~w0Juhf+(pO4 zpkw0)9|pkzRh3deKqpR~d@};veXH8GA5O?QQY3>bCMhYCp4s{{6;R*vn3GM6*`=k1R1|#6d@H2itNCr$Uutk3rrK|P4(n0&{g)Tg zr9YyB~{UFaCDwt!c7qb|1+Y;weDbYcSI1Aex+u#psL zYXn2)g0P=2T{b7?%4xP{%f%5py1M$FcievnxfibN2nq`m)4RWujtt&)=P(%&LMU|H z{w~~jbxPicYQ{{!ZbH^igv+3Y7Wn>srHzl*{Vi_y-5p^z(O~PN$K@x>>+AkN3eIv! zVyOWxaIxvFFn+EMQc>!c$#3maB~eJbmW1Dbh>d+>$)Hg#=80|}4^UQp3+N z``BV{SRyiUZVpMtJeMk=KQY5zqd(G~^%dy}G&FhtjHcvD4J3hAAPIQ%+fe+K1dx4j z29uZf=j){#LYuEq7&X3@24DDR658z%6zkRpq;Oh`JW*GB7xXd2P$q%SN*CaY&QRQH z2Ry3lpFe+!0=Df{rI|{Set}aepDPB$nu?*`F(Y`kC+Y(Q^F4Wq4|0e~r66Scu^JI) zKE#mRhfTi*s|gFeG%Fs;P!59pur#x3P~DY6lL$;rZQU2TS}kDPQ>Usi8cfbt`;0-S z`UP6h>t3td%1ZcrG)Gdg0dfiG;iRtD@>(!vP-tjB%aC*&eGV|Bm`nh7S+kX9wG(5W z$C)~hzUmEv)xymsnuoI-zTo{0D^>G-la@xVGYX5&zdY3Rpo; z?=ypP8JW$pY29j`^S zEPCCCgC;qlSUnt3<(3oy16UsCt!UnMl=7>yB25$14=>336hrMgBlu8u7nur>x^k&7 zgYW7>ahN3R3DK{JllUR6Et!xDW@cFP0+pe%JB~o>N*_jhdV2bCfUhvZUn3Khfpl`nsP4sjvN;(%rTUT-S7X zbpVP#n!dQxuCG60MOsQ~v@fu0*P=#o)2DY{!yO5*U{qT#c7c7GP!xVcLgE7Y;zj^q zrp*^T{jS8luXKTa8?Z5$RxnVc)5w!InE3F>qHlAtgft@0=*jTKjlILp#2^-{Q#H6? z%t;cc?*Dd2L_yD2+d>+Y-*}QdJ$hW%Kj~3Q3@CwT4`4G1qCfbO9%f*f?*3Io?tO#GxmfAqYW;KZd)H z4g1H^rn)oSeFd1BExJGTj6h%?8HAu*K*pgwTrX5tD|ab7;aoeNJQ}J$Fx%IB`vamQ zA1M`Sun*|gpaD8zVB#F~9lUiaKy$sn+bJRPR~+Pgll@46uFh$1=6KTCac5jKhDuKM zEA;M6B_il)Q!RJ&Ppo%emyQv;1Wkqdhb=xVI8moJpevuM+fW{;$7aqN|J|hoTVR85 zJ_?&#hC;mT&!^aM+KwT%#2m1UKM+{V-}?N<$Dhle=dfGw)wv`*aH{Yo`W7?ZB@86~ zRa)^uS6R-7lo@pK>C49A?a$S+Lagp2l1@gQ_|WsK_c!lBTork8vZ;Bq6}i<;t8{3# z*yQA7hV+k|20RoA&Vik9&|fWrf$3M;%kA#sk$fCY)@SP|bcPNskEHbp%bA{X`nRld?HXN+0^Opi|x7u z;Y77>p6K5DF96#5_|!;C+}I)j^_T+6I-f@#(#whEpfdj~^{+_pBqOBkOL+Aor5uAK z&>j=e>!e1*Nso@I^?r2*+dKjBhj@$4(uGOnX7_v6`>lhkQYW8jk#|MKe#?E_kVkY7~em9XAX zws_+0dV<}L(&ct$KowyZ$YxMnHEz2#Av`=e=XV=;_QNR5YCKYKWi?VDnp8fOP3ms> zRRK9mz|O>H%0blZ3fdql=|JwZH#-Q=1Am67A!`a%Rd$=a(L2R4V$J3-q<4uGtP6X>O|8(vCpOr=t zUINK#s@xC}g_tjBiBb}cl=J}YdWDLGdZfnIfX#9OiI~@suci`}_0(S1nT8DSw4s+bSjo#O!S5Xy}gm(o)pP}^CS^)1#jrAbave5d}FNl?47 zjt@rxmiMBh`Ktg$!7N}b=h6SjERfE)MNwyr?NwH`uBT#|RGwl)(TB_gK(l!jvBY@e zV{I#q&@A%c_5Zv6;-c~i#eKGP7>3kpn^P-+MfTt|BSO$4zfGx z+FIV!2ypg?!kyIL*3%(AuO|>*tA5*mj2kSBl3CYXQ@$Miqp@;?-@fik`iEDyWf)zG z;;~sRlkOs(!dtnt%?e;8$S;qg?V z^uWyka?{z<*&*9Je%W;9YXkAwBD>xNzHJY!-uTSVdO`1{M?H=86I9LfFJTE{=2Lf7 z-c2c^WN{0ll5PjF9ZQWz~kLPMwbBJ>2PSv@`wp zXi1;FCRNz)ENg|1tHqJO3y~=r5gM>Df4ZZ)!gs0CfBO z(2B)QD^E0QiVyn5vU;`>e97pw$vaNHdRv(@!|4Q0&{5fy49*IvPICFTR`$|CvZ!4v zc%uqWk1BHTa>)Snzq4rU*^_;CMYIZ)#4W82hRui2*mKjU{Hj|*tWL3Zz61DJAKcAu*{fj1m>?%(lYci0YW zs$o`E;UjPi>`twEjZ3$vYj3B0%G9IXW?TP90zH6$y6wPlz{)&Uh z?pd|^2dSvw$KT1k4k+95L+--|*M3*l*1HfHthevD<-XQkdcoU|Y;%3{K-OxF{z}7< zo9s1RvN0uWi*q%VtB>fFkSAZTLk7#q6v)zs%Q2oWObD#BAM!;Ua7O3VMT@1RWfe6n zuh#u2Elv8ZM30ge2&jo)zAkVa zhgTL?{izM$L-}%9ba_ZfXwKCfQ$?ncvr-^E^h~_CM2fW~{sok-OA`urx|p=bGM@A& zP^rb~!&zxYBjCD}58e3qF4qL9D5mOV9f8tfD-_dPan5U;vQP7l&wJo%-Or#|rH9K# zS)j1|0em6-lA*ZF&uWXUU?Fb9hr}J8)7EpV6$6{Tf8L1Q1Nx^iw|~^M3cam!i%ZL1 z-)D*6*s?`MBoEqjRhop(w%ZKKL{hk3$7*)119fXBdGSp_;U(XIPV6t7 zY9wH5y}C*^d0=vhgTLv8zI+u?uAo`+NXj>uL|=;F#@d?J@TZiScJg`(YSsJmlo40T z16pFD)sIh2S0U*UUZRMejOOUM@&c_;TxrInpkg2~x?L-F49q*iC9z2L7bB8sIX` zM7I?XPx!4qm`OOKKRSxZ&(ox};X0e8&#d|R7+%0GXxUjrtWiCt_Ui5ZQ_%K)`-tjr zCXt(^ObJZ`h=Nl#wPKWl~An-_eSkFqMp|CN-r2Yetp3$#4y8m5gYd zT~o{#7C0MrkKanId88^-!Rn&~4y(}RXgPEM=DS0vk{nFnW_JA{-IBj@!X|qvsQ3cb zDRSvqQSQ;+%N=3OHqeSw-HbLEbF!v2#7*{8-9 zbL0GR!z@x5X_FPZl&6jli%|GxzKj~Tj64s(Z8v2;ZtsO&N(yMR2y5ttmDazKtESQJ zwp<}N*`sM=F_7BJK5EuxylzObpi;>;lW5Vt&VuDDs>}pe#w8)>&u!uUCVl#eX+$BU z*Kbcq{h!uHIw>I4QwzJg`T?><4_jT$vGGm!!ip9zyLsP?y1gdRzj^!pn{m3;eq;PY zi6(jc30qMh3+52wmtrD^9?t;Q2kNj>>EbchtyU;rb_HdcJ$4_$JRz@Rikc4TXq({M zSU8bU?>sMLc(Z!KfZc&4FIzBow`$Xv;nVE`yV}RT1u}k^SvV6^yUbYg~RuK}&uI)Cf6= zQ8p>w;EY4m|49wOA>b^q{E<%@K)2D_4!@I;dMIPJA+Q)DKls!v3K3E0*&zATrO8d7et_{SLbjdU_ z@5|*oxnAdYp|{^m(;-A~azsLl!s z2F(Z&R8srth)aP_>{BYJ#|qlEL3}W$PnUPt8AKp+OqEh&=Ls!xt1>WCe5vch0SCdZ-a z#UJjO8a>_mR3en4siJmkvKqTdu z8l)-DtWckgW8~I#pe4c6=lBy2f^~yt(LQYJ)s*kliZPd*x=Y}-h>6k05S?@Q8me!X zJSU#^EKEO91kRZrKf19pFUPd?g@bh2iq|X9B(}?y7lzdQg5n)G(s{OjSIn{$>zl}* zn*8^iwr|rB*^w*Xzw&qH?C<6?9mFQZ9}km7M|V~4{b->7ox0i&ujXLxMXS@@t%aIy zY#1%*b}8=~Ux#!-4oy-o@0IC}hwc&j43toMv)d6R(j=35`Je6Z8?U}wD|JoAV<{=& zO#ew}XlhiO3;axA-U|}=2ka@E5ba@$N zceWu-NW=;~$M?%000w-W41BslJq00r1x+1hmO8~X1!&H)x}hr=LVRorrkAQ~j#LwN zX_``eV^=k}ur(v$QUyj%PUyaF!CrnRLkBS)@XR-13S8drdG9Nm4L9|5v77;#UU)~(Ew&}#OriiJjwG+7k zM9-e5Ec4;V{vZ}&D=gH#C#WxQG3O9Y!*!qZMU7>ju+6F-!^fIGG7}8hBB_&Z+2$jq ziNg^okXqp+)!WznHhWx+p{GHcLXB;S)R%2Fpe5A1Z>4C^iuU3#3sz8$tXJ7>UWYMM z`knSj7Pvo(!FynB6I4YcG3|sx=(#>Kl=)PmkoL~?$z-QP>IqxZLPlAO?x{-tJ4o#@ zUBO%B7HGt195pW0`AktQ_x)I*Z$v>LrCZ=t+3l7aS5$#Ov${N9q?dK1IHUmE8D197 zMg$9}T4uMsFvFG9dIh*&NLPcpg?=^x_mBmLnJ~M~`8o^D?`PRfg%50YCo^fvwIzIN z6VxJvWmp{HZ8F^#?e4spDCbhkZ|P3Rd|#~)+_&U-7UAr2#r3*U=y&%T?U z9`;3G!r#cb-1?OmFAD8AW&c9J*xB7z%dYVq6828TnlsKOAtIjbQ7ik4>H}vN`i2}D z5_V4q^m;mCW=QU9U;`oY$WK^$NJv=l>!FHsM9Gnhy8ijlkQRq#QE+enJNVN}$56b@QOMEj?uUgJ2XuR#!$gZKFiB8_h>KM`5(^&7vI*<^GckB?)w^`hW+zrC!Cxq&+*-Y#o$=J^ zS1=zdlAvQ%a(^p31)t^c2cZaz=as<-KoLrfV3Saca#n4UY=i?;-K78eSPGPrxz}+gUesu$=0Qjv8ddj^cW&MSe@n8<=ZGM0u5cPn#49bv1q!@oXg z(s^>SXrKKL>cBA~ElOaV!>K!6(ioWWHq%r#qHoDr1j0jk8wR^%s>ic9i%TMUqntPo z!^q{J0ofPsZ-i;HiDzT0xMuV;oHkHt(g3(7q8*w=cXkoHx7R}a8ptMM>>V%vMkm?qb%fZy2C7x2l)uEvIf)8(eB22;XFbmwTo_;<53Yp#uRWq@5(msW2d zJ7V=tF>IhK~&kOR{a`{N?o z5Aj;g*>7k69^}M5f5zpe!i!FNO7mUcPa~FMWr=r+*$&~xv&^VB$9nn`v7A7nSGkSJ zo4=K`u%(#ak#fRObuFT^U%gCR7yM0F5CZDMZrWbl9ZFv-C~ZdZZ?M7#O{rDF($sp4CGc`TVkDF~(Aj!hXf z7jdX+>?cjXW5auqodP=_HhV2H{MEr+o((M?O7eYI%T*BheeVvPJ9u-dgn_*|x%5vh zuuxUS>FMJ5!xUYDW5A2TpwQlab(bk}7;EfzbGEiAt9m@s_ADoPMYxDZ(G!g*h>lu> zz1&Ata?d(d3oHcL<2faa)6&u|Z|apx4F38kmYf8-b37hHO00RGU(lREnaCRxw%Z~@ zpXs1_%NQm72^X4xPJ?MyLmBZpf0H8YL^ZFqchu($hEaIr*C&Q6fNMZ44$s|2dDf~L z{WW!YwpD}nE}cNL<>`sW^r%nHCF&q8Sk*5P^e$*g97_-W{7|!Snd+`7+sTNp3MjG) z;1B_KD@J~juI0r0-VA_FK0MeZXd1`qLHTbK?8`D?OQg|QWwtwvQo|_6Sx}Gh7$?9z zvZykUk9;-D+iH%qXVR)hNDAMbH@#6LBf7gWm1(>zCms z+8SeBCjYQ+<&zI3nB;lYa^4wW2{pUUV{fM*jp>iZ*a$YvAZxrH!#ED7KD5mm%8FOO z4o&*r;?(TP=HDx8kT-4RJ3ppwO?5nO!LL_n3v9!XuMqtQj_KVJmqkuYp;C(x0=hvB zZ`x)0w=x1b3^$Q5e@7=C;p?XXCN&-yp(6gLR~s)wLLvs74X&9{5dxe)xGQm{wV0f+ z*MC~KO)yo+{JeTAwh0a%WI`A5ClB)?-jpFWs0ON+^dAvhWC0wT$z^u8g-%hzJ^b(_cNS8Q0vzBl1SMK+B4^Cr{e=-d zJ`QHZ#%r0CvYkoMI6)TW^f5eeiwLccDPbahL=^MzFKV;V%MW_79w?LP)N-DMcsy>& z%A!S+-^rreMGc#1M3s0pzYsAoH0M^z?=fb^}sbElHwW?$w-tyq68940L-YwMoLx>i4sVb1BoS&EC-V1 zK(ad!Z>=Ogfy5`6s{{aRxSRNcM_xehU@cpxX(NJvnB^5deNLTo(S$mXutUTx7W5oud83E2#IOT<<|SfylFZ9y zw@xti)B=xklJ8qw$%7eL^vaOr^s4>xV4~?l-|eQ1l7_>ql@$yCk01rzIW@Xf1AmQi zzhzA{Abb+VaLW3}l!LyAFwR8C;EM_7YCzfO_GHz#hc-2Q0ZM2DplU)0x^{-IG#gHu z4I@Op2B6XVQ4_PT;%j2)?Hq`3H<>w6_WuVCch%AZFlZ*HRkQyS7Sjh|hI83PzFz<{ zKDSGw;%ZJtXt?};;$3yO0HmjHOF;c6c6Q^8CEmu|BKGS695D&36##6v?$e216Vr@z z4(Mpm^3;$G{|OH6asx5G*7iy7FO10Nx8DN-J&}leBPKPtKB%*9GwwHXF`vG%Cq|cE zvnXkpUk(?}+OJ|`2+a<+#0Kcb&PM(fQ)*dFA$OT%l>#SMOE2(!AEYPZ>y@RbB=@b_b zqX>1C|3?;oh$~?pu*BDFz8xfrutJf#Crr|E zh}O>yzR-90cN#SGD)A2`H-XBLOXbiZ?u0ByKs1NmUpP3w1N5~2#V{ZeES6dYu(MSw z&-SgBCPn(iS8LLYzLy2JMa=zQ9hfa{Z=k~ zWH)Gi`Z1GjpbFX7YZL=LJsOL)(i%evWWbNq@i1TbM5%b@B1>3eIYvGdk73*<+Pf?# zn7kGNE~sbDDqiOe9vXH6gyfpE*8aUwOtX`P2NzT`XNlFIX`+ER?wlqx|? zM)`ypq%~cWCWSos!qPj(g8&{!;4*2_-i9;v$7D!r`$Ce%mVB<++73o4R~3^u6F0)% zCXzRTS~8xS9oa%_+tZOgx3pLUb9^uqSc5BJCer`!q6LPL2D*JMrXuR@3iQsp@g4J< zbhYj{kp3Z)AoZD%h3`St0P1xmBq=2G06r@=-*Dk_ILF2GIpKN{FK9`Oxc**MMn3eZ z64P%|?8vB2(**Y|V6R_Vr*6*XWtuuREQwQ63{-aab)P2`pf#C5>)NVJ48@ImbQHYM z=}o0`F<3n8EFJs4iDF8PdN0(w8^?jfO^jk^^e!26V&_`NUS1UQEyI(c4fvjqmoDt< z_aLO+vfG<7qb?Azw1wzJOBPwlB0JZ!0(v9y-^7zg;=f6@29m9TWY;;%8I$ZfwIsVv z37{bXG$dHr{M}ll1S^xkuo4(n0>erW{`ttu|3Vm6j6%(YUM0aJN$^M#mz)!01oK!D zmz2aMB_VG~$XmjuSg_xduqnjApoFON|4-D(!8Lj;TBJ%jxYz2WgtW7O+$G_IN%&wA zKA41RD4`lIFpUxxtAxcWAxKNOTN3V;guC^Lo+07he>`|alGY(f>yTs&%^{xyp7sCD zj3H66xoP9td%xe__Jaz?;p~sDi#3jGN*`AYv%DdN*_XWf-ix zRVp)yeIOOf)OC5{W?6Ki-yU#ye604<^$VZS2T!!-ubd&GCxg$qZmiQ$KE<#}?`|L>#kTTO0qpXWShe9yeuv(eaK>ZJLTMvNFS z)o`8erV%5?Ge?XVvva~YxbjTf^9laoXSp`|2y<39@))bjyZy=0u~V3OexG)6K&L{xNW& zcref{I$L}gG`ONKFE1~PL;r(|W@J~gkK2GH&>5I6KE7@Yy6^~!vWl|ucmcI8eq^fP zvLBwwUPbd~(X8;)jZ`NSYpRpC;5&Y7FBidgs0;?x6Lv&v`cla75@Vda;EEH&$Jxb4 za0y6JSc=zMiqnR#qW|M{gsg=(bTW{Q-MLf`zf=XkR8?E}VyzDLLSgAz72%?8LdFL= zds}Z%X1e(>+}B!fboWsRB*G~N@6o>#Ex^Es?6rl+aCY&8?VJMyo8c8yFtXqZTSzz# zhgT60Pxa~FNw_h(VCELse?;M(RDU;T7hmDsf;;^f3{O8dufZ273_9I~BGd!niew)j z25a!wTp6Ci^9jG>1?n?sb#%dO7^~4$lAE*N7QuH_6bJ%Z(DijLZqzOPJIgDp3O=Ec z`@bwaiSHJ&GlM0#AG52)go-}{jp zJ|B(g?<@!UikSh~)4yNw1Ul@;?$=>p2d3q2G)w|(!DRg0fbT|RCl}9+3|}`tfdM%& z{QMX+uwqa2!CErKgX+WZr#tH~JQ+y$on2hX{+__Dk1J?1qo`7ylUD%sadpck%g z0SHvqVjF7rUj;)ETtQ2b{m6hW0*Vy$eVNpy3Tp#sz+;__>x>nw*=rS@NCEzoK%5(S z-6kAGm%%i`JL8?%N_Zk$iAkYRm_&DN7Ewnv(3wVYGhAowWo_xK}9=f6T`%PEz3pMPjw?Y&pJ;2!67>$f=3 z5gnU6H|Xjq!g{d2HqMx>h$p&vP$@K3oZvGL)&?^}D%oJOm$kwc9HI@*$cDY~WYQ)a z88n7yPV^_b>mhz3+5%uLC1V}LPsD3Ie`9kIw7Fqt{w&%|bQIafZrV5^TT$Lv=bxm_ z!rwShggicCPmM9IjViu8Pl zjTmA!LZNMTch*^pqtNvIDGJtrMmSYNxrV(^>GD z(ihWaZYtmvMjHieP7mqlze*dMsH^R70x~6n9-I7=G7SXW0UHK9*+Rh+RSjvzz7#eN zXoWxo@O8bX72cF8v`m^4e!U+cgpi8?TbvCn7=Wp8Iu9j7T|)(sK)?pGwQMK+ChRj4 zb8Rm;HN%?ZNhhxZGz7~tF*gK>2{06sB3qG71Z#G|&`A%ig@bz(5yBu%Hi6In7ImN( zdU&9YZRBpn{wJw3c2iV9`1g0HLmEw#Hw3gZayP~OgVce>Dgr|PP3rJQ?iM(p4y0nJ z@J~{Qe8->Yok4&X_;1h&L!>h-KyP_WM|83G3V>|j9X@)V0iR=@C_seH0BT?wJ!oYL z%gCLA>=N_AL~{&7koIA|(l}5Xuo!8p&{vuxeELg2sR;f`0pXU5NNTCTQ!Bxq0*zOK z{f6Lzz^@B2>kF($8??y+MNP-Zc?6h_%tR1I82(J7J{mI=sXIF3cG7`Cw>DuO6#m}LybHw=5M0Bb0p@XQ=y z2wl)x0iJ>HQp6(^9pb-4u0#b7V1=T40WuC=2}SA(BG9~lrO${WjCBn`9#qKutPm#S z2l^T#^Dm9}Ex?-^_H!TNenA{L*8`}tfEdR@>7S$yH$)M;H z^LKwkZ`>i9Gq*t0!MU{u#dm*GG6)?-#W`QZJ3W75pcPO@#B!&9kawWb5a0bh{|!DC zDk6wF@V!=w{~&c({3rrLzl3+@Nau)9cQE}Y(Le#>Vg(VH`~{SOUMLdHw4s6o{0r0@ zn8o^iX+CCb4!HLz!$zn5!wh?1b;~#qG)os%iZCCB2cN}4C?cq4SpdRQ5eA5idIzop zQ6|_8_Fc^H40w-KnT-4W(C0Rn}e}`!r zRwFexgj(2NWH_Hk8y+xC-gr>`_KRzMC=LPo5P~3U{l{nnd7{|xZ}Cm3KYRNJ=|VMJ z_TQAJ67U_15dK-78A1mK^yKg9+Mrs(KgTyi7St$Me^Z`V9t%;MFgHXoHJ0NJ@m7L5 zhmisW)ky_CEqDd}GGTKM8g?$iPOpgeA$IA{dzha(nFcPJ5H=-QpIWi<@(PNw{Y}>`gIcjl1X%*~^ie00ENlZ)KW>Dseom_tz9a0k z{`q0hgu{@AtdM%<|Isd}mm-Q}$bZ%iHTM8JP!)U+)zu8-eVyp22EPU8yiQx$h^-3! zQ;NTHAkiNx?{uR;usvOECIxRzhv-RxOxlb$rKuuM$1>D~4yw5x#PQ($bWK_C`ImN1 zLBBm&MwV-#a!*xuwp{PKLB|-oMu8p(S;u2|cU0JA{n#~iWBEg_1bs>4PhHj_-BKe# ze<9FC!P?8ofTe60Xc$N&SwVkea3>Yk@uKKsvEJfQ!l zhdRhmfxs#-{(q9g>ZoF;v_PlS{i`1C@O@E_@nbgw)n8H6i>hrP3n7L;4m~{DB?|gd z7;o2lKv%_25Z!wCLPy2lm_+phpUx&)TKN%4C|WfPaCX-xJDK57FB3;JW3k9OIKg!{ zTmV@YqJ4LL1>$BeKj;fXjAj~Oq`Q`3gt92OZe*^{5Uv+MqTygKQ-5P!Jzt{1e|Mih zOytKOgj*w7?7NH z0IUafB$#u6jvl&(S#KcJl+pJ-S}_r%YYN}h122v$q1xbyETGTUPuH-@UH>U{ROuVt zSxjq~4KTvPWJaJOnybODg()CEvKt*6ib9he{|Qf}jFVTERgzcz_(y4w)50sl#{>o3 z$3H@^Fu;WoRD{z+1KpQ`vZAaKi1feay%dGa`#p=Loe_lrDE%XW2G*4eAT`zwp1tm`tyfO5bReh|@8SYTSfJp&E`H$Dk z zqnIytECZi#10e|&Sy$q{W5z!uh zO&7=tiyF{`6&qz*0zJTbKdAQrI)ZhhKYli(I^ExM8Pw<2>%SANie^ZJ6BlSz6bF3l zaew^m4^|a=78HSQ#0GUSzw)2(BT6_W1zDWX69_XNyt0D4>~M!657Wx>LVO|Tgb|sUHnUK>V?V5Gq;9$ErjKpVFncQ5g5Lk=u&+FgQ07K@Rh2FFyBOX3)YPw(unXK=+2s(`VIOH zOju&~A?o$0$mawaE5HmcR1r-eJ265NaJm%q9^{JyT!SnIyXFkp2>29tzHqL1Gt0~dx=UWWVDehvzJI7ZiCACCM2#2^Fw>!+DBEM6B>7NPt6XIveO zsc<3>EWZ?>K2#@#v%5%^f=&lyw|_wWz%Iui#K)owgv%)7z~*6)S7QH3ciq6)ivrm( zOcrBPy4Y$4#z@Ps=^RYMu$X4Z+0={C$|%L!s!2P8YhfHhQ=Zs(y3^9Ud`TyTuQl)57bb53$F?u&*Ni`}+AXJU%|V z2R)zuOZ^X!EmgqdaQgadh3o3W6Qr<^;Co~rzajg;<8eN0OW_x=H&*D4tP-q?z12kx zEOfWv9g+t2F2KzXyG<64$D>c-z2Hto6)0X}??2rNAL%tGEN9sU$z4tp4QeEFynI$j(r`TS?=!z z|M@+_Z)3gPzxw8|7O?Pq{|;aS4E!UkqIi;hecdPkE54v(e!{OIfD@phDCirElk%WK z0tEY8SVzE~zaM~gN*GQec>4&G{~oLp>e2r_tW(A-LmoKT)hnuga`pXK@Xy1Vk`i>X zhHi}~4Bz^H9M?o0V;~2=414|r-Q@8@Cs^?K0h0Q%eg1bbPUz_dV4Q)83G%$)nS4Jz z@DIa6=qddHff`x(pgsjcB^25WdxD?l=Io4qFJLWei<_T|nHL!gZdmYJ6L4*Cm^ZZZ z>k6G<;jc+3sKB?e_d;S25Tf^@U~oYEj>0yVjEwCK#$5rl`#QWz~15N0}Orve4E}v>5g6%}FyacTPIJ_`uJ1M$cBw z^r-()aSz$2@KsP~P+x0sU9#n?8~1zdx_oK9o$<%_1=L-yj-9MIX2OicT8>&{N>($A z11gHLd(Ut}s;8;tYT5_?zIAy8JG!r}ueX%@KB3Pw>XwP>+f(h`Ne;K0^T#>A=SZyD zJ25EAp`2$NC%>dM`dZ)Cb!o&=*os?6jQsQ>bK<@k%%F&7S#;^PnHKkfFC*`14n2z_ zvrK~7ToU(gA`mg?mND-oW-x0?!zUv07N6dl7(Ihic4j+oueO+jF_$={PUX|`!VSZp zPn^KHY;!^KTUaXGcoeK(xGOQbzHaZG9lVS-YT)oYI>&D3b+Q~sp-Y8{fX1 zoa*!__ox_CEJAJnz*At`obrctYc{{%iRe0Y2XmKxxjbDbi7``1yT+82kU=~wm95GmxOps42N8}D>u(kAJ zehU3p`ffz=YG7T5hSXP)d=<%8D;a=XW4>C+SK#{UOTPM&ukQV8#5Kq>evP=k2EkwR zlCOEm*HrOq_C7FS_?o?cEvS4gsC=z)eJwkFEjtcM7@%DIwG#ZbIRCXc|FvK8wT1Py zg*B)lC#tLX1BDyX-B?f_UD~eyid7nt-i7LIiVqn_?U;L(^w!loH9sIExG2YQFYn-; z#`>v)dXlSV&0yMGGfG{Hu6jTNxQPDrDM?Y4uhDR0v^?$o)3n;IQimP&a}omd_>Hk` zxzp76GxF*sv%4!ROS@W{GY2VP>s|e+Lq+=~B(?Z&Kg#D|l zjs?8i;P5g*{&|2Mnect;twCbIh_Qw~aEjLj`X0nQdrN3mx4qlq&h0r`lW?Gr7%hH4 zy_GxZRc%VKtOon-X?a&Z_vOt5PU}mR=6(3G-mZEF`FpO>G;!*K*o9{d4j3!PB}VUi zsV(BLbKtP)mZ^GMN383mrS;DOz`@05Fq=aZPRwPVlL`y&ZeDuyl2%Ahje}HyQOtZs zSb^I7@gXmMJ(@r7T->7UE?)iS`^uE6`&?>S?sr!waSV?w#Mn1z!$(fggU-9>?}4s1 z6rk3)iQbc(x=Y9Ll)5~Lgb^Xd#U6t)Tcp7j z4P)nFO8px!?_!G)JNfK(Ua^GiO3jwe`}o42QnPF5oV*uTspo!~+iG<{vp2wKuBJw4 z$32H5MS*!T_A^Pg{uUi=p*<5gJwN)}4T;a7b*?>g26Md2le$Al`0J5|SrRy19MTKNzgPo!wiLy+17L!{a8igzG(PkZzLeGb!)t!yNXP)N8HcSG8_Gc66BS zopJ-dKT&pCgtmQq5l%xY$+FLwNM@D1x-RdVzpqK7k3T12cY<9IEu*_quD&Lut+|X< z!lo|3xouk0^WllSQ||8e_lHUOlBMnWSqr}Bx9)hRH+*zr+&V4p!c#6B3$#(g9^T2g z@bp`ChfFl)sd;9Hbl0)6W#&aDILK;Lp6DtRs=(3Ir1Jf0`4Vzzr{q$<`<#VmFnvSE zy`RP@3a#~M>|5lmYuJ9`0pUPGSh-~7Ia}Ypj+TV5g=$ff5_v^N5}K*OZJfrtq^v7V z#W0p2?XNwY_anuC_nvR)h;tFLuP+{J4jBdO8w9sr_2wlP9ocHI$lpA;eTmc^3E$*9 z)4M99%XdoBm-p3r7f4A-bwAp*BAY-?_1PpbTzBT;Mv_@K#Os*AEZkd6{k3AqZO5sx zduRpw_Bib+DLiIzlX_Tk(Girev} z*-eu1S?_;Sd4GG!y|8Bq2^4YWuHpCltgo}Te$=kgr7g(d*U{!D43-SU(I{l=hF%^kFv@sV3I zO9E^1Vpu$j-pspFRkTSLfJ-*koGr? zdvvDFo8>&yC-RidcHXlvdv$m7*)y3PMavH?RAa6yvQ782S{bS_LlX=t$?Hwd9EW!q zO=I_(G%UjVzdx9Lw&V4IP(}Ln$|Fs)e5)TsCKZM~Yd*MheoiE~oyF{lgZY3UDty|g zocMwW#Gy|D`1Tqa(KlSI!~*6t>DH#WQb1WP(eq|6@a)&cLej{p!lHJxxdNwLR2md&PA*YWFRzH(VA zu9rXfKaiwdGhGnKCCgXd7~Pe=_1kYHsB!q9*1f)aO~%Ce)?N4L8B^C$9V0=FVY_x@ ziJ7dv(2Wne*gcbZ@u}ac;nt-+8?4K_rtUbfWAsWGDdKdmzEyYaf?4@RhmQ4o2#ntD zxli7B9Ev=j?qj*iKB$geJ+(vThl|{ejT1{u7Wv#>;qZI#Lw5CHho0`WniBVqi=B&O zT6e@z@1LC4WpvUqZ@EnTH~h_a-#H;4GgvQ2gG-(E`Y}%dNdolb0jmpQgtChV52$v& zopZaqtwhaubw`EuqezqbMSyiH?K9HWWVct;G!i>Hk)y2F7c<1hfxB9naM;XVV`PZox$xSlVbTE) zcR2b?PBW(@xlHC*(QKlO^V^P1G6mJ&z8Ck6?_R=hHL8gkE}bzyPMGj9Y#@RIjJ~p` zt{Os~%=Vun%W|!*-j$q>XL{a`*39mT-q5iBTdf179ti;r9SM>4>ROXI6OX)}AmZG& zX3Svj3a`G5Har*yTr7Qf#N^e}L{6K1kY1xjL0;iuk^>5n=qsBJlWb=eEC}&aEforE z^ZgZkWhQOh@Y%S<8)1ZQ(ZB$fAkRmT&74n&*9~boZ`xQJO?OvpxZAvczS4@UEx|RITDFGn#ElUc z$D2t{H)M5J1~f;PzOt;Coc-a~_AWD%IZR2;HxV<3m^3U9KpsghdZLXuIC?1pl)7a* zc`^A>kxMrmxum7uPLYZ%gs_0}gEaWNSD{_CGF8QH)iLF-njgyay&%aGK3~4{>v`fA zx6+gH#JwLR7b(wTzqsO(#N#G4LeO{V7~?)SNgnX4DQ*W(KmNhS;oKav8B}}`W}W?6 z&kW{dUj3^;kBs*g3GNF%v=li=#i@5USX9koN~SIwE$Y15aNb)3&ug1g*B^U8O#bu- zgZyVCyQO?(I)2=6&%79?2(EdHu{{L*BS)+;|B|T(Ts4EW*BP5Jx^>9VbrbFhXi<%7aR~ z>?a1l(d^dApmfzrMyPl3ua>{^efWL#3y2}g@5&^s43l6=Ui~&=DETR}`o+zd>;tZR>bLPL&~=lbMUoy$>&tg@Q@so+x6w$#1Schm%8lUkxn zW}9eqIL~&FunRuXeroje*-Xi#g*qbWotwTjQO!>#0mYKx;-EbpvPnR1Y5jHSl+NPp zsB>|ltChKq5lw|J?5HvR?&BRY0=)N?`WE`^znuDFnMU*R!rYOEq``AB@<)h}UOEK3 zoaQEXB){9Xh|l4`=g4}FoCeO@X{GhG^SW78FFh!ct5VJ{?0zg4rn+CPmFu%VV%qBE z`I$9#IrLf^`Qd(HM0gztu9q~QMer}a?XIb@p^cF~`=hg(W77Ia*|V4)rF%yXRx*riKe@$xCZlR0;>|&bjiT$Dd?s+( zO2fkVSDqLzZK^44*qPRvUgJJCjGt6c_P~Z=_b{2r384Tq(- zfWWm69&pf}i_IW~dy=Q8JB^(BD5T4#bbfZn1IGHd#bFH*+%0FK+;y_S3ztD)d2LNt z5sw*pm0Bpy^eEmLAtHjCVghMZY#a;ispSgT={niQ?G<1^s8qM(D|U5EWd+GT#DCu+ z^>pPA9nDpF`^1cw7itP|aC@RnvGM|=q47FI1p%XS>KeK;q7hpZKrQe#-1X%EL(@BQ zrOS#-J2$I#gpXe|H=*NR_NA#kYJ}1Sgi=2{)WY#0?YDC1v|=wDGT6a-9R3E( z>{fF#9g~|8$jy^16BWII8>8&+9^4}1;I`m{p>*5=2)}H&v{$ZEbVU#cuBYzN$&9^- zIO}f_%HM_)Ux47b&+E;OsEFROld4JOY2M%*l_`sd(J*q94xDILRfPqj?$IoiQR~6k z-5h!_AY~^E zuTLv11*tcU)Ga%aYqX z8u+F*wcz&AOe5}P%FKtubI-*a!?z~djQn{6l8%-J=#2))I^;2Mae63dVV{oFiUO(Z zwi55hcchDUYS0T7mTO7{BfmbgZKb_!Z^#>3Y92tzQGC=qHRY-YaSpwqH&3d1cee?G-moj@M8(fJ^tSu( zpKA%`W(UjY)CJ(38G(X5Me;Th>L(Jpp#OED|YvCn$XD4y8MKJ9u?am+FVr!KcwO10J5G z=i6c$E&+u$xl4w!EBMU9l^+3ah~GM~VliLYA76z%sFDTFC4@}$F(s!4L3u3*Uq9p! z*t+Jh?uBT12}I-vJwUk09zRAZtMfzoDE|7{?vVa?scmxA{XI`i)Gl|25z$R7~`%q zv&e>#snXJsVAcD=By4{5n!c7t8cD@P2G8?`(=x#vB+;L zIG#c_RwTz~W^*bX@{m$gV_t8lQY-_dpe?CFK~8uU1a~2owKaLb8utI7=7DMBCv$kw z?D3e@4AR)}vp_tNx9>W#lT&hFv<{YsY|Xi~u~uIO2G_UqAh0B~mUtvQuHbR%7g1yV zH_wVwT6pDFYjMG?>6!~_60$>AcK&|g?$MR~GHHXFS$;-G^Sx5JV|Zy}&Dv{CZ4jK~ zYlum2Ufsrv6wlk9nV-;j;tBQs?w)0}4)55q`orX>b&3XL7c0LH#m;aBY3b-6H*hnd zM(Xr9wCnIAC>==^EDQ^#y%ozpZ~)b>D?0$L7t~z3y8nwkJtM25s=fW@c*3;6Hw#(0 zw|`gyX(26NYcT#{RPF>VnfBn$MU1YcKx9_r{iS?+R&BC(E>*KwHsF zz(T>yBuf^91DGn(0mOm>Sfg2w zilE{50ch`wr#wyr0fwbDxs{Nb>sdNB8##+YENW0e#{OqH#@0oN}vfS}{Xvx@NbRYR7bVMDl1x#nR-{rBFfj zZZOcaj_r$W%aAr!E1&Wus~*mO@aE#NxPY=f+)g56#kmr{C&coz^}**hH}nNJ+?<KROlRo1hmj;SP_ zY>%lArrJVimmI;k`fPJ!d-;KaNKo&zuF^g`?&Xjrd&4>l!dCuZqEY!1*Q5J{j_ci3!J#j&StdGavn%+%g;7VNprvxwcI(x_LdL{y z4o_ij9`jBCQ^Z}Mhy}6F6&sGJ`P_SXQx59Fx2TUi}&&!%KnT<3># zP{mAj5>>_IL94ePqMfmlZ^qeOyaZcsJwBeic4GJQ)GVdmcV&^1;XP2K&wtJcG+WbA zaR`g|PEMBH{r&g_8y{8`a%s7Hr-+Eh9M^%9J9sPudw}#MmK)rG^$Ww^O!m(C@NQ{? z^fcA)P~ku7rbffo(Pf}Pp{j)+#Ef^#1@|^r*5}YEo1L)&#t@bAfT*o#eZ^QzwU(ij zfu=0a&+>Sc7T|T~$5}0?mFU2!I?>do>d?8VgZe_bvid&$;cmIuuu#>9KYedjR#vS^ z%y{xpt>Aif45_zkc$l+4>~DoR@_gf1#qa43X^FZ#&#Mp0P`k9FYkFw=Ev&sfmmkf@ zQq>4;xLLWTKA=FYj8ob}@8~+cYvJZzi|z@WD66B|B6RGMDYQ@=5d_{4wou-YS=ad< z4qY$PdTSgQvp-M{sEae8xZ`sc0Q$SouHw=o*^@a@)`!RT3+knFGD{WU(L^Zi`)z-x&%V-r1w zqCC*}_9{RK)$u4+&~}By^}$O6!V|@hrCs{rVpI(%YheWF5K@m+Bp-_RT>6hnD%*zxwN@b@L7`vCI^;xEAwE&1*Je|p^tq~Pes*QntDx@{{WR|pL&AA#?8dR_HuHq1>8*+x*$@8#GcrdqbOhSc0ESwuH zD1@Hf$-~0xX1B;V%~HQ7X&q{%Zr?RsE!2<+ z4i;ozTrRfb(<}gz9=0&Nu>1xZ33Jhf{zd{6)BWB(ZmKzk+6HA0V+eBjbPlcj6sfm) zYr(#SlFe0x4lerSRBsvljA6cOM7YHm=yHrfAM|%Q<})Y%?(148+qWWA|G=V!sGM=; zRAhSwv=rv#l}5%X9of;Y8?m-s+SJqoE-H=#viA$9B;x4}v&Tp{VNgt_4@hYK}(w?oHS!>&iY2 z?Ocaqui*m;BS$@h^zfNV`XofVGk~n?mGesbj&I5chm&>s4^J*2~ArhoOrxV~); z*%?<7AyDpqN5S(JpmW+NsUd;@XXIxw$H@B4rgkZbi#$l9GjDcHZN zuLqi;#m}7fnv{zd*{48X7{YstEFX5qj(pJT>R49E!O>R|i=R!(5D}GW`M~n3*GHqR zP8mZyVBGU2CWgYb3oXby$AaR4N3GjmK)z3+ z)qX$>atFoq$d#)4U3C|)GBvb3ijW^gc(pN<=F{j_{97pMX(N-aj60(i_~C7=tPH<3 zw~B}~qu-2$FMb4!yK{aaR&yglPbNBXM~Uke9j;x+!+Qyv?9&y+Wo@})>l&-8#b>gf zI&|ypo3HfSIgd--%g8M5cG)4Tq4iHC0LD46?JyCa5M+}&ap!1c)>~F=)!`iaeCoMj zWB~F)A*R;iVHa9r@dn`Bz2w6>lQ})Sn8acS2hwm+F2>n{EYr4?m>@8dS&w2<5!?v`js$5niz92hO+qDS z79{bdyosEi7Jq*cHh2qShFvmmd(c`34?}$REPeC5&D`4hy6wE)&h*tH0P797fm?Gv zgkpQ30S$M%sEHgrLbnfJ02f(+O?2*TcT;~GEFqx6$3UO4^R}F`q(b_i{A-x9*bdyt{^W2ZsTf;|%eEe#@1DNU#ntiN$jHhWFUwP%|!8D5Ru(C{VrJVbj|7#~YYvN@zE(f*pUnId?T}x#w zDxjt>A7)E8MgRzmzUG;_9wEX^$hl0k#d7M-9MG6w&g6ar<8r++sGeP2cw9`aE{&3M z9?g!};;6=|eMfBQ^GJ5S#L_xFZms0y$-}{8%5K1p#gWWtWZMm;D5W!5E0#k)-PU$4 zcD_XDyA4Y#U=YkQ|Iq{G;+1M#NvQLy@E_@r?)T(PmVN8-i#YRYknWV>t(QkI6_!e# zEI$n$=mVfkZ306xq2#B;u3Ryb-0?6l8rpOy?x)nQ^rB2zS)0Vgy%i?Czr>|Fyh{!X zgn``p+&!kRHZ(T(hP3WEe$~|?F#o-T7_;kcP1$fn8@(9nHaC9ceT(+$K7a~JPagf0 zXfvTV&S24=#`1!rVRE7N%_oZBhnM_J5!N@}=xb&4iN~$}@M!s($hgZXC9A6(d<-+* z>dC#Y;eSGUgxgqY2)%F|fo#C?iVfDc>_biFkohNOGbiVvys=lRbK@GouBGpxU$OF` zdVR)RysHuAhidy^@B1fIee;4LZ(-YJIclp0WruC&g-+(6nTA0-Y}G0Tm`P!9dr-J~ zV+9h&bloR8^lv&~{&r1on}Nox4M$dfPcE`!@vs?UlaS6QjZH_hGvv8>C#4sJ1qas$ zmD|R z6Z0-u$hzeC((BgL@>^0J>oRI<83$-7FV2c*6-b4x0WUhYwD);xS<^jP8<(9BGtPxE z+7o`VUpD<~C)-(g)OHp%&VMtSpX^#vL4ZzT_>+V%qRt(H1Ci6<^trz7R3} zElSzDwnI%_{7PP2YEUn`TCb7%Li}{{_nLY}y&vA}D#(Re3Mva6N!re{<}Sp{Z;-ei zeG4kCch64-T}@%gshUh`v;=0|;07hozk+hcQHszeulKD`uYOuDFlIluN&T_4k z@JwsaT%FZB)y8us%q)g@_B~|f+mtjNv1DYnq^E~IlM`oN6!*vGeFx|tK#vKvn; zuR~*;Xo{t(YedCtCW#bUwny6O9n7!C6>$7sTnVUpcdl>COlZ)zwsV@I>6}`Ni?)=W zmZAeu`uq1mDaIO{5KX*0ba zY_v})Q!31hwad(^lYo97<3@*wCBQ{oXFTdgpFDz)p?D7I44Q9Dhi0+qfpel#>JN4R z5^71Kkwu&`1l2#3@;h&3PJCi9Pptge@GZu?gnTf?Bd%^I@>b7LjihV$1n6^QnIwp4 zjZByVKjXD9>$D6qX)S$NU;myp&74d^Gw4dH!%T5R_!~IGErQ=zq%XJ8xW*Q%9D0FE z2OjMH2yu90LhBT2P)R7&V_gPMuw+k?ghmqQJ%mZYaW033qwkEjsN1CXAPAj#u?@tB z#m_9Df!lj7Y;Rm&cXgERvCy1j@l~BU)r|W0E#KP*e~>T8-Jtx+E6RYExy957YHjoT ziiN$Tb8~;6CxT5^AbPuM7jqMf*f9!|T{F(@HQ|es+qRdVBb4vl99^av%HB-!&7?P* zuv$82%k}=Qt|`tm(^4Bg#^Sgb4i;|9i3ZrX@fyOsjyij;oj(isUU)?m-#?&6-_KR* zh_r*30i0{!ujpFg8po|I#lIHg^j!6K8480S(2wI|g6Uq2jloWYQtFEe5oZhpFb*

|RiZpmr(K?ra z&IfHXXEJvH3fPN6fw@@_gazx6Fj?+{_4ge~et8~a^b?VczJ-b+jJK08ef$CR@%Jm+ zdHe4*QNKX9WP_bp&miafeDxJ$l5Ao?_*Xqe2|p8rpLw1=9Ua+O25Kps)fl$E5s9sn z;FObQ*lk0cZbFgNi)Zf-b*`wg(EDoS{b~np@c$PhZ?U+4ac_I>7q|e>zT{_LrhQ;P zQX=i=ycYaG=ZN2zVqR1Vyl9-=WsM67PWBeL(qG`KtHn4MFB^XecqYn#!8M!^1?FP` z%*XDQ#acTZU>Y5K_ZGvDInBR)tC92tCKSiDqxpY{YXwvylCp1k7zTHtykY7U~TMBdlST zB*ia@j*SitfM$S9Ej?hh-a%Q+Z^F^$?!S@Vm>i&N-+u8dDZ3Tlm}M!gKc#wIy>O{P zcQ0N7>TJF3} zp1eSK$N)+|{Rr-sJvVNrX&lLWqLUTOn9)H}5WSY0Ai z6a{^QaQl;#-D%~Ca`4HpqX(gB5+VkUD0V=zq$MW9 z`PNiUs7d2a`-dw^ifY*EQ&sm7T71H8T~B>lJvHKNb!sm=c*&yu(!08QcR8g7SX|Pq zD3S{!ufJ#i@b0_5i1^0L@F6Z8D7}FLA4Go5mO&@4SejS>^R*$G*BQ5U7|`hOu4(I~ z-A-`m*pb~+%b@U;8FlY7QM=__Y^XJ<-m14uuCH0M0J?@X?=z`!LB{+mHSu-=Wdh9T3u0;(47+$+Fj0VR3a5FyRyDLN2heO+;dpYXA-NX4p*Qt^P#V%>@;;J(v0xgP*45sZcg2axb&Af zb*uwX=lYxuebblF5Xn_lK2Vpv!j`*GAxV@zZGk6+iqHGc#ZtXa7$u#=(P3x3pTx;d zubkZY)HQ7NPc!cobsO*(B+Oy%;#ckvLCV0u&+#@S7>Q~>?fNw(F{rt^?7{;Fd9=bS z3AH@QvR`#VdzvIVbLmCSC7+z}$EfhsOaPoE&mFM`bJoEDFOyMnD#(F2A(BfAYkI~qoa?0M{+{q`{uz1s6mHfD#?!bYU5b&X=^1&wGs~Xqp80*b(^TadlHyu3 zZ;sk@^h#n^(5vG-mvPJ&YFF`B+e+BH0*cg1HF)$+wb1v7W^hoQUDmVLI31&B8TaQh zPc8EcF*_~I^j&r}eAJ}nr?w9L>xUUQZd9&<%7n4AH)@4%nlP8|Dih?CT4`5AzFDUk zcDIS9Jgw(q!?zUf?~a6PM|X%?V^Xf&4M#$q%-i-k8?{D`T|0R$e?EWbi*;qTJ_GC8I<>n;TulV6-aeL8GTtc#rf6M|pnP5MJ~Wwa*{Klrc3 zn?{Y}{9rw8{26rQjYcCQ>>_x$u8X&}@i@k=FN|;HOp&)}Rt&nLR6rQBO`d8E++hxjGEOextYz3Hc&F zEOX)Vhcrk&V(RMu|2o!!Ez&+N9Ge?L3@z#_l1d-pzSA?}D2U-k3p z)8F`UjAK^+4i6(fYB|2+ru9mzEBd=_OGik_og$N0sRy?Fa`wt(UOJOTcTJ3zNRAq2 z1)ykmwQe}3P7#0c{R(9KzW~iwS!*|KLdR0!X z$tLgLOW!`bFnM&~FA)I|Je8HP6!Rh0h2FlM06MsTV_Pf+2@AhTLD9RbYFnY<$tikiJM;ub0QOD1<7HcMTZq3|VjQ630ZF z1*9Mgw9D>Ou$a#_-fQ)=`Vf`L%lgKpESz|?G=6;PWTePt z#?HiXS4}t*gTX_tHfW6M&AJaJu4bB*E4Y3=DxT^E$0D>+YmMJHWM}S4q7+m;y1QvO zqu@k8$^pB(m6$s*@}huocP228CRpCwWk)jA>>1a_95r@DVfzw^r~KQh)h7?#c%iyf z@1QuIIUJQ<@pUC+o<;a25(u17_4-dSU=9hMQ3_bKG#+uBnYV=OZd7sE3 zoEE%YE&*Kev2v@vfTRcPR@lbN+i;}ePTj5Z*@a>;d%BaeXrsn!HfZ#vwLH`{E;Rgp zxHp=#{9ppyn&p#XhKVf(!z7qLSDnUnOkF_Ysmh4BX*>9^so~Ch5YM#~#!O*OWgbd8 zB&IPrg122R@d>un5M{ef0_HoY7GpHz8sBg%awOCfyYk0-@v>jy18obD>Fc@V(!Raf#FUsau1Hz+eZ!IfpPcQFXfiS~Y>$_m(=|ma z7hKOf^7PrWUqfx1SbX~rg!UJgH(%!-?OW>-SI6$yrw&CacFzjvYGLFQx4 z+VhTtw6KBrp`17c&HS?#<9UBsO5$R+%1_Nbfl0oA!OWlp)8M*B@>5`JZrM%O+5lMG@eKXloeF4s=R0lQ<OP4X@tXOf^j5Ol{PJa^9b4C&w;3xPJTqRE?jIDv^E$Fwq*`xu2C}{# zU7U%@(hqd>YEh13YE))N(Zq&YhhHPNwY@Fz-+XWCHUmYHV(i-omnMkuV;eXhI6)CL zS-!6i+O1y33+R4eZLzZsE=%MSp^9A{9b(pz+-q5 zIMWCA0KUqteHREf6Y5PQdfqv=m!!Q4CBK9-J;{nwn`-YF+}7Yhy0ux73L;@llaMOu z3@M-=n&uQC(`DjY- zy93hSHaci|txkD&SBYy^bUEb}ZsE`4>aS0Y-#>+UwCLt;F~|IZMBc`Lj`i)8Jg?Tc z$CT)h$y46jymF{2Ugp&>y1w~h9#|KQC|L2MEZTlwymZO zkJxXNL!Rv6#akru>)*Uoj9Ecnog{fJy~nWqdF8v->^}M6l)0lKUn_8@R=Xb-A)~FM z^Z-Uzjrz?F3lwzCP&{J?=)^t8QXj4DC~4buVB4;unTd5?3P!Odfr(vwIr4`FKZhrp z+i1qyUsfjCn@lLV9L=7TawdZ3xbKX~uD-0Xk{@=MO;_SZRcX5IUoV0Ur|yGh-1EE{ zgSfEqA!5QsMq+V3LuW?Dv<{8nbe!GXlb6)%wkAtvwrcECm$oZxeRe#?>}|YrrCZet*B@{z{svc>`JpYAyQ(^DZ45`mX|=`!xH20?1q5L@ z@fc*`YJ*@UD6D<@f}Y}MJI2>e*~K3f5|qO)e64xtO}K=kMM!#;4Ckg@RQQ%Bl>HHL z3G?{lT5ew8N|YF;b^)Bm$iJ({NAO~lBPM5a>cZV9=&hzFdeEvgCbyIw=TTJDNV z9A_Ok+t=*g>uWwi;(-! z>Qp7CNoLkLw((SPO=Hg6B&Qp|<@D#n%oUmN#@PT^KPSGtfS9K>8-XTqw87I+^mL3X`CS8mXD4{7*LW?QPGie(Zilq`?zaC#wEtOjG z{Z0`g1*)9^?$Z}y@yK0$Bbsk_sd7y{2& zh268IcAdeKpCO2n)DdBPTHyl-aDjN)Bhf}VTK%CI7;N)Ai_Y%3UM*n%JdWdSuU-%@!eMOGMc%UPWiqCG z*RXqZ>Th?BO9ME&7jR5*YL)DILT#y}K5ddg?Pv#Hh(C)FI$}xKPrY3u&%8d}e1(zx z|44i5xG1;o5A-4f$1QwQsdh++lVBWV9L|XG;T7oa5q) zVic#3o)5d7lLZWCl@Qp$uQ^3TCV+{q~K&Rl6Lht9z$j>op;H&e47p&eU>*VxS&ch0Mly52buhk^UU#$@1#{jwy;4J%KS#&w=ry3L zwt!s5cB<*HmM)8xMCTL!oCG^=KesqaI>85Z zvk4LW)U&eBYTzMVc_QVmI|~fz`vI+$u$OmFDc^0I7q4pbpxT}`3f%-#&36Odr{RWz z`YGB`$ifyJt#ztI_*4whQ)(WgfIb{VS>CG~e_9Q|CZ<<_P0tf6kFCCFBk;aPd2r-1 z|K{WYc{e)sz+Tr;(dLO0B57r*a@?0)tix)qLxbS1&(^$^t^4kp?NF_LaEPeY{Hl3G zEvzG3=$Tu)f8G6buhDahp2kG`Q_8%v5a*S9v)!jh4==5wE0@U;LkU=Utq(-}cUHCE z?Ga5onoMkwv-wvRKNi9PiHoCv&u30HS1*9Q)Ht@6$L6Xq;wu2^Io0;q!+RG6_iqVq z@K*>hB9PC5Q9IhHbtB=BFQ#@ng%e$t4Hl;-pmjZITHo;c#gIc*Y%S% z1U~G2-OF!#K8L^#(IxSoMG?qdA>F6JVtnCc^OvSq?Ys*$@FUd$a>~D1T+CNGPoS!+ z8k`c@80!<74p_+@i?n(Pz0O;?*C}m-ytLvt;bzyd&#d{xxdp%gnxSaxJL0E_mT_r^ zV?FAk5^BA#&Ls$OW6PPj=b_8x7IBIiwF&!0h~fm0S*l1=p1RZQHOB@p3vJt%fa*f@ z2{l&<>9*4*Nzd5FfvsX{pPZncr?90ML6E_3jy_J2bs_Qyh?m4=`IN#MMB+HP zu-g;*RE`$AGe`lagtCttqV_`xHCgCXbD#3Ws#F$U>iwy}?u3sNi=GvKaf^_6qj;US ztQ}NK*D@D%c<|l?&=8`%x;Cw0(+2>IZWf50z#maK2{5`#bk5dU7zQc00()#>=QBdN ziTY-kzY)?6pWXG)nRig=7D8}1GuV-3_*qORXob| z1~4Uy_QBD|937sFo%%7a&oHMh8u4}%C;#~>5Xf=m~F{Z6DCjbzl-;(DF@# z#<|f2_!CBcvKd!R25!?O*?MfK2zjCqC zdQ(qxXLV3*2CP!@`~)#tV2rY9uBL z?u;&!H&JsBh~bArVAY<~{WQ+!Km)Qp#CYcIiB6(P8~oNwK;xKEpJa{~vf>DgDq2%t z-J?ZbMtrh3&p+%yz^ZX4eWR*n4=tl#N6d3h`XrNZ3LBFN93eTD3=Fu9iPdrX^19xg z{~hTD`~G{2O>1?T^;&_!X?UiL%jQl&WbT`j(%cGkn8c>$$Lt@8&D-(DAzhd}TECrBuuP);Z~kiAlw@`O7BWU7gS5aY&=N)m=?%><4Mk8%zA zl3lXPx7}=N&$k%SGCoP}kWKwoLrB$G7R}kt8`mu-BJ`@;{^3bNPVi9zzQ}aQ>^GHXj`y>ki^I11@vSqi2EI2U}>`HEm(2OD$UCGwc!$xLf}oi{e2$?Vsta^2HnTVI0ZEbf3x ziL4*G;($BrQEz~iDr_WJ)}II;mY`m0F?eew2^h+tMzQF7yjYq_c_4{o{aJsgCK z;?RSWC?oR zv8Ajh;ZY`fAg;F_Tcl$mmA42W51S+$1C~2H$tj@z@o{-CBmuhHf15XFk8%%F)w?~= z7S)P#qG;X4fZ4MxD7s^1l>+7z1bapa4r=)bNs-Zn6)#=?$oJIuozgy7&+ev)0g{?6 zeg~q*;gTo=U?lwqB9b5SbPinn;OF=OOP78JWl+(ptE$*)bpd5v?zHHwLH7TTW!(*P zXLR*>Ov%#dbouJ#vTFK4azxVe8z(FE|0oXw9;qC--JI|vtONC7&Zlhdt>?wSbzE4S zmN7bgqE24{e1SeUv>`j@VJb+XwLRKYY`uXlCn0p)vo~&d7bt$jyq@~PMT3ObzeHXL~n@A|zt zcBW)T%WZ1-nh6=OJJ|T_r+sPkGJv_aT)QG3V$ME^KLtCK4lcEvemP(V3u#5R;(B6^K2h{LrlMQj z(Ej(LdRIEbyb8Q`J5yi{Nc+@V|ND&E;Edb3arFN=BmO$-l$kn(>!U!vXEgQ%FzY0Y z4LR0^Up_uz3Q<+&Gfh8hm~^@jF2N?TNB;4>?j-O0-*;|Mo(LNfMco0h69~tbf9JN( zUh7N)v;BnBBBGSam(E#e(!+_)Uia{tXQ zdta2}{oMP)m2tN7c^Q61Y^^~wg`;$+oX zSHhoH@EcU3s{)e03KNj{J5z;EKJao?Mpt)MUDk+o=!?L=k&4A8@`_gP&O%rC&BeR2 z|7y=Ld>I4JS#_aCtwpJ^eFV7R?`Q7zd`~wL@~bqhTe&&){Tnuu8;aZTx#UJ z{ckpnZ9120C`|65l(nY% zWeAtnSc<2Wxd~wj?`oyl%Ok-%Wq2f&Ui4`0Z{2>_GOh#CA4w44$z)un!hGA?P5)uL z6@(!}=={?otIg_dvp(nEL`er)r? z{%a?(v6ZvM-(=-T)~WwK z)f&sEMDkDT@~o_eKI9-kH^%DmYjsdc^c{@Bn0QQW{M!;1_!#_ZH;2_eMeKNC=*%y<46nE2ok#C9mR>zmEKI-srNOBhdDc%y8RuTjwpa)j|Y zLVuJCM89K6(Ja!G9vwC-+203dSQH;ij(^I)XXGqzK$#!Xit4I)GMmjAYdaEaUz%xk z3uJu|5#ScUc;9l;kXEY}OX`0(-q#=%6jQul>^6MpC;WMS z%P3{;2~~?rfAc{0m`84;kz&>Z13@!fY>pxBzgx6VSKp0{*AaP9ykQhg|P@8`VsrR zyZa&M{!*CgHRm+B`Ks$!k_?-!5;|9 zPjN*y3_FCwpZ44nB$EVqUkC4;P7&*8%;o+xLVbUP|kiAowN7>AVt7>}k^=o-x97`QYvHF)3 z+$x87O`j&2N$otn&keO@5%ABIe+Wt$tB<rjqO)_3yk^FyC73IzNg7W{9B`UI1TKEoRD#AoDUK5KAxjZo_} ziy*D5d%&${Zi83X@!lDxtBT)#@vh<}e2MA4Q3Q+XJ<*y4*EDT+!;JGlwt*PMt zy0?#0L=CWMQ1m3z)k%#`bf;ZHzhD%C3Jbw=aJVHI{m@{#D@&DKEB4|ctm74R>FE;+ zuxHtTFt1=cy8gr{WVCRvHGJF^i`i3XaW5Lft$$Ub6VUDBX;XiBgj<~YJN z!+jhFBr}l3f>xYm|4JHNo=rp1fhP+mW^NSd(lGG>j5i=hv-o8c0-jBs$E*-t$4V=R9Ez&%Zl&KouSg0vwh1aBl*@kR=h6F7Do(YRO242Aq~sJr9H)Z8`oR@hwcHvRALUZ!m3|F=ht+F z$N8pL&$L8!NV#@B_q5lQFxwV9*x`nL32e{VbYoy&lQ1gYc41_ml~#FQt=N;#xRAO_ z=sA7d)btN65ak2f6TUVt;DmjJ6@b<8dRr5aS5}6nI7ewb#us>8zM5&#kT+1Cp3#jg3h}YAKsdP;9rXTdxE_7gipw+)Y zI&E_{@0QRfC2Vi9P0ixTbKEJ(escX3i^aG7m+ik{`9HZ#KNl@tI&$qP_V01Srw72S z+z*^mpkQJIX7_FMF&6BWVY?MaRF>H?=q7>hx zwJ0jv=j-#P9KiwiqfWBw?D%3)3n!8h>T|)~sA$$Zti{E;Y%{&Vx61(+nk#O2K2Uut z(0Wbp(bBHHtPqYT`);aOAKe4b_#MrTAmyW|{^vv!B^EIog$WaSavvsI#D?5$cselu=%z;tbc% z6f_)Q$4}@ATOF#eEDr|^1fN;Au=V6w6K=c}wHstt8u5Wk#ISIBw?5l|DkROjFU?#V z$A%}teDzW}i|GR)t=+AP2#1d6i?U=Fd0^%^2n?7j`Che>71=H+)69Rvonq*_zJHkg zNJZ4|?)4IgjfcLlpbh}7fA=!HEv%v34{%aD8%^iDWng3GYEkRSj!FsUq4sboz4=WOzKVH|k9!LDq+EHql4bi}mf)x@OXE z1OofZ-a18#TzH^r^ucQ_<&9U}ZMo^*=?)*IY9%UZVwIf7Imz%!muTZ#qpJubvN-8{ z=&(tfElC=bbFjL8Ym3t3OywV~;g=Wy^>rHmk4y&fGqqIM8r5nZ0TFP?p@?HFBSq?0bi#r^3vkMt!o{xCSkF#bSZV+U5OMkGv zu`|Mx-0inY51a&aw=HqFS_8+r0E$u$Ucig<5w<3BZ_IXU=6c$X-)kTfbnOK>>tq%i zZ1j^0d0eC`F+|gOi#^MyXdCV>>&w}R^cTS9FO}-%dbs!>t(e-)QCPHH4<5IqJ-kQu zo*S0O`SR7eS>X`>eCD_|Ya5=P4E`-e$8&N_%b z1c|se1+Ux1;l7yqfyJG;mk@$U))kfb87rfio@HZ;X6&G*AMAS!M=4v{lo!u2_n?=S z1)B@q`-ah8192VQB0ZCyt>r)-4ki(Pxr{LFoK-n|G?%sBn7EJj9p@D2<)^9WNR) ztI=So@FzAJBV1m>(TqFR_Xpes1Xe|e+cj8-O_PtA@188D- ziRI#RU8XK9F4rpw)>lkh(HQY;8jCU|lRNt@M1IlSQ{tYuRcv&X*nXV$w!wNqtdDp# zsWS`BOmI;CPQv2nJHba2lETPkTbXH`QFEF$zaZ4bVj?byKU%sUfb_rB*+*aam_kK? zkHKOydzEgGuVJ8rK$F3_}(sg9`XJYxs`+?!)Uji%lhi z898%1f2XqklVW=g`p9HkAM&5Uehr$GVzM__>n(^JrIQwgq;7BoUkw^J6>eJXvEpct zo2y$}gw0=$So8##Gld%jOqQK%cZKy;<1MNriB($lyj(jo+o0g_$h_grZ4Ob$%7DNYB9W<7kJJb$D(_^fLDt1fKLAuKN&TdrXWg&cR2?w#`v5hO-dmhh1_(Er* z7y42NY3)SU_FU|U9evWz6HUF!*4ewXsmtm5k&lw_cU<)V^dVS1eAMN_6v_dv!1sm; zewu#12E@Sn%VkJEr_Y4T)jT(^=Nn}Sur)L2#(fM#zl?$CI6}DTRz6NMp08~QxbdWX zYCh(GTII3^s}WX+p%C}Z*kXgHrQpjQi&50sQLCyA%5_vu5c!e$Xdx}kIn0(Q**vQ* zCmmy$(>ZB~Jy^v{;Y%??lNT0o;Eo*OX)Jj0K7W1vz2*jg0*u{_^j^nYf}i+=;#Cr8 zb2GSn@xCG!a2Lb%ixs;hP^zh37hLXJ12<@@FcK5vS_MEy01p^@iz2WxIya`#sPA{a z@HH(*RQ0W_GT8L<5mbQrp~lUpY=TX*J@|*=xgs~;q(r?Xh>6LK8Gxq@zS}_~Q{M7S zDGIkbKdG6StvelbZPu%eWp<%aX55Jyy_l2y`g)KduTV^j9lm283MMyEl&vw+F1JtW z6IiV_dgr$|7LErD<9(Bx7hgaKvccGg1J5Kg5TLBc4coJkpS*kMqs|xH%F_)=r41=? zTccN4n`h7q2E8^VbeNFEa^3|$Yak52q9Hju20Puny5+uwEPHwP^PTKTS;|$0wbGbD z*2LVhDu}bU&_JMPn}}OT>S8OoI{Fi_*hJl6Bnnm~J}bAfJjA2kn&Vzm=N{{Dw6cOyq@fr?*mHkW)3x%q0*wpa1ZBCaPnjq7iD|x&XPq!dcupZ`Y=?rFTDV zdek2KXjIndGS7FdzCACWj_Rge!O+h1Gv~avTyTF)I>31W;%#u*xQKw@V}@N;zEPT* zfv!dGqM;@{%?5#3%p`L+9+^xeS7C5f(;#$5)$9KGhk6A}8 zgVEgs*)Wg0NuVWu^$`*i+?sC+Mo`4ou`dRr;y77Fu@Lj{fa@KT4$y_G5=3MeED1^f64WihVx`?drTJ@24~ zY-O82i*}V*7AB%|R<>Kgo6PUG zb8mpTH(^b$3KzAeusJ+&{0pWO;x-y_DsyWWXA92_d!jsqZ$B`^CETS|*Jb|9mph_@ zkyb&;{yu66*6$AcTor~NtxMlGV84Zv@ zm&C!lr?6kJhfeBjrSQ>G(B{jaZNMyI*j#IzV;R9Y{$b*aTS;EbDB{sN=oAZ{<4jx3 z`Kikdt`@cjTlP3b`~IfGwXHpK!<$+GH=n&3xJ|KsQc3C;pbmeBgJ3HG*Q8(q*Yian zsj6#4J)0CrbQO{UEW8NLY0}}@%8&OdCu#(N4ZYgKaVqL-isXOQa$xK5FqN_B&j7

^l>(&dEzdK2gEd@;;SYRSa68OjmY=J%?D5JvD{4}&rYhCcdKRMWuK}dq|S^Vp4tj3y;dsE$*HBKx@Y6v|GQ@cJY&MNRb;-a z1idzsApD3SkH7@MqTw}I(`j;O952c}{-^NFr###9@)3Gt?S~p?O!$jpc6gWH;Z!K% zImCpIOBGATg>L>1d_f8kQ&ra>Fhqlv5KPYDXO)>w8c+$19VV7r3IFy!=|$yS#O?)Y z5ywpi>+1uB%dcF_c-DLvuqzY^9Abim$~3;`EEE5p;$hMN94UagGUkeY1f{~1O5vAs zpfE~LR$<4(TM4c3DS6v(OoxtCwg~2PTFO!ph8tT-SN%2mG;DNMZqsgA=*}! z`qazeQ+cs(epl+mNuUW=8MnZ=7#V1`=Lvevg<%RW9JN|e{SB6Dh-0UICRg!P7Bd~i zcTYI{V$-gLJQ}iTr5XjviTm1?{d@s`l&*(ZZt?yqfefv&6Bt&1QD-OfU-|j@f1zX; z_`~|HTY=6LY$>UsI0J^d70H|L z5^S?5B6kYiT=CgDvQH~MxtLUJB!XJ0$8F#b#7OYA1l+PqUUi`=T>;qV73=~oNV?;b zMb_3T*X#)x-8JGCNEI9Hy@P(V{-Sl@8+Ry2y5q#T6`XW?pYC$oQqOjqc75lI{_|A7 zUxfmlKUnal=IwxNQ9jTh7hcCK0OH136Zp(FtAp!ShkNH2arK2mp}AO!bsR=FpEp%n zmV}c}%y03XXV%c$g4BX&#^PfE0F!> ztS?$i3AjS#h&!!KPalNWx)#le#2m)&7$+^Oe)bGkMy}#MQq)NFNl7Jf_USHM!dDww zdoZaH*{oO*yY&Q{(Z|PW>HqckAZFIG-I>w^H7{(tf|OoJZ*Q-R%Y=jEIR!9#vc)Bw z#)s!}zM$Zl(+jQsur>3!+tuNpv8B7bxQ~RkcV72;k$P6q9c-bp^i(_o}UquVsdy`BBbh8H-fTlMee!(X^XcZdh~zy0*J!J0FI`V>hc6M zBm(Kjo?;Db2klgPQE>)$v4joO=dsXU+i&q(gM0U!rDfI1OsK;MFVv0sNoT4(mYC|I zPzGIoQ(gSb-sp(j#3$;~V|fVfR?T@g)wR)Xk@PB6hsf`-W-q8$if3-Nif0&|)hGP^ za;Pry!HUT3NxK8MB0xkZG7b}`ynS~7WaSPpi-e!mDdRxvb^R@YW;_Dcl=#MN25@NY zj_>MN5>cI(bKc7*;N@CBI2v5v>gn+AxbRRU3*8&M8~rWr;*I+?ZtQm3x5(EXmx|%M zU&4{Oc#EO7{F&HlLyw!IafpCC1@+B->58sWMK>I@r8VsoL|77 zz9rNlF=uu`1TKbCF>^C)Eh?H*48))_HL*iES;$uvt+Y{5b_x2kjn11*WpTuRx$skebuG%`n)*m8KJ?~U2u%F;N zr%*1EOeh*nu2#+JVYjW0;=la!F$Lc#R=~5`F!Sl~WXvd37|*LX=;E~}>Tz!&Z4lbR zSd>Sl^#=xub>Wr1mI_#zFGU@WSh`fI-W3ILikX|SZwBq-=wCk0UwA$eX~7ZjJF7)& z0ei`-YUJeMrI;=qhbexmVI0IIV{{zFEFK(FABS3(UUpb0zkHAhE#m(32h6j(4 z8cgAM@avh37GlHcI*DtCQ7pV=Lw#Y^`3nM$L$5bLmEt#t@vIPt0!L30~FBRw*q!x3RV{rXe>$ON$4vb0aSM__qv8BV#Z z4`0yp;l|k5Mn^2D9bw87tCC!tty=-?oHz4?!St|}1@|9L1O5mjr58?+QVful$%js- zvGnIP6S(@IO4#t8Dveuf&%3Dv%r!)FVSOjIk16L1$&BsjiG}%e*Cg2Lv@iAbq8?~X zhqShqb=+Ln7j&B(ZpZmU7!pOzfp9HjoZ>sthdv`S@gCf-M z4w~Q;5lwul*kx{*8?V68JHZG90gmg1cRgncWyQex=Eql!j~`Ey&j#P=S*3PpO?ipk zquBC(Ixm%ajOU;tH32)JXnk$>S$%^afqjhN5P1epx?_5wb%xVUagmRY1P5-2Ui%EQ zK}~GOf#va1zsP?x$VJPJM)T8Sp9L^8=9!`W*<+^MJBtVU95dN399it{ef9EubAE?C zfx?i%kHnr6m+!5Fb4aR7@E!+_Eh%EMw>VSLO^z7X18e-dLV1Zf5%=#v5TMvwKx#)w z|8t!f6b@kXv#1(pVZ)0Z=iGbhiR@!=+-~K4ho(&lZDJfq=Ae7-rhoZRcZ_6E+e}~a z2{qWqpf||D4j5_%usnSkE6MQ$F`W_QP6pH$;a4toW|lj+NGL?#YF;1LtTdp*PnZuX zD7@#M_QX&CGKCub;l#y03>`Pg|7saRG0A!QKNi0a@e|C^_$;}tn#g!0jRe&D;{pSHD>qWqpL&lwgZ1QH~+U2f&tS)d!}WU;aL0lf!#@W z5Mb`K)MGK=y|hkUvBtf9LAtu<#Mv zNs0U8VGQK(O`POQmu8J_ouBWqx*pDE6Z0vuGsKgvKC&X<_rRWj0W^&B@R`raoO|#V z$YXMNck{8;e5*z`)?Ka$wep8A1P<{(&D|+P|ojC=_Uu)ftR7 zfpr)n>hB!4=6n*RO91N-*>h(4IE@|po4)EBiyxKIvv}7yi~8LNDbS6AMOL*$B=SV{ zFs2VA1dhjJ5}P1pv3kO(3n^H)j~ymZciT*G9;)YCs{QU^3OKbAL65!C~B zioEcx90>OTj`0N%MPIOfVodY-3Tr3Uj=RjmTs=3&akl>8&f7A;k|^uH((^#iDhR&H zZ@oN@E9u@t7Wi|ZTcSMg$8(dcl)a!ALHPZv*J=jHR(86ap9NbFJmm$tch&yKzqm?i zGWXHyHDn~i58+>abrdxU;A%i(_E#s?hP0!eSEMDZ<))HTdxqDsJgjKsr)pDOWGjAjVtvlCl(=2~ z+BCMY=XHhC76?M5ijzoHF5Of?|L!=SLJUC>Mq?UUGsi-v0{mG} zz}SUTkr~-+d)eyV5{Z3`Ymi1hG)REA5@VAjj41UHH~l?h8*Li8s+kUkj)&fVH5dO4 zaTT6`)nC79JoLvwe9#tSOca#^;*wS7ty8kFQ21Rq331K+qR&VgUu$AG3JZOsm9+_f zRGj)#vxQk=Ot*FVAN6x41y;BMavANCpgy_9RH8>b>`9?OHwXbQ{hn?I&HtvaQ=Eo^ z!D|b+(z#RFJU63^BYAE0zE~rkq--RfavfW}*ux|0;j!{?qX7-gFxgk1FZ55VP8Z3` z$df-{9bua&^xti8q)tekpD#4`NpPq!%pW>6JNgh#f(fB$JY#)EWWwB{>YRmTJ!Fk^ znetHwV8Ce@wZMV1(=?@EM){A9yC3dFG!sh<7twe&VapJ-`1k0}Bl>_@%brmIi5bLS+i`FT854Bct> zS=Z1vy!ry$FA1Kp&U*^c1-e%!HKi5Nqr>Bbukov%9jo0J;0A*GTzM~Ggc)!o<0AF;p5xmhto=0#cD zO4zL`Z2>Hjd4BRwO(3`Z^Z7=WC7c76LrnyKs!$?5FgXHZBW}lS-)}2LtChE7NS>5`4$jqdS2%QdvV`V?~Gn2Xwgl^uPUUbWw>0ell+>SBqG;ve?qoO&WlSmskF zyb)?ChqVM*5vWYbm5`ccif5Q7ZLRjzV^ZcPC02i#Fj7eL!G51%0-*RxiE9p-Gx>V~ zXWvmR_&2Z@Wh2*Y@BeKTx^Iv$WrNuDHX^Sq>O1VT8y8nM?3{B5fo-rX8D&;HgT?Q( z+#2|Xks`?$@mnXx@j*>O0MTyi7RLjhiK4C8y9$_opyXBajjhUzXFJ0etA4kuKh10? z1JGZFoHV;1hyzHpMlsd)rh!oTxfM3Y-#dZ+V+HX?Pz68Y0z1c0qjr$y2yK{1z|5FGyCX33O zdFk&Nh_spqt{*tL)OD?SnD708tpApQCQMTfF01rUu}I{A485xzU4K5BCX$uGBr~&_ z{GXHk(CNRw9ycw*1LuEE=sioR*<9CRS=`XHzNp%D^N&u_m52{CAXMcjKmSf!-~@bk%%X4CfR8Jou&em-+qWNTt|_NOMsKbgllJLj3AL!z zW&V#%`GEL`cbf?uKOyB5_StLsmq#AnL65HMtM1-<5$)U7Id_7>A8!L%bYV{3KLv#0 zzK%zEn)fK`OB@+)_k6sjOeJ|pU^H?*%BV=~^KWOVq8f{fXa z`sS)%L_OvM8$`Ot&M(Z|OnFj@e|}azqK7`l2V{l`YDeSk<+iiq;!hS!21PpM{FqPA z1sIPF(KkF+LyEb)-JXP^HZSdiLN4=yg|4N7>b^yD2U%Mq-8@N(S#gS#xfV|%9c`Ta zOOnDDv<%e3s~HQix%m0bbBM)d|Vb!_54WXu0M{H8JDy>hyZpfcufqjpdA!9+Jd_ znH>7A(mj)@Mh3*i=-Oo@8cbj@LK8`Pv&0{HJvVZD0VMX*esnVayXIRJk!a zJqwJ$3%}1xPDez9K=1Ubj;E=(fo3YX4=I z&9U+8d5zMI!=ip+?Ndi>&8oQvOCPPPb*qF-67n?nhUy0oR~u=}MMPPIh^YDB%JPhS zG&wMKw8+;uYh;bF7MN#829}V2JGbbsf=9C!OX6x?2pLOT;n^+}zQ#yU*Um@cpg$YI z-;5ABJ?JNFOZDVRqgsZJ6EfMa$FumEIkdqBi(b#V=mk#uM75^+4nZYuwuD286<^2o zejTUX^|?hJw#VbhBx#&NZOfsM8Eq}a4$}ke_Q57hC@q4nxPNoW46*;an_!JrTz${*JSm^W;Lkx2%xh)1WpZs))+@rQDNrh z5|)L;+EK@7+|xNVHqVPkZF;l<_n3TVo5FL%`lJH6a;S2=?tXb8=kS<{z~S>*X7kjx zt}AYr9&TQ}+m(D)y>TGo=Fx&@YXz~93wYb(46J&~p^Zy_T1#XrWn#Mwo&Io#fY0R8 zKpN?m%U#l~Ir0I?NuBkq`QHBJ5rkc*__XW{n#j=bEDN=E|*VgNo%BCDY+@5=uG(yK|ApYy%az`s<2;Z?# zB^d(2^G*H>X{F;7tixk-m}DW}bhdN`$8E9l42t%)bINoKcaoKS{zA-5O^jA8c|p!SXX48>hR=4X+Do%VRSsbwMfRMhYl9az||Do8eJ^6{;Gq9 zN?5yI9@x0w#$$=+=rQqt9gps*=mSEsMVyY!GmHFVfhkgb;XR>SGP7>iR=8;QoU8Nf zI(sOm!p6wIa}#&hbednJU<$lkmC$~Zj7O2rgn2p%1o5d;f? zEKI^eRE-3V@Q>rWbP#*V&wjMVC7c+&kdZO-e%kB>;Y8T3mnk2i6izaU0`x?IuL#@|abbisvstC0y?S`o$gt`kjkIbo#yAR%2ei^REgh(vp0f zdirtd-6L7LyAo#Rm4REWDsA_|SnjHx5$tZ4%#X334ZX0$l5KiD$H({%Tl>4aJwwbk zindcPf{VBakhwRmF<*ZA7v#?I3X2Sn^Awm#9#rrisX_bUJ9Ud`)sD7qO+cnrHGADt*ogKU{AP)s zoLgL$R<8Ex-N-QWo1Kr7-TOLA{q^BDUxLXN>#QUm@LXv2s{G!PYGxJnSMMIZaWoJZ z4tMptoo7C0v7mSgY-1y?)3H1vB_o*F$5XyW8k~zbbmd7~iV%*t0h^Do9lr2s-_I_C za`AMD-GDwi=dYu-)kkbIOZgpTNhLx$=p4=VA-{ryVLrPjB%zX|Va%$J>R(X67DPN6 z6*WAEUw7@6FYMo<@}UDf7{3O1ASfUOKHOe;Uh}O~M@zGWDf5JN!o?otHN4+zNzgYQ0fWq;WU zvol_)sInCJuf`aO`8zn?8M*-n>lA#)k-`m$4pUw9!=-+nuUQH91GIHGBUCCB#(s!v zlU%CYO1I9_4HO;OlPwzQ-pe;Xx|4hj2r!1=|9)U;0=YzK)PR-gUSrAR$Gm-ePEvYv z;qlR0EurV75aclVK$8CBWRKnZdmq)@iXP(*Ls{|MsvfxHutdu?X{cj++xWv1UgJB4 z&Ltwd^BMW>gmSH-ynxnvHz$7SA=zeMrb&*jNwaZ-L$yZaxQykTBUxXwi0BY#={RY(8pCD1*63I(fK zWppwAyc;Y{ohru`_tx&^e0K?S5p%9{SfOw-1%(Y-AsV<4rls%*yQ>2mXI~oq<1T;P zDp@PW?o|l1691H1_bd4ipFe6c7p61`k>4c>mov)=27u(}so%x3iIX)*Hcq1$952#J4*T?2ybjNbTMf~FkNETdYL38yhdjo2|6WiL zE@FS13pJ9NSHyT%^)iKW_Sej}6f4mov!Sr(PUNIhI!-B@b1FGSl!xKbLy%d@61BGb z>niT<6*;>}3eR#*R?nP6Ke|LR$fc?n`!(Ia zV*0K%!&?OsN8<&jqQ3M#?$nHkoTV!RZQhx7LZ(ktHC`%<{bpCeR|v+J&0f-R|N8)@ za3v|eh4<6?{Fe$AOy8gFlN{Y-&It@-H|T#g@(JK7a)QGIJ3XH5t!LDK(uu~iK6zYUqiP%=)j;0)ib1yFQh+vU3y#=FKMGun^~`s1>lCCCj}eG zE~=;o82Cyn>AFR1*G*TZJ*ghi8hJ=zku>>wfN-ayNbqbsN5uQ5fFWGW)9rLx>(OtH z;;W7}?~YU#=YLb_4SaQa=o4sdMSm_-DC37^f*@`n-aY?l>#a`z=A(ya{*d6>2S9>@ zxZk7#l(j-gM9Z(thfnYAv2JCrX*fpwKM6`WKmMtKZ7E zzXhtKN>QAbNHPC;dH)gjc1pT|sppul`%I#sGR%$4bt_(9gu;XQBQLBR<_htT$H<)? z2*h{M$nbrf@$LdPih&)O`!-ptIQ}p15!Oil{x{d0il$7`yTGe)xom5(+F}G$7y9!` zx_$XCvndo9NODF@F1t^u|+TAfMs;1#!#K%Z43FO zMVJTGBAaHu=xJ?N$)S>f&5eb@6h(S^xMtZC^>M3^c%d*xd798aXt@Vyp?Ji9572T8 zaK!=L{DYQ}GrSo}@#Ga*4mELiAf4v6Q=ppPrXm)mTob15tCSB-J)=bpe49kR+qX~n z#Is}C30|8~s(TMoR?e2bb9V{8B=BgO6Z?0`(FRhx`}pl4paaf|1q`Q~AowUuHQvI$ zmRjYr#j<4U#UT>XDRb2TqGgx7#Z0j=IE#gd1*Y}(3UV2YcCLGo3MR_NaK~*}L@=vJ z-FRHAT<1^huzEEj!#?vNvvO&ENBoh(tVwH(^?dJmT~6i&pR%=SzuJ$MZL8pg*CldB zdFqvq$Jo@9!&p?~d)xP;3}*9n`#420sQ91ksfhr#tE%T6JNQ#NC_qkIG-tqv#oVA5 zgtMrdzg|FGV4o+0R$@1TAl|{y?o_?AkSn+%CzF?|BuWmIIgSL-Rmu1xjiq4 zC)FxsN|BsGRfs~-gW`({bDH3bVxcF1%Hs1&hWCIdqn?m0ZZ3WipRO!7O}*Rv+I6F- zAMg9aJ6Em`a7m9=dsXj>Y`m>H+%@muR4ld8ZHwenN@Xu^Y8k7%E&eN2q9_Z%qI(Ctiqh7iuMYD)A4WPtkv?39aZZ98 zG2E8#c^Y39jl{qB-IW?#70qv1g9Ajhtq7PZ1cE(q+k7h!g#9porMcW{uIfV+<75E! zT^44p*&E4ODy;;rElhdFlMjd-dCU^hW+f`qZ|uTw!+@P|^w!}ayvFVgUZiXQ8+#vi zxW6W!HBnm1+qS>R8FpQ%q0h5a(R4YMuWxRAXKiMoGfCWv=*$<7Xc7I}CIbqWtSiA- zT+!#QD_5`9yQ04*-wPDnxK_Q###lzbi?6r(3++$QK$AR-CFQ}NiWURb51w^_!H?0U ze`t+qs)?Ri&0f)_Z)d9qXK#y2r(Lwu+HA;e%O<=$e&LS-isCPOR4U%P_Kqe57cb{-6ju%+m_nHg8BXkj5}W#Zn0Zi&9`tu^+F#36Jk{oV)73|+ZT zRonY(yHgR`nzM0ioM%l2@{@3`F&I!!GG4nj|Ft35VSn2;EARrB*=${i2+p}*740wh zMPL=CBST3r>bD2z-^_{aV;FE?zJH)_ep^N$hrEJzAx}a3MgLmJNK{4zi{+D(hG(W-ts{N*gLs2w5_=86#VaB`PZWI>Q*WSjSKpG7Qf(^{#j2b9|oT zIgaP|JHEf?(I2HT_kCa2d7am}yw2Bo-C8PJS*L~?b08Xb4L^zM9dnlrARdX}m#Lke zwkU97`j)L4DdK;}i^E|2Qzp!4E^r4hpPUKbcjH!%V9%mv4&O%8M$MSLz0q(#M60I$ z!MRxe_l%2Unq!2c_~yz=h25cKZtbqa?gcfy&9t0I2izm5cicq#U>6?VXxfR`RPC|T zXlp1Ly!<6wA7gopK#iX|o2)$6T7V{FzGzicEiYNky{>ce)t>8t<#ozN@LGtSZd|ax zvr8JwvYzAHrQY=PbQywDa{@X&bYl^tS)~ZIfJmO9HtRRUbUVC{HBAXw-}&5Bg6XlY zbMPp5a^Mlvwx&cy+N;_K%lr%1nQJ>eR(|~QQx9s#p;w~`#d_`QtC|_ZDrM7H{9>s| z?O%Ztn>xs!j`W(uhOJ?#miWRbgI6n-9(imL5ik47j_2^&wUeyHBlmc|RH9YDgnbEG zkBh~xid)7+4w^l?SehH-8P!vUS_6_mD7t2!f%jkM~e}-I1?*+U&h-SP= zo}`Y{tYz?8OT1&m#0v%@>Qmt!8SnYQMo1Y^cpjQi^`lF zk@_oW4p1#8?>-J{$^f&NxjfnDG%F&mt>V__hMLvvF7Zt6DRL3^dT<|YwUrlrgDDfCmu~UsTmLW(az+&4UHLxt9lLCxnoEmW1#m?PE z!kQ5rwGJ|3fB4Qd!CcHVEv4~7_D@T7jeD)vZJ#oP<=V-sRG+rvxfCS#xN?T)ach`+ zY5CI)NDZ1>r)*4H2uVNt()F4M6MAk=EIXnZz1ak(=rDDuV&>zWt}yL~hqF9m59e1j z%VT`~(fUq_JKf=AIPb|zH=D7R`YI}3)T?>n0&PX=cWPh~Ztp zVobGZn8zx0_}B~0Lqs?bSocSqZmFcTBK7R@IYa$nhun?h1N0v<`3 zeTl0qg!S7DorWFUST@Y@ST>&f-Ke`B|Fl5gsEm{2o(cVAIX%V#ZQ6VO~smMG|x>fQl)mB-sLbNXAm@^fyyvez)WOgTi-A8<3<(F`g>0L_oTWj_?q>LekRA! zn?8GXoFilwep31*K6Lo)kHFg96+0kn{x#mH$knv*+l(>Ey#n*Xxplvi?=mB4XbZ1g z$2WHFOMMuM#%Ry8dJ8dlBRjb|bYp#axSaJJcHadMvdDS%ja#I$2vGvUjB7yP~ySnE-PHI#qi zui%?J=g|iY-r{YvwtX5nPLxH%8?(q#WxCNF;yUP!g@&G^8=)DgJ-K-PxbN|d%k97p z&7N$=@RQu8yz|h!JDB!zNKOccL6SNz)6>zLnJRBwkpo$5v_akrn|=<9kXG} z-b^iSF=Tw)7i8PRLl#Naa0Lxq7ep)ukC+HBdqJvH-zc(K;K}I2#>&SGEeUm-Knr(L z(ez@x9pt=Eg5RIBNRa@uDD$st_?7M_vj=1(Ce3{nXwgch@!jQ@2Ypt~xm!oVM6;ij zWxK}e&{b7Nw>I8qx97~k6Y5n`E}>G~k>)C6UW|-S+R8b3y|-Jh&~Tk9z%}Wf68N5W zDETiIG+*pT>gdHE&o7$PmvHZ|gi6NCP9K*MgF9XF;?HkC8d4Fc@nItUU39@oOmDvW zM)zJ^wPlZ_d(TKrin>xgKsaXkodW-rKllk8D+pk(zNDiUf7+LqvcXl}4Iuh9#}^s; zd!I#H^GO);D{eug$*K(~knN;?E|DtNrhpi!&kVDL5Z??7gGQ3w zoPen@56`>j(~{a9zV6S*zKy;1&`(jUMLly7w$%RG=f8#)f68BIPLy=Zc-~`@K2KhN!YAKR?&+lf2P>wzpIqWCENsO_Tdk zYg_`$0tVmT^v&~dd_1J>=p_m7$s*fS_}2$qGU>utp-GDH_m`8|5Kuqs(LdwOo6aCQ zx!D)EGwSEU_=XV@GM{4*eW1dnF#Ei% zJ7u!;)EAX~U*^|-jVl}aL=09(dM>h#dTWo>xt#H<)IWzVI?Bt?>T`4YW;Gn-GWywS z2j<`zovh@v-0AmDl|Hj`D)V2|B^T#lW>u!(aN4^D&DMCT#vVn-yEi!b9O2MnH;YEw z7cCL?xypF&iCmugM^?6k99!FHwC)x6T*Fb~lNwp{6}_Y8MhV9FJuzMeib3DL)@7ed zyI~q*2Qfh;`2C4Hr3i!lui*bi_vii(e!7F0!|imvTxI=yOk?%V@eC+!+}n$~p$`14 z07XM+iU!>&@1Sy*NZ#7RZDYquk;Sw&ag)XA%&W3Nwe)AC>WMqeDtX|5HUe)>C!8=E z(J}X;Cn-1dwrP&Z*NzDlyK5iuaIY4HlQ}=V&0&w}Sjjz7-os6au083uhMgu260<>W zcD_oKxTV=C)bvlA6%4}YE$PY^f8o-Ajds>w>D1%}>XtGd1#lvo$?RHtjXUE~{=xe| zp+s<7NeG#P6eaE>v&@RGK+bk7c5tVakP!(szM~@j>d$5$D-#os`#m3nI1lukM<_1Q z2(~op0}=YCD3u)mGM7GoPX{x*7NL+QyJL3K9R_uy8e%{cyMrymu2bn z|NK}rY|~<Me4Q_W{ZTGs(++H#bHm(J!YFw;UnwUg%Zk+Ql;I>-kFt)7h(l9@8+fqp^AxiSb#vG@1v0=Y!2Gz1?&uhL&YoH*u@y zZkOL#G1>DuAfSYspmW7V9-232RW|T65ADb!tKkw#AA%UA0sHATY^Ja?g(QX$K1!sL z&{367;IqlmQk9>#^Q#0}2Th(_xP({fTd#|Q%~c)i_zUFt@(4gLRq1;+f)w`Nr4aHt zVT}tPLR9|&J*8%J9|1VlAXr`D*_$4x>lH&BPTaEs1eav}Y8PC>?ABiCP7TP&1(?({ zE!@&2g9fLsfq+BapBv3Y2DZppW>mpnkEujmn7QfddTlHlcU7@ih}if9)TOPEb60rE zZrBmNsynAumx_f`x-dCTN&fnepoq9mWM6M767WF_gO&p+1dznF0k33?wJvp=nSk+R=ADgiA%s=QAFAdZ zZ|a;x>gp8kqbZf0doW?hBQhcmO%1V;j%;pr*caKU?7zX(mYcTGo@y__vOmU9-DAfM81Hy45uGb!8$USuKoezU?z00C-Qdi5DC zI+9<})lN@+j+;dvWJe>1J??(Ts0Fr=#wPGGzxW?CK?l%uXc-h*6pGaqZItOz8& zXw44lXUtJbyO>Mir9997Y`n6tL!ZVqj_o!qEC=PVB^#;~?SS~vr z8=?=&Z1bEIVc<~(*?M3{MS>kg42~AJ0EDFlbh}?f5*ZKsP;=ev6%1Rd;Ta_uWFz+O z-Meg`!5D?BpBom?8&5I{%WCTs1sfbUg+LPwP5$0q31F1{nS0on+lz?~bNoPuSwqgf z^uQ&w_Ht4U+U}(*oZ2(4kS|JXw9c7+$RFS9pkDk0NNoQ`gV7p^1q;U23lJ+CO&-y^ zf_c@WSX+Uq_Y$t8VyXpdGjdc!PaDOVH(y=Xo{@#5jYZa8F#?wA)=v0O_xKMuwYU$c zAg4nu(~ug0vJKgP$FH#nX;x26oZcdD1aS@_Lt;>C;#vi~A62N{;l{_QRD+SIh3jW| z^M^noO9?p7eq|`>MZSL0$~$fpuca@1+h8CTwnY2@_ZB~5+u6Z z&?|3vipP*vx9kX3@;!h0Vzw6m7p24=W-!BwJzykdbLYWd0NG_@O;Z&LfuaHXNB>QL zc|RuS@ut0cX5H}sHz#FH`}6*YX<|pY)^qG=!F_nuS!f{xLEF>xa1@23>weoy%(UwS z6FOtlfP+a2iGk2rzO}wg@`sU9J;L!#hA8>Wr+hy#%b&l9guX~O)haXEb)M?#GUi8> zHnrF5q#Z+tQ+EO%D>Vq-;$8U(4gbnxV99^=0%3xCq`dDokHm48kEa`xAqIyI9WvW^ z=Jt-(#**IDg$cX?6VdiV+Z2LL%n~8`m+-MnkN;y$UUq|VO(<;xe|5LXuv8x$Xa-J> zvaGKNzoTsK71J4BR?T}%Tlm=CvOHIp7rfm`JHci)0Sa+aOg|?84q_8(Phsm&V*=)# z&t$7QiauLZF|04{!OWG~5(9rmDCwIBV@V2dZN(+J&e8n*vbP5I9z7T2+-rE!^@ z(`$l-wjHUSc+%|^a!Kw3Btm|A_MPj#ndG{0xsYc(qXrl^Z{Ypk#PfF}iqjjM4hYD+8)l3sgN3MKR-wQOHBmVcTL| zDBk<)Vf%Ri%a~-g_~|G>h^U}3lTNI0UA88U@4dkquRqHnA)uTFIWc$L;$O9Wai9hB zDbZEVJ?fL)oE5djje%8H$a*iHs%TvB=^}6g`{ikjzWHA(6Q2NWX z(tgFP_G0?hE^UvBix5%yGcnooVnozpe%;KxQ?kYD#&`%}1i*q3iYQ#d5no)7&j^S> zQ`){R&QEvd0B`6G@$7!^p@SWv?w}d>lW*~3Z*U0!efy9fmCN#vQ3Crv;~J#e!vKY8 z?YZ2=c0IwX@aOuJ_y>p!5J{qJ zKP*jpCN8k3);beWOrQLP6oT@4Mw`8e)1Jj7{>{lPR}#C}6N{D6%L!HIsF`+K@UdG*BYFav zhM+M4E8g!}8{#~$i*D;*y4YVfJM|U&nh}4(C3OeC11kM=Tyv{aWn^TVd%e+dL~jG4r@M$*Y?Wm{v%=ER(-!FngW zsHga5-V=t=qWXpL@st~lMX&DLH28-%E`;li@(SjyHBd?1_by6hDYLkw_v3u`Bd?)M zfU|eyu_J^Thb}OFPW5|maqTaH0I-Xv4g;jgJ!_BUQ73JwBp*`M;A7PElNk_Gu_M*hXx^HokU9wvrwesBvHo3&4vLGfAd?4d&Eq}erA5UKCd&+xpqHy zxY54OVXpBf7r=I^5mGkU=dYwLEX#? zR|*gGQ`{**$*!QHrfJIVGZvF?QQ){X)l#?SLR_sS;Y5_N7dfxKz-=x=E;GC`wseES zInEy5P*9%B5Za1p%$)>v01ULC*76$Z)YWOn#u@W5c2h4`AAl2fjgrqwXlZGgy-h?| zLULe_BN{+$^U z*Xu?VLDddcIfru{t8#UNon&$*0N|#Cq8D1)22~WhlN=>e0W+Zsk7#^n2+^kBYn$<8 z(c^a0(3XdEG)_D$l>gBC{LH2})UiPj>2{#z`X@i^Cq_IJ3y1%SZY+UVmX<6l{IBt6 z4Zg-#?Qt9FSMeNJa9(7;0?%F%3v>u6J5}o3DT==pTosg!hQ@qgo4p37Im@g}O-}&r$EDGRIONnVv6FXR%mLW=Qkijiu>ea#OoQxeYELoE`kh;RoKO8$-jgTB z^Bj~R9kP?}62Fe3#f>v`Gmr+HyPp~;FA=AwrH32Nfkf;iz&DEK2hRQEzWrnGUNWO` zcX9E5=MomGid&Dbomr1*@v?NhLnt36lur^o_7NM^-rM6AdUEo{8e7vaTMHB$U3`MZ zJMK*OnAXQi(Mlp$<~RY*|sFGfuC9`cHR8L(Hu`z#2oj;s$>T?&{t!5Qx3kuo`Z z<_?eXr`ib90yB)z<2}YdtUVwKfESSan^1F&pIbf5{MvH~p7b=Q>EZ-hg1}ZNn=qrWoph7@A0)l)-)Kxm%^hjWsq^(cix_^M(4%O_0k*Yx!cl z2d;H$y1C`v*vgl|XIU~^)||`hxML!o4i>`bPON0-(^H{`4W5@BJ0yrG14U3tt76@u zikczH%$p}2iN_tZV^bzT1_Q5egus@U7)gvH0N^+69<8S=Gx9Vd_PU^QuEvPd$ETZ7 zFF4Bns*v0~4PeEyy)-V%=?|~MF_dA)rYBiNur5$_kIUY6B&ZbL-Uy*|=_i^1fY0!U zSlKv$AfV{zxgq4xfy9kt9{%=ETw*j+|)$p(b=xWw)X% z8pnNO^Sfgm3;=j}dzN?{OKyMvG>jEKLi}1TqO>p>M0v%jQdk*8>olh%vU7)A>26^E z<(a?xXrVBsdv-3^?~*NMkks+;knwTH8D|k-2iw|SUBwKUyrY)%W0N?Q(m#r5hYj*t z>|mM?)e$yUFC68@eo!mO-Wp2w+$r6~m?IC5e(CkeF3S%ZT?iN)d_6V_;hgp5<`HYUMk3&_POM$J#!sGWG9;(hbGYy(n;ll_~@}@=v488e#&J_bf#80op-dxSUD0$-h|Vw|R(c z3Roq^_xGR4jjFl6NkUv){6T4mBX!8qjk_j6Vl;4R-l;KBrmjp}5%n%wEK0!l%PER< z)4?B}n^pTIsP|rCGthmMWJ8C=b$zg2F>@j|3Sl5=9?G8doJVD4~JAaw%AMr#GSTn|_ zhJ$kJ`*do_y#+l_#rMccT3bx8-NZRgTiZBk8)=*Pl>$+@jJd+-h<`3r-#Fo!b zU2nSZBNS65vYpt1Alvvp)bN!JBj+T6+SLGj_jr5~vxeR*p~gb%GnsbE4fm(D0f`=i zT4xzOGs*S6!gJ8@WzMh!UIP&H&P`<*$C;4;y{Q2otoJTau|(V~_c8QQ;Jlx%Tkh0w zv!{RV77Bqf(wa8hISJSea3h6+s}sw47GFBe_c3fPknFxUUi@Z|E}H_Hj;W18iG&^2 zCh+6eI@yJKX(hb|MGHaDltOOH*n+-FRomcF0jG4ioK*`k%d?@zrOe-HDe3pq++}_F z)V-#jM3=8vXCLc!B*qk9j9=HH$il`N@lv{K@gvPT2|2Qjd~)IO$3c>DM4$d!s$B_e z=}h+5fL-vBmg?CZp(0`RZZ%A1@lL%2$Fij2@Oo#W0N--Lz!{vP$N2dzdhvmp34 zDHv*WC(*M%g0xN6_48TOx9W|RV-Et|*d9vT+C-_$r&|`g#ksgoFT2MdcfCZubW!{1 z(%NeggNA<*=!9M~_n_OW8h9D!+=M%noM48n`mmwmn0F>EZ-HS^?Aeb61q0Ypxu3Rz zZwoII%wBq;_Ok96p~bXx{22d<%c_rTkXat3gF7kl3bqe@(7NYpo}N;OL6*G=n`_T7 zFi)wuj%r1nojDpXVi>`D^w@zRUf1XbP%!QCr0?sb? zucmvnu;P72l2z8pTQr+MJ#&!g%x+7Q!{^q2`smgP$tycwoLD#RamxLq`N z-w;G{B!}-*usy+cJJ`^61b15y&xBQ+$cG^ljs%u(5If+j;L-6SzqW#A_R=%18)qL{ zX;Dt3d&SOcBDFSd9dX`Ckj2lBQ@>H98S}%*U0i-sL#7eDvb}qo(5Sl8nv{<^Qu#~w zKMgL^9|6vv6Mp&nrk$BiQ36SHCcf(kdi|-he`~+0kOY%&7j=!}arFA3LJvznMg%0+ zXOy1P@K_ltdR|TpULZ~zBlw`SVP<*7`p@I96(AB7uu-7J&V^rB+vsEPI)!_WGe6Zu zk$BsgRTJ9#b1z{_5AvW1atff;N7gZ+*qt^dKWSDh8^@J<8i2$Z+kOE*2iD{Ly>)Yn zbo_Rt(aQ|yKaUHlgAnyAtN)(ycoj`}B?VhxBXdQa($$shw21nodt_ZiIM?i2QA(ZhKIwUl(3Cz~^U|YC3%g~Nf z?V@_#Gb876P|e{2&-=0{Q4bzIO#dbYEp%zma0{1NR_kZQ6uEY`#lR`=tqn#rTnzJ) z;LlS5Ezq(opp;MDnL(#nR=CFOl(bA2=?{n=-F@ZCm9DJYS9jUwD*4ZzC!7=1t%z5^ zocqClxki|_F80ovs2COy5figQ-Q5GxC)oI72#o96>OeOTx4$#KG=z4quaP7&Otp|2 z^(N|XXz5Gy8*M%noC`cztWvyjKBV6_jW%3T zc%hG$1Rw%&6I_)_G33~5aSbCJ3_BR;HRB98XhXSBUIn+un4AQ4H&~q1pO#*A4M;iG z-4q;E=L`TCXVUR^7o2-?)L5>@UHJK_7bn51&$GBSnI4w0;WCxF!rO&WH_v^ycCf59)57? z9c|BWX?YpUBy`VA+`KRB&{t2a;_O+*5hn)_Gk2a} zU>@KPnnEn(#;2BT%T*{h%Cv*K~u2SDQ9Gj>fBuc$hw{SZ0V28$Yr)ox;J8 zpzv6>+~?oCAY(>CP`ydi63Tmtyv?=!%7Jml2Uzj`h{-Ooi=FgNr%$Y<$(z z_fkjTsC_nD?UvLqj*aoz7CEtF)_%{hWn<#f{tt$llk=7glm_K1U~1%B(PI8QO+gFP zlClyj2ux~d#|*&u{gm3P>;C&4yn=FG0rvOq62Vpy3ALAu1b zyA8P<2Qg<$@Nq^hGv??n^*b3;_0nB+%__@>y?CsS@NgH$`>Z2mTC^ioF3(R5q7;<4 zANo*xySXRgVR2%5N#mWn0ox|JTi6(2zo`#Ibda3}2af~Y@O<=d+2TnE`9wskePYLU zct@v#S7kq9q&OF6nK=>N+PP5vhhfU{^R8e06 z9Td!qXK!eK*k{+5)my5wi%c%{@;!Xh^ekAbD0gq) zeo(5>6Y#kyS~H49h0&l{Mj{mpOACScvB}=cC9r^Ucu`UNu><=~0bf=UuQWYgV9$7T z0aPWDw=U4w5mc*l+`*T*fa`{62*WK8^D_ks^Hnx@pUJMu3V-;wx7(~1&O95~`Id(- zClz#@`2OfP=}bMdiLiX%_41t~ihroWnzccojzBj~$Uh8tkoMm|%K<@25P6nUW$I?m zu^|-BWim|m)JRBP<&;ma`N)|emO$^8?=q=c&%Ea?cS~|)B3Tpp20^j z`rSPqo1l-XX3p}Z(H=1xD+e5naLVkNOq`9CL1W`!&v%5=_)@AM6^yd788-O{m(tk z%q<2CLGZnAcc+)s7r-oyS9FT(Y)!aWo9R;EC_i~TTA;y&9NU=S4{Ds|>k}kG$x`=s zjPusdd?a|LGDYvMgxuJ0!qJoh=kcl^4jd2VAsrKxN0XY zDe{m-b53xQsZ#UKnHB=lm@jt?k+mAZ0TN4XK-Cb~H};nrg5>ia)Aqd6INf&qyZHoE z8l5Bn)^v5g^@y1XPAlE+_c`;N#}>F*)%~60@oUKCVgzeV_uG)Qbnv#lXBGZ)mQ)Di zTUrCW{lj@?9BBG`99R;ylTu~rbkyARoIAmuzk?lQFK~2r&Wp&gho-|Wl0{he3G5gz zCZo9c22+Pxf%pkb{KT3%W9q4yPdXDM+s~xDq~Y zmul=4ZNb!^Ap2{=KNLFGg3lyR)AG~onpE{?QweDr;qOhNXQ?9x z>~Yf?S(1+B3n^uuhq1n;b5ZqAbSEGp@1FE1rAIr-;-N9JrUa{g8MLp2%X3z{Z~cXM&eKCwy##zvrZlXRV(ewxX&e z%j(34n_m5t|MZ`lLC22*j{(R$9Ca!?w<_hnu}mY2r=A>3*XGTDnW&cL^2?yT8}YtT z5*EVV7-VJ{HF5mkdIwdm+UC9;gy?f~{$J?uXVu}K=2xd!7LbveU$~HJ{vnyW2VfDd zAbl{4URt-|V5JpAtkKH^vON^KE>`&o9LYbOhN3%no+ICWxufrqd?$myd zKDLQ*-35kJ^zj;q<({fYyPIZ|4ba^9tB9QSK!2l705;0RoXRFbMb?Sa| zYTgq|90*d0dk#R`Ewq=)Z*&SM1TT-X$Wl^=8`?n6@N(#C08GEX+>L;_mQ(L|<`|P9}uv^t|6mjXqzvwPZO9i~c zhSA!v=|a%TgU5pkIxQW-oJH^#@G#K&3wUz>wg2}j=wwV#f9Vwuq|z1L_g#x>Yysdk zGe=~_H>=E9XKX4Rdt{9qNGR`?E@bw+62>Y2p*xw2jRnkKh!}P@fu$Pj>GQ;nP?9ur zgDDxVC1yRcsxJPy+Ssu}3)i=gJ9?h}#R>nVyKKDR22Z}MUba50CKUf@$ zSjG2k9aaT?^KBBe<+F|-)%jchg;;?0314nsS8*u>+CKp>c~2$sg!{La6m2c7EB=pf zQkV0^l5P@<3NEwm*Rvx^d4)>Ud&`rD zCW%EAgcaHPn&1{d655hj!I2OL^addTrbrn@c#0DFWiO+2HHiDnh*~UrL@3mbgLQCB>PUBa z93$DrWapkW%F$AM&hMd9p%zal@-C)jGNtiipWRYb?;MO^xttsm^1FCaBw9q2ZO+`; zNvj8K{EV6gq0#lg&cuJsHp{xO#R_97tCuX_o|nJ{jBSQqLPw>$RXwOve$tHO#!oQJ zK$9Bi+hyinPgwDF22buSDQBwa*KPdN7NCHZ)HX>R;WW+eJyX0u1BU~2=9W^I80Ye- zACB=BqY=gGjfZj2sF?H7?n>gn*6XMI*098}H(0$;W!Y<7?_N!vL@=iUPeUn38P2J3Fxv zK>#|YQQPars+d(b_7AEtp!hKY-c43?!?UZrQ~^GA$zL4sGK$SG)-IisgsLj3%5N7) z?(3kf@0I{3sl@6R=LM_?Ay;fPPYF4F=_0)4S@nyP$&I7;Gv6Td2IP38EMFs%nWq8$ zu%&5gVy6k?T(*HJ0yBu_EcJxHt>r_OE2*7z=x#k4C1bJ zpL(p1qvWAw0_wm?4gD1k4s4eW+-tWZ%=lgQOdS(El-;b~zXS2M>X24MDw=Ys^`!Xj zUBk{OR(#}(%)dy5Oef3iI{Cn<`a)Vo&OG-=@{!1QMY%9yXEN7LFgR$&iT(}Vk+ad!(bHE34-i8DijlRLN(S~l&H7mezbvz z#9$%bd_S6Mdtd{8)SwsXrPh<&d|f&ydD}Q0w1uI7mu`saVhfAEmKOpom|$$&>Kybj zkajyeOX`rRiNUTLyy1}&7U}^?@;|u%n`mf_GoCH`8P5XVY&s+rv^K8`kWqQ~B7P5r ze#FXZOoQ$HN!X!#>13QsAIMcSjTgaNP})MEUX17Lj_tQ0llrqHEf2wE4PhefsPon` zVPfN20ljT(r`FnTz&p;P^%L7tLcy`{^=IV6J2>s#i2TrV?Iyx z>jsTJgvcxUjUOj6rlV9snhq|{2%3!FZ!SnA+@E~}>ksm5Di+{j4iCZ_DWH@s2wBd2 zu{wGTUc3}yV7z$cwj4vt&{O{bvH%9M5PHoC zD!G1X^FT#6$%_P1MzvN53j9-h--e5gXRYl<{3rp{Q(m)AUf$&3C7VlJd<)Ggxc8&4 z6MvYbJ@La5}C-Nv?YEhLnD`OCX^yfyoY3||Z?#0u7( zr=zzbu2U5PuYfr;#ndMN4)0EUaZbgpH#34y?%>g*=M;S=9$KIe`AvPk&u)u?HYj}L*lA)N%+mAR z;ZA48{2iiIPvN=N)H9}_BaKN#JBG;7eRAX!d*}wgvgCjI3VdJG3Hs|Yk3s14_);&O z1H~gE7uaGpsJPD`GRfe5Fr91t?CRO31TEof*Syv)`H%HBXl(-joW4``uhswg)3u+K zyJ0qO=l(tpHN8E+yvLU~e<*7OeLAjyOWk!sbO-;@tLdM(rT`MxMW<0PYarC=CB_0Y z*9zFkd1Yy1ffOHo{jlJD$ntGlWltY z&K<8_&MhnU-LKFN#G{wNF%esa$y+`ap%z;;>2m*5zv5*$$6@0SnfKg4N6c_ z^_2|)339LuQN8#~K)^8DooEqv6jj#e%b*pw0iHBW)%EP8cN@UA&F%~}V%p1ETU+C0 zJd;4@>Tn_7*orLT_sQ8y0|P#5wYPlJqW6%l()?@gE><1TJqxOhr=MxZOx1@iDA6A3 zo*hkpJWv7vC9Abq`9XRfm<&MI#Gscfn2iZ$iFxNMt#i!ty2ea%atC@?d*eWNBA?~H z$s&SHj&_WM6?~V}d7)`#GRRB);^PcStYv-HRc;DL(b1E)q6mO=o2#s+GQ=wTS0VE^ zg<@u-0|CrZ*6nNTPn1!X?jDsERwW)qLzhRNJsJy*Ql26$nCcn2^lbxOc-5P?XvZGT z+N2X>1WGuj`D*K-MwR6`W@Nk%;e&d3E-fl>TF<IX1S-s+j6Ul?udX+8$Z3r0ppxq+a3o_WQy z3Ukci{pU&|Pw3@aV#xLR+9>3Hr?zqj@An&s9?RP!-#21nWk zkptiY-v6pSADBVNgyP=)6#rpr32o}$zNGG*;0zvN&8TAiFB?(;QMZ8?0gQU^ZsmcC z@pHrRu-HvI#UG|oV%xz{NLVPnYNNmjic-apQsu?kh)v&+alb3)irvUH4klS$slM%a zRkJd~WF38u0H_ui(}X!JVx;9%g`nSQX2G6SD~w>&cnCVJ{HdfiB3gb=qFI9$d6zBn zU5^vTe_Oe0s$Jj#C-$>P0P922D3mrG=`GpvGI7)E zXF+4oWaWZ>jya|c^v)Oh&rKAFGZx~UIsocD^54wkT2?oZ$@heTHzKmmPWI;!Y*41) z)QtEKPXPzsaGrz5Bt>mKIC&3c<^JFfX61eeT&fsO3xe{6T(St=Q;nI zTn2W5jaPL<=Bz#|Vv+V}XCN(x=Zln8nTckUK%dC<$hTKd;dLMK6>_R7ol719*&Cl!3ZJf#Wrfs+UiiHL~g68OaL)IUSF0I~l#sr?o})(?D=i~j4L0nbxC3jpUEujP(v{m1+KCa{~A07i1Q57ia< z-)7B>#P@+l6u#}G*9ZP$GyQh6AL}6WfEgV7%~=2r%YVoxfBWozxiEpv!Y?gZrD;TZ z_jU%^_*P%xYaeLeBSV|+!bJ9%<$7oJ6vKuy^(+UM!SMy35C*i#yny*Bc@HOEUzwzm zSg+xR))JlA6Y)-+uASa>i9QOh(Ps0VDX;dHz=B|!G19huR}_P+0zs`Te)el!g0%!n`y&mzcVUJ!w=@iK44NARoB;cA7@^81DH`OB{Te39ZfXJEFeJMqn-XxDEMf zitv5?lKzaaed>FQv~t`+$eIf?S2_?xSRRspT)87Hd?-Mk)apxtFb3c_t5UTy&(hP0 z0(tL>2xE!2xZMZ_wymsqrR6+)TCudq<|zdt>g)Wj<5w1aH9s{j(@+{=`7JAjKsCY9Cx7cXn9xmD zrVbGuy1v7fcA&E|X;}yyuDO^HYB%S$D+IbE{Nn`6zf??h04U13s*Mfb?+H$dV+D94 zLQpmY8Un>PbI?|37V~?*cRs2L4g7PB+Uhle{|{s^uuLjRj$JNze(lp-%~QY4A{^_f zIcGeKPMuZPyI#WQoDN>XrWDMD0(cSj+%eDsNmM*n`o!pm_ z?VC`61W>GPhADalHJ2*qQO5fg->(mY+WXM9ao}qv#;m^ju(ELpsa{*NmgV0cp0kFL z54+4UKUXcihLae_Dy!L>6QL-HrN}?N`2AAV*lV~15h`dwVdFZuiwkj`+^KnRoCBZZ z`KEu{-?wJtdb^zqQIJknXFhU}r3Q<`)7h>wM}+yN_}dtMj>>|i#v``SpZVXX)~ZAv zgt=e}b3~OqL7IP#n)wwW9aUoE0|X~?HV-$kF{dcJgE^v-kCQ*|`0qT~F0r%WE!rmb zf%yktUHg5CVc$n&w#fgxKz>{re0Z%rM5jlIc>_Z!A?6gL44EV9zg;E#mk7aE?uiJE zJ8I#>nG#zS`oGd&75b{CubP)t^RjBwfAd7&eeJ3vU3H|Z(aUPcxEeD471^(bjQ{V4 zjMnyZo#r-v9eY(~KdCHz@lRe}ObeW@6%3;0EPwklY`Zj-7PxS$fARAxY1C)oD0(Ab z&|;hcYV1Q*)iOhqFilXcFr1?ECh~cDcybzhkm*wph^b+np+Uy(VKQLS+f< z894nRuWBj=T(C>!TXlHU@>rho7{qh&D-UA%lVZPLhv)K_sO6CliIV}tX@LbWKgNVa z&@{x#2Q`Q9M}1>xR*ohw#U-P@QOyILD3vPy)S~d9<=GNJ8p)t)aq3lb1qB*Kk5Ca^ znSg!iT^~jsuC(v}4~gQx3ii@>t-a482Wn+v`}-%&P*oyof^Qb}m(TwFJFIMXLHb*l z*Rql6&Hwz(Z=b9V>mT9#F0Gf?m*&eK1p8*tg7YJqK2bD0YcK(nWIj|aO{-9)tLcZZ z-yQ{R5pw#;1@J^sKKS=9^if--86!HJRbPVVRNfRd9at&&BbKT}{tD$+++a~&-eFtp zFaSEu8Tci1+2^&U%4~kP^kVfc+t1Ebs0+aoMV z+xtvRVBcLQcQ42&typch?#jmw>{8DguM5Vej@X2Q3vi0N$DU9rVZg?fY_5|EF3Fpv%mbpwN;OgG+edA4JvTP|% z(LX3dY{dr2+{T4~^^&!j-`@g+wn2xu_Y{#F2Ah(xFL}5B?x_{)eMB4Vs3NIX-({PA z4ab)i=O2qppzxy-aD0+uCs)pb8{C(>c$|;9Oao@B#KeUoK&|k2(On3q$>y1r%Pk9F zzX-e)^ZQSOui;2`>MCgQD$i4`jCOdIy+xH`bTke%@OzL7S7CxnW) zMGB33)X2`q;YgRZ)vmaJYd63pBP}1aS(U$~a8^9KgH0U%t3^1HrW`Az_-diCQbnFcr*0>;0fwAH?(Uq9)>e*3vYCW%^q ztu&a}9|29x#8ZgS_*ToVO?Sn|E7v3?Gq>ZPBijoWO8}1))MtLa^v0tKTrf*|XRLc* zT={yo%u1t~gujMc=!J|gFg0^P57?W)D0L#WBpUtrED^a_A1Cw+hsEcGPLF&72c z<&iCH_|RAyOBx4W`r0sh<<_nP@~Ol2g)?>eT2MY|5?sJQOzq%i#~Y-K=`#249}@{4 z23WiD+?EAp=C6E>fi3U<1f)g%d`NUVB3Z37?(ZwsviuRQ0U;sR0ckl@yv(eb*fcPI zXr+qhgT=_tnft)J)qw5ztpB>^$<`g@$Ri399`UFBWP>wx84^SVYjjI0)5zH7-8uBA8e8f_?8RbT*dcGs=$AG>%f*?br35SWYt0Zk982MQS53I`==3Kjbed! zT#aJ?Cq=QVMrzeatr{t2n7JBBtwvI-c;G4?_%pW;Ud01f@xaxh#Y+5bwP*p5w$-A= zYSH3vFz)|=qQz>u_rEjUD;#sY{F4j7Ofh~deXLelnFWf~D(h;M^^a`*`@C(`<)mfI;dHcrk V7L6TCTLb=RozXvyRkI8EzW~T!v%vrW literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/traffic_light.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/traffic_light.png new file mode 100644 index 0000000000000000000000000000000000000000..ae566bf8334847db1630bfb5f2cd3739d1dd7c73 GIT binary patch literal 114927 zcmeFa2V7HU`#-D}_nwFYv{q4(8K#I3rYHfG4FW>gkgx(_BU*8=Y#pd5;2sD_5sNbCo7-5C*$Wb!yzLwv&DV;lN(hO-QtJ&wMc3jK;gg0P z+1(TV_LP=1lN8?opYYDkj#m0s7CY?VxvCO4DIuIBx@E^U9fHPMF(vryXy;%Bf2mm! z9h}fDO17>}BsiifDk>@@g8qer+UC~gu684qKzs18a&@zFBD1$3E(G-ASkzik%xzeQ zttFHxB8H0F9WC+7j=OL=1kK&9tZOJ<&Q`2zY@D2I9N~#*O*f)Be8d!wO0yTWV>4dF zaJQHt#o3;yxy`}N!9m2u%L({1`WeGdB6+I0nmgMPoGh&z;c=FptcT&mq%pGKh!>l1 z5fPj;i+CH?;U}>lj1Fkqc@J-qeW#7Pou!o<`)<~q6elM~ik41NMsM zuC7kh(U(~}IkNZ1zQ!5UXVmKGfc7|6qoewEmK0mowbEizELzarm6Tzf zA(;rPY+*2@>H^NMC=~sBl|g^ir;?k z7jC$IF{Zz>9Ox@%2Ih|L!-~h!VT#wV4g)(dEw>|K5>Nz_q1XZ6HOwun9Ctdo*-=;q zWZ^`iIFZ1L9nlFzbE1QdtCKs~Qpw5D3F*G2m9@FMBe3hs3V2658)SMECucZn?&i$W z3u`-11S*Qy1M$O0!BAL7&{F0Ub3hjsMPjOM9yV*m6g^46W2K$jG{ua(6vZv{J>7}k zB6jB6c8d^|ojf#fmN-i<2^_&o!h=X6dJydKRDzO>war@qa|*~q|B$pU91qi&D4 zAt>QJHSHbTwUl?+5Oj#58ulup>UN6GM#>^~I%=vCMh4rh33lr6%$;hx9gWBY^l6)> zh?Tyl<4!vXdy8!Z3IQP1T;J18izMM;LDH2X;&yvkh*2E1>j}6?ZKiLpyafO*caWP4AuB+gY5{R`=Lx@9Ac)FX0F@c_ErKy>)>` zU34${F0QF9PSr#->L40byfl@>z2Q0H=s8--aIG>(ne)0{M*5l}>f3gE8R|=T8Jjysf9#9=*HA1|WmC5|K5IoJ?MG9s*V4%8jm>Ne(Tdd@~-wjzi& z*rOLb8)vS+Tf`hRhM+@mC)leXej?gDVJ!(wCB#p}YZZ4*9S*eFVSD~6+O(9!y)^Cc zA_OmSQB9?Pk~Up;O>YkJ_8(phzV=3n7V5x>sLd9FdUfmPvGRsD6+yOC= zJ|Y{D(6F~bdOpTR)G-?&lJx8?l@vvYBvp5!m=U0nh>SX!rGH>kB1YOao?r*Cp1KVI z({rM;`nK&JmaKCU-%Oj%E*7sa+K6CtDo8*7Roc7=%6NAzkSPK5SnHpZsW;#b*f8LU zEfGhMQ737-5xqo!RtQ7@U$;9N;&$1vEt6z{+fD(5U~|#a)>2K^2{09Q=OCf3tS$x; z@Z6!T=w*T1jh)ld!8^mQos9Gy$>!St4Z-rXbksp&EDXh@=q2t&0Bg3w&`AZYB?9+| zBZNVktOe)(7ImN(Dmb9dOT*sK>z|}f(@tCr;osk(4rw$&R2|Sx!+w{@KS&*DtT-U_ z-=q$wVXrF!)PYpg#r{d^kni{ty;Jja2LBB@p^kKh3g|70>4-A+T?~*7yu%mIGvYkv zi99*z44?+4(W6!-QZ?*}$SyG-OwhqF1Zf}UD>c3GfW=5#*}hT-;nQFGNpbL3VhFda zI8ti^JT+uJlcn(z@Vqg&!1C*C%=!lF!GkvGqNoX3k0(Ky0M^EV=8<^)^>_=o1O5by zNsxa<&jPC-NBbze{c75^bWm(DjO8kz8wltAp7yGPbaip+N+Mq1tv&x<1mOVjs5v8Wojh@w*@Gb|Gj#c&*pTrq5;LR17%)Hur+ zi*FeA7y{N1f5$T&h#{0gYgu>(zDpd3P;`v{;<%CxcmP8b-LsH!^hzjF7vq5D!z+D7 z6rriC4)U;p%+C;EGH#@=(a`zUcwZO1sroSYA?|0zkz@AxEin#?l9U~QI$elybS3^t z>Oj7nr0`ADA)Hr1)PX(j8Wn;4P2Pz^j3fHjQN-8V#V*hzh$z_c9Tq{2*T8StJ5&rb zy$P`QT}bBM|Da@0^ojYqzo9qwkj?4nBI;n@_)+oQ-;@kOM^16hH}Ouzo#1T<)Df`U z=^x}BXf(ukf6sq|kA;c|q7Hnoq4+;Y9Tq=wz|e2uoet7D0@NLL{gY@Q263?%2TcA3 z%0Mr~3EFt5AOZipRYqp9lyA+)G<5*?e$TMcZvQaD9$DSe^ajmRMwKGWhvC3yQ4xx; zs#&^#@HPkoI7YoA*MTS#>;}6Q^E)HHV^t>2VL$YBQ8}vugjK6h6wb;sQMKwX*7=%> zkSFjR<#8f_8lw;xbod*qRik1DR5AIR8bQ!O*(E|D#Q9yL^0l`5TFks2(s3Hj5d%b ziVgo3-z0{!w||f>RKxZ9oAQ(ZzGD%>Kg%<9=-_~!{5@S8RZIBi_@+*U8U^)l$`i|D zA!=jihA5`Sa@;ZAidE;(5F?^GDXXUipP*mHZtg+D&WhdX<1sniVwG zDXw17&1A1AEC(1633ek{A=@9}@M3F<740vYo^YliALfEmcJu0v%tHBmPU zGAhB_idb&LOKNz@K>L*FZs|>Mhr&Bq!y8Ob8Sg>F8Id7)5;ND=!|fu;AV)`4SB3_v zjtYeF;QW+#QQ`czHcmmk9jO`yicq+>k+d|}?zTfo6FWwP7Kpi$!}#VXyUF^cX=+Dx zhg1pLlA6CaS;sU>HCXKhZ!0k)XA3o|q`J4dH$mSJ+8d)Asj!YSQ5B?QQEbm6+J7pjfeZx*tN`QwCn>Cw47N*Mv`gi`YT=H5E^0A;X=b4ED++p1 zu?=Lwh7d@h#|OIvR$B_=t)c@oRVb|B*1-)LD(;&4HWYB_UIYU}3PB$QtLmPX_NwL< z+9IfxDMHYuQq7e_SjX)|Jk6CM*tb^|Bj`C(pe+m`+AdEGWkn|qltjUC4INb{_IjTB zBoTPlE_Y336*q#~fA=|m$QM?-Ze;oRulWq}M!`3Sv=a(ftl~d$e6b5@lbVd1mA<8i zg`FbRLd?IdqF@5DGnTi1~6RX385-*6q4z& z-@T!!s0_s!ZM-)GF(5g-C#(l$Bp7pmh8{YGS+6&gl+krxte61O-38aGfD=cBP&_yy zU1+ln(>1PeH@r(F8S+khs)rGb258`5FvD9Mjn&{3VF-v~Zb!yuqR?Q+f5K5oiin7O zaX@TeB`qZ*B*S(+BYc&VG<#}jq@NO#6c>^J*&&DYUvX1xpZb5*P5sNWIwH`G#`?C{ zl#7F>t(Cr>mjS3COpQ1g=^J^&-@|h;Y`35)Wkhmxvru++w-A$X)WT^(A6drLNXN+@ zY85aMpf395n6@a)1GTis)Fg~hN_jS)f z(>5bq1~%mb&p}|rc2_Ld!MUcva)D~lODBnV0@#2%pn3wdOAz#_C^Hw)fT;;hHLNn_ z37@^eRRD0wLDtFm1P3N?3P1G$(3`A;|u2^kR?A#q8WFaNL}Iy@mOD#9MT z9N{=bVLDlqjngB2ha~&b|BBy`U^DCgXnOOn`wfB@o>jH__7nyD$#xHOFQEu=+AU$BrpwCqhdmrwUCj{% z?>a2X^sLSGH9a7SLtcJ|miz81ovTFtij*#U`0>iRZNF;vu z3Y?OdVHDWLN|n&8tc4CXQv}!wRWcnTn9o9(t_L%pn6JQaUQ5}=4X_xxGze#H#1Zyu zDcfS*2Lg!z*FZN`XBTDEH84?$-G``Gu|dAaTT={XZlP+Z1?h+ens`$tqVFJI5x_S{ zTd-r6kbZz~u?HUjvl!q{Bv|W1>VamIFrW10T65sSm`cldA3MxJmM_QX8tu!Ge}GtI zgrEI=#taM4S(QZSHvbt{M`J7O$N@_zS?CYdNcOBQk|nFN0qN`?P(QM(F$(#yCr6k3r*c0)?C@+HEH(^KpBY|EVCnPQg@3>&;z$mE43E`yJ$NwvE&rWB)rwL<5 z`e8u&JKTSVd*n{O!#xYuS+7g{{|fFUq(r5K#AW^f?q!Ap_5U}Zo?WH-4)tT9{(D8} z_jj_ssq*x_BE+gteXj_is?YyR6(LtAiaGmDR6&{lR8K)dTufR>hW#QjJ7thW{c6-C z80ka)7wbaotme9-1HXlUy{^wr_?*pue=Yl8ovRq3HWF-28kt`XA9J;G1bz1y{Z2fmg!9kG zAy}gwtUu9c#7-wW_>qP$(;X5J5edQXIbaHnSOlM-@W~z{8Gam#IqX}%ZeZgto-2tH zg_wWez^R0!6i!G&9Hx0#|FC0` zVQrC-{PGh{BO)o(m>nM885vE9OAGy1i}e8RSZFmu7u0sEsAxh=q7AKkJp8~Fil;{C z#qV-Na^WQD5h^oMtVllN#0qiu2(f+%$wwqp|1q(O2Jd7zLl9LxnUa(L&OS<)tLr(|JrYL0YY*V*DEg6gOUtBtR+GcZq^n|rm zDeRkoEz17TCoG~sZ9@uN2Z51|`O#HS|4cJ4(~ z(e)MRh5hH}QQ8^NF_En;8k*y--+Z(IL{4}$e>`hLVb$g7MsrmWy?(&7jGF1+Me$t}EGznM72mDmJ3x&=O@;4P z@!cxETg7*)V8vhGBdG7e?DxE4Y{dNCD!yCAcdPhr6_7`MFMNEjL4B`5jjDluw~FtT z+3%Iv??v)2pzyt4@x5R1y>*0Ik0YB}|A>^oyqdj`Jn;H-0+ zUL~aq-N{+7BS-9qsd>NsFm=h$9=AdX;=#pw%s!cc%nLD;~IGis}$*-OAw(7 z#nYzIyb?A?#8e)QIPR1s6QA8eJ1t2v%J}$T=HoZq#*T?g#VofuWFG5^h@QKMQ0@h)|pavoujs-wH4rs zUj%(D+#$I5l4|JD;^uUxjLtZxI7=aX>H?2L3r6w}gBNjSSm@D@a#K(fF(YwbOn;uL zd)CDweD`lVghREpWY+Qqd~WNVHg)#0MSPXkkv;hVpYuH{E320{1@u?e!T&fXDwJr!Es-<%!LH1Mj}W8kwC?Lthys^Vb4 zxb01xlmPunZ&@Vc7#r00)i=qHsq9;xX12A1e)rue9FO+O7ZrA?0Rs-A{avz6^M>3XOur&`D8_hM-171L@Q!`3 zgCBNu9meEB#nj+JLri};F+8`_n9L)b@lkQ&s~ItI^UgMwb;!0H&g`nfnR234OQhd3FV$rWr(O08BSahsy$z1LfqN{Hr;Y2^|`ME8h7%P}^80o9$DL#$!%i^+c zR5lCaQ!6jFjE67!4xn3@RG9>H$K<1qzuCTx2U;Zb%~lcz2Wn>C)AIjxye;&&=9A@a zQ6KnMQ1|Tdygxa2=+hP90GY1ds(RX><9>3PI^)=Q+7BUt8l|Wq+7mE&PSl;k0E=5B zRpaY6(R1)1cV6Cdrz(kp^p=dIIv+phPzj6I_X1ZARqgkGt)Knb$}yYakvo*!rM7iJ zgem;r<62}}30#c$cy0f|S4UHi^J|4Yma171zO~ObyG68hZnD4Jr`zFvn}TNX?EY+0Gw4sE zJzm!q5H8RA!<1QvE3avV11`m9ry9L3o=!7)N5PGQwLsp5^C&)!Z+IhsADNq0G2dqn z+}z)CVD8qX52+P5?k%Ui337Rsb7UocYkL7swC!T>(V;t8!i}+=M;LOdp&JLEf4D}? zrZ6wKFp|rbTsrU9l9t%}K9cILflrM+N5%#-kp6zLPdX7Po?ulS5?}-pV5*reJ+ryg znAn=xweh0|pXiTaTN>-wnt}MpOP`}e*NrHWmJ1pQqj?c*=?bqL?!x5GHh7)F)FRt~W%Ya-QCn)_jDG34sD8X+Ms9?Ee`VWAeZ|hx zi9}+8{-myp1(L1BGiZ!oDSYGQV7dt8;L;d%2IL^O5y_zkJ`=TM(o0U!kES0ATvo2U4=BUDWt|{+#LDZ|^#0HmpgZ^z#=}(w}^=9;F+YROHsJVs@23kP`xv@iqk9_UU(@3wDvT#W6PSeO^^*%_F&i z5M1@g=ZRL1S74h5=1A{tsVVonq}4EkX61Na4rDnj-{B7wHJI88yOfT(oGBpZDLafF z9d@5Xi#uJ}XW4SjEGZ*znL|!aurRr?wd_>#$x@9t>R`S6ke5r&gTbruF~+4!s*s6{ zq4(ZJz=>coa}GLw><9qqV!aR;A&xY!nHN9aG)0ow#*K}x?V#bWE1)GvNnzSCSFz{a!t2uv&nLf z2Iu_qc))arwx5m~C!!cNgzAQO@-a8PelUzldQSG6ox5EiZqf6WyDN7UPHtFAF%FPT z?UbSzo5g9>gZsZ;deq@ombYlly}%#piqc!7WMj3MrQW0VU{=YCG}>pH?$|W@M$*_#Ke?9zCW}~kQwFv{)|h>5&k9D2HI5qQtxqi#&!$ja*pY6aAyDlNlB9h1lHS7-m3X zu>dnLR$@Ub!l$nFLD6o0DkCN3k$i9T(2-)_zUOZBm4KnADQ&s?$s{Rjk#X{$I4J-e zV&-(DqI4WW<=A**`brrKoi8?k}O zG20#=YqsFKNlre-Rp3NOzZ`1KaNE*z?*~MRB_~p5E&)<_Mv~$~Cw(w=d3Q1q0=t)U z`cPI88Z_s;lTb80j&XL@_<&wvZ{Vc;@!SUxW!|cY?Js4x7+`2&r2!3H?z!(G@R#(N+HL#{;3S}he5drNnT?f_|9|95Ai zZ~WvA`k!ZL6J;3E{xZQ&FwFOz(}x)}_gBYc5Pya#V}IDR2NI2-(Ms8UE2%hapt~|* zf`4m&HMf-CP=E6MYPWE?+A!Ic_3zULgO*#QYx!R6F{Q^99-TElVN%$80g3bH5#j_- zvXGx}w5={bKf%BE>7?FxpOzz#Fkf~37-8zYq14c)*|R0B-r~cRh%ld)bm3A1KX-iU zr^2OU=*1}Q2NCz{#bbbllIjd@gYKAqMytP6{N2x=CiOPC6^9l|)nvGSJjCn0-UC7b z3s!9IHQ2kK{LWZ(j0IpSPy{eol(C0^9>@dm$|EfNV*@XRueaH$?)sXr^~dIJVaD`) zUVTVsj{mDG5qZ1Rcnu3&==Z1QGm8U&6TSjd#&H*{^9-ownTS~Aa#s;SXm#(b=20Si zDl2QFQ){vmsy&YrYCq2uy1v4Yi80;#^u~cHZ(@f`qo0o5?nYJ8`lnlrNfMU+~3oNW;68Y zq=C$e(waDu-+7n!XA)nQ8tVrQK93$0AGGTESo>KprAn-5bAMB<4?gv`lhWg}%zX;k zAUOZT-qpx19_<3~aB)Z|I;TV*$eYfeBa`s+b79}M;6(R>`0gx#?ls}k7bjHN)t@Im zfQSr8_8Rip%fZ7|qp;tpJ_d@eRa!c%s_`B%8*0$c?adG2b|Kt*)xQD0bGsN0+)p_+7ChOZQp~zN7f5Db9cfEjmPF$mP zfeJcq0PAkB=0^-VmXfzy>zkl`Nk@JMS`+cHS%PEK=jq zhOJ-%JEM{F_Mqc*ceuUrvbxiHrbnJ2)8qX+`?1%<3hwYaLL-gG4Z{HxYsDX5hYGPg zssHYclnOFi?n0fGt~7V?6tlih5yZ~9{vxOtR31>{7d%8dsjGKnIhnTM#lkw(<-K>Zp}_fOr)n)Gi0BnZ@tg--+)R4735jRtO?W$Hqtgee1UEXvI+9d-9-@2U z?2g@gK0iqijepKhK_O#xUuo(R*|Xv<7HwM5bisj>?&GCCAut}Q;wI*lg&2t70YuDq zB*+sXq<=JjO>Mkv>!vAD(ssLNf!{FoZOiSscK<-|P#kRU(}@jWkTR)s1>-*_30P3)epC(cUQYK-m%La z>Ns#in@Eqr=XRr1uB~`>(5xfs+-7@x<=vm0kls5q5ZtQPoMscUQYt>yt@xY_ZmYOw z;pA$!9Nsl`%(l98@2E&*$758)_E!jaE|a{MAoVb~j?(9uzbeuFx?b53Gu=x!#FTx$ z7I0J`fp$}@4eJqq6nf<>#DTf54MiM`g5if$GbHkJM0F_N^YKEPK%1vHOVDi#dG|q8$#EdZi2rj5VhO=5;72 zsg$JaWTc#^CsXM23#2g7pWpJgoiXvav9e>swWwv4zMt#9(cxEnG{z-%oBAxKr$c5a z`u_IAjY`?5Ve&#-b3>6lyHrr?lkJ-Jt?|(yK`OT%iWx!GQ2441KE!Lp(-&aos=mUl z<5_MmyPozNit-)T&Ox!}7{j9rgQ1x@`X5FoT%kPYR#g#;tDi>^&Un55v~!h9E?v#< zoj_t`OS*p0)?uY;?;dQjsjJBk+3>9n6!@8VXyp=A+7Ru4vXI3i`h}AhhFYlE!6YaZ z6xC3Y3Trc*{FD9#l83Y0T>A4?n!qU&k5}8D$wQwC^>z$gau?T~vU`5ikc+Whzjl0Q zZ{nntkT9$~-itBl5$dJ5y9Gq2x8SJ*vn3DfDfqoP$c>sM;gv0SFS&kv18u3fTYL73 z=AXN_iK&;herP`YG#A15u_Umg_O1p#N=@Q}8EubAse;F#bd=U95D_~F z&Ma$DnSXbB?$YBzS<;eA#d7#5v8G4cIYcHDh#owqy?4d18@<#>rN%vO9GuSJkMjI+ zu=$wMjJFK6ki%=jH{W#q=vK5PK_0ark>OF9JDooYx}{l*IWhnO)aHVxFEIu{V>7btlh`yGe>7!x zm0PjgMFEkNw1~X35H&HQ`%!7r6F!d`NsozmVG< zmwm0WFP#>ba6|iQ&cyy!Ghcc8VmV^dT^Ez{e(wv;v|YIGAoMY6P1jN$wQ#D_a%vKPxI>zbt{&+_Du=> zOd6`C>zldj2GZKrMdpxFtBrgEN@ePEmKZzkTHa*#xt6=FxYEh2AgKk)B~XAf_7!H9 zTB}UqP{FwkE!MJ`BkLrz$xs@XlQ0^x^NYJ%d$bKo&1pS@QINrbU!zHu1K96&yj|_x z)|6D7_v;QJo+O)MA?r%-^4ro-{65+`Fq=_v>*=cTD!^q5g&6M*Sfs#iQ`g7Hs(G*j zz#ATPpVs8EDy@0NJT1^Nxzx!ARij2RPF15`E~q_YZzm7eo|jPgwW3x`<@0>)dtG)e zA8$SZ<%*~auPNVrr}zCbsO*PSxM{(Xm7JG^a<?iMNkNIJ4 z2SCisbZ^q;Hv+@6 z01uE3VD-OYwOTimlJg`Thi%)aD_d=f)$!& zTlvk6hcX+kR~}8PnX)IJ2%m+zoJS8yw6YTOnloKvnHU11DR99;T5E_N!^Vf z5DQ>F<00e5=d`KeyelDn zZ|M8cXmvN}Kxk}yhHI9Oa8uc)VjsvwJ5Syn-;9Q=2Rw(#CCVD4uh-Kdo9dn|=$i#f z+^B98{p(6uYmI`_qQtDJ4wD(?eEkNqc*HLEyl4VDYFPg%WpG`K5^9wdm-0|Gqj^z- z^1UqajMb?lE{FI`mEU?~aWOnj?BUQpidhCR)-vif)BsVK42+x1G}$5s>9Ti+o-b)Y zuCkQhqd$ltR8l~VExqPy9L+_}t@X%;<*w`*KOCU23Vx*^vbyRB;?T}tU>Ea!Bf<(r znMGb5dgY{n?Qcu3*#!(fx#p0bv%BhQ=Y|?otG+JR-NbyJi3MxrdG~Kj|)ig*L4->>Z*5O(l0#gd-){JtR~}nK!iTM zxp>OwSz|&=gjV9P+hsP_Fg>0P&T`o%^ZBZ_+vz4;`%CSD@MsIM4D#mSDJ zJeg+zIVN@2LuU9PiB1T;%A<+X)GFVs$5GT?ljTC%VVY8 zSFrO}w{Gg;yJ0ltr!bj5ro~mzHC_O>lTvRdT^$+@{s*J|x+{gVJee0v{PND=Z1N6G zNl3fr6IM>NTp{Q0t6%IkekNk#BmxxWBJU82F^@eHxfOr>&Ay*o2vXHc5BUzZU&$@n z?D)>Orccke^EC13t~twPCA+E|65_+wGCfW{FGQw4I-l@H(O%*~pFO~g4v=AFcUSBT z8nwoc8d6S5o#fPWZR_HEUh1CeV>3?=zCEsa6jv;LsV6|QCr`>Ey*ahD0XO5D1~?$5 zTTn?(A_S(wG)Dfb`lv|67Wvwb59^LT6&4kF6q1BwOyb7cCXpt5AK~?`n;Ce{)?#c8^Ni9%{88brZ}5nD}k|ra2JOje*M5 zhjK!ts&-D$JSV;(Xx7TJQt!7sA8JX>4kc~vN~{eqq%z#=esu~+Z!BKN^f>=w_IQ;? ztfv<`L_kT47isqKFkii zj!D@n`_}!uu=ZS1u}~E80OVroppqMke`20`&~SCU4aq^BzU$FNxpl~_m65lbtUHw< zKh#?+3bPd!T}`hhza7rwUtO$*UTb3g^<8bX!NPg_CjL-c(U=ep-R!s%_46q^%-yv) zkdEqjmd|*PBlpF{sHzFPd4T-1_3}ckkffq5Niln1k_pL978{AP4d{QgrtQX;k+_dq zejCH&TJDxaDg6Qbd4of34qWS_j2_*Sj$Gitx))F+>8^51tjr#C*z)mt^pewY*_V8J zsaXrb4?dZa+S%<&?R{~r78*N#qU}!v5?1J&`nk_qA$|Lf%{bq9T?T7Q`rhZoM(Ip3q*>mufMR^KyCxt2O<%S>m?^yI zdN4qkhV)=h`J3pWG-##wJqxd$d1%D~m@2I~%7aFArR%HQh%kgH;0JABipA7%2sBOH z0HTqPu5!ze^b4>mtLlpl%#@#6p=O2(Vs$sJMV*}~>sWq!DbB+&13HfJvppIY=JJ28 z56F{%bW}L|v#V%XWQ5U1P3bp3mqRl0Z9}DGeCm}~eJ^wS{af7Ho|=8O*jj~V7Jzz{ zTd9M6ZSSSB(-!og=@Glc?41e%shHR9wOs1Kl-zXk6RB;~`(3(p)(m9=pbc z_amJWRUFeGhk$mIK;$L&+cCx)vLB9DI58+W^}H=CZ>K|f#C0xEqN za=TSg{_oFtzW;CyvJoCsAS(M9#ye0Q_DD;nIaT!aJN*F5BWq6`wwf|0#A@oCO@qCG zFZF_9K<~vfxu+QhbV2R1%<+#si}c*@VHBq4@1eTyl|4&l3QS9Khdb0=Iem?ub$@PA z*veXhXbhuL-~T)eM9ttZ5Os`IC<(!Spo&%Pc-h>rZYpDKU4>`Xff!kVl<+)25U&=ySMGhcp>?&#vj(UZ$aSgC>O?-t()!UeK${xOeVD3uEAqPk99W!YppS1Cl zru!6%Aowe)#K|IMp+M8bBS$wqIC2Fg;z(<*S>3^u!ssxqyn6;0n;T=Z=uqzZHX0m# zg`+;KVs7P$KK!nhkX-q!arRFrggY>P&gjKX=%l^b9fA$5yo0Ff-QBA+hvNrYKDj7u z;VDif^hT6Ro(f-EnU&Qrb28(m)N5?Me^huAcn-=t=TdDv5RS6yda)kd!uIq`Qbk-_ z&cc8j47cPd6{O0;JS#h1IWd-sI(uaDzLRV9bMp0UPUeBxx6`9wnvb8 zb)N_J&cG-fR47J6x2djkp$!>WjnKB*@6v%56SGim{iWqy`>UniJ~H@RTztpR?j8DI4+XH!_G9Vt)IUl zYisVo{p1-|Hluifal7Lp1n$Ac-34f4yHMbsD<#7mY{^&4ZEyAWshsIutd^f2>E9iJ zIC~)`Qt=fw3N_lOGNJ6+Ra+{D0|t5PpyohZ=p35-X0fP%R@n+ux=%_^xaadV;i=!q zRto*RtLK*NhNC25rkt^#V0FjG=*n;3P4?qDi!S?CM-UCKhvTN+*!*v0$!4a1fMbEF z-<1^Zjuz6ooL{qhh?Qm6?(U=$E;P+TS}{sb0yzxxs!nAr&(CR+sD263&1`N@hxxqL0 z)xMD<)HTelZEqJQEBB;^XRXLKO&NHmNwZSO82Zo!B7Wyn-5%BRvBE+46wC(!J%A?ip)!#CR=s}fqMwL>4TLd1VIQ!@mHEJoLxbY3bk`_xHHu4 zcP;m7qWY$q6qA?SeLs_5E_dFF0mDcY_(On~UzVB|UMEb7tXUA5W8K!3l914+h)->p zEgd}`{%pV?>zmJ6F9N7i6^rsbevbg*RtG zPk9U}JC#5jK|4ejpyMYXlRs5=wjq9hOKi!0^3BvDnX#%1m)(R2A+{!PI#S0~P(+EG zM!QVpGQp=_)_+PG@7brlFaj6S={*ap$1tEzmVV>Rpy~ejn8?96w;#vQgYx|bU}^(( z?<8b5+ras)+b{HCDPEs0_~E6i@i=3eI4K!bTrzndVq+Cja5LHdYIa170P|`<t6w62BG zgAX;E`N#XrdDl&0$Np2-A&CbngM$6Y{55PoWisPeQ^C~n0mrJH4zOlvqv#6642m}7 zFjuYne5TX(llxMOuwvC{JpC?$?;;qjqF~nlVJirP?q5brb4rzcESdM6>Dp=HUI7^H z^z5j#*Cy7L|5*JDfv~jO`+~c5U6lj<`kg;=n7cf71rX$2#Vl;_6lMq1V?N+h)zd#= zb30?yem4}jZ{(gIF6=T7@uHe-387RJq*3#9gz37guCeALM|E)83*P$=`pr zcJ}-p&#L(~;qs{i;!?RmiG*9_U7Z{sxC;GzZw=$jITk6lhwt&%h26byAf`XFTx9EN zrle&*?|ARO@80iS5`f_ti@=o@-g~&iVTZ}0;wj41crp>+v|{M%Hz?#n-7`PHw%<-DytB@% z)`Vo%s>lJ>xjvx)oN@j!Yaf9@)0&o1^RKMrVmRgZwZVI&t1G*ga*)LmNF}|MkXpp> zbIp0Xw6Ew#?-8Vnzqu^tmI44XWZJtDqHE#if1pK=hB&6=Fx$36N2&B^tuxZ zwVIeVQdPEf(jQ+R*xYwUhMTXSZ)pDW*3;F`iv8;@FRUAgjVpat+)?&hr(4;cGWn-9 zLxbI--}*4((co;)K^kDfV5YusGY z6CFM1lzpIu-dP%+{rR0RDLS?EP^r=7nDoZ%rjjnhxS82KSA+$3(@6&(X=ahn`ntiz z@=mFK=+y=iU+RMy0y)i8#;dN*cGL11G-F4ap_+Vp|D*ZAizvo{pNsj!LU?2oYP!;n zTQHW+7fAIRI5*Q6-`$elLhi3W1#^TwkAILS_4j!RJ5FXu==CeW-JQ41A+)j(8b3P2 zoDBYsJEe&SNfx|a`~u=tyD26)%n1HUo|(qGRwaRl9PN(|M9lE zPvIT-)^`FTnCV=e_i;L-_vB>8*~yHdDnaWeu{+HHi;Kd;b4;HNCfF{aR9CLAL<^tto zDY_0X6U6yW#^&Gy7s34V=OyZv|Fuws?Cy#T=NtrjQpc& zlR`}6d&VUX?8Ng)Tr@74^_(3AlNf3VCDo=jksF?sS)bD^F|prE^NU$6MG-vyY~siT zhSv)`J#!v2&v)i}Z248oV5JLBs^BH+7r7hh12%6@Ry^-t@jPG#@x^XxqxAFU=@db2 z&MQsKhtzVjwZM8V^qhN|Ft9tx1XnL$9oX{mX>$G5_JR{khxUs`w)?`Q7+dMbmeWo> zX6~CXY1*o>e<&18o<<>NOH`KX}wWDe|_q73c=^uJWkA>C zd39f3iLvO;gg~Ld_%ja|#41qh2Tbn7wjQ+J-jVFJr%+ruR3mk+_}id(E3wVv_=9*h z&keY8+G*ls?5wiVJ_RYAGs|gS(X`W(Y2EH6@&4Rr2DLqP2%Wc=MUu5*9L^k_GoI71 zlCn?=@6XL+25mek zXsjoommsDT5lgVQzj;>jPM1tJH>K(N^o3?K9ky;>&2c?lSTCVvQ==l%^J()}(bv)? z+WGOUW$9BmNh{D6n4zj2nTFYl#X1%ZALnBX;=h9*Wsq!pT6Go-=-CTvA!L_D<@ zUy`89`My2eb%poY{Scii&2ra6PP{mMUSge)!Kw=yzivMvaLIMU?q1h-Cr=+c_A*dS z$jy7$Hb)WlNKhf>=?#n>hiAfOoTkuj*x6P5;=1$D$@mWc^H+j3Pn~^v{K>l9+%yly zkGP+j%hw3jT>m*WTeq*j=7xRRjGH=%7o9e6(c&w2%~0h){Neo*0?CVxotcE5yQ&K| zQazIrYMf@=-Ky6YLoWH~U=i@>`aRmcKFhULT}QW*%CA;jd9sjc#C>@xCo5h7c#wC0 zU6L|}QAZTYj04Hr?T@B3_33|D*z&7)O8w#VJ*(c(>UH{JU(yCkTF#2JNkk+BeVRWS z>sahKd<&?vl;fF=sJnLoQ8$Bfd~WN@H+YjPc*aWa+VxLwDm=K+-B7SQ`Oe-qRK4^P z-ccMJUR4W>(A(R`a0Mb-0je%#vVkpu2c{-x8vR;Q7V>VNkNVy=@3rpB;vUL&d)n#V zn#^gLz#n0mC1;LJ#K^0HAf@rVLU+Q$ehTw( zEJh6S4>nwd7_@IS>?~BFoB8b0b|KKT8h+>7nd@)69&hMgmOv0F^>lH+HJ#Hkfwv(C zerR!NA+|~-e3?#Rcv#o{W;%&+x5{HlC?a!=t?s-HkjRfYkX1t19d)%a>3+X((a1IU z1~m>!dm9hDo1zn>jLtbnAw(sYUvq6<@*#VO-!Exc?*D)#y_Lb|?88pG&Nm=i=XZAUM$m|~=Idq;HtTyqK zztlo<>aCnyRvr^{hkWjY&X1H3e)$tYmj0$~rRuxmo*XRRbz%t@P374o;qklLw@(dZ zDo0D)G!rpul@5UQi@Iw3ffx1U66A;HA(tf=zlOm&aQ{gW84e_62b@{R88W#{UKNVg`L z5L>Q!@0h!Xm!=8IP_*ehM=&{j8I0*C2_B4|dx^;D8!N>))Lswk*JzNvUvt|)^hW=O z5*7X(C!cH&7+jN?s$eu2JLFdv)Dkqb{p8c$fH`w0W_MNWjih`Y1azz8vbqC!gozn% zrLKsnUkGfu!N2X2&wI1$^M6X+Tr}kWIw;u!F!gv(Cb{T$R`-@Z&Bt*cLLGp0jIpb<(^`xR1;9Z2hr(HYXS>z)|!(5`!jT+y87 z6ThtP3@9A3eb;_=$AN?sA@fQ-Cr_o-$glMFkrH`wX72Wyg!ZA1PTK(bGGC>#Y2osG z<}JeO=P{QBHoy7szK_d(OA76d`?V9luIv2pQ>Lq$N5CW#w^Mg8e=&?47?2_OQ3c~# z?!vPSiSwQeVxJE_#`w`I-)`d%wEEAXA;pgeoSmyzhNy{hKh3zmyy}5QOr=f6P?A?@ zS^ivglghkxbdvuq%Ak75=~uhkl`(J#VGZgx^h;;eY!_UNdOruJw z(V8*liGAIB0H(-hU!QdZ3G6jY4l(F*tLcJoL%MuTz5AC3Tyo-#C?Z8M%wJmHuo|lR zVQI8Ye|zv?4R;3*O}2Z-^CjDoPW4qr`CYv8diqfI0lu_7<9Wo{blFj|B z=lnuD&uc_Hf3xJ2)MXp%?Q=CgWp}?@e}gD6iSb~I7avEoSr6Vub>f)~n7&&GE5t0P zP358;Jok9H>4~ca?NVpEPg_<6&Ca+rg*KV+vS(?4r@e1jT-#Br7@wb1>?_nN?wD-8 z5!mrOxa2wR^6KLQ$)xi?y}aqz%GdscaI?lCLo&{Q*t#VojH8+cgJzoCF+6b;ot>8j zlDfV!ki6RF0|+qA@DoP6Z# z_}eofX?iBp@6E|;$t*@@u! z>Kyq}zJMKqed<%gx9L9Vm6w(3DRsE@gUO}5=dBT^9FN)SpK8erQ7Ahzq<(4Ruq}+h z)7aa@XA6O2h+c zx`e7{%Njd+oDRuK5#S#4l1-tWanw#Fath8G-SSmHG-a z>>j;sqDv-_^Xf~x(v-b_OV#=9Zng?OFupCT?eKfaZuJ{>7s5>eZwpV{ZCrU{_p2s_ zGL7gnN|(vkxK}U-Qwa8@YTMPH^8TVw79vFA4EJ|IBXiVwu%zVP5rkLiiZKpvPQ+`S zGVRqk+Z}wzE1mL_3e4Hr?^dJTPJR)4Kqu9nxeu^Jwef=XW&W%E{X9|u^8V{Pg5u9C zXr4g{O>6Zs@pjSkSPY4$$Ip_S#4=5J4~U}n@+?+FqKu%zWHsHrcEgo*aaEW5GV>gs zAC=h43GG0Cu7WRD!*bStJrsy<*Ic{!9cbmdogANX3~)3;DG;+-ZeR-+&BcYz$l5l^ zB(-%_CnxwThd|HahmA^D)*=n67NJn)b?w)qt`O?GuII@8M{6N+zwmqH4&je9lWg`= zV0lVjMqqJ=0Ua<9H|`65g%(pJpiVBQnCMr^WH5p7*cXb!ECTRo<+ zYvpBsPPZ%vib)Dq+pu%>z#~X5x1RjKQ{pr8@{RT@(E$;IjQUoixc!t*Z6yTmZTjcV z$W>u6*kH8qX2U*TWu}gr_5iW4$Fy&QTSm#+D-|cNq=a5szIj`H^ojHgqs%MW)c$~g zLYb2E1ForQo?-VC~IZ8O2SLf~#l6zTMb2VmF zM=GhrDqKBwNdKc}s@YGWnMxafIn4m7li=tw`;~k7SBJIsX?RM87j1Pzf$k?%UM1F zo>a&B&+8f8SLIg->J*3oM>K2XvtfzlE8=m zA8lVA4)q%TT@yu;D1UOxBdzMuQMyRHP|qQppH@?-qwBGpr$Xgr}a zy$KpLnoNZYY2SW`G?d=s|Ek|`U9RRW6Hxf+J=pClzuQ}qCNRq=tt85QG=~S6SfT6{ zR3e^TW=Y2817=rZ7-NPe%(OkVkPDNA2{4nx?m=nh-k@`IL{&(3IW>>NqSYWafDxtZYk?&1_aOnZy2qY9Uj z8)?3Z6536W+PId0C+xKp9QfT7?TN?lWM)XafBc}v3#WMkg7ezFTHh2-s2TSuvgfjC zn%x~JC#_ndxDq|cVYksZ>;%wTBf&lRP54}meDpFc8FC(dmGB^TWtnxC&As_1Pv+wq zXL&!wQcXuenR2}~q~^Xq(n%?^p0cA_p<{$Eg$qFz`x+Xthxk1gq72Zc5`yB|KC^Mv z2yC%#DA=}>YYoHNowB=17nt(sR#R0qLS8g5$G7XEjAUIKDj&AV97$Ed5(XI0&e)rK zjoY)eRV6;Ud6qH%y zNcNq0=6Z$S2^`xwU?ix`@0{4*!}NVmf5H!OkjtetiaL!>xQ|VzLrt?XkP-(#4_GEnZ!Yw?6R2zmYWw#XQ@0XInn3WXL=@jVO=2F89!t zJ}T|h!jAey?UJLU!)q$WPhFp?o-cjJYoe>c-- zI^YN|;oQQB(dLI}qB_4kIZ3xf?=YFM(tg{fMWe$No-$ne#O1D$fzeuwTvsz6*^YNK z@;&pe>_o|{aqFiUep>Izk=SjX*e)|+mUb^!>%Gy0WlSQ5;G-S*V7Ko@13%Nj;zeNu z3wDx&LE@QxjdD~QmnVz_y|@;Cttap|fN=z5>0uG~PFe1s_bGKEU5$=Vmw3^yU^;BB6DQBW{W^?10A1OqeCiS z?|M#LvUz_d(=Dmk_62g7sUy8HmD4%Jd9-li^kqYj>AHvXh7~czv;3KN9DSrAut5KZ z8p?PyJhN0y18ov9F2YqK4Cm$54*zUao(XCcvRlk3W&E*?}_e$Hri0UP^sYge4=1)#4?#Zb& z?W35VBO+gNaFi#Nzr#L<8lr%)&`gdyrRBM4M=e(ETi%1P)HLUm+aFU_KX)v%ZavZ% zU3C+*`4qN!B=N{`)pQ(JPV+tc#~;c}xl8V`F{>{gDVP@w6}Mjxj?leAn7f{-uCUiy z;-Ts@AD&B84ttk(ifjWLH*6Yf`f4aZBxh%l`rM2#Y`pjesr_g$aCYI9s85(KDrK*r zQPF|<%w(L$Ls7K#uFnRu5dj~x0w3e-o)DZ{*Y07Y>Xw4C8!iKis)> zjc9TLfywDCvIs`LyXezv)P^4%?}(w^g%&47=hU-D33{p-Rb-AV0vA)&Be7D@v8M?XH{7bKwSskjzhZ9CtRK0?cWi zlU)PYYTOH!-w9_NJzLxAHeC^PUt)-)_sSW-!Y#NuZe*;~o7mLfo{CWKXxY)eBD6R9 z#+a3B^^);)pQ(!40+n`ea)3?;5p+<|smSdJ>|n5aePs>0uUl+6o$c^@mrX|L92T+? zpxBL=L4dmDcE{(b$&f(UFeI*UyvM{a6x5Iw~& zdw84{v=W)D*QDF`BX@|dP6ilM&+60sS0ICJK_|}F{pMF>Zr1^urHc7%v=1bgz#trL zW36?hz}gD*o>$pdg`dcXXQe>qia$nD5zzn}C-}=DPlm}ay^0+bOV>E>wX7p*+y7^B(KlVhJ80mL|%=_FSj6IxD26H4@j=CrE8a{kr^IA>-h8lM>LxgL8`CVZ7L`KuuE&jNSdlhn&R7*}t?QS0Q z^YJ>-&6Y$o=wLe=`>g$UQ22zyYd|*yiU(@%fBT*&05=jmM@HoB^1@SA#4PIMPOKo~ zYQL?jOp6-%yUsb9+UY+2ury- zN+#uOx$=2yO4w|Ot+Af7dRF;w0v`YHB{LAMyryTr6GQ>9Va}U}wPlGX;R{|V44Vgv z8KB+SQOrJ;aGVb|wIiiUAA3P8iz`fB*!ALFTA1Il>(Xn=jS{?HXYIpwcU@6Nxes~u zvL~}1K_$=w@9zEXF>@edac+>++SdjsHBsIV&NGWDd(X`=g-?$rE8&Bl=NV5+ThB#E zC7LU!dP9ORE^|p@SqAjI*zz2V;OevERw=x8^YWG{DNn`dV`u1Z2TnS;H2n&i&kMrjILo$g-UDNHqwp|NQU z=ePA)lME-A4riq+$`UeCW&P?EFCs|(sK=M73mP)AE5P_mBpA({y7i2z?^R4auxt$P z4(QGTxj4kzs3=q#C6nPaNJKpktpD96IGzI@i;JmQ7>KH$8`yYCnS&&t70xv<8#KV@ zTRxJ8a=$Sbz9&JH6q`@cwQommVTj>dZlr?Z|NrC^G1cd_pF3_L{~xFW5QZZ}OCrBB z*H*y15EIR;`!jU9!t`6uokZlD)a}OixzlHn-YIJPa{ylb2S+d+opswSYu zq?BGTT2=(Ne+9ya_t_hm!AsxQWm2`claZCW)-D^7nVHGB{7p3+e#~|Lg2vS&zg>+9 zI92?cpd__Fzg;MW3K>$2)sZ8s_&F5=>z{w0n7_N61lx(?SlCcQr~gl_}MjUEYtp{H8jv{Gz(h+aF=^EWB|i1@H) zf7Jr)dm?GzB5)PSx(-~vM*7?fX#m1qGzlp{9k6!(gpF(gQXdiXjg3{lZNjTnn$I?S@ep(lnEcKuCPh%&etOTfT+T^KKUD$tGE9XwibwcL~%G3ak z%eMGWsxVM;CC{d4N>5#r50^{$PZKuVNpd9At)S{NQs;Uc|5rbCNUWVPEGl*$5U1Cl zd-+DN;t!hc9D`QokJ=m%cd}z$yj3Z~>I0Ptbc`9J>SgQNbqt;9_~BUTs^arXIjL}L zF3K<~JlQts^siQeEe@#4sQbF1G=%J`UM(5&$QtX3Zpl%b!cB^5j<%q5%JmVWc`Tz$ zmYI6q3=b$k>S{xJ3W|wBa7PZ~=2JN&ZTTtaee8MKn8jDlDs^iJ0nPShA`uoAUKzs7 zqZ4&)f0Q6U2#G1fo*4{uZ7yY^p6tH?t_*>{Hv?{9C{#hPUS7Mr6JcPW)-gULE`vY+~=i5qLCBQ>gEs?+M(ZWk;7Xa_X_ARpd4`3IX{L$N#+Ja#JJ#XveE?aY0^WPhY5K%{y7&2%+s5JSae24 zRxFtlG*>Y%I~=S^C)o4mqiXHHGFB1f$12xZVtYz+X7%VtMUbFxH-zNGLI&_sMdIO5 ztl^ftSPv}_ z9uOKTUl%?O__$c&sHHJ~kBZk=?a@e+UekrCxAUY8cxImU%dNuLh_#iJF)IG9`h&aF zqZ@VX^gjN2fAUg+yHh8#b!$|r-_8-D%Y}mz>#4jud)aS2G#kG9XzIPkwaX_ek#6|xIRu<$V&<`?X4yv74L_|iU8jgulz{rsNx7xd2Ls)IIa=U~(OPqE1 zn?rZvTg}l4+~Qy~`e-QD)a-Y2%?9S!h&EXUc!U!~O#Rk@69Y1akCP%TNM+lHr%@bf zczj9}L3dW|uk8%^UyW6}G}c%*b6r9NQexYqi}P4*5>2IqygcZ>JFdK^6R{@ow{i;KLJA{y479*#Q%;$}C!%MMe^!c{S>^Q?j_a$usyTQSSd=Qx z_&Ns-|0xZfe-8T3PYVHH)dntaoY_Xs`mL<2R%Rg`4a<7-%gU2c2~j;Y4wQJ zSB&uDsP9{!&;80Q0X`T5ThG@`yEAvNnFI|lz0TaAY`kv7mvK{QsvDkS+*;fd-1DQ} z?Z=iQwg9~u*t33QA5kYV40C*0R}T2SCq=XcMd*yZ8&dbsa2b)b)PF+ru|pY(|0l*DS0x>Lo1aCw{t`-Blm=w{2~^6$5J0{2j3ol z@-I_LT)HDDCS#%>XgWvj5CJwEvleJe4Q0Czp|Z(g!76qhV#yOGs55`}^EXd@Vwmi? zAh=W2DyKX}(}6bcCJoPN{Vd3|?~!`WMpAUWx?R$dvl z@->H!Ucu>?Lw3jl&op*@iKbovb!NH#5)r9qeW8Ak(UR+~HmMw`8eKPFx}DmrjO@O? z*Zn}U%OXOhPA*KlbLWtWcfiV!dg3G6Qv zOe*y8+$HvZP=&hxQiKXMA!g`4iWe!941#cQUqH(Y0q&GgHU$63qFcN6L`=j_s!pE)$TvrCSbFHpS#U_7d}-T*|%)wgj$&k8pkL8N_T!p1=h?2Aswh# z+eh?}L#!w;BTv%o2QPEAD9ZpWIH?$HLEKIeT#7usvPJc4f=268_gSN<9+4e6`csp~ zBROO?EnRBN=~a`Z8iX#Y{%Yz$^B%NS=-o#LAX*@p4dRsuIqU0NN1|_=XJk`7hAK~m zN4_{tc1nP#8D38jSzIY%1KSp-gKrFNJkw3oedmX$p}N9~-M(Wm^^U>`TVR)`yOsD5 zzxBuQOx3{mSm>`Q2!|>lBKWdbq--Ogxi4&fmWL1U8E}XJykZDz7B1zeilw0sqQ1yQ zeB?@8kv`hZWbIOYGi>y*y}SgHHI83KoD0+1wx=8ni^9->VzMm-zMn<%+g0FKZiq)& zo*N<7Yf8-0m7MeSWrm0p>lxgQ97~MXa-!@Y58onI+%HjcbGM11kqm;~=>Fk~J4waU zXQ$??IwS?Hs5aj5cZB8a$W3_ZE?aV4XT^nkf|9B0tE}WZ-bUyHt^ zvmpTUFlv=$$PJmJUa(D&_UyS3PaNdYgg*DRD2t=(0d+%BJc?7Qf4d zA;{^@J`PZjrz)X38`u0G@3sw(d$Dfmov*5I%azfyxEU8vo)q1_Uwi!HEQ5jCc-&z( zJPa|VS-77doxgWL&@L>wN7(0G843DjKXm{Ps28;)MsBly)&@7+@o+eWf$u!~rQ?+Wv?0|DY_WCLRs&nu+R2|C z%O!x1unb#JS^#d&gK8H?GGY?(j2NL@e&i^B=dm%e2WoV(nhki;l8b%)GR zHnSp7=EOaw6Bn+}IWZIy1CHk#mRY-@pkq9?N218@OJCsGA2dAqlqF0-2QpYG(8VjDg3It(EjA@b) zHf|T%;v=~}{s-+OW6rJ&+p4=+)NV*4{Xpk0Qb}?d+(^Jj z=G-|;_Gg5^&>Z&tvOp65MK!#r5!3s)(l;uT#<8j4s1s|aZ%ivEz~>PsCJ%2Kkt2f; z5gMUZxn#J6Z3qsUwK|aM8nMNiQ)!MVUQW0(xRIlO17&Dx>y(X@xA^RK-f2vD4I%rB z4EXx8gUFD%g8$SLs251V*RSvTV>}=@hq1|t!+tv|-F<``e8pwTW7Q~qwEAkG=+l!@ zCqaZl@jpZ;Y`65lDWXo#QbTK9fOri&mytZ^m&;Wac8!$0GV2a3oi*Uz{i2uM7Pe_d zD!fZK3mC!Qo4WrUT>O-o$_L5<*L$%BTo0hMb7w!q#elyL8TgWPpX_unOq`|0qzn6; zH?N^f7pIHKQ23Z42XtlTzt3*$?81u&-G_`$Qb!|DsnXq0`b@>E^?^NXU?>%^VtnH- z0t?iJcq1h1b}{fZ17I8NxYqt4AwkCt>eGb<*Ph-<+$C__mNl3_7SUck%>Iy*#fGl7 z*RC2osG24`#1-jsB#kP1Tx4$}c3w>Jx2#n2b4^#*X*McZ_-Qxy|I+~!B;_iIKNJS3 zKI7UfKLO7d0ApP>y7gwaOP#>eQ8&%WjQ2d{WULpk(R=K)H3UO-eOW>UcOzivz0c6M z_$+7KWb4n|H-JN5ooW>7! z>c+n87bm@TMwwEpPO?VWJ+5Fj4S(Ug+8oyrGTctiV~laNh|~%*;OrI=>mGy0N5P|4{VlfCsyQsQXR3gTO`Ho>5TJV zi+*d%%fr`OrP*y4^~AiHj07Ry07(+K`%QU%{>&sLwUqPml(iES2i$#0eBi3Wa_XdLqm{^1LzI zMmQp0Rre80#2k@OuKWc31Uzn&%z4x4UornaDxn7!1nsuW&3y2O61c0zBa%Dg6fVKM zGPXKQ!RF!*VWarl-I^j{!Tp1am$gjGkjacQM&wTHw9`?PPUOy`n;MTwesNaB8VQYi z?19i)(Dng6)UTlr7Fj@hGr?yy^g(wzL7MYPOvY06047#fp?+eXF7P_-qL9r4FgVRj zsn2!7xBrht-*tK#P1i` zk6P?c5iDjm(ix9RFAvyc`Fzi79AT^%zL+uo=5n0m?Jccde%#3ObGzJD?6>Up3X8d3 zv?59wr=K#7Gak^N2XIsTjrE*s8tkAnHNN@?clR;+aRovqs_QTQ`=2Af22!c~5EdA)!o-Zc zrwIcsk%6FdGdA{mH|N?v#r?KJWregd-EwF|?BNjM+hVzu#OE*kFyn_XX$9DOlcEM+ zmw$%)^V5hB7%SM0yHUQD0-S+q@3kHfk0GevrpS4}o1>Y%fA6zcSc;C`b#>hv>Usir z%%Z1h1!?wBN03`STq#5KZKKvNsNC-o5X_*_X6q@kOGMX^2_6rw1X%iEiw!$Nv-8d@ zaa)P>gz3JgUpVYvsjfS;?j$5~$gNntybQ_CIHM@s#nH4nc^#msf7I#wr(619xa?E2 zzy^W$ub{P(t_=ZVu&E9q3Z^B_z&r>nL`HACO_`tUqFHSC#p;E?EVwaa^?;?$3&PnpN;(KHT&gxw8`TjcE+mtn3{d6|+$ZPZf#MqM_j5)VBB@ zBKq=jp3uk8N(wizwpbZ>_+dcw&JVx`2or)EfO->$9e(NR*DMvvFo);@h$XrIB>OTIavZ?MOxi?!>oMEhhPkc zZ7W+9;Y+#%WY|SkfFL%FVCf;&hu`^Y>&~=kah#Dt-S&U9JG<H$nX1E!y3&BFU6) zz@5`f;m=p)HFYj1#K5}o9isRO?ET=gd9g#kR6jyzz*H=1j_883108ITk~Ck5nf+u% zR+0eDd=refgv%i_OsID8!6|0mSK)J1K2)jPU-K7ndzO!DR8$QLijh1rFqOuIy@8F` zdF#=tW5et0%`e;A$DQp$N>0u6Gf&fu_m{RFBYM$)Z$tqx%*>H1V)uoz00}%32%5$q z>$H-oAg@m<>pZRQkc-MQ07+U30*qo5(F))YwVc2 z_{a+c(=4a;pZ>DtXNmhv25#}i0FX0U`hk{|dJ=s*nw#ceBZR5gj0p+Fdk^pInL4`p zyM*ytxnGd_V46@iZS&?vcmVJW;WT5K>z`h;8x`JpPRDPOLCdFqw_$Czzrrc~ILjX* zNftinb2{>%97M0gRTH)Cl#5P3DkQJtOumT?v%w zAMXdbpQ0HU7(9IXMP>E|o%)NcgX@qy4G2F34n5`f?vY-q3N0r6w%5p8H z*OR$=6(oUJPa}P*EmC_jMkw5L@VZ*lLSbP>4SQj4Hk}kRX{a+F$seUBBflRs{u&(_ z?PSYjKfN0klYMXp^ba?Cz~l9;xb z!I31tuLcw(-;@&ap=B4J7o*0u&GV?22oSTq8gH`(T`i-q!Y7pPww{pvarA!BnhSs$ zM)$~^vDv0M#)xV|jLYnol5h1vOj!?h2q-;FDX)I^X#?wT4Xh8^lCA}M!E-eeA0j4k z11Iqs*RQwtnpsB?Mk;dTV=gidlGL+{ga-~fveokt)^N$5J&crG3a`* z-0rhz?-y%VFlG-brhBsJXKje3aktq39RSj7C3fSXH01rTf|Rvz!9<1Blg|0bq~l>K zU5OnZz2&y{?6zgMtdpq(d0N@9z6H`vlp{(PyI|E`6$s229kUdY8xB_u6Uf<`uQ3Df zd(7nhVEBy5tD38NEh^4?oMAX`x+f>A!pvv(^XMLE---X+z=|cT;uU(Z$x2i~j57Tp za4W5!R?tF>W5=sCX(5jMBi&GmT#2xcLRT99py50rOieP4o4wn6RWrDxGIj zH>>@3rDa-&ne1>YUnD+>(NX7IlsG`=rzs&RX^0cVsCll>HTOR)o$a5RvX0ZrF)A4> z7Ax&y6!b$Ju%CG=BwYQ_OyTKqy?G}4;*SyXKU=F$p!%XQ5@>b6_srao?V#LX}j zrqOFZ*2I>-_UxuLn8cd-G)K)1k;cp&`>PgUYYx1tZ_wPsBTwQ*85G;AF)9+ewK|(+ zH&D12$EhBd-Kimm!w)nQezJmRKyfhMS3Q9QAR}O@$F6?2-kQjRqgD%!QFzSRGgAhM z^0`9hTJHy;Z15NDyJHzo(XDdpF{a>^Xn`|x4|eW&eOxNBY^3uRvVJ-51TWj$DFdC6 zN4KQBHXJTA-k%+;w`MWOG13!*_jG}-{fR{_vc~*I#oS1ldL?U<_A1PAmdlfHPqkPn z!u>fD4o*(G{)odr9WL1^P&-@3?Xd!=H)CL8?aVDTiMr-@>EwQ_(bl?qf!8mS4g2;y z4Z!HVz*t~h=k@)UTN(+2gHA0n26^f+H+4(%w|s=*;ilfJdUk{PXJ>>a@7_qz8m(s( zvkko=I~EF&Zra>-qMRI-%WBS0V$}=I$`h9$&-rQ7PLP3O9tpKeXuzF%17o|^CoD|# zdr&X3s|1(aDK_j#(4DtTy}8^^&^nwNJr>DITUP4I%55{PvYm?!tgNdFMF^Z!&>5jC zayuIqT@x?Y$@9?DyfTDd3sT{g@+FlVlZp;(8ffMlwYk`^*i!%V?WTJGFqSa9{R*%x z8W?$J5s&ZZcH+W`%z=vVhbGAfq~8zLzE3(aJ=B&J5iVf(Eqd{rsz7_7VAZMBM`AmV zs8$vfsKzAiHs4_yxD4Vs9$UvR_u^? z`1onII*tXY96Mw6NGY+_v6XqOhFMeOsAry2gn-A~=0t4iz3HC<(}h<+O#H<|QrSjm z!T#pWoX77&j%TIN@-nBo2%z6CA4HU3I~ilUQUt9!uVShkFrSUgf!Zlw8m* z@{{}{#^75lTVMEW2L$$(tu8APN{tciY3k91yz_lo5iBg?7qBYzFB#ZJ8{KG6ZA(4# z)&5D>Oo$D7zBMN!Nh*n)ad)gG2#tVMccHjh6>Izln?!yB&i_1n7wq-kMDDneXSq4z z7F$+gF7=<8D&&;5 zx0ov;S1aCa={kdi%d+QAk%d3n6+gZegR8|?*>rXh{s>V(pANQpK*&t@s)4s9_{r{l z3na_-J^RxtPkaKcD}c3qQ8r z5hyraGg`l?i0CRWkd2g)=EV#pdVAXK;01?GQdPn_im7BZLpas%MS9K+R-iE&@vjPk z*viam9*_>1l%&4pK4$ABo9~GC=<7&5TSQAY4dOQy1Cl4z)^YA>L!TD!PJ@PacUO{w z3H3QfIZ<>1MyH<83IVd|M|}TRWK)D7IYT_Ck>*6veF)TW^le2fT=f;xh1;B6LAqe# zW%-)et6<`^fl$|uX#45UTydXhycSaBWJwT@Em8GbH{NVihs>%#2d)>{Jap~)mmpF zz8?_&-lXMO0o1(A$&Tv&BdnQb2Gi68c4 zPA!_)D`1G7~Ci5mjDY0>uDpaLSs{KlnM?~1NdIdSvIv)jw+*RR)R zeHqe)Rk}s==k!^-`x%%y1=;qXEGx`%kH1UI#Q{xRf@Z+CFW1y`No`SAJmKf=_d~Se zb2~w$g}3GEWV=GLVz5B=hy3B11cf6E@m%oAmzg?BX06fmYc~<|y;;_+*{xk-hzZ7E z?G|upXAxW*Z*Q#6a$EdnRAQyxvjiHUJfO+=cOQd)65^n}kKhsXp)IOsfif>Xp4$)p zCFmBKoN6&P_WGr2f9McO@UBMvBqkHQy zdY}0{ieYJF4${QB83Mj^y!{w*eWouNI3hho#iw~)HmqI=`Z-31rl`o{P7^KNIB&uo zv7j;~{s~c#H++tm>~0Kg(2(2B0BJtXtl4$d@QnLoU#jEDkx9LLc<*3X>8R!9o<6tAqQ!vqfr^8}2pGl|hjy-JrSRBZ*%P<#@e!!J z2sf6E5>r)=7GDJt3~#Wp{HsiR-%S9ZwN3QTOn>|5=X^)cwK;zj*E$cO2BAZ<)u5}T z^f1-6ir3LjI%LRH#ULhpNM8~AebZ&eKVJK@_5i3q?}`6#Qlslduxz1S?nncF1KxUK z`~&6jil7F5!Dg=&=N1=fmzg$6>)5bWeCB**vbbIU#)B4y$zALAXoBJ%ul&b5m$xs^ z&-cyKHrj?5Y_$#3QZR_PZjBVs=&7ZKzS<0X+v+;HbCqMWpS1tZUQ21+r`mtns{;^o z;vGwMB_+UNg931@fT4XbxD-CSW9dvr0>0|^WC4i@DkKp*gSR(yl)avnMz(E`pS(BF zl@`Qg9W-0qz|Sh<(Y4-JOitbxzju%6YFn)&E2a`r_w;gl3FG9;Hp1Odd;A&2OEJt# zR{mAj4d2<{JupKRtng^`C~s~6Z{l`!M3_ujyWJCWhksj%dSI`Fh7P1D9q=0jA7cXk z=1Pcl#wD)9`&09T`Ba7T8;=isVlgnw(F&He9Y{NT1RavDrZwQQYm6)Kup6p0wAYA5 z<<$^Wj7vA<=F0(+M5pL*;oLgac?}CwW>Z1NvL;GG!+E;vvzYzm!|2jcRbd3Rfv%&T z=5w!V`ZHu(kG_55{fePz-me1u8}~e;0tC!PueJVj-z*>yuoBoy9zdz>_dV+c*QMct zLVmeBeh91ptoZD*{v^zsaJRPB4*-(>5_tDcVPj$aOXmb>r}|@*z?Ke|^yHbDX~^sp z8^wDS^0WBKhlGS!UJj62_|iHS&n%5}X=9HVey|P$FQUk-Mu096eH0Q%yC=a5BdKAh zX~+z;$@TQE>oqQhExXnS-8TK#S^E-OCE-dfx&onpcF-EgzY5yTXfn_o^aq4oKSl^Z z_akVSlxt5OlLSG$P-D1yTJDxFe{|F`r|pG9xYoV-J<+xgQbC}<{oW(0u95Q5dqU*L zY{$oi!7OkO-%^_1_~=Ah^Mv#rM+N1XqMh5fe>~6yAW!#cK*6IUILwy=GzO=xCg20? zl9Wl#5iht<*Lxi~3+|-_t&oez@?p!V;Up=3SW;%`=@pTdwyz5QUh!O&_df`lhXvh|A-B<(ttW8#%e>yY+0k^?16qc!p~l9S-$6ZM8o90bV$O zZe+P9UHlk9=n1MMA`VgincSO6tMdMaN;s9dLn2buvR-BiYuVQE1=`4j{NytnL|gW_hh%4B(fJb%jeaj!{Grt zTkH52F0-L;-hA_%|7u>>Rb-I&_mhv^yHZ>JF`Ah`uwOg;eyDccNJUtPM*W8+L)lD; z;M_9ZkP9LJh&ktWE6EJqKlA*ziokwU)e`UDyp}bW$*t7pGss<`9N4O75(94$yqrGi z*sW(6Y+60mW9+qye+oNqIDMHNX!Dd8ne761-D-xzm`AY0J=)#Rt;PQw|JPQPWCLL@x@-7 z_lNThRwomcl!9BF0#q@`_IgStuX&t17RKn-D)U-^1AZCgk?%5G3V_txnX-?_$Xi}{ zXv)5j^Nwc9&CI)0`r+I zF|6?%@3VHc!RD5BgWG3J{D-8kCd33xFsvMgjF8YeDW``1t15^JfW7lTPMOu}6d)g2JhvV7vUNYN1HNkW8kOvV?}NSBvTSkH zaDirz;f_0;Oegn?M6F2~HxR1?R@^-=s_H3YLypTB1l?al6Ct-TfND6jQ&*6$Klmh5 zS#e>%Q{I8UY=&Y2oCM=%@c9i#H_92#EP4Mt-pT3EJgz%E`0%kacj59R=+Y(O@M7z@>#wx@nGF3L`)2wgZSm!qS2j6+&F~p9Wih^1hFO6#xT^ z072Ndi~9qcd4bD&j54;N@5_JUkjdE~WjAg9p zUzYzIQH~{56+xLJ8KAQi$=;a%sd3*6T~X&GOaNhAZJZB{max}<{_SIT#`Tjhhj*m5 zT^U-h8^om#NFbY4+K>A!kf`tpwKj-j^)nX^r|kC!`E!Pj#C{tSM|{WFM?jAo7}wlU zvG0OCV&`}FF#0cD^&3KVs(UzmIx*nTOcGJ5KG)_KAz+xq5?~`1cP=}BITiF^MQgYwOFt`Z?}CR8d+|^rU)lwd7u+~xP?7XaOW1u6%rKcj(#~4nMcLv#5iZ{pmx7cU%!;N0Y>vxlEU zob^=fbS2ME=48{{xDXcggLQlcN^}vrZzI9=*=(}Yesf7rC~}aCB~=S@dj*63e>XP; zF)CQwlZklj>(X~m$hL;hzQy8+uT zU77CTy9W0QTjtx&;;X1+w>3f7u(H#{9)T+y=$hj2d&-NaaC^jxHBotPYIF|%<2Df8 z!tsA~!2D1J6+MKLjQ7a}gu8WQjhr|7hSbz~gx%!Ly*%5(*qswlG;y;4p!<9f# zKU4tL64NY_Tt+|GU|(Q6k{BjgWW8?IC%@9s*7izrkv%GD?b}yip%la{(NZUExX^J} zZX-c9N>U_COa5S)V^LpuGm~46DMtVK^W6boAU#h4=_-c0$da87zuO(bnkaigZNRO+ zSp(EOW{;1*p*8c|C6^s7$8AW9f!JmZ3V%$`#jEPn4>#3(8NiN;s1*OO$p;Q`4ZEF&!WF~;k29!r_& zOO|fC6%#AdkIAcv*#S52wap1byQevx4xH*w!U?{12q>J z%t>?7>s~Ln`dgoB_ljIuN3`@dnHq*qsc3=ooXkw|H$`KI+b5e+uU^_bz! z82sFqMoGZbRdNG8{iv60^&=i5LqRhR;qvyj%yyCu1c%SeVfG&2oY!&ku{sEAaD}x; zsLsa5rl*YN3t*e{$-VssVQ%$M;9=c&~GLd(GJN>yyG$IN1b_d3la zdg60my4q~pySn&8{c~H+pvw^UP*1CqPdJa$D=`DnqoI1{d?R+5_tBb`&VDM_*bh1V zb&nHV2T1^;bA&$V&5x-AwsJ_~aisbxOxm?4fR-=&`6&UDo1NB8nz2&O52Xw0s+hL~ zaCeV7H@6JRR(Uo)MiVDjVS3T0+GB4yzIshi{VfPZjkg|XB;Y?;Fc#i$qXLQhPm-2$^WyH&q3<+1pLey3*flT?=igHjVswITO;m>$YRlH1!oGsJ-eJxokz*;jmQ(5<*{*&HQfoT@7Abbhix zNibRyOA?JkyRLU=Z|Y^ao6U(RJUvq)vaYMdAAK;lVw%^kH~$@DmP#0}(Z*PWQVhlOs(&$4aMc6c!MP12!EPd(#Q z=WF`T-MUHNXqk$4V`n}+KDMV5B^$I8U)?&C`1k`2uTJg71$?S%l5kt>LWioygO$7R z3cw>~2FvYqeNJ6o-B}rVC;au+Tz9^?Le&}p&l~k>sQr-r@9WiXs1EuK}2 z1U#cSGGjFdb^W?gzC$9mFGEflVkMDB?pYSYw$M!ZP~_5@r1G~G7acQ>ZWGJw_4!gQ z(n#hilYc^|p_8AyNnh)PMO-lK$jtTLp_!Dr(R2WO4+VikZjlD)HeFP`^3pe&t@v^2cx4Mkm>}t!`C$cM{>l+%fbU$DHSTD6qPtmcK!n0HB z=cOuQ5xwcT`Q_86J-5N6YXKQ|o`>wIuI;Yu^cT72*%KTc9eIt>O^#X(%hZz-`p@xTN#^likZ?h<^lYKaIIpuMl#Lf8I zW_bo*OMJ$R2SaV_vuuj2=6D8!RZP8h-K#dXDIN@d%}rzS+3JRoZfa4kJ-9_$!LufR zcr{siW~cV({mz!ML6oIx#Ni5T8`64LqG#Ja$3SqVuIxSzM3~?5=%ux50g-_0qm7X6 za2>iqj%4PtA~w%rBi@bcd|}8b(Hb`O+jc#a-a&7$C;!p4;?7VKdjyUH?U5MPX54 zcFDIZwd8&;Ive@coj$GOkM^t=27ZthI`7?oihF5xp4W=B5+9boVLc3*Gl?H$zN?sk zKY(f$C@3QzgNn>BLreNnBWB5I?F0%BHRrn?=(dWWrk)(?o$?5-WNR8nwH+fCV!eg} zmRi(m`_e!%xH*`1G~=uv0(x)ou`d_tL+Z)7zBk!h$K$dN+Kya*q(dtsFE_ooLCYJa z`&Cyxc+0)`Fq%^>NDz7cjHK4935kqmrl#E9nBZbXk%d=02h;s@* z!rilo;6FJYHxuwY=(Xdeo}r^%MN3qEIo4wfMv(~{x)zrTTvndfCVoi`eq1H?lB9-n zrkQuDsbDr^LQr#Zow*u^3GtB4a0#k(_aMcLy+WB0B6(5!zGT?e=}Ne`P2Or>hIh5uUe0!~iITu22#2r*(%r-oAB(ZmHFefK zcZu0Qf&P8i3AXrKWHSX+#D>enB~Dm+UitVi&nH3V7HfvdyLt9D{_?XjL>4m+B$1u5 z9iZR@E|YQiAQy3!b3>Kt^Jma%cDl`O2UR82d z#znG~H`2nV`K4Cw0@)oFDP#w8yL+&)IPFusBzf@hWRGhjTVisVHw$iWhDWC<_}AgQ z`!lMH(nWVtM02#F)&fTB9#z#xpkip}O7+~u4Ek=lvUcr~(LVYzWnkUA^^vx#zV}F2 zXI@MGdLUm$5c!W^kf7zqQbdSHMXaoxGZF-s^K*`LvyG&HCK9+u3=Cg-3yqBnJ*5nj z;DlUyX}wI^qkM^XwFbnlIf0j1v@|-*b~MAXEe=@?1S;40k~FihWLC%X$>Tfliyp+^%kW(czP+dpl`1YMT=2>4HaK>;**!7nTomaB*#^+qSbbh&_2|z4j2-U?S5eUy>@n zjM(kC!@Q|*T|+FYuqDDLPl@b-n50aU!^cL0n%x~4W7)N@#!~yjw%0;VT(`LyQMnch zcV4}FbSQR>XC6LS{#*d_ZAqt;@9v}1Ly5+kSLOg`dUs#;KqLLXWshcZ?uNQn1T1~Z z9ro?c^V})V41JqB-;Ba|E#zLUNVGXO-+83_X})GBtr28R zeN%$7OTDkk7^9;dTJ7WWPKsh-E_l4DU3$LK0tZXHLK<{NjJG!KicfT(xiJc96UJw( zKlUY}4CY%Om$Uw0mhQ^3*2pod8Iox2cb=ZCn(EZ+3Lb4@XMFzo ztiucFP=aficCi}fPIZIxeLtFj_1S*0gZ9)Pul&fMaGVISYuWs|4=5do_vQ?5gS+0| zQ_Ke?h&6j=ln~gKenV+x4QMwSD~(;ZD=JzJSetbo_FkVV?$n^F93?9kF@oS$R*>o* zc>c)EsMz+32+1_}o|!%r5JZw}P8}#45;A~i(pyn$|xhqD)O#z#ri z61E6gd8DG9>NUHl<8t(!pJoCf=wY}-By_!`vkc{elPXp9nQfNP&Ae|pFw0)?_0amT zpi|{S0jO?hc7`>)L>cGBp>%VzKWNXnt(#}`oO^Q!wtS;gZf{%1Nsgc#@3mb3DrB5a zWl7#9tV#^M>Pu_{W$&c)H}hnw9k7op`ARS&v5L2-f^_?jx;9Uka43!(i=_FRU#!gp zr?0{Bq4l4z;hf^FjfJl&5ALC#T8aj}m5jZ2jK}uX8JTHH)m&tArerc$eu}D$$R-W)J#Zu-tN49H03Em!sZ~_xqw?aNARFWp*&< z{g#WukyhouAR_cFAjaw{4;%~ryY%pc6ySK<43#>Rfjo6&P_y5uzJDzqS^ zl6@`vGNiqPHrbc#>qwTd)2i(I*k+KdgAv9sWBHy>h2Hn)_jvsN>G4YUZRYvBuIs$c z^Ei*=I2+__y9?|m1>RKKF&saBe5BSOUn|AUUR&kL2NXNF_;4)JRM^CpYn|DYo!AZ< z4EGHFql*CwbZam0KbmvUGGpA%8NJc?^FVy!7&0yd{`nv6y?VWD&gyCYeQ^mJ_o=tn zN{MGJa-GG46v7$iuH6=2+X}lZ;Ju#``tKhnx(BLoNxQVG28q}XU9BjoK$|I55c{_v zZ_)qzu6cE9gUsmmst2V_ZWo+c373YV+$Y3_FAaV7NDW_W?q2{u0f$xr3Fh@mH6EC$ z;%C~+eWP<-ruxoxzqaH_mJJ@!fD33`W5>2`tz=Gi|+eaKR%gXZqAVnChN+QIU-Vga#aiK4ft zsh@#zhoWVtK{W)}U(^WOj?~=+UEWE%LGG^eOcMD&5E)L^GEYVrm%jAPzb0W?XsG%1 z7^=8-o#{079O@^_x6jV6{q{|?+xZZ#CG*m|xd{8+w=#kSw$tE_aN*zC5^lfSjVy8{ zFKs(d9md(cyntWyUa*B=x*p^eMZ|7_c)genXDk0xkP$rE9s6$MSD)vHXEAV0xoGwn zt@&Yg)iLY3E{Fcs;O*{yL466~4cAT^zk6nrvE3$N`xUKHW3H}$jsf^5ieGx+vaw8k zh?5>U`(^ZY@D5o8<{?(Tp$T|1&frm@afj#e&QZNV?Rls7hIop>eY0?dv4-n^_xmnn z_(W65TQbnN}jg=wpB8@(ZYp#N%Tn8=(o6XpT!l};ST3QE$t`S`x* z_gbHsL>cUx&K(eFbRSuEu~i|B_BOcDr9`_$@M)v%N>FFPaO9Cf^y$@?N3&Zm*;wbj zt?UqM=}Vt*c`R*7k&^ICJMNN+{m|Mq_YOdM#{9DbK#pkLUK=iBxJ1Pr&YyAj`f2Ku z56o}tTNI_r6EwofYFGuPW&SuDx0K}6Zgh+26_%|oerFxGi!`DHZwFop$*C|K0;m9< zsHpMzs)l7(4h_3Oi5o_*e{v`5^A695r{M`<&hC>D*+Z#+#vvgr(*OJ`;Wcc=45-3i zDurNeDhd}JuEr6>4~ld2>BHZ74N-Pky-r#C{n4$9pN1ktT+;=F5B{~Z=U33z@utB+WQbdeR)O{hyYL_9st0=4qvww7bjMgdb$jSBJGH|-t$HEI z+yQ;2pZA`6!o}+VJ$5Y)$6f*47HwSeCOrJ0sB`eIr~8G}&kt6=)&6=V#0Bp;%zO0c z(N`%oJ;*^uOxw01_H5e_JImZg(8*JprDz=XJV}%nzi75O{seSX8Am?$bFD@kT?U_| zTfOzTz%Ig=!F_E&Ii<(SN)*3Fy5BcHT(^|DFv_hGBdtF(T&D^6r-b`xZh-Uh;W{Z8hzvBSlf4zw9(N3}y&i z4LU~0oGx{iU&od@i)%kN(g@Er*V0zE9Y%M4^nO>JE~q3d#lYrYmXe%oGn=aJW!WWS zZax@g_j#W&IFPh8_oc+P(=i^pfc+9K00#uxh7MXMg!eRiz1E<}zS zK=g?fp{xpwoUZf>6r4g&rqMpD_4{UNFl1kpAu_I`egW&(SFyrZ?R& zR<^4^V8u^0o$Ex}oun(z0)pL@J|0cKNlMo)H%qo{%}m?AkMDuiEz8HJt1KOH9~8ak z#(%iSNllh&GD*+Ja)+9=F9#R6V32&t8O38 zy|;}ySjJ5&B}qB-Ej=kh#6I1*K}NiAvsWtSBIBX?^9?DFcQi4I<44|&sTq$2O?2l& z_O0Salp)yS5g_M~uv;eJx@x%H0?3ClA!_*RFL`!vqCJL4t~*_iuP>>{mg4a0cIhQG z%{&ufQb4myXx53NjdeGUHRh8F8&^5pl?pVmR*`^^ANf(Ly;WMv)9Fg!OP_wUM0``6B z4An(~wI_3QT#_2>T#jE5GLLdw%7e9q4jg7n-I#TBsA=yAx>Zc2-AkpVfnrGYsd1S|LsXUyeyZb98$il&SUZ%9kX1B`BvghY5 zIFHYafWwhhN}#iQh8=wb2DQ1=`Czk6vrS~Y`8=z3_Hs5RSgJAl%->+6N8-#3e5)AK z^IQ;mO%T0+TN0cGQj$Au&+%QO{*zouR_S6^&%~_C+*p-Nm6GyJjO_&I{T+5P`=hg} z9$s9%57_=>x$c)`SJ*!dw9I5IzIujL3id<10%iASNVHbgppQ=Y z@J!cE{(>Vr{wXzWx$!9Lf+6+c-i-Eit{IfGKog@)a>`zPlfZcVwMwj{HJ}Y#(1B=0n6{i`r6u7bLav>71Z7_$gkD7NXMX+ zc<4$ENg%tps-sF&>htH%Uj(xUZhp(7ex5u>%&s>s<`J9wvcfjEIMNgWfVpfu zy--Ew+bjb`&V$e_@kgc%2EKTB>k#C2zMH`Rc!?}VW*KYRE>!XJ4&3>;gf>kvnr-u( z0M#3pxKW)0vM0D>ebW!+`nEZT*DV#V=q8Qr7HFb&B|ew_m_gcli7y?Up5d4AbdPpN zwy&8;I~M=oQ`VcrNG-!?mq*p%Sk+V{t$SPX6<+$`Mrv+;S85}ST&%se4Gi<~%Q zq9(nN=s@U^`1RFiZZyT~=kKa~Z};UDhgV@?R;&k&%6&Y)MjiKX`7qU%q4R^bZzx?o zHweOeHxe02Y|K_em@ITH$d6zFm7-NKj4my9r6+_R;2KOPUR@XV-q2=Ph3~lK- zfw%P#<@|RcBESE_{~;Uq96bf1j1zKV#-GnbbP0YR|6X>LokxF^yDa6=9#R_mrDs(Z zj$izJ+2wqZE1^7>zXlhJLT_&xRVQlKx~=4dXFMwy8N7XZY&BIfI{E&5395fmt(sn{ zFo=cYm+P?R?@u!ggrwgCSwG>Mv%sk!b6d%veyXUFFx!mK{Z#2pMPy!(9{%7w2rI zsPKBrHr}MNSKhs1=jaiYHlgZ;`>%fT-I|CO?YB?4TOLnDrL&HMTLaPRIHOg|bnzMg?EFBmVU?WJ?Lb!HZ<6hu z8Ji~4u3io6&hmCAILBYd&gQsH7|3|6EOq5szs|0CbwYV;>7cMn*Juj6cn=E%=5~cq!duIJ)DM1joQn~r#XvamN zCCXfggpCB5&mb=~#_zXczFlYYH{7!L=}i`~_%alcVXk7UBksnh9?M5N^W7$5M!GPL zu@o{PMbYy-Nw`5;lUTM=p3fjoB$0dl2+hiZzfrbbQp6}H@oY?DDh&3GNBjd0=|)Se ztLD}D`W)lDlVn?smK<0U7Rwy8cYht^cb5+@mT$?^DQP{gO-hnnIAQ1ZpIVcbO4F7s zEP7zlKDoNM%?mRbo}Rp?fXaq$I|d15{!-JY=VmZmJ|O0p6D&cI)~3whMuGEBqa_%ialeWmvWv zF=fDD-59KUv6^Yxvu6Y$(vA+7hXo)h>}^6)iJ&p=iyF+@%^EnX3_nOGlZRNuu!(7! z_Tf#diw@+zAeMOpDN*9or16X`x{}r=qtGVf!JYD<#p0l6hC7nU|R-@MYZ;JhPf?TDPS8 z&YL6`#3k)7`0;$hxE>G^zsuT~MXJ~S4X$(IS?n3_eu{pfr2do^lrpL28= zF;t5)8k^7X~Ppv)rkDPrf6QMb>gY)>X3T_?Idd)-?d@TDa_ z{Arh*w$5B~1Uf>>)tJnWYBGZ@o>rCrktkJiN1D1yJ#!^Zyt6bkHBn2ke622tFHX4@ z`*fbcwUm(6t4=j6_T7KYCKOFB`v%QfgQW=!pT@86a)-g1)ZpqP#sB={fFHXh`pwP_ z%%W$N>z6$&HleE+DJ8ni#rYTXI4EkzU03VY3$O0dI|q;V;JBFQ?nv;zNS$Y%92ZFW zRKJt$8(!hyh=qkkx_Q9cwnK$O5+vaxSw3je@8{*|c8WMbb{&{p_+fc0R_M060V@Wr9m z-m4(Qf-#qiV{4rM9I;_R`S@mbUp*PGxmi&dHb%A4WCv|EbU*U>71xk9C~_JYXb+80 zq;8k^I~c3{#@J>oNxBxevj0y$zU?g6RKA-HzW*+EF`~wpW=PLc>SMOGroqEcCO$j} zZmm1xpzFL(_*-UY8-y^1kPS^w2Eo zo!%zfjN366-8P#+91@{1_KQ6Q%vA($?u)wHnH5>$jeSsJE%~eG`s@)G|6|YU#1{q9 zJi@Pc_&j4>j)>DEU=?Q;@r%;KD-o^4hHA~pDQ*0nQ{obuZIt%q%NHMIVoM38R=sZMZ?=BP6sG7a-;KX$ue{#Rd`d_}V$bprHDr%#fI_u!1;)kxAI{$9N^Bbq)6}RanvU@ z+20TF;bL_*U77mAWee?wn6 zu+QjUqQPYuVvs{AdzWlk+t@iAHL&f8M0@8EVw87Q_xq18Zu|st_ohZs& zzU+eW{jH46Z+IoLbFEubUvjBMkJ&;UlCPZtqN=k1`v^8{Sx;@`Ter<09>K?}2}C|_ zyEdFwN+K}RVPZ#^^5seg+9!8*F@GdpE8b#V#5JO1EA6bUOD~gUF_vCjz?96{Sht(2 zF)+gKOE@5gKyP_KznJ7A(7LmCC!YA`&<){RlK$Hs@HH-tRE#g2a&!8Lp=vsi6bi=(iP+f#HHAk14rkghNvKJF5DsD36gHDjW<3| zPeAnLFmZr)77Xv*%kCo&LRRBHWjSXjU{cyq!tCTZSVk;TYD?F3_Y8RhGlf3x3OkJ| z_Qg**%NwH>+K#oY*hOBvWo$)Q?s4z&&9rrSsG2(&p0bh_E&JX#TD*|)Vw|^p_@M+M zDNlz-Q9@~ZsMZa}Ye0LO35oMCbR8Bu<3GvG@^y52=Y)MPHbGYnNLih3R40*4)5n~l zpZn{>{_KPYhJEf67#h6dm4YBklWduO!Kc4JbL>i&Cub-IxKvGGs21}R?!9SN=kIX} zyBV%ZI%LFs3f(4qJbQcyAm8_AlFPKHiYy zuIPw(hZ0pRkFgzL`P!CZqIJR+s~lgM(wXC`r;Cj(3B01(iga^Z!DZqP$jWPPTb|s6 zRSt#jV|)DCfQAQ}*I&;WY$BdNL9jhhLtAe2QV1T;eYw=LIK|zOeS{2Ztxpdbq-e&I z<;f(hNy`-T_=7sBh1)`9i6Bfm`}1XYnlX#ph-C2&7Z~p(hyWr#&R>JQc>#uO0sIAM z>|gln5`#78m)s>SYa`*Ym=ItFZ2-hHaTGZ2Wyo z=cQ(oUXd_6J(AtF=ff0U+urKlw>6;xni#ZkaB-GRTY9=)PQ33DNjE7mao+bWCgxXvBGE$hL{F zO2|@tLa^J6GsV*P?*)MV$VD1loV2RTpRv++hiQGa((}E=Em?>=Cv+YS56OS5f@@ro ztkvUM#Y&m35khU2{{8E9ah9`XFR|`)ZFU(Yok(`ap)d&DvI-H6J%1Yny7l{jSg;w1 zT!9`FGAvNC#Nl5&Q=ELsa==hIsa3TtU-$8wwDH%k)O4f_mCwTq0}lLJdjte>Lf7#{ zB^o6&J{oV(wNGN*6IH;GI((lfv8L?3zOdV$_!_4Ra_jB-~hBngwLC+3?XN2^%z~2PS@+O8`jbPZ`9+X^VR4&eU#|H zD*4qE9dLz*MFj@thJV#7x|3Ag;})4cv%s*QC#~x@_g0j&J9@H)c@|9>I=oNFq~~Qk z7{%O3(u5C0Ou>~{f<{%6qukH%r^$%PabUd*Wv&d{pjPIPw#z z9~5$(Hd@)fC>5Z4oVfC43ODt3+DHU-ybFhWlycbN#X>RE|0?0q`dfD% znOa&5(KXc$*e`H|9~w-j4J6^UHWf1O0)oJS!E0%Mk_{p<~_Xr}E;DpUGqAI2G0gt2oK`F->6Z;TXGY zQA-O`Sm>QpTD|N&frPZ41VeEFsxizlmrDG9EXUV&f!;+z& zwK#}+1}+j0MB-^kP|SyIeglEgSwKGbmt+aQ1X>dNiYL_{?JI4U`na?;88a z6~kMadHAkqTeL-b=E|7YSKe&PmO zjI6NWo{oR8vgaT(VduBRG)*C_?v5xYV3HJ234w52d= z$5Gqj6^jSvx=}MGNCBvm8OFKO?Y^?o7CFTfaC1UjoT}gCtQdq}ZJMvdVGbATa{j`SB8y2Xu#_@m5wDc7t}Mg%)d}oK!z2-2+tERb zQ-2C}1PgK6zJp!X=tr;$_WkqZg6dP7Y@Ag>C3X@!2q!~c(i^=FL6>A17b)GdDDj^> z=%rl2r>&Nnvt{&>3QSy7$kPb6PP5@ruc*eepAVB4Unn0sBxds8mC4hGI*Io43@qY)9|(jIk=jcoTlEwJ|-+qsd3 zM8A;MzUY)Y255VOB>Q%EEs$R{~Z)`Ngvuy>EJB#8g;BtopW{!^>lLym$D#Md{mbgA~^6G99Fvt)6Vb zWRrdnAp~|+Ye0CQg%EuB$szIvKINeS=mjPM-)J$>20fJ)CU$4LxiOQJU=gW?Afx+D zm-dm;4G7X982i_UM^rVWK;+I{Mij`>bg$!V41r#2ckqGrv046c^ifviY>6SyiVpxS z1^cKjQ5RJ|=4jfb(im$h<0O@qn+M}kVw&qPJvUP>RCJ#-Ex3v+b|c}$XYMm;LDQ>( z`ZV#dm?J(@EX!aad3L<<-B_4ql?%Rz&GpyxX(i!Y1@Tug+lTJSyFku!kxUWxUfXUQ z>B!13SeNePB^0ve4WWu4-kMvw)ygI%k7dv7OF2*>?Hp`0nX%FmU~{|Ko7hNGmM$u( z@U-j8%bHRJY&LfwGN}M!7KkpWKtVfvX_xfP+8I9aAz|C|Yrs;+FSK2+Nu-$l2Z|#W z9sTY3;o%Owz{6r%1_lvrewaxd>3c%3q}W>)$ruTjxnZ_IEcL;5>ktPW z){uHkWJp(X0I7T@k7l&%Tds`gtp2liBpyHI4BaRaAz_g|dX1Qw`zG4HzV5bcBkC_B ztz8eqq6k9t?CEc!(Cse8GRVN|V#OP59PZV4GVG5!RhieF651V(E3ya$2?$gd`nk@_ zOZ*iX-WUgi0+%#Wf}um1_6nQGckFX{Y>nC`Fi({?fsh}wF^tYXb+^;8#yXwYyGzqs zJ`ZYZsii+fw;cqaw_2ybS3Moya*?s=3V?v3^*+Wa?dcY_S0Vr9qSYO1C5Z3ZoHID`J{MwmGV;W+x9+YXc}IpIC3fPguebN#Sx!ZN^n6g_}&At}Ay*$rQh4BH~$lB8Izh?0<6 zl*nbU7<9gQ7E7`o>MgU?O-fFt*a#CpixR)eG?BiT1&;zNAm7(0&q_T@FaOHJ?fa%h zftP_hqY2hIw4nbw%y9&>!D#YO%k)67+}I=4XrF=B zbYnweIXMP0{Gsn1o44+0%nTO}9xJ)rlI%7AQt6ljW)j+Jr12L=&-gpw3B^IIqAnfp zUsLediVE2nDJ<4vEYI4eG47)}`4^)LyWdZG*U9FuFGUmJOUhST!`VrBIJ)7jQYnfw zkuW1IcWq*as=OUGAF3PzvX8_yxUSd_M6ADQwp~{3iBH{#czf-!U%#uWG@wzZ2#C%! ziW=oy-((Ao5a94i#EZGr9tdy9(FL(nSAi|}Ok0N1>BwDVME4A0+FL>TvU4AphsvdI z+`AZjXt1P>mde#9Hz!$QB4ci0VbJUA@MW7Zv?YTwS)vg%TotK81+K1a>{aycDPVXP zPsMxj#vN@YsTl%+e&`fPO}vb(*82k<=liPXCi1OYxH8%`S$`ZJr^j_?$I34KVm8GL zbqr#-)PT|*a$n|6TdaidLikaIH*en#U0QJ%Zyi5BiBG7ytn58F7@Bnod*rdbAhSb5 zl&JF4ss{w19N2Uf=45A!bE#^<-oTx;w?Tk1Rmjr4uN*tHaRXj>2FD(EAdvA%`=pc? z6qp|LE}Ok-3+dOkhf|U~l>GUCt7jA};={*oHEr|}kM*8{Vow(We_O7u5IE;;LCv?e zYVo(q%xxQrW7<2kvku);zC_XQAAbr2D>wc9?Da9IH!I%6ifrNfvjc_QZ%^vS$KXn+ z<#NLb!MB2HhLCUh|Eeeb@6z_{AJJ(iY^pQM@ailMhN|JI{J-gfd?ho@=SMr+4rdQ9 zu8cf*K$~S$W&pVV(X6F3P^r0Aze)Hea>IeTlQokyE;P^TDD&)=nKM;;8>oxU0;c6X zlIdsnpued^=)Loq+}+F_(ZUY)Y}PHw`a`3mqvaMutlw5VCqzZBeWM0G8N26SW4oGO|8lzml6Jn%6kIg1M|6m~EE(V-8 z`Ao}8Z{9RxO(RzNZ{rvfk{KEO0;l^b{XKqkOhGQ{OCnt~?fki0M4wn&Y$z$4pkRd$8 zv=#3%pD3!tOO?x{0wsN>mZ&7L8UfKKu81W0j2(G|b0WKGv<` zV_x>}($<~so*V;kx|J*N&;p*{utb%$Zh1=K>z6MNjBX5k3#2sgXOG<1&pj{eCc@+a z)>j!|Eyid1?i2k%e2k>_{pBUc-iFx2r_X~el!{31Y0zCx6#~#v#qwerfDWnEnttDU zO^*<5;&5Fl3X-OSs8(yq)Q<*fD`P_Y)T0Ek){sGIYt03}1^}f0)?;+!GJW#?wGbKC zM>9|r*b*RA+DEWz)KnWCGIZeesM<6)RmJW%k|5!n_m@($Y3`FfH*@M=P7Sb5QVsHL zxWAq$xszQobZ7}|Ms-T~w9`jkH^^$fJfgJxAqJO~ zq-;@*-c(F|o1U?aI#K=6A%bz1X8rH$MY{ajEz-srdY#=Ud7xz}{X@$_0y|IPUC*U& zgMcy!_<{A%es=ckr?0u9r;O9-*qeNrq}(T4f#OcU^!m0SHid|AU}(PA$tVL%8Z9i6 zMO^|TM78^mOBsAt@BQ&jL`esmuB{AaK1~ZOMsbP9y|Z7QZun-8>4|6eTWrEE%?Opo z0jJTudvDrS`1C2HEEW=k@l5~G_(R;>;$S(f`lpe>afTKkCzO&LVL!@7;Hq~tx~STd zj6IdrE-z5;{*fy!x_IQIVZi18h2fyU=H0~H5#Co%>oLS%dr*rBxPNB<|hJ0z`?9_Qe<0>)z*UrS9pOD$KYBTpfYmRQ{v;CWez zj4P@a{AZW&HcrGbk#c->@BI`tVo48PZitsvb0m15$SAl%5H?P@YEHOP*W@+PteyUj z$u;EvVeTO>e=6#(#L&Dyl_-}!NoDttcgMSi4iEjj@DZ4G5qJIi6qtULV$YIodJ><4 zbLu#)01CNajv{lYB_uWP)nF3*R=NFZ^ch7p#zQVz6GPEyIPckORjSci=~}#M_524E zl@#KrB)^pmUd?1ZqENkewD)9@*F>QBtssZhh!o zrZ%|-Hp$z0b+)#3x4#0)&Hr<68(gnblN&AS|D1p8#~!tY`#(3c@E8~8O;U#C+Hx%$ zDy8~YnbAqGfdq{YRD*5Fcf_XCO@)4)v3S|vVe(~7EKIOLw`7{VZD`+{)h0-~CR6rK zOqN1VQD13gNzc656>n1T_QC&q-*FtH1;e)_a*7%j@)fWu+OymF<{oYqE9hB4LX%?X zQ1sBaNctp@^K#%z>@LZ>3bNN8E(E4~wn5H&MT47*$by#rSlaU#EoM|wg@~%0UXP}0 zxPvw;0n00yI^@-`-K#sjSQeZAf4|7$9t38Fl1>R+WD_(rG(+A-qytHk(zZ1)dLIv< zyd=E*OqwAEjV`6wfctK3=Q$8zLD>*~w=d^OV}#$@bUd^2#g`K`v1RsUxZD|zWOG&N?2A{}kMQHi$DEK0Fc+YB8;ep3^$ zk=4rfTT}q9tgETN)_S6bWK0Wi?xw-Y8xG^1Q~r~X?kb2F%redpQ(`po$J!Dcf7TxG z=h+MY)UDaO(`ty|hmUiU+t<9R-;(PPH|I4JA7w7fRw+jZ@Tdy6o?~?>CY5QiYVnrc zT%t&aV9(%qTE5kr)8L-wyQMA{&Cy(M8SeN!fatuWaF4T8){=lK?mtPu^u9}KYS=^! zzL_5wi+Oo@16{}8@+F-~QqHg|y7MeJSgDDQCj9YEeW_&kiLMah?F2>UJ(*+%yl)jN z5+oV;lK&ArL3b0G@!qgufdbvle=sa`c&?}8q!L9XBTvO#TML_-tg8DXVN6QJF+GQG z6iO}6efh>E^e(T7w&)uP7dy(U7#Lx=`ui)b2Y8Vzr4hA6wFM{la^8Ic23i7wWm=)8 zw;uxErtb7(K~p>D(vf(fidG<^q8ntXS4XMNsy?T5N1Ky?p?b;K=f?@bSh~UWG#|D# z4z_hu*>Wv1*mJd9dBV3zd`q$0{_DYKw9Y>q7m-P41VDGIl*^K@OW~$X%6&j^6$O+J zN#HBQ&p80a-gP+Iy?VTQa5|RPV(a+?E#3athzPq4}d1VRf_S;55mJV2>Gn${nk9_3G74 zUZj~LljO#zUi*(X<{(SV_7U=gkg|%Ag!^oL)Wy5T}rR;}J$(Jqv4t^mK zW?YDHZ?PsQZR$)ZLG%`#hZP6&_}pkq)pietJ7r|Nx7T8m63Tc7tJqbn>$u(v!J_p% z5PAN4h%oNfwc?E-iB1T~-y8cawi=|UP4NOWb9CV5mmTR?stzf8y9%cFHW+7ME5_Zg zRlYT=dY<#ih*Cam+&*l_BSZ7vo0gI{jmM<^DE?HA)*(cJa8Ebx0IBK5*-E; zQed(G{`#FVaaG-G1o1Fvvo9EMS=5tjx^y;8&PA zvxOV6OB;bO%S1>GvW6h~!xjz4*rIBQ_dN$ukEa66zKwjS5n{3+Q+ijHE$P1XqNrI& z9^>5L_yUMWso*}1&|A$d&8_jJp6$cgWPhtyxRD{c^vG((XI8-Qfhj-Ac&4I^>`-;W4QVCvY~D-x90|4Pc3>V zFHfYmp@ckgW1^k$*Ogwd@z1wSfm5cBkrVZJ?@+ujBwzfKZR6bo@bLj2>BYIxo$H4Q zY!RSlGd}Fc$Jt0y0?LgUysxcl}f97jgA!y-@4i;Ex~dW(K|(V2DRFKs^5}Opk_xku9Lm1@y{ z(D-X4_o7l9!A~zkH@n~-9=cw!)3O*59*x8&^|Dkug#RoF{%~2@z*a; z)Ca}hs8m?BPn_4?Jjz9H$BWJn0PPZXh?K$i9Ad5LjY-4T-2C9=(s#Qqr?$ebD^caK z+)&|=%3*On2?>cl+55N6+Q4WK=YlghQthFik}W_nEfu9g0cU$@RwQzvj}(9c#<51?=`riO+pc;I_RV zy7u7$y$p3cH)5v$u?`tw8%J$-n#ow{h%QFBf<3$2Qz9@Dl3gBfd!+-WWl-uedO0{n zR@-lJUDt>Nn(bg>XXvEhwH9=s-av-UDeZrD29&|KXe_vGAM>N%e}m&YQhyJO`SS`*l^2I=FPYtx7=rv-c=xvy=vEYcT>6hn3#2!7FR2Y zJl2&IpmWmH0XH`}J4&foq00G{#36IBAwl}{2Q9*heiF7yjs5e}J_pF&+_Rb5K)E&m{yarb}3n-y3GU{ERGY0Ql(8mmP?g%8~fFv=P4ERO&(iY;hLdCAxxFL92PQ4O-wxAjb}&AzGN#T%4VRD z+?R>*z;&w09}VT-#gv}{HtK!HE5Wd^^5wAa>tzqD*PlF>;v!!~q({1OTN}+KIYhiN z%iqy-B~aBUr5TK854N19F=06Xo{x~0e2n~#R(iZq@+ zeX6>{*(kQ@(1@(?tta@1vrW?;fFrk-DKT~9mEWFJZ4@?I?Wic=^2bJGAOV~ijnc|Dhv5{(A$L&`3Xr^tpYp!s$t-8ojtu7SpOEm@nE^$)*-&nlvn*B14}{K1Axj&HduA=2A^0)Uex5CCxHQ)c1D@n zT0`%yLS7)DaUFmA!x`a_kkQ(++T4wP$~QKjJJE7!a&^b^J!lbA|S> z{^C2s_TS`O8khZatG;~W5tPOANx?-4_CB9Q>AtO}2!MjN(F|~v{u;TgRP;I+9Kh*& zEA$J!=y{Mk_iX-MxvDR_M`F5iIRs!7QG8Vy5F}u2(BY#oSwFlc<%M0_^zjjev2DJI zy{(+S@2;HCo+1D+R8eU4{O&Lv&~75+MO%+rg89hzfFN+CDujL`<`iDz zxb?>XNnuGyLvS|vIGnsnNB=oiNvqoV+XY}2l&`YyngR{(ZU>;;YTNgUG~$5o_tR~> zg{Y6)n-L}VE9eU$ssoc>W|w(oztALh781;#@u$HMbDMTtq`2PkMn;?&bE=e-ivs52 zKV1JldkAih+3ao5``e4;dbTgYA%4vwhtWmF-rH@wJ&DRc5}jESeNxm8MGjif5Dr*= z_j6y(yzyp#bnmU6yLVHNC#B?Sis%(K6)TWaNhC8%5r2pGG18O`pOz;spmx1vdSeJU znlZ>lkKF@ifPYPoz`rVjGPhi&$-X(^+at~8j=}n=5)YTJ{jN4gRoPKA z;a-q4$WyGO!ruC5svusb5GpS|Pf$iq`C1JB1-$M-Pb63w!OcQI(?KU`HUC%LPRrjY zDw=$Ps8fr-f9MTP3+MXw86W;fGb=$#xf4`8UdP;unghP2UZ7iX9~#;ZAY{jxrqine zA;#qofcy2nVcQ_z@A@;=UH4HjL`u-PKx*c-cf(@n;|>>rT$FfSczC5kkYOSO5mJRi5H=znLnpPCKmpC%tlC09= z-s@`{h+G5dI$2$}2h1%k2_Uf5g^nj{mN^)Go?&-3_MXT`d@M!rNayS0R(3sm0yaAv z+|s*>ga61+|Ge1?k(D93#!14qZFhXSPUqXS){3nh`?y+Y^~J)f_?f6;V7P=q*z#_t zVEOl(aXsPTa#M0nQ*k@Z*D$a?RsWdXz^s(KObvSY%Z=+a(j*Hm!bgZ)R*4YHcaD53Xq?W5E7rGnEMBmXflND# zy3x!+HckDuFVfW67o2`Z`#6b<{UO3^vtwfZ%rdW+eS7U^;$xodJ}_@p-#d$OuKQzK zV4K2gPXnVe8UG731S;ZPO~_Rw?wN@BJ2YM%-L**R z%ka>AAj?cnN_uEhn0k2l)qVjm(;=lsiZfs2I7D|f&bzPD-zv)M(oj#a%3;I=^0?XQ zZP1A^h3sVB7V1hLO|OkgUY?^1?z)5}dgM2+9|PpS)DcUI#UvO!{r95z`|rCZV6!$Y z)1LDC=aNS@aVnf0#^q+_|J~_NU@SAv%8w@O|70(4v$n#`wZ(6ge(kE=cv`4k^5izv zZuCRpKtjT7gIvoMvv7RHlVGO6deRqf4A0gT``^%pN6zY_?8>JB;@Mwm!HaN9aM2p~ zB4z%rU*822z&3_H<81qvr|mwye-~bq48r$xC5(ekcO=Y!Q)6VaBgk&xv+y47u0rL7 z&HVr7W5`QGvuuNdulD}Hj!LVYE+uZG@%w5*4WBO;!dn^mk+9(*0yRG3@hq+E^@q~G z`hcr{RBF<^+wM{YV|r$Oi|g&!!sYLv8dm~zpYA9CiqowANd)9CK^dg*sg~n^mTp_2 z8pjd;$u%+e4$g?pIA|>Kii(EFi{DZ^y!oG6st@r=5k}8GTYLL|cfnl(-T8eZf`3Rm z`O*kra(kfaaV?j@W*9kzO&`d|8q^0yiZmtucx@k^^{p) zyPvxvP}%>o4&z>A?z{i*Zk1n#Jt=+ge_z9ev`RvDS#tm9NBX&bHdEJeE;DsOmv?i@N5@$7~;LCftc-W2gq1pf(vtyfkSP*FDzzAV64dp5u6l zOTy{K==q^Yueor`lZ0Ydf(_Vi`DPK`{CF)opO%v8&E`3)?n=PpvZ>bVECHLxql2&A>PSC{Fv$#UY+{(?=HQu@B8=f*9IOjhQ!36!@>?A zi8ZiBT=J4jOI#Fg&rVO`O4`PqIP~Gx3WRns)c4!Qjs$QW*W2X!W6z1%@!SR*x2P~iUUs4b{q5Ai0ERjU5vAc z$FXl`-sOtL=>V}oUtFR3j~_q$-44E?!p)lwvwJcq)+wX+7z7(VhhvF)m9}n!5xAlv zY_7uNbh8vy-v+b(dvugxoVy{}xHrbY2BE{8>_iusUz z>w9DEa}SR#_qbwJO2pmd+A46}`9xoANwRzSOmvGB{&&zQ6MmuIn!Mj3)Q?<7L^Vhf zAC(NB#|zEh6XFqA88)FbTa)F6mr*mqF{hVW158U(+?T1AGPV?)-$KuHaM_4r3&xj# znH-gQwrv-O{N4XH(a>(&)giaZe{xyhi+S~L>p!;QeowW=rLf6LPvGz1mfUe9teTo{ zwWdyau-Z;ncgK3tH~NvucS;7#8Il{$dU3wg6eBQEd?ggVlT}hg=J!*zC^qtZm0$I6gUtKx0dBva+>?uuMI|fL zlq0gzW#h#Ji;4j>Q~3-lF|2$>s(fI4Wz1Q2*g09ee4);=Zjp2C$vNaX_`za>LQwtt zD*itFPa5&kx%?J}n3cs`!hEyPQu8Rrmx@VIqvoj@0&89YN2KD3(aY09%RlQ)f+=I! zG39f%6?5amul-i+9V2CD-!au0RB^JCQb(JWg`#&JIeW_Z&S+AL0^9Tpeb-^{5ldf6 zN{Z?HLaZFjXwDWwjn1}mD$OmTai82Ps5n^c<+)tUv)(ySG_fyFJrJu zU9|;QIrmCgP=ZRf5<<;?Zt(r&A-6K&9!LFQOP!HhnHe?qo7&o9*h^{8eMgcY&rI~+ zVDj#mo#&Rm;nn<3p=GvVMY?R6lpSlbQjAscyB)gA2jh_KCrmbKDDf@uw6(SMTB;LQ zi~W5tHYYX{ueh-!m27mh#oiAzFK+w@*}0P{G$k1Gika>TRPjKNRJ{X1ZmE*#YOgb? z&9?ieL)?72DJ4m21q}!=(RZ2bEJt=u@mtc56_pvitQH}=)B@afg2CMDnzpawzUYO` z?DLhgDN<6F_q+TStNfyts;i{uax5KNCVfr3vR8a39vw~|mLqyv*0?M5Ap2cf=I6`c z9s;5DpLhGdfrbW$+Cq{<4%WuoZPe~_&GyF4MiHsyQlS--*WAeklarPY{CXfKMx0Y z`|YxbKj(PuA6%F{7T~PPQD24j6pbf@n#wK>$1abK3d_w1V~ay@Y77-5vM+I*`w@{M z?uIRX!e~49=JVr}D%rW5mj3J&%4k6ONWhg0YKk8vWwgp~yeb(dPwuH8E>99;VyHrX z%0;txzW(!k;~975-AyIRp8wzPG0QS91RvSbQ1Nr0yTh-V^6{Ev_NCwKv205tN>ySQ zZ*Ovep<^IPP1Lv2($8(wxq8@;%)Z>uuF7pP|7oo3!qpp+ry+nu#%H%Eqz2Wh>Vhm1A7r!V~kvqFQ*F_8zued=O zsgf-&@KqMqSPdIwo~gqX%Y@b7Fp7NJdRg}-MHZEY`L~YYz9U5qGE}nN5`lZ_Ww6h! zE=GbMNi;iL7KvH7%E?|%-^rO6abwSMy$VMC)9cUVe~y;6`2LPA7&^`&e?6j{vO74+ zVWqnwTIKfC?%*&J?}6+(-(@t@OLBKt7dX1#@tT`)M>&Z%%J__YNU{lLm6MGw{Qug!@~Eb+ zt*?whL~ttB$WW47$r=R_o45hqP2>aDYQx+D2O5= zi2ieea@$=e^WEpqDZ)A!J2`E8P*>YnuYoQ5!X zn87)ycE*|_{j6?L+qH%(?q~vVH9eKHJE`n6>AjJF4o68hEYzO~`eGJAwM__S6VzTL zaF?~an=L4XA5V`w^kjRY9qIKvL6|{zb-iZJTTSOof=^|7u2`miS0Z~9zt)FQUY?jK z>uq*qJDT<8JkWm|s=l^3yX~T&I7nFBly&600WP-5%#csvU4{Ql)iF%_3S98MErC`T zVy?=GFjW$2b*b+B5^fR3R0K<#1ZLUq&Im5Kw5KerwbEX!6DYY}yBobZga3r(1 zyJqoiWTg{CrW|+zsF{A!0^otg&8_NwTD4ZzRCHyjw5ylf+f*c$PW9^1?s{hyAJ<)D z9N#lFuP&swF7moRV@7{`;%_Ch$^!zwa74(LPax1#IerBZWM`IjUChC7xc0kdVCP+f zxXOL4PX#HNl~zG-!whbZj%KEk=>-~-MPq1nF%t_1V3_X zn?C>*GMrrO<5R`nYfYd*jzuhv9WRO5pBwiADXVd zdcdAo9OH_dK}op$hEbG3tlNQ}cE+{9S5JM;#rYRGttpD@{=?vWcEjU2QOPal{R{4Y z!(^m~k|mW(C=5hUn5qEoFPS%ABof)m>e}M^UtIUsh_3T^HrxYiSPa`smrm%#S9T{_ zJiP(!#fZdy5A`gFIiLMzj@g#vO)T!Ds3QnchN!KP3tL#Vigywj?II^I&&B66)Hp6K zf+Uv;zD-qOIGMiwzLwCwM{74laZ6{7W>QzXxg&$w3?m_HkYVNGgF%AUL@0tNQ{r8-s~y9LoQMTf5w*n3A^)qP)6_Yt34gO@lr{>J1ZIaM zUCv72{<9`r9JBEi{6&j`tV=L>YQghp3`p++s)G60Z5X-vP|f+mKE!nN^ziibv{C@f zFGQx-U=Hl<7mgzJ4W2=6HdwFZ__GMiGzDP35feG`E%e&!Jk8R|+sCIcRX9Q9#(!MJ zr(9^Upn1wRAHud`&{!TiU;u_;H|&v&b5Ij8=kpHkvGOm|61MhC8v{@fOd3E2i(nH}s6@;!7auZn+MmV6!CvO#voMB7d+A)6dQ zTH6F6e6py(l0p@ke#+EtlO-=x>i?`4Fs#N~TU!fWEQ^}!#AxhnslT_-I4apvl18SV zvSlNsGs3Y=>x}p!Mjn@&4`*v6P*PwT%*93$&-P3MU^V!N+}^TpgQTgSLDK&1`o{9J0R2)aOmU3SENrih;}kvIFwGRKoO7Wa-D2K^ zQp*$()!Uv;wdAqqr=_RQ*IP;}-H`F%gh9N6tDkSuuYTH^G~Ln)zECi4!}mjA4Ml@0 zaCzy9`sLWF>k$*s5bhHk7cj%rB@1rIX;Cp%gJ!m?)<H z+Lq5mPQLau20nGUpt~6s5E`cr8yaKbEB-es*P_9QGofCk#?ke$XFEu1-gO0kjrME* zGWy-%{aeQ=AO{MiL<6QO+WTBiA8>g-{bX^y;bPU0sUYdXXO)C}_h%)vxqdH)gW-k= z0K;px!kG#JhT>sN@qLIc0=9&vcHqE)#JfjKU6MQC?4#iCdmK!i{KVUs;_1;u4#R52 zz|w>qK^mh`!1{)VA?_jy3Rnq5DrdjdzPHtJc?a&F`d!e`(a~5omnl|F=|=V)vWz}5 z$Ax&F0*Eq~DvE2aLp-BhdLDDLK~9)!1Kt#?jg~WIMW6eX0NkyAWE?e8TljR9rRF3s zZnrj{&W~8o8&2(ZzK9ve;K}Vh2b#I7_M;_c@Kz9+&G~@Fs+{>D*Wo2$$&jQOz`*<% zeC6Ewa`>%u6^IaF%v2&o$@4jfRsJJC50p4~Ofbr_f+3AL*D8uFbd~%g%F)rrcL%}? zcmKxDw$~OsuLDiXbtwyY&C1R3J>3+8C4R4;v^lvSdbABO{!9L(rUTe-zQYB>ei=$VmS~{73#FGfdXXPN24b#i3Q&LrO2SgoCVlkz!G1sG zdos)VAiC|Fb)FdvCV<}v_cCte*EVz~+2hciC~VpH0~Q^}IUBz=IN>Bn;txb-=! zQm~Y0Fr^V9t{%}~hx9P7kE_4%TSj01NK0tR&KoX!KtzEOn__{OPHs3jp&Ut;W(8&& zXjss6ogf&bxyPJU%neYsk!R;I8gmVZGbpp!^2y>bFN{|MNnW2-5^Um$3jG50@MvnxxM@pnvaeDG4%o|z88jT z1JnRBha`_0sPYAN5ycslsV;==Ia2|d=k2+rhuF3OTC)&cuA+GTa14 zcKkAMrs8H#1zQ-cB>5T+t1Ly!@tD%*a@!=2YM0N5ca0n2=KMcYhFDKw4x~AV&b7Fo z=`)T&Mu$;gE#gs(Tx0eJnIStL5v-9<4WQHQ*1}k;pa4hXAOB@`sPWhAPR+aN#~n=z zd#}DT92_+e6dD2o*s6I)qcxhtv+uyf;*~$y2{5YN@~F18XC=yAUWSXqdtP3jrm(FT zGheEtiHrm*&>(yM70hQf6^P)%VTnC(5%HV7Jd8{&S_|ZMEUiaNsM)&!B&~e)IVGWr z6g>Ym!irRh7LC;LM`VH9gBek7R=kcp_h>{9ZZ$o3ffh~g^^3c&1b3vf4Fbj5bAhP7 z*yH{#U66l;OHC@1wdC~Hp{RdxcY#eHVxdwvuV0#>9ayc*-k2E^hX$%BEj@24d(Sp? zk~YV6J&`A>@KX^sJ!dmbGM>9sNgk}R2@$`T?^&=m(kiXuNqk`EEJ1#1POxK7<-t~B zqNjUM`-Tj&#VvOS)>elY#Xg@ebVQZW>^(lnCUhn)ZoL}WlqBg9hsbP-W|fgfrubTJ&T4hi!P`zG zk*)Ubo4;Q@yEizfF32&xTzDovCp$gESJ5$xfWbSzdXs|oJne;&BPpPZR_>iC^ga`{ zwEG48#aI`Sm>rPMtx0g77u5aAAcuI*B2ZxAV3yUfl}t2ABZ~9`x+fNJ?=;IIW!nM@ zBq1`jE0xa>eh(q5m)#*!1^ek?%u^ZSH_`lWcP6NCRB!D|B3mpO)uc#P%Yd(yAAfQf z`w9uZB275QfS;)JbZ;`@r;JH99x6j;iaikGvU^QY5OY)t#t>)>0~IE2l)fZ|DwdHkkdGoeip-Ewa^g zCUv>vTm=uvJqiNGv#EthLiOqVr-h;9%;r(5oFGrnT6Asj3cdttl1Fhy+eFa3nLyMh zU*(ZA2~$jTMQSY>sQNir!me3{d~eG|5m;R`8HS#HE=5aMb+{CE;|BG*=e!Uh$B& zA=1c2m_lud33ewLR-Wu}!;KZ)eubth+SK-^qURs`1~|h0Hyv2PV`)}J_gDf=I&K}S zoPJ=_ke)i|>Lk?6c2@YK_69R8l*oB8dQ!P2Eh6-`FO#a{zDLox&%zYWZcpEZ?)(#0 ze(7*&0F(MW=NX0N^2f$CL$zsW{u>aUdr9S3s?%BH+dAKn-(*b&11jBOIau?cKQbip z(ffa^uD=rXHE`1Q)Uq_IV1=Y`^7tEtzwGVUze4r z16o>7)f{l}17_BYUN61i3 z1uuKLWD>l@v`5%@!w#)bN3_Ti&~RqhY?F;Fm)wo372)9mEaBnR@&#xKz(UV^ zB4zoN7CHfA-zeZJz`4o_81;ntPYkTm!-Z&O(Yg*^{7j`;vzg-H-2u9TTn4lmnoB?t zBXMse+73W>UnuF=t2u2>Bxi=Qe^Fe*N?5|l?U`O^36PD>hX6yLUw1A368yO=JCUxK z;~j%h^|n3kz$(^s)Kqz$fL=zr-yZJDLXtF{G=nppsT;R=p0IAIr0W--oPLH-?pO8J zzG^YArfd)CC!V@5tS5$7fR-cQ+`cz9V0SikJB!erb(2aOw1hvp)Jh@!6B<9v-J`-8 zO`AJR0EU*HOJw0objRZg49$D&y&@Kt{5mbl30h~rC8DwEGH1}_fd#o>PDfOi(~&cernCf=69+fx1Y zSiGl+_cY}tb28r3#2ext`!sk%96wDVZ>BNv(-ino965!=kK*9xxcYNTyh(~50+bh> z@I!$33DN<;fHz4$W0Mqbj1I6gXn^32(f`WE=nv5|6Gx5GR$BGF?GN&z72fB<`&@F$ zf%m!aK39Jr!24WypG#h(fW!3o<5&3OSMoD5c%KXJbK!k1Xzt(-e##H@%OeHe=feA3 ze{r8HS5_RScX|{$#NJR Date: Wed, 26 Jun 2024 11:28:47 +0900 Subject: [PATCH 003/151] docs(static_obstacle_avoidance): fix wrong flowchart (#7693) Signed-off-by: satoshi-ota --- .../README.md | 6 ------ 1 file changed, 6 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index 33abc8eaf40ed..b27723ab2066f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -485,11 +485,6 @@ title Filtering flow for vehicle type objects start partition isSatisfiedWithVehicleCodition() { -if(object is force avoidance target ?) then (yes) -#FF006C :return true; -stop -else (\n no) - if(isNeverAvoidanceTarget()) then (yes) #00FFB1 :return false; stop @@ -537,7 +532,6 @@ endif endif endif endif -endif #00FFB1 :return false; stop } From 4e0522d8eeab7754a36a7d213c17edfc2944c150 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 20 Jun 2024 17:43:21 +0900 Subject: [PATCH 004/151] feat(static_obstacle_avoidance): keep object clipping even after the object becomes non-target (#7591) Signed-off-by: satoshi-ota --- .../static_obstacle_avoidance.param.yaml | 17 ++++-- .../data_structs.hpp | 12 ++--- .../parameter_helper.hpp | 4 +- .../scene.hpp | 2 + .../utils.hpp | 2 + .../static_obstacle_avoidance.schema.json | 15 ++---- .../src/debug.cpp | 1 + .../src/scene.cpp | 22 ++++---- .../src/utils.cpp | 53 +++++++++++++++++++ 9 files changed, 93 insertions(+), 35 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index fb8b02f1f0158..80d2128bf70e0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -5,10 +5,6 @@ resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER resample_interval_for_output: 4.0 # [m] FOR DEVELOPER - # avoidance module common setting - enable_bound_clipping: false - disable_path_update: false - # drivable area setting use_adjacent_lane: true use_opposite_lane: true @@ -285,6 +281,19 @@ max_acceleration: 0.5 # [m/ss] min_velocity_to_limit_max_acceleration: 2.78 # [m/ss] + # path generation method. select "shift_line_base" or "optimization_base" or "both". + # "shift_line_base" : Create avoidance path based on shift line. + # User can control avoidance maneuver execution via RTC. + # However, this method doesn't support complex avoidance scenario (e.g. S-shape maneuver). + # "optimization_base": This module selects avoidance target object + # and bpp module clips drivable area based on avoidance target object polygon shape. + # But this module doesn't modify the path shape. + # On the other hand, autoware_path_optimizer module optimizes path shape instead of this module + # so that the path can be within drivable area. This method is able to deal with complex avoidance scenario. + # However, user can't control avoidance manuever execution. + # "both" : Use both method. + path_generation_method: "shift_line_base" + shift_line_pipeline: trim: quantize_size: 0.1 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 5f6a4526af580..dbedbfe1f70cc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -120,9 +120,6 @@ struct AvoidanceParameters // enable yield maneuver. bool enable_yield_maneuver_during_shifting{false}; - // disable path update - bool disable_path_update{false}; - // use hatched road markings for avoidance bool use_hatched_road_markings{false}; @@ -315,6 +312,9 @@ struct AvoidanceParameters // policy std::string policy_lateral_margin{"best_effort"}; + // path generation method. + std::string path_generation_method{"shift_line_base"}; + // target velocity matrix std::vector velocity_map; @@ -336,9 +336,6 @@ struct AvoidanceParameters // rss parameters utils::path_safety_checker::RSSparams rss_params{}; - // clip left and right bounds for objects - bool enable_bound_clipping{false}; - // debug bool enable_other_objects_marker{false}; bool enable_other_objects_info{false}; @@ -440,6 +437,9 @@ struct ObjectData // avoidance target // is ambiguous stopped vehicle. bool is_ambiguous{false}; + // is clip targe. + bool is_clip_target{false}; + // object direction. Direction direction{Direction::NONE}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index d7335165e5622..a79a67d5fdd4a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -39,8 +39,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); p.resample_interval_for_output = getOrDeclareParameter(*node, ns + "resample_interval_for_output"); - p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); - p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); + p.path_generation_method = + getOrDeclareParameter(*node, ns + "path_generation_method"); } // drivable area diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index f1769a45be530..635edb7c84f40 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -436,6 +436,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface UUID candidate_uuid_; + ObjectDataArray clip_objects_; + // TODO(Satoshi OTA) create detected object manager. ObjectDataArray registered_objects_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 76f8b1e53955a..1f68ef7d49c47 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -121,6 +121,8 @@ void updateRegisteredObject( ObjectDataArray & registered_objects, const ObjectDataArray & now_objects, const std::shared_ptr & parameters); +void updateClipObject(ObjectDataArray & clip_objects, AvoidancePlanningData & data); + void compensateDetectionLost( const ObjectDataArray & registered_objects, ObjectDataArray & now_objects, ObjectDataArray & other_objects); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index ce36cbf949637..e24077e1ecf11 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -16,15 +16,10 @@ "description": "Path resample interval for output path. Too short interval increases computational cost for latter modules.", "default": "4.0" }, - "enable_bound_clipping": { - "type": "boolean", - "description": "Enable clipping left and right bound of drivable area when obstacles are in the drivable area.", - "default": "false" - }, - "disable_path_update": { - "type": "boolean", - "description": "Disable path update.", - "default": "false" + "path_generation_method": { + "enum": ["shift_line_base", "optimization_base", "both"], + "description": "Path generation method.", + "default": "shift_line_base" }, "use_adjacent_lane": { "type": "boolean", @@ -1450,7 +1445,7 @@ "required": [ "resample_interval_for_planning", "resample_interval_for_output", - "enable_bound_clipping", + "path_generation_method", "use_adjacent_lane", "use_opposite_lane", "use_hatched_road_markings", diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 03b17e7729ed9..05bf1abf620c9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -147,6 +147,7 @@ MarkerArray createObjectInfoMarkerArray( string_stream << std::fixed << std::setprecision(2) << std::boolalpha; string_stream << "ratio:" << object.shiftable_ratio << " [-]\n" << "lateral:" << object.to_centerline << " [m]\n" + << "clip:" << object.is_clip_target << " [-]\n" << "necessity:" << object.avoid_required << " [-]\n" << "stoppable:" << object.is_stoppable << " [-]\n" << "stop_factor:" << object.to_stop_factor_distance << " [m]\n" diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 922883f289de8..824466a1ad3ad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -294,6 +294,7 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( registered_objects_, data.target_objects, parameters_); utils::static_obstacle_avoidance::compensateDetectionLost( registered_objects_, data.target_objects, data.other_objects); + utils::static_obstacle_avoidance::updateClipObject(clip_objects_, data); // sort object order by longitudinal distance std::sort(data.target_objects.begin(), data.target_objects.end(), [](auto a, auto b) { @@ -653,7 +654,7 @@ void StaticObstacleAvoidanceModule::fillDebugData( void StaticObstacleAvoidanceModule::updateEgoBehavior( const AvoidancePlanningData & data, ShiftedPath & path) { - if (parameters_->disable_path_update) { + if (parameters_->path_generation_method == "optimization_base") { return; } @@ -999,19 +1000,14 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() // expand freespace areas current_drivable_area_info.enable_expanding_freespace_areas = parameters_->use_freespace_areas; // generate obstacle polygons - if (parameters_->enable_bound_clipping) { - ObjectDataArray clip_objects; - // If avoidance is executed by both behavior and motion, only non-avoidable object will be - // extracted from the drivable area. - std::for_each( - data.target_objects.begin(), data.target_objects.end(), [&](const auto & object) { - if (!object.is_avoidable) clip_objects.push_back(object); - }); + current_drivable_area_info.obstacles.clear(); + + if ( + parameters_->path_generation_method == "optimization_base" || + parameters_->path_generation_method == "both") { current_drivable_area_info.obstacles = utils::static_obstacle_avoidance::generateObstaclePolygonsForDrivableArea( - clip_objects, parameters_, planner_data_->parameters.vehicle_width / 2.0); - } else { - current_drivable_area_info.obstacles.clear(); + clip_objects_, parameters_, planner_data_->parameters.vehicle_width / 2.0); } output.drivable_area_info = utils::combineDrivableAreaInfo( @@ -1078,7 +1074,7 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::planWaitingApproval() void StaticObstacleAvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) { - if (parameters_->disable_path_update) { + if (parameters_->path_generation_method == "optimization_base") { return; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 05561318039b7..70de9e9499917 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1690,6 +1690,59 @@ void compensateDetectionLost( } } +void updateClipObject(ObjectDataArray & clip_objects, AvoidancePlanningData & data) +{ + std::for_each(data.target_objects.begin(), data.target_objects.end(), [](auto & o) { + if (o.is_avoidable) { + o.is_clip_target = true; + } + }); + + const auto itr = + std::remove_if(clip_objects.begin(), clip_objects.end(), [&data](const auto & clip_object) { + const auto id = clip_object.object.object_id; + + // update target objects + { + const auto same_id_obj = std::find_if( + data.target_objects.begin(), data.target_objects.end(), + [&id](const auto & o) { return o.object.object_id == id; }); + if (same_id_obj != data.target_objects.end()) { + same_id_obj->is_clip_target = true; + return false; + } + } + + // update other objects + { + const auto same_id_obj = std::find_if( + data.other_objects.begin(), data.other_objects.end(), + [&id](const auto & o) { return o.object.object_id == id; }); + if (same_id_obj != data.other_objects.end()) { + same_id_obj->is_clip_target = true; + return false; + } + } + + return true; + }); + + clip_objects.erase(itr, clip_objects.end()); + + for (const auto & object : data.target_objects) { + const auto id = object.object.object_id; + const auto same_id_obj = std::find_if( + clip_objects.begin(), clip_objects.end(), + [&id](const auto & o) { return o.object.object_id == id; }); + + if (same_id_obj != clip_objects.end()) { + continue; + } + + clip_objects.push_back(object); + } +} + void updateRoadShoulderDistance( AvoidancePlanningData & data, const std::shared_ptr & planner_data, const std::shared_ptr & parameters) From e12cf5b7568e9868714404d087e2d4848dc6cff1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 26 Jun 2024 09:45:01 +0900 Subject: [PATCH 005/151] fix(static_obstacle_avoidance): fix json schema (#7692) Signed-off-by: satoshi-ota --- .../schema/static_obstacle_avoidance.schema.json | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index e24077e1ecf11..1e0753a288a28 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -17,6 +17,7 @@ "default": "4.0" }, "path_generation_method": { + "type": "string", "enum": ["shift_line_base", "optimization_base", "both"], "description": "Path generation method.", "default": "shift_line_base" From dfd2815980cb95d16bc42999dde2b8c7833f9703 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 27 Jun 2024 12:47:28 +0900 Subject: [PATCH 006/151] refactor(static_obstacle_avoidance): organize params for drivable lane (#7715) * refactor(static_obstacle_avoidance): organize params for drivable lane Signed-off-by: satoshi-ota * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json --------- Signed-off-by: satoshi-ota --- .../README.md | 38 +++++++++++-------- .../static_obstacle_avoidance.param.yaml | 8 +++- .../data_structs.hpp | 8 +--- .../parameter_helper.hpp | 3 +- .../static_obstacle_avoidance.schema.json | 17 +++------ .../src/utils.cpp | 12 +++--- 6 files changed, 45 insertions(+), 41 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index b27723ab2066f..ec139b9a8b099 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -760,7 +760,7 @@ Basically, this module tries to generate avoidance path in order to keep lateral But if there isn't enough space to keep `soft_margin` distance, this module shortens soft constraint lateral margin. The parameter `soft_margin` is a maximum value of soft constraint, and actual soft margin can be a value between 0.0 and `soft_margin`. On the other hand, this module definitely keeps `hard_margin` or `hard_margin_for_parked_vehicle` depending on the situation. Thus, the minimum value of total lateral margin is `hard_margin`/`hard_margin_for_parked_vehicle`, and the maximum value is the sum of `hard_margin`/`hard_margin_for_parked_vehicle` and `soft_margin`. -Following figure shows the situation where this module shortens lateral soft constraint in order not to drive opposite direction lane when user set a parameter `use_opposite_lane` to `false`. +Following figure shows the situation where this module shortens lateral soft constraint in order not to drive opposite direction lane when user set a parameter `use_lane_type` to `same_direction_lane`. ![fig](./images/path_generation/adjust_margin.png) @@ -784,7 +784,7 @@ On the other hand, if the lateral distance is larger than `hard_margin`/`hard_ma ### When there is not enough space -This module inserts stop point only when the ego can potentially avoid the object. So, if it is not able to keep distance more than `hard_margin`/`hard_margin_for_parked_vehicle`, this module does nothing. Following figure shows the situation where this module is not able to keep enough lateral distance when user set a parameter `use_opposite_lane` to `false`. +This module inserts stop point only when the ego can potentially avoid the object. So, if it is not able to keep distance more than `hard_margin`/`hard_margin_for_parked_vehicle`, this module does nothing. Following figure shows the situation where this module is not able to keep enough lateral distance when user set a parameter `use_lane_type` to `same_direction_lane`. ![fig](./images/path_generation/do_nothing.png) @@ -804,15 +804,19 @@ Usable lane for avoidance module can be selected by config file. ```yaml ... - use_adjacent_lane: true - use_opposite_lane: true + # drivable lane setting. this module is able to use not only current lane but also right/left lane + # if the current lane(=lanelt::Lanelet) and the rignt/left lane share the boundary(=lanelet::Linestring) in HDMap. + # "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object. + # "same_direction_lane" : this module uses same direction lane to avoid object if need. + # "opposite_direction_lane": this module uses both same direction and opposite direction lane. + use_lane_type: "opposite_direction_lane" ``` -When user set parameter both `use_adjacent_lane` and `use_opposite_lane` to `true`, it is possible to use opposite lane. +When user set parameter `use_lane_type` to `opposite_direction_lane`, it is possible to use opposite lane. ![fig](./images/path_generation/opposite_direction.png) -When user only set parameter `use_adjacent_lane` to `true`, the module doesn't create path that overlaps opposite lane. +When user set parameter `use_lane_type` to `same_direction_lane`, the module doesn't create path that overlaps opposite lane. ![fig](./images/path_generation/same_direction.png) @@ -972,21 +976,25 @@ This module supports drivable area expansion for following polygons defined in H Please set the flags to `true` when user wants to make it possible to use those areas in avoidance maneuver. ```yaml +# drivable lane setting. this module is able to use not only current lane but also right/left lane +# if the current lane(=lanelt::Lanelet) and the rignt/left lane share the boundary(=lanelet::Linestring) in HDMap. +# "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object. +# "same_direction_lane" : this module uses same direction lane to avoid object if need. +# "opposite_direction_lane": this module uses both same direction and opposite direction lane. +use_lane_type: "opposite_direction_lane" # drivable area setting -use_adjacent_lane: true -use_opposite_lane: true use_intersection_areas: true use_hatched_road_markings: true use_freespace_areas: true ``` -| | | | -| --------------------- | ---------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| adjacent lane | ![fig](./images/advanced/avoidance_same_direction.png) | | -| opposite lane | ![fig](./images/advanced/avoidance_opposite_direction.png) | | -| intersection area | ![fig](./images/advanced/avoidance_intersection.png) | The intersection area is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) | -| hatched road markings | ![fig](./images/advanced/avoidance_zebra.png) | The hatched road marking is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#hatched-road-markings-area) | -| freespace area | ![fig](./images/advanced/avoidance_freespace.png) | The freespace area is defined on Lanelet map. (unstable) | +| | | | +| -------------------------------------- | ---------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| use_lane_type: same_direction_lane | ![fig](./images/advanced/avoidance_same_direction.png) | | +| use_lane_type: opposite_direction_lane | ![fig](./images/advanced/avoidance_opposite_direction.png) | | +| intersection area | ![fig](./images/advanced/avoidance_intersection.png) | The intersection area is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) | +| hatched road markings | ![fig](./images/advanced/avoidance_zebra.png) | The hatched road marking is defined on Lanelet map. See [here](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#hatched-road-markings-area) | +| freespace area | ![fig](./images/advanced/avoidance_freespace.png) | The freespace area is defined on Lanelet map. (unstable) | ## Future extensions / Unimplemented parts diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 80d2128bf70e0..3087ccc93934b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -5,9 +5,13 @@ resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER resample_interval_for_output: 4.0 # [m] FOR DEVELOPER + # drivable lane setting. this module is able to use not only current lane but also right/left lane + # if the current lane(=lanelet::Lanelet) and the right/left lane share the boundary(=lanelet::Linestring) in HDMap. + # "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object. + # "same_direction_lane" : this module uses same direction lane to avoid object if need. + # "opposite_direction_lane": this module uses both same direction and opposite direction lane. + use_lane_type: "opposite_direction_lane" # drivable area setting - use_adjacent_lane: true - use_opposite_lane: true use_intersection_areas: true use_hatched_road_markings: true use_freespace_areas: true diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index dbedbfe1f70cc..d02b39047e71c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -101,12 +101,8 @@ struct AvoidanceParameters // computational cost for latter modules. double resample_interval_for_output = 3.0; - // enable avoidance to be perform only in lane with same direction - bool use_adjacent_lane{true}; - - // enable avoidance to be perform in opposite lane direction - // to use this, enable_avoidance_over_same_direction need to be set to true. - bool use_opposite_lane{true}; + // drivable lane config + std::string use_lane_type{"current_lane"}; // if this param is true, it reverts avoidance path when the path is no longer needed. bool enable_cancel_maneuver{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index a79a67d5fdd4a..84cf7c4e33d26 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -46,8 +46,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node) // drivable area { const std::string ns = "avoidance."; - p.use_adjacent_lane = getOrDeclareParameter(*node, ns + "use_adjacent_lane"); - p.use_opposite_lane = getOrDeclareParameter(*node, ns + "use_opposite_lane"); + p.use_lane_type = getOrDeclareParameter(*node, ns + "use_lane_type"); p.use_intersection_areas = getOrDeclareParameter(*node, ns + "use_intersection_areas"); p.use_hatched_road_markings = getOrDeclareParameter(*node, ns + "use_hatched_road_markings"); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index 1e0753a288a28..db3215fa8d238 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -22,15 +22,11 @@ "description": "Path generation method.", "default": "shift_line_base" }, - "use_adjacent_lane": { - "type": "boolean", - "description": "Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane.", - "default": "true" - }, - "use_opposite_lane": { - "type": "boolean", - "description": "Extend avoidance trajectory to opposite direction lane. `use_adjacent_lane` must be `true` to take effects.", - "default": "true" + "use_lane_type": { + "type": "string", + "enum": ["current_lane", "same_direction_lane", "opposite_direction_lane"], + "description": "Drivable lane configuration.", + "default": "opposite_direction_lane" }, "use_hatched_road_markings": { "type": "boolean", @@ -1447,8 +1443,7 @@ "resample_interval_for_planning", "resample_interval_for_output", "path_generation_method", - "use_adjacent_lane", - "use_opposite_lane", + "use_lane_type", "use_hatched_road_markings", "use_intersection_areas", "use_freespace_areas", diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 70de9e9499917..8d0f9904b5bad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -2238,14 +2238,16 @@ DrivableLanes generateExpandedDrivableLanes( current_drivable_lanes.left_lane = lanelet; current_drivable_lanes.right_lane = lanelet; - if (!parameters->use_adjacent_lane) { + if (parameters->use_lane_type == "current_lane") { return current_drivable_lanes; } + const auto use_opposite_lane = parameters->use_lane_type == "opposite_direction_lane"; + // 1. get left/right side lanes const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) { - const auto all_left_lanelets = route_handler->getAllLeftSharedLinestringLanelets( - target_lane, parameters->use_opposite_lane, true); + const auto all_left_lanelets = + route_handler->getAllLeftSharedLinestringLanelets(target_lane, use_opposite_lane, true); if (!all_left_lanelets.empty()) { current_drivable_lanes.left_lane = all_left_lanelets.back(); // leftmost lanelet pushUniqueVector( @@ -2254,8 +2256,8 @@ DrivableLanes generateExpandedDrivableLanes( } }; const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) { - const auto all_right_lanelets = route_handler->getAllRightSharedLinestringLanelets( - target_lane, parameters->use_opposite_lane, true); + const auto all_right_lanelets = + route_handler->getAllRightSharedLinestringLanelets(target_lane, use_opposite_lane, true); if (!all_right_lanelets.empty()) { current_drivable_lanes.right_lane = all_right_lanelets.back(); // rightmost lanelet pushUniqueVector( From 79728ef2bd2a2802eb7eae870408524214409062 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 4 Jul 2024 16:48:46 +0900 Subject: [PATCH 007/151] feat(safety_check): filter safety check targe objects by yaw deviation between pose and lane (#7828) * fix(safety_check): filter by yaw deviation to check object belongs to lane Signed-off-by: satoshi-ota * fix(static_obstacle_avoidance): check yaw only when the object is moving Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 4 +- .../src/util.cpp | 4 +- .../path_safety_checker/objects_filtering.hpp | 18 ++++++-- .../path_safety_checker/objects_filtering.cpp | 43 +++++++++++++++---- .../pull_out_planner_base.hpp | 5 ++- .../src/start_planner_module.cpp | 5 ++- .../src/utils.cpp | 34 +++++++++------ 7 files changed, 80 insertions(+), 33 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp index a19cbda6ccad7..7571a1f61d1c1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -152,8 +152,8 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( const auto [object_within_target_lane, object_outside_target_lane] = utils::path_safety_checker::separateObjectsByLanelets( *planner_data_->dynamic_object, data.current_lanelets, - [](const auto & obj, const auto & lane) { - return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + [](const auto & obj, const auto & lane, const auto yaw_threshold) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane, yaw_threshold); }); // Assume that the maximum allocation for data.other object is the sum of diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index 99bef9c243508..4526c584afd12 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -145,8 +145,8 @@ PredictedObjects extractObjectsInExpandedPullOverLanes( route_handler, left_side, backward_distance, forward_distance, bound_offset); const auto [objects_in_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( - objects, lanes, [](const auto & obj, const auto & lanelet) { - return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lanelet); + objects, lanes, [](const auto & obj, const auto & lanelet, const auto yaw_threshold) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lanelet, yaw_threshold); }); return objects_in_lanes; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index 4fd6fce325f49..f73f989174b54 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -56,18 +56,24 @@ using tier4_planning_msgs::msg::PathPointWithLaneId; * * @param objects The predicted objects to filter. * @param lanelet + * @param yaw_threshold * @return result. */ -bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet); +bool isCentroidWithinLanelet( + const PredictedObject & object, const lanelet::ConstLanelet & lanelet, + const double yaw_threshold); /** * @brief Filters objects based on object polygon overlapping with lanelet. * * @param objects The predicted objects to filter. * @param lanelet + * @param yaw_threshold * @return result. */ -bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet); +bool isPolygonOverlapLanelet( + const PredictedObject & object, const lanelet::ConstLanelet & lanelet, + const double yaw_threshold); bool isPolygonOverlapLanelet( const PredictedObject & object, const autoware::universe_utils::Polygon2d & lanelet_polygon); @@ -168,7 +174,9 @@ void filterObjectsByClass( */ std::pair, std::vector> separateObjectIndicesByLanelets( const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets, - const std::function & condition); + const std::function & + condition, + const double yaw_threshold = M_PI); /** * @brief Separate the objects into two part based on whether the object is within lanelet. @@ -176,7 +184,9 @@ std::pair, std::vector> separateObjectIndicesByLanel */ std::pair separateObjectsByLanelets( const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets, - const std::function & condition); + const std::function & + condition, + const double yaw_threshold = M_PI); /** * @brief Get the predicted path from an object. diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 469be03eb905c..95a498b7b8475 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -57,15 +57,34 @@ bool is_within_circle( namespace autoware::behavior_path_planner::utils::path_safety_checker { -bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet) +bool isCentroidWithinLanelet( + const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold) { - const auto & object_pos = object.kinematics.initial_pose_with_covariance.pose.position; - lanelet::BasicPoint2d object_centroid(object_pos.x, object_pos.y); - return boost::geometry::within(object_centroid, lanelet.polygon2d().basicPolygon()); + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; + const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position); + if ( + std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) > + yaw_threshold) { + return false; + } + + return boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pose.position)) + .basicPoint(), + lanelet.polygon2d().basicPolygon()); } -bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet) +bool isPolygonOverlapLanelet( + const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold) { + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; + const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position); + if ( + std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) > + yaw_threshold) { + return false; + } + const auto lanelet_polygon = utils::toPolygon2d(lanelet); return isPolygonOverlapLanelet(object, lanelet_polygon); } @@ -174,7 +193,9 @@ void filterObjectsByClass( std::pair, std::vector> separateObjectIndicesByLanelets( const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets, - const std::function & condition) + const std::function & + condition, + const double yaw_threshold) { if (target_lanelets.empty()) { return {}; @@ -184,7 +205,9 @@ std::pair, std::vector> separateObjectIndicesByLanel std::vector other_indices; for (size_t i = 0; i < objects.objects.size(); i++) { - const auto filter = [&](const auto & llt) { return condition(objects.objects.at(i), llt); }; + const auto filter = [&](const auto & llt) { + return condition(objects.objects.at(i), llt, yaw_threshold); + }; const auto found = std::find_if(target_lanelets.begin(), target_lanelets.end(), filter); if (found != target_lanelets.end()) { target_indices.push_back(i); @@ -198,13 +221,15 @@ std::pair, std::vector> separateObjectIndicesByLanel std::pair separateObjectsByLanelets( const PredictedObjects & objects, const lanelet::ConstLanelets & target_lanelets, - const std::function & condition) + const std::function & + condition, + const double yaw_threshold) { PredictedObjects target_objects; PredictedObjects other_objects; const auto [target_indices, other_indices] = - separateObjectIndicesByLanelets(objects, target_lanelets, condition); + separateObjectIndicesByLanelets(objects, target_lanelets, condition, yaw_threshold); target_objects.objects.reserve(target_indices.size()); other_objects.objects.reserve(other_indices.size()); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp index 7b30745057743..03b6e13cb2d3e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -74,8 +74,9 @@ class PullOutPlannerBase *dynamic_objects, parameters_.th_moving_object_velocity); auto [pull_out_lane_stop_objects, others] = utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, [](const auto & obj, const auto & lane) { - return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + stop_objects, pull_out_lanes, + [](const auto & obj, const auto & lane, const auto yaw_threshold) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane, yaw_threshold); }); utils::path_safety_checker::filterObjectsByClass( pull_out_lane_stop_objects, parameters_.object_types_to_check_for_path_generation); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 86e35aa52095a..2d9fbf7355415 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1221,8 +1221,9 @@ PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( // filter for objects located in pull out lanes and moving at a speed below the threshold auto [stop_objects_in_pull_out_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, [](const auto & obj, const auto & lane) { - return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + stop_objects, pull_out_lanes, + [](const auto & obj, const auto & lane, const auto yaw_threshold) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane, yaw_threshold); }); const auto path = planner_data_->route_handler->getCenterLinePath( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 8d0f9904b5bad..b46acea4c30b8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -2064,21 +2064,35 @@ std::vector getSafetyCheckTargetObjects( return {}; } + const auto is_moving = [¶meters](const auto & object) { + const auto & object_twist = object.kinematics.initial_twist_with_covariance.twist; + const auto object_vel_norm = std::hypot(object_twist.linear.x, object_twist.linear.y); + const auto object_parameter = + parameters->object_parameters.at(utils::getHighestProbLabel(object.classification)); + return object_vel_norm > object_parameter.moving_speed_threshold; + }; + + const auto filter = + [&is_moving](const auto & object, const auto & lanelet, [[maybe_unused]] const auto unused) { + // filter by yaw deviation only when the object is moving because the head direction is not + // reliable while object is stopping. + const auto yaw_threshold = is_moving(object) ? M_PI_2 : M_PI; + return utils::path_safety_checker::isCentroidWithinLanelet(object, lanelet, yaw_threshold); + }; + // check right lanes if (check_right_lanes) { const auto check_lanes = getAdjacentLane(closest_lanelet, planner_data, p, true); if (p->check_other_object) { const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets( - to_predicted_objects(data.other_objects), check_lanes, - utils::path_safety_checker::isCentroidWithinLanelet); + to_predicted_objects(data.other_objects), check_lanes, filter); append(targets); } if (p->check_unavoidable_object) { const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets( - to_predicted_objects(unavoidable_objects), check_lanes, - utils::path_safety_checker::isCentroidWithinLanelet); + to_predicted_objects(unavoidable_objects), check_lanes, filter); append(targets); } @@ -2092,15 +2106,13 @@ std::vector getSafetyCheckTargetObjects( if (p->check_other_object) { const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets( - to_predicted_objects(data.other_objects), check_lanes, - utils::path_safety_checker::isCentroidWithinLanelet); + to_predicted_objects(data.other_objects), check_lanes, filter); append(targets); } if (p->check_unavoidable_object) { const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets( - to_predicted_objects(unavoidable_objects), check_lanes, - utils::path_safety_checker::isCentroidWithinLanelet); + to_predicted_objects(unavoidable_objects), check_lanes, filter); append(targets); } @@ -2114,15 +2126,13 @@ std::vector getSafetyCheckTargetObjects( if (p->check_other_object) { const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets( - to_predicted_objects(data.other_objects), check_lanes, - utils::path_safety_checker::isCentroidWithinLanelet); + to_predicted_objects(data.other_objects), check_lanes, filter); append(targets); } if (p->check_unavoidable_object) { const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets( - to_predicted_objects(unavoidable_objects), check_lanes, - utils::path_safety_checker::isCentroidWithinLanelet); + to_predicted_objects(unavoidable_objects), check_lanes, filter); append(targets); } From 56025132b1c3d21757b87b83089a3819d9f8dbd5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 4 Jul 2024 17:07:23 +0900 Subject: [PATCH 008/151] fix(static_obstacle_avoidance): fix issues in target object filtering logic (#7830) * fix(static_obstacle_avoidance): check if object is inside/outside by its position point instead of its polygon Signed-off-by: satoshi-ota * refactor(static_obstacle_avoidance): add getter functions Signed-off-by: satoshi-ota * fix(static_obstacle_avoidance): check next lane without route if the current lane is not preferred Signed-off-by: satoshi-ota * fix(static_obstacle_avoidance): fix parked vehicle check Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../data_structs.hpp | 4 + .../src/debug.cpp | 10 +-- .../src/shift_line_generator.cpp | 16 ++-- .../src/utils.cpp | 84 ++++++++++--------- 4 files changed, 59 insertions(+), 55 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index d02b39047e71c..49599004e0952 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -352,6 +352,10 @@ struct ObjectData // avoidance target { } + Pose getPose() const { return object.kinematics.initial_pose_with_covariance.pose; } + + Point getPosition() const { return object.kinematics.initial_pose_with_covariance.pose.position; } + PredictedObject object; // object behavior. diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 05bf1abf620c9..e9838eb4a2cfc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -64,7 +64,7 @@ MarkerArray createObjectsCubeMarkerArray( } marker.id = uuidToInt32(object.object.object_id); - marker.pose = object.object.kinematics.initial_pose_with_covariance.pose; + marker.pose = object.getPose(); msg.markers.push_back(marker); } @@ -80,10 +80,8 @@ MarkerArray createObjectPolygonMarkerArray(const ObjectDataArray & objects, std: "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, 0L, Marker::LINE_STRIP, createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - const auto pos = object.object.kinematics.initial_pose_with_covariance.pose.position; - for (const auto & p : object.envelope_poly.outer()) { - marker.points.push_back(createPoint(p.x(), p.y(), pos.z)); + marker.points.push_back(createPoint(p.x(), p.y(), object.getPosition().z)); } marker.points.push_back(marker.points.front()); @@ -142,7 +140,7 @@ MarkerArray createObjectInfoMarkerArray( for (const auto & object : objects) { if (verbose) { marker.id = uuidToInt32(object.object.object_id); - marker.pose = object.object.kinematics.initial_pose_with_covariance.pose; + marker.pose = object.getPose(); std::ostringstream string_stream; string_stream << std::fixed << std::setprecision(2) << std::boolalpha; string_stream << "ratio:" << object.shiftable_ratio << " [-]\n" @@ -162,7 +160,7 @@ MarkerArray createObjectInfoMarkerArray( { marker.id = uuidToInt32(object.object.object_id); - marker.pose = object.object.kinematics.initial_pose_with_covariance.pose; + marker.pose = object.getPose(); marker.pose.position.z += 2.0; std::ostringstream string_stream; string_stream << magic_enum::enum_name(object.info) << (object.is_parked ? "(PARKED)" : ""); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index a171ae9161041..c3a67eb074d73 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -165,9 +165,9 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( } // the avoidance path is already approved - const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; - const auto is_approved = (helper_->getShift(object_pos) > 0.0 && is_object_on_right) || - (helper_->getShift(object_pos) < 0.0 && !is_object_on_right); + const auto is_approved = + (helper_->getShift(object.getPosition()) > 0.0 && is_object_on_right) || + (helper_->getShift(object.getPosition()) < 0.0 && !is_object_on_right); if (is_approved) { return std::make_pair(desire_shift_length, avoidance_distance); } @@ -363,9 +363,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( if (is_return_shift_to_goal) { return true; } - const auto & object_pos = o.object.kinematics.initial_pose_with_covariance.pose.position; const bool has_object_near_goal = - autoware::universe_utils::calcDistance2d(goal_pose.position, object_pos) < + autoware::universe_utils::calcDistance2d(goal_pose.position, o.getPosition()) < parameters_->object_check_goal_distance; return has_object_near_goal; }(); @@ -1027,8 +1026,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( const auto has_object_near_goal = std::any_of(data.target_objects.begin(), data.target_objects.end(), [&](const auto & o) { return autoware::universe_utils::calcDistance2d( - data_->route_handler->getGoalPose().position, - o.object.kinematics.initial_pose_with_covariance.pose.position) < + data_->route_handler->getGoalPose().position, o.getPosition()) < parameters_->object_check_goal_distance; }); if (has_object_near_goal) { @@ -1097,9 +1095,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( if (utils::isAllowedGoalModification(data_->route_handler)) { const bool has_last_shift_near_goal = std::any_of(data.target_objects.begin(), data.target_objects.end(), [&](const auto & o) { - return autoware::universe_utils::calcDistance2d( - last_sl.end.position, - o.object.kinematics.initial_pose_with_covariance.pose.position) < + return autoware::universe_utils::calcDistance2d(last_sl.end.position, o.getPosition()) < parameters_->object_check_goal_distance; }); if (has_last_shift_near_goal) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index b46acea4c30b8..f14c8bcd4d83f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -293,8 +293,7 @@ bool isWithinCrosswalk( { using Point = boost::geometry::model::d2::point_xy; - const auto & p = object.object.kinematics.initial_pose_with_covariance.pose.position; - const Point p_object{p.x, p.y}; + const Point p_object{object.getPosition().x, object.getPosition().y}; // get conflicting crosswalk crosswalk constexpr int PEDESTRIAN_GRAPH_ID = 1; @@ -335,14 +334,16 @@ bool isWithinIntersection( route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(area_id.c_str())); return boost::geometry::within( - object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon()))); + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint(), + lanelet::utils::to2D(polygon.basicPolygon())); } bool isOnEgoLane(const ObjectData & object, const std::shared_ptr & route_handler) { - const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; if (boost::geometry::within( - lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint(), object.overhang_lanelet.polygon2d().basicPolygon())) { return true; } @@ -351,7 +352,8 @@ bool isOnEgoLane(const ObjectData & object, const std::shared_ptr lanelet::ConstLanelets prev_lanelet; if (route_handler->getPreviousLaneletsWithinRoute(object.overhang_lanelet, &prev_lanelet)) { if (boost::geometry::within( - lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint(), prev_lanelet.front().polygon2d().basicPolygon())) { return true; } @@ -361,10 +363,20 @@ bool isOnEgoLane(const ObjectData & object, const std::shared_ptr lanelet::ConstLanelet next_lanelet; if (route_handler->getNextLaneletWithinRoute(object.overhang_lanelet, &next_lanelet)) { if (boost::geometry::within( - lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint(), next_lanelet.polygon2d().basicPolygon())) { return true; } + } else { + for (const auto & lane : route_handler->getNextLanelets(object.overhang_lanelet)) { + if (boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint(), + lane.polygon2d().basicPolygon())) { + return true; + } + } } return false; @@ -372,20 +384,18 @@ bool isOnEgoLane(const ObjectData & object, const std::shared_ptr bool isParallelToEgoLane(const ObjectData & object, const double threshold) { - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; const auto closest_pose = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); - const auto yaw_deviation = std::abs(calcYawDeviation(closest_pose, object_pose)); + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object.getPosition()); + const auto yaw_deviation = std::abs(calcYawDeviation(closest_pose, object.getPose())); return yaw_deviation < threshold || yaw_deviation > M_PI - threshold; } bool isMergingToEgoLane(const ObjectData & object) { - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; const auto closest_pose = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); - const auto yaw_deviation = calcYawDeviation(closest_pose, object_pose); + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object.getPosition()); + const auto yaw_deviation = calcYawDeviation(closest_pose, object.getPose()); if (isOnRight(object)) { if (yaw_deviation < 0.0 && -1.0 * M_PI_2 < yaw_deviation) { @@ -422,9 +432,8 @@ bool isParkedVehicle( return false; } - const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; const auto centerline_pos = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pos).position; + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object.getPosition()).position; bool is_left_side_parked_vehicle = false; if (!isOnRight(object)) { @@ -442,7 +451,8 @@ bool isParkedVehicle( return same_direction_lane; } - return static_cast(opposite_lanes.front().invert()); + return static_cast( + route_handler->getMostRightLanelet(opposite_lanes.front()).invert()); }(); const auto center_to_left_boundary = distance2d( @@ -457,7 +467,7 @@ bool isParkedVehicle( if (sub_type == "road_shoulder") { // assuming it's parked vehicle if its CoG is within road shoulder lanelet. if (boost::geometry::within( - to2D(toLaneletPoint(object_pos)).basicPoint(), + to2D(toLaneletPoint(object.getPosition())).basicPoint(), most_left_lanelet.polygon2d().basicPolygon())) { return true; } @@ -468,7 +478,7 @@ bool isParkedVehicle( const auto arc_coordinates = toArcCoordinates( to2D(object.overhang_lanelet.centerline().basicLineString()), - to2D(toLaneletPoint(object_pos)).basicPoint()); + to2D(toLaneletPoint(object.getPosition())).basicPoint()); object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance; is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio; @@ -490,7 +500,8 @@ bool isParkedVehicle( return same_direction_lane; } - return static_cast(opposite_lanes.front().invert()); + return static_cast( + route_handler->getMostLeftLanelet(opposite_lanes.front()).invert()); }(); const auto center_to_right_boundary = distance2d( @@ -505,7 +516,7 @@ bool isParkedVehicle( if (sub_type == "road_shoulder") { // assuming it's parked vehicle if its CoG is within road shoulder lanelet. if (boost::geometry::within( - to2D(toLaneletPoint(object_pos)).basicPoint(), + to2D(toLaneletPoint(object.getPosition())).basicPoint(), most_right_lanelet.polygon2d().basicPolygon())) { return true; } @@ -516,7 +527,7 @@ bool isParkedVehicle( const auto arc_coordinates = toArcCoordinates( to2D(object.overhang_lanelet.centerline().basicLineString()), - to2D(toLaneletPoint(object_pos)).basicPoint()); + to2D(toLaneletPoint(object.getPosition())).basicPoint()); object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance; is_right_side_parked_vehicle = @@ -527,9 +538,8 @@ bool isParkedVehicle( return false; } - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; object.to_centerline = - lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; + lanelet::utils::getArcCoordinates(data.current_lanelets, object.getPose()).distance; if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { return false; } @@ -544,13 +554,13 @@ bool isCloseToStopFactor( { const auto & rh = planner_data->route_handler; const auto & ego_pose = planner_data->self_odometry->pose.pose; - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; // force avoidance for stopped vehicle bool is_close_to_stop_factor = false; // check traffic light - const auto to_traffic_light = getDistanceToNextTrafficLight(object_pose, data.extend_lanelets); + const auto to_traffic_light = + getDistanceToNextTrafficLight(object.getPose(), data.extend_lanelets); { is_close_to_stop_factor = to_traffic_light < parameters->object_ignore_section_traffic_light_in_front_distance; @@ -792,9 +802,8 @@ bool isSatisfiedWithNonVehicleCondition( } // Object is on center line -> ignore. - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; object.to_centerline = - lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; + lanelet::utils::getArcCoordinates(data.current_lanelets, object.getPose()).distance; if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { object.info = ObjectInfo::TOO_NEAR_TO_CENTERLINE; return false; @@ -844,9 +853,8 @@ bool isSatisfiedWithVehicleCondition( return false; } - const auto & current_pose = object.object.kinematics.initial_pose_with_covariance.pose; const auto is_moving_distance_longer_than_threshold = - calcDistance2d(object.init_pose, current_pose) > + calcDistance2d(object.init_pose, object.getPose()) > parameters->distance_threshold_for_ambiguous_vehicle; if (is_moving_distance_longer_than_threshold) { object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; @@ -944,9 +952,8 @@ double getRoadShoulderDistance( using autoware::universe_utils::Point2d; using lanelet::utils::to2D; - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = - autoware::motion_utils::findNearestIndex(data.reference_path.points, object_pose.position); + autoware::motion_utils::findNearestIndex(data.reference_path.points, object.getPosition()); const auto object_closest_pose = data.reference_path.points.at(object_closest_index).point.pose; const auto rh = planner_data->route_handler; @@ -957,7 +964,7 @@ double getRoadShoulderDistance( std::vector> intersects; for (const auto & p1 : object.overhang_points) { const auto centerline_pose = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pose.position); + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object.getPosition()); const auto p_tmp = geometry_msgs::build().position(p1.second).orientation(centerline_pose.orientation); @@ -1326,8 +1333,7 @@ std::vector generateObstaclePolygonsForDrivableArea( object.avoid_margin.value() - object_parameter.envelope_buffer_margin - vehicle_width / 2.0; const auto obj_poly = autoware::universe_utils::expandPolygon(object.envelope_poly, diff_poly_buffer); - obstacles_for_drivable_area.push_back( - {object.object.kinematics.initial_pose_with_covariance.pose, obj_poly, !isOnRight(object)}); + obstacles_for_drivable_area.push_back({object.getPose(), obj_poly, !isOnRight(object)}); } return obstacles_for_drivable_area; } @@ -1495,7 +1501,7 @@ void fillObjectMovingTime( object_data.last_stop = now; object_data.move_time = 0.0; if (is_new_object) { - object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; + object_data.init_pose = object_data.getPose(); object_data.stop_time = 0.0; object_data.last_move = now; stopped_objects.push_back(object_data); @@ -1510,7 +1516,7 @@ void fillObjectMovingTime( } if (is_new_object) { - object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; + object_data.init_pose = object_data.getPose(); object_data.move_time = std::numeric_limits::infinity(); object_data.stop_time = 0.0; object_data.last_move = now; @@ -1520,7 +1526,7 @@ void fillObjectMovingTime( object_data.last_stop = same_id_obj->last_stop; object_data.move_time = (now - same_id_obj->last_stop).seconds(); object_data.stop_time = 0.0; - object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; + object_data.init_pose = object_data.getPose(); if (object_data.move_time > object_parameter.moving_time_threshold) { stopped_objects.erase(same_id_obj); @@ -1617,9 +1623,9 @@ void updateRegisteredObject( } constexpr auto POS_THR = 1.5; - const auto r_pos = registered_object.object.kinematics.initial_pose_with_covariance.pose; + const auto r_pos = registered_object.getPose(); const auto similar_pos_obj = std::find_if(n.begin(), n.end(), [&](const auto & o) { - return calcDistance2d(r_pos, o.object.kinematics.initial_pose_with_covariance.pose) < POS_THR; + return calcDistance2d(r_pos, o.getPose()) < POS_THR; }); // same id object is not detected, but object is found around registered. update registered. From 9029ac5e6bdc7ed89071c9cc652198e3870716c0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 5 Jul 2024 12:49:24 +0900 Subject: [PATCH 009/151] fix(static_obstacle_avoidance): ignore pedestrian/cyclist who is not on road edge (#7850) * fix(static_obstacle_avoidance): ignore pedestrian/cyclist who is not on road edge Signed-off-by: satoshi-ota * docs(static_obstacle_avoidance): update flowchart Signed-off-by: satoshi-ota * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md Co-authored-by: Go Sakayori --------- Signed-off-by: satoshi-ota Co-authored-by: Go Sakayori --- .../README.md | 21 ++++++++++ .../src/utils.cpp | 41 +++++++++++++++++++ 2 files changed, 62 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index ec139b9a8b099..ddd0d473d2cbf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -659,6 +659,27 @@ if(isWithinCrosswalk()) then (yes) stop else (\n no) endif + +if(is object within intersection?) then (yes) +#00FFB1 :return false; +stop +else (\n no) +endif + +if(is object on right side of the ego path?) then (yes) +if(are there adjacent lanes on right side of ego lane?) then (yes) +#00FFB1 :return false; +stop +else (\n no) +endif +else (\n no) +if(are there adjacent lanes on left side of ego lane?) then (yes) +#00FFB1 :return false; +stop +else (\n no) +endif +endif + #FF006C :return true; stop } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index f14c8bcd4d83f..016972dccb38e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -809,6 +809,45 @@ bool isSatisfiedWithNonVehicleCondition( return false; } + if (object.is_within_intersection) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "object is within intersection. don't have to avoid it."); + return false; + } + + const auto right_lane = + planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, true); + if (right_lane.has_value() && isOnRight(object)) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return false; + } + + const auto left_lane = + planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, true); + if (left_lane.has_value() && !isOnRight(object)) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return false; + } + + const auto right_opposite_lanes = + planner_data->route_handler->getRightOppositeLanelets(object.overhang_lanelet); + if (!right_opposite_lanes.empty() && isOnRight(object)) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return false; + } + + const auto left_opposite_lanes = + planner_data->route_handler->getLeftOppositeLanelets(object.overhang_lanelet); + if (!left_opposite_lanes.empty() && !isOnRight(object)) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return false; + } + return true; } @@ -1840,6 +1879,8 @@ void filterTargetObjects( continue; } } else { + o.is_within_intersection = + filtering_utils::isWithinIntersection(o, planner_data->route_handler); o.is_parked = false; o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters); From 49d0c35e84f91a351386d97839abae9a467de1df Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 9 Jul 2024 16:32:05 +0900 Subject: [PATCH 010/151] fix(multi_object_tracker): fix publish interval adjust timing (#1402) fix(multi_object_tracker): fix publish interval adjust timing (#7904) refactor: optimize publish time check in multi_object_tracker_node.cpp Signed-off-by: Taekjin LEE --- .../multi_object_tracker/src/multi_object_tracker_core.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 54255e706e35a..173cec9489f63 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -221,8 +221,9 @@ void MultiObjectTracker::onTrigger() } else { // Publish if the next publish time is close const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period - if ((current_time - last_published_time_).seconds() > minimum_publish_interval) { - checkAndPublish(current_time); + const rclcpp::Time publish_time = this->now(); + if ((publish_time - last_published_time_).seconds() > minimum_publish_interval) { + checkAndPublish(publish_time); } } } From e7b27956d90f91dae5ca3fbf298cc623044afcb6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 10 Jul 2024 11:31:07 +0900 Subject: [PATCH 011/151] fix(controller): revival of dry steering (#7903) (#1405) * Revert "fix(autoware_mpc_lateral_controller): delete the zero speed constraint (#7673)" This reverts commit 69258bd92cb8a0ff8320df9b2302db72975e027f. * dry steering * add comments * add minor fix and modify unit test for dry steering --------- Signed-off-by: Takayuki Murooka --- .../src/mpc.cpp | 5 +- .../pid_longitudinal_controller.hpp | 2 + .../src/pid_longitudinal_controller.cpp | 63 +++++++++++-------- .../test/test_controller_node.cpp | 27 ++++++-- 4 files changed, 64 insertions(+), 33 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 1f3327bf28f2e..79748f23e7aa0 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -765,10 +765,11 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory( return reference.back(); }; - // when the vehicle is stopped, no steering rate limit. + // When the vehicle is stopped, a large steer rate limit is used for the dry steering. + constexpr double steer_rate_lim = 100.0; const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01; if (is_vehicle_stopped) { - return VectorXd::Zero(m_param.prediction_horizon); + return steer_rate_lim * VectorXd::Ones(m_param.prediction_horizon); } // calculate steering rate limit diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 9291d538b022f..39c75964dbc72 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -233,6 +233,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro // debug values DebugValues m_debug_values; + std::optional m_prev_keep_stopped_condition{std::nullopt}; + std::shared_ptr m_last_running_time{std::make_shared(clock_->now())}; // Diagnostic diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 78c7ccf832514..09f4a90e14898 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -597,21 +597,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity static constexpr double vel_epsilon = 1e-3; - // Let vehicle start after the steering is converged for control accuracy - const bool keep_stopped_condition = std::fabs(current_vel) < vel_epsilon && - m_enable_keep_stopped_until_steer_convergence && - !lateral_sync_data_.is_steer_converged; - if (keep_stopped_condition) { - auto marker = createDefaultMarker( - "map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING, - createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - marker.pose = autoware::universe_utils::calcOffsetPose( - m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang, - m_vehicle_width / 2 + 2.0, 1.5); - marker.text = "steering not\nconverged"; - m_pub_stop_reason_marker->publish(marker); - } - const bool stopping_condition = stop_dist < p.stopping_state_stop_dist; const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel && @@ -670,15 +655,18 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_under_control_starting_time = is_under_control ? std::make_shared(clock_->now()) : nullptr; } + + if (m_control_state != ControlState::STOPPED) { + m_prev_keep_stopped_condition = std::nullopt; + } + // transit state // in DRIVE state if (m_control_state == ControlState::DRIVE) { if (emergency_condition) { return changeState(ControlState::EMERGENCY); } - if (!is_under_control && stopped_condition && keep_stopped_condition) { - // NOTE: When the ego is stopped on manual driving, since the driving state may transit to - // autonomous, keep_stopped_condition should be checked. + if (!is_under_control && stopped_condition) { return changeState(ControlState::STOPPED); } @@ -721,19 +709,42 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // in STOPPED state if (m_control_state == ControlState::STOPPED) { - // -- debug print -- + // debug print if (has_nonzero_target_vel && !departure_condition_from_stopped) { debug_msg_once("target speed > 0, but departure condition is not met. Keep STOPPED."); } - if (has_nonzero_target_vel && keep_stopped_condition) { - debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED."); - } - // --------------- - if (keep_stopped_condition) { - return changeState(ControlState::STOPPED); - } if (departure_condition_from_stopped) { + // Let vehicle start after the steering is converged for dry steering + const bool current_keep_stopped_condition = + std::fabs(current_vel) < vel_epsilon && !lateral_sync_data_.is_steer_converged; + // NOTE: Dry steering is considered unnecessary when the steering is converged twice in a + // row. This is because lateral_sync_data_.is_steer_converged is not the current but + // the previous value due to the order controllers' run and sync functions. + const bool keep_stopped_condition = + !m_prev_keep_stopped_condition || + (current_keep_stopped_condition || *m_prev_keep_stopped_condition); + m_prev_keep_stopped_condition = current_keep_stopped_condition; + if (m_enable_keep_stopped_until_steer_convergence && keep_stopped_condition) { + // debug print + if (has_nonzero_target_vel) { + debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED."); + } + + // publish debug marker + auto marker = createDefaultMarker( + "map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); + marker.pose = autoware::universe_utils::calcOffsetPose( + m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang, + m_vehicle_width / 2 + 2.0, 1.5); + marker.text = "steering not\nconverged"; + m_pub_stop_reason_marker->publish(marker); + + // keep STOPPED + return; + } + m_pid_vel.reset(); m_lpf_vel_error->reset(0.0); // prevent the car from taking a long time to start to move diff --git a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp index e0dc5ede906a9..48ffab52e2b15 100644 --- a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp +++ b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp @@ -589,11 +589,28 @@ TEST_F(FakeNodeFixture, longitudinal_check_steer_converged) traj.points.push_back(make_traj_point(0.0, 0.0, 1.0f)); traj.points.push_back(make_traj_point(50.0, 0.0, 1.0f)); traj.points.push_back(make_traj_point(100.0, 0.0, 1.0f)); - tester.traj_pub->publish(traj); - test_utils::waitForMessage(tester.node, this, tester.received_control_command); + { // Check if the ego can keep stopped when the steering is not converged. + tester.traj_pub->publish(traj); + test_utils::waitForMessage(tester.node, this, tester.received_control_command); - ASSERT_TRUE(tester.received_control_command); - // Keep stopped state when the lateral control is not converged. - EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f); + ASSERT_TRUE(tester.received_control_command); + // Keep stopped state when the lateral control is not converged. + EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f); + } + + { // Check if the ego can keep stopped after the following sequence + // 1. not converged -> 2. converged -> 3. not converged + tester.publish_steer_angle(0.0); + tester.traj_pub->publish(traj); + test_utils::waitForMessage(tester.node, this, tester.received_control_command); + + tester.publish_steer_angle(steering_tire_angle); + tester.traj_pub->publish(traj); + test_utils::waitForMessage(tester.node, this, tester.received_control_command); + + ASSERT_TRUE(tester.received_control_command); + // Keep stopped state when the lateral control is not converged. + EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f); + } } From 65e1d20b68b309954946f9f225d2583fd3d5be87 Mon Sep 17 00:00:00 2001 From: Shohei Sakai Date: Thu, 11 Jul 2024 08:08:39 +0900 Subject: [PATCH 012/151] =?UTF-8?q?fix(multi=5Fobject=5Ftracker):=20calcul?= =?UTF-8?q?ation=20of=20detection=20delay=20diagnostics=E2=80=A6=20(#1406)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit fix(multi_object_tracker): calculation of detection delay diagnostics (#1317) Signed-off-by: Tomohito Ando Co-authored-by: Tomohito ANDO --- perception/multi_object_tracker/src/debugger/debugger.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/multi_object_tracker/src/debugger/debugger.cpp b/perception/multi_object_tracker/src/debugger/debugger.cpp index a3ece17eab112..e692ae76468e4 100644 --- a/perception/multi_object_tracker/src/debugger/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger/debugger.cpp @@ -98,7 +98,7 @@ void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & s stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Measurement time is not set."); return; } - const double & delay = pipeline_latency_ms_; // [s] + const double & delay = pipeline_latency_ms_ / 1e3; // [s] if (delay == 0.0) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); From 8fbaf162cb7d34039d35627b123490214086a81d Mon Sep 17 00:00:00 2001 From: SHtokuda <165623782+shtokuda@users.noreply.github.com> Date: Thu, 11 Jul 2024 11:28:18 +0900 Subject: [PATCH 013/151] fix(autoware_external_cmd_converter): fix check_topic_state (#7921) * fix(autoware_external_cmd_converter): fix check_topic_state Signed-off-by: shtokuda * style(pre-commit): autofix * Update vehicle/autoware_external_cmd_converter/src/node.cpp Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> * style(pre-commit): autofix --------- Signed-off-by: shtokuda Co-authored-by: shtokuda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> --- .../autoware_external_cmd_converter/src/node.cpp | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/vehicle/autoware_external_cmd_converter/src/node.cpp b/vehicle/autoware_external_cmd_converter/src/node.cpp index cbff8ab5ef2ce..22fc1c319a4e3 100644 --- a/vehicle/autoware_external_cmd_converter/src/node.cpp +++ b/vehicle/autoware_external_cmd_converter/src/node.cpp @@ -179,6 +179,9 @@ void ExternalCmdConverterNode::check_topic_status( { using diagnostic_msgs::msg::DiagnosticStatus; DiagnosticStatus status; + + current_gate_mode_ = gate_mode_sub_.takeData(); + if (!check_emergency_stop_topic_timeout()) { status.level = DiagnosticStatus::ERROR; status.message = "emergency stop topic is timeout"; @@ -195,6 +198,14 @@ void ExternalCmdConverterNode::check_topic_status( bool ExternalCmdConverterNode::check_emergency_stop_topic_timeout() { + if (!current_gate_mode_) { + return true; + } + + if (current_gate_mode_->data == tier4_control_msgs::msg::GateMode::AUTO) { + latest_emergency_stop_heartbeat_received_time_ = nullptr; + } + if (!latest_emergency_stop_heartbeat_received_time_) { return wait_for_first_topic_; } @@ -205,8 +216,6 @@ bool ExternalCmdConverterNode::check_emergency_stop_topic_timeout() bool ExternalCmdConverterNode::check_remote_topic_rate() { - current_gate_mode_ = gate_mode_sub_.takeData(); - if (!current_gate_mode_) { return true; } From ae2e9b093e03012943a21b4d582cf718ecddfdb6 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 18 Jun 2024 19:41:15 +0900 Subject: [PATCH 014/151] fix(system_diagnostic_monitor): fix local mode config (#7532) Signed-off-by: Takagi, Isamu --- .../config/control.yaml | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/system/system_diagnostic_monitor/config/control.yaml b/system/system_diagnostic_monitor/config/control.yaml index 57bf1b86c2bfc..5551ed4575929 100644 --- a/system/system_diagnostic_monitor/config/control.yaml +++ b/system/system_diagnostic_monitor/config/control.yaml @@ -13,14 +13,14 @@ units: - path: /autoware/control/local type: and list: - - { type: link, link: /autoware/control/topic_rate_check/selector } - - { type: link, link: /autoware/control/topic_rate_check/local } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_selector } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_converter } - path: /autoware/control/remote type: and list: - - { type: link, link: /autoware/control/topic_rate_check/selector } - - { type: link, link: /autoware/control/topic_rate_check/remote } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_selector } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_converter } - path: /autoware/control/topic_rate_check/trajectory_follower type: diag @@ -57,17 +57,12 @@ units: node: controller_node_exe name: control_state - - path: /autoware/control/topic_rate_check/selector + - path: /autoware/control/topic_rate_check/external_cmd_selector type: diag node: external_cmd_selector name: heartbeat - - path: /autoware/control/topic_rate_check/local - type: diag - node: joy_controller - name: joy_controller_connection - - - path: /autoware/control/topic_rate_check/remote + - path: /autoware/control/topic_rate_check/external_cmd_converter type: diag node: external_cmd_converter name: remote_control_topic_status From 898eb5a9009a48021ef813f9c51a995e7327e3e3 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 11 Jul 2024 15:28:30 +0900 Subject: [PATCH 015/151] feat(duplicated_node_checker): add duplicate nodes to ignore (#7959) (#1410) * feat: add duplicate nodes to ignore * remove talker * newline * commments * pre-commit and sign * rviz->rviz2 --------- Signed-off-by: Dmitrii Koldaev Co-authored-by: Dmitrii Koldaev <39071246+dkoldaev@users.noreply.github.com> Co-authored-by: Dmitrii Koldaev --- .../config/duplicated_node_checker.param.yaml | 2 ++ .../duplicated_node_checker/duplicated_node_checker_core.hpp | 4 ++++ .../src/duplicated_node_checker_core.cpp | 5 +++++ 3 files changed, 11 insertions(+) diff --git a/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml b/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml index 96dce7eb360e4..412c59e66e2c9 100644 --- a/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml +++ b/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml @@ -2,3 +2,5 @@ ros__parameters: update_rate: 10.0 add_duplicated_node_names_to_msg: true # if true, duplicated node names are added to msg + nodes_to_ignore: # List of nodes to ignore when checking for duplicates + - /rviz2 diff --git a/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp b/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp index 9d806754f3c20..66e125de666b7 100644 --- a/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp +++ b/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp @@ -33,6 +33,9 @@ class DuplicatedNodeChecker : public rclcpp::Node std::unordered_set unique_names; std::vector identical_names; for (auto name : input_name_lists) { + if (nodes_to_ignore_.count(name) != 0) { + continue; + } if (unique_names.find(name) != unique_names.end()) { identical_names.push_back(name); } else { @@ -49,6 +52,7 @@ class DuplicatedNodeChecker : public rclcpp::Node diagnostic_updater::Updater updater_{this}; rclcpp::TimerBase::SharedPtr timer_; bool add_duplicated_node_names_to_msg_; + std::unordered_set nodes_to_ignore_; }; } // namespace duplicated_node_checker diff --git a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp index 384c8fdc46c5f..c9bc07cffde72 100644 --- a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp +++ b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp @@ -29,6 +29,11 @@ DuplicatedNodeChecker::DuplicatedNodeChecker(const rclcpp::NodeOptions & node_op { double update_rate = declare_parameter("update_rate"); add_duplicated_node_names_to_msg_ = declare_parameter("add_duplicated_node_names_to_msg"); + + std::vector nodes_to_ignore_vector = + declare_parameter>("nodes_to_ignore"); + nodes_to_ignore_.insert(nodes_to_ignore_vector.begin(), nodes_to_ignore_vector.end()); + updater_.setHardwareID("duplicated_node_checker"); updater_.add("duplicated_node_checker", this, &DuplicatedNodeChecker::produceDiagnostics); From 7fc43944d32002452ff7bfd01647bb12672ef5fb Mon Sep 17 00:00:00 2001 From: Shohei Sakai Date: Wed, 17 Jul 2024 15:17:38 +0900 Subject: [PATCH 016/151] fix(dummy_diag_publisher): not use diagnostic_updater and param callback for v0.29.0 (#1414) fix(dummy_diag_publisher): not use diagnostic_updater and param callback Co-authored-by: h-ohta --- .../dummy_diag_publisher_core.hpp | 23 +-- .../src/dummy_diag_publisher_core.cpp | 183 +++--------------- 2 files changed, 36 insertions(+), 170 deletions(-) diff --git a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp index 071e665ece6ec..bbca397fb47ec 100644 --- a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp +++ b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp @@ -15,10 +15,10 @@ #ifndef DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ #define DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ -#include -#include #include +#include + #include #include #include @@ -64,27 +64,12 @@ class DummyDiagPublisher : public rclcpp::Node std::optional convertStrToStatus(std::string & status_str); std::string convertStatusToStr(const Status & status); + diagnostic_msgs::msg::DiagnosticStatus::_level_type convertStatusToLevel(const Status & status); - // Dynamic Reconfigure - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - - rcl_interfaces::msg::SetParametersResult updateDiag( - const std::string diag_name, DummyDiagConfig & config, bool is_active, const Status status); - - // Diagnostic Updater - // Set long period to reduce automatic update - diagnostic_updater::Updater updater_{this, 1000.0 /* sec */}; - - void produceOKDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); - void produceErrorDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); - void produceWarnDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); - void produceStaleDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); - void addDiagByStatus(const std::string & diag_name, const Status status); // Timer void onTimer(); rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Publisher::SharedPtr pub_; }; #endif // DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index e46c6e4341284..3432aba0b486b 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -14,22 +14,9 @@ #include "dummy_diag_publisher/dummy_diag_publisher_core.hpp" -#include - #define FMT_HEADER_ONLY -#include -#include -#include -#include - #include -#include -#include -#include -#include -#include - namespace { std::vector split(const std::string & str, const char delim) @@ -44,82 +31,6 @@ std::vector split(const std::string & str, const char delim) } } // namespace -rcl_interfaces::msg::SetParametersResult DummyDiagPublisher::paramCallback( - const std::vector & parameters) -{ - rcl_interfaces::msg::SetParametersResult result; - - for (const auto & param : parameters) { - const auto param_name = param.get_name(); - const auto split_names = split(param_name, '.'); - const auto & diag_name = split_names.at(0); - auto it = std::find_if( - std::begin(required_diags_), std::end(required_diags_), - [&diag_name](DummyDiagConfig config) { return config.name == diag_name; }); - if (it == std::end(required_diags_)) { // diag name not found - result.successful = false; - result.reason = "no matching diag name"; - } else { // diag name found - const auto status_prefix_str = diag_name + std::string(".status"); - const auto is_active_prefix_str = diag_name + std::string(".is_active"); - auto status_str = convertStatusToStr(it->status); - auto prev_status_str = status_str; - auto is_active = true; - try { - autoware::universe_utils::updateParam(parameters, status_prefix_str, status_str); - autoware::universe_utils::updateParam(parameters, is_active_prefix_str, is_active); - } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { - result.successful = false; - result.reason = e.what(); - return result; - } - const auto status = convertStrToStatus(status_str); - if (!status) { - result.successful = false; - result.reason = "invalid status"; - return result; - } - result = updateDiag(diag_name, *it, is_active, *status); - } // end diag name found - } - return result; -} - -// update diag with new param -rcl_interfaces::msg::SetParametersResult DummyDiagPublisher::updateDiag( - const std::string diag_name, DummyDiagConfig & config, bool is_active, const Status status) -{ - rcl_interfaces::msg::SetParametersResult result; - result.successful = true; - result.reason = "success"; - - if (is_active == config.is_active && config.status == status) { // diag config not changed - result.successful = true; - result.reason = "config not changed"; - } else if (is_active == true && config.is_active == false) { // newly activated - config.is_active = true; - if (config.status == status) { // status not changed - addDiagByStatus(diag_name, config.status); - } else { // status changed - config.status = status; - addDiagByStatus(diag_name, status); - } - } else { // deactivated or status changed - if (!updater_.removeByName(diag_name)) { - result.successful = false; - result.reason = "updater removal failed"; - return result; - } - if (is_active == false) { // deactivated - config.is_active = false; - } else { // status changed - config.status = status; - addDiagByStatus(diag_name, status); - } - } - return result; -} - std::optional DummyDiagPublisher::convertStrToStatus( std::string & status_str) { @@ -147,6 +58,21 @@ std::string DummyDiagPublisher::convertStatusToStr(const Status & status) } } +diagnostic_msgs::msg::DiagnosticStatus::_level_type DummyDiagPublisher::convertStatusToLevel( + const Status & status) +{ + switch (status) { + case Status::OK: + return diagnostic_msgs::msg::DiagnosticStatus::OK; + case Status::WARN: + return diagnostic_msgs::msg::DiagnosticStatus::WARN; + case Status::ERROR: + return diagnostic_msgs::msg::DiagnosticStatus::ERROR; + default: + return diagnostic_msgs::msg::DiagnosticStatus::STALE; + } +} + void DummyDiagPublisher::loadRequiredDiags() { const auto param_key = std::string("required_diags"); @@ -189,60 +115,22 @@ void DummyDiagPublisher::loadRequiredDiags() } } -void DummyDiagPublisher::produceOKDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - diagnostic_msgs::msg::DiagnosticStatus status; - - status.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - status.message = diag_config_.msg_ok; - - stat.summary(status.level, status.message); -} -void DummyDiagPublisher::produceWarnDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - diagnostic_msgs::msg::DiagnosticStatus status; - - status.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - status.message = diag_config_.msg_warn; - - stat.summary(status.level, status.message); -} -void DummyDiagPublisher::produceErrorDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - diagnostic_msgs::msg::DiagnosticStatus status; - - status.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - status.message = diag_config_.msg_error; - - stat.summary(status.level, status.message); -} -void DummyDiagPublisher::produceStaleDiagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - diagnostic_msgs::msg::DiagnosticStatus status; - - status.level = diagnostic_msgs::msg::DiagnosticStatus::STALE; - status.message = diag_config_.msg_stale; - - stat.summary(status.level, status.message); -} -void DummyDiagPublisher::addDiagByStatus(const std::string & diag_name, const Status status) -{ - if (status == Status::OK) { - updater_.add(diag_name, this, &DummyDiagPublisher::produceOKDiagnostics); - } else if (status == Status::WARN) { - updater_.add(diag_name, this, &DummyDiagPublisher::produceWarnDiagnostics); - } else if (status == Status::ERROR) { - updater_.add(diag_name, this, &DummyDiagPublisher::produceErrorDiagnostics); - } else if (status == Status::STALE) { - updater_.add(diag_name, this, &DummyDiagPublisher::produceStaleDiagnostics); - } else { - throw std::runtime_error("invalid status"); - } -} - void DummyDiagPublisher::onTimer() { - updater_.force_update(); + diagnostic_msgs::msg::DiagnosticArray array; + + for (const auto & e : required_diags_) { + if (e.is_active) { + diagnostic_msgs::msg::DiagnosticStatus status; + status.hardware_id = diag_config_.hardware_id; + status.name = e.name; + status.message = convertStatusToStr(e.status); + status.level = convertStatusToLevel(e.status); + array.status.push_back(status); + } + } + array.header.stamp = this->now(); + pub_->publish(array); } rclcpp::NodeOptions override_options(rclcpp::NodeOptions options) @@ -258,26 +146,19 @@ DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) // Parameter update_rate_ = this->get_parameter_or("update_rate", 10.0); - // Set parameter callback - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&DummyDiagPublisher::paramCallback, this, std::placeholders::_1)); - // Diagnostic Updater loadRequiredDiags(); const std::string hardware_id = "dummy_diag"; - updater_.setHardwareID(hardware_id); diag_config_ = DiagConfig{hardware_id, "OK", "Warn", "Error", "Stale"}; - for (const auto & config : required_diags_) { - if (config.is_active) { - addDiagByStatus(config.name, config.status); - } - } // Timer const auto period_ns = rclcpp::Rate(update_rate_).period(); timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&DummyDiagPublisher::onTimer, this)); + + // Publisher + pub_ = create_publisher("/diagnostics", rclcpp::QoS(1)); } #include From ef232f23223c5e5a58d42cdbda909dd5526d8aec Mon Sep 17 00:00:00 2001 From: Shohei Sakai Date: Wed, 17 Jul 2024 17:05:29 +0900 Subject: [PATCH 017/151] fix: resolve build error of dummy diag publisher (#1415) fix merge conflict --- system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index 3432aba0b486b..51a0846b45179 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -140,7 +140,7 @@ rclcpp::NodeOptions override_options(rclcpp::NodeOptions options) } DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) -: Node("dummy_diag_publisher", override_options(options)), updater_(this) +: Node("dummy_diag_publisher", override_options(options)) { // Parameter From 9bc020d216365bef6ae0adc4e01aa3d4b9bfba26 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 8 Jul 2024 22:55:42 +0900 Subject: [PATCH 018/151] feat(autoware_universe_utils): add TimeKeeper to track function's processing time (#7754) Signed-off-by: Takayuki Murooka --- common/autoware_universe_utils/CMakeLists.txt | 25 ++ common/autoware_universe_utils/README.md | 249 ++++++++++++++++++ .../examples/example_scoped_time_track.cpp | 61 +++++ .../examples/example_time_keeper.cpp | 64 +++++ .../universe_utils/system/time_keeper.hpp | 202 ++++++++++++++ .../src/system/time_keeper.cpp | 175 ++++++++++++ .../test/src/system/test_time_keeper.cpp | 53 ++++ .../path_optimizer/common_structs.hpp | 52 ---- .../autoware/path_optimizer/mpt_optimizer.hpp | 5 +- .../include/autoware/path_optimizer/node.hpp | 7 +- .../state_equation_generator.hpp | 7 +- .../src/mpt_optimizer.cpp | 63 ++--- planning/autoware_path_optimizer/src/node.cpp | 71 +++-- .../src/state_equation_generator.cpp | 3 +- 14 files changed, 893 insertions(+), 144 deletions(-) create mode 100644 common/autoware_universe_utils/examples/example_scoped_time_track.cpp create mode 100644 common/autoware_universe_utils/examples/example_time_keeper.cpp create mode 100644 common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp create mode 100644 common/autoware_universe_utils/src/system/time_keeper.cpp create mode 100644 common/autoware_universe_utils/test/src/system/test_time_keeper.cpp diff --git a/common/autoware_universe_utils/CMakeLists.txt b/common/autoware_universe_utils/CMakeLists.txt index 9e86ddeb60692..2fdeef2119ab8 100644 --- a/common/autoware_universe_utils/CMakeLists.txt +++ b/common/autoware_universe_utils/CMakeLists.txt @@ -1,11 +1,15 @@ cmake_minimum_required(VERSION 3.14) project(autoware_universe_utils) +option(BUILD_EXAMPLES "Build examples" OFF) + find_package(autoware_cmake REQUIRED) autoware_package() find_package(Boost REQUIRED) +find_package(fmt REQUIRED) + ament_auto_add_library(autoware_universe_utils SHARED src/geometry/geometry.cpp src/geometry/pose_deviation.cpp @@ -16,6 +20,11 @@ ament_auto_add_library(autoware_universe_utils SHARED src/ros/marker_helper.cpp src/ros/logger_level_configure.cpp src/system/backtrace.cpp + src/system/time_keeper.cpp +) + +target_link_libraries(autoware_universe_utils + fmt::fmt ) if(BUILD_TESTING) @@ -30,4 +39,20 @@ if(BUILD_TESTING) ) endif() +if(BUILD_EXAMPLES) + message(STATUS "Building examples") + file(GLOB_RECURSE example_files examples/*.cpp) + + foreach(example_file ${example_files}) + get_filename_component(example_name ${example_file} NAME_WE) + add_executable(${example_name} ${example_file}) + target_link_libraries(${example_name} + autoware_universe_utils + ) + install(TARGETS ${example_name} + DESTINATION lib/${PROJECT_NAME} + ) + endforeach() +endif() + ament_auto_package() diff --git a/common/autoware_universe_utils/README.md b/common/autoware_universe_utils/README.md index 22b9355b09635..2d24f84423299 100644 --- a/common/autoware_universe_utils/README.md +++ b/common/autoware_universe_utils/README.md @@ -7,3 +7,252 @@ This package contains many common functions used by other packages, so please re ## For developers `autoware_universe_utils.hpp` header file was removed because the source files that directly/indirectly include this file took a long time for preprocessing. + +## `autoware::universe_utils` + +### `systems` + +#### `autoware::universe_utils::TimeKeeper` + +##### Constructor + +```cpp +template +explicit TimeKeeper(Reporters... reporters); +``` + +- Initializes the `TimeKeeper` with a list of reporters. + +##### Methods + +- `void add_reporter(std::ostream * os);` + + - Adds a reporter to output processing times to an `ostream`. + - `os`: Pointer to the `ostream` object. + +- `void add_reporter(rclcpp::Publisher::SharedPtr publisher);` + + - Adds a reporter to publish processing times to an `rclcpp` publisher. + - `publisher`: Shared pointer to the `rclcpp` publisher. + +- `void add_reporter(rclcpp::Publisher::SharedPtr publisher);` + + - Adds a reporter to publish processing times to an `rclcpp` publisher with `std_msgs::msg::String`. + - `publisher`: Shared pointer to the `rclcpp` publisher. + +- `void start_track(const std::string & func_name);` + + - Starts tracking the processing time of a function. + - `func_name`: Name of the function to be tracked. + +- `void end_track(const std::string & func_name);` + - Ends tracking the processing time of a function. + - `func_name`: Name of the function to end tracking. + +##### Example + +```cpp +#include "autoware/universe_utils/system/time_keeper.hpp" + +#include + +#include +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared("time_keeper_example"); + + auto time_keeper = std::make_shared(); + + time_keeper->add_reporter(&std::cout); + + auto publisher = + node->create_publisher("processing_time", 10); + + time_keeper->add_reporter(publisher); + + auto publisher_str = node->create_publisher("processing_time_str", 10); + + time_keeper->add_reporter(publisher_str); + + auto funcA = [&time_keeper]() { + time_keeper->start_track("funcA"); + std::this_thread::sleep_for(std::chrono::seconds(1)); + time_keeper->end_track("funcA"); + }; + + auto funcB = [&time_keeper, &funcA]() { + time_keeper->start_track("funcB"); + std::this_thread::sleep_for(std::chrono::seconds(2)); + funcA(); + time_keeper->end_track("funcB"); + }; + + auto funcC = [&time_keeper, &funcB]() { + time_keeper->start_track("funcC"); + std::this_thread::sleep_for(std::chrono::seconds(3)); + funcB(); + time_keeper->end_track("funcC"); + }; + + funcC(); + + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} +``` + +- Output (console) + + ```text + ========================== + funcC (6000.7ms) + └── funcB (3000.44ms) + └── funcA (1000.19ms) + ``` + +- Output (`ros2 topic echo /processing_time`) + + ```text + nodes: + - id: 1 + name: funcC + processing_time: 6000.659 + parent_id: 0 + - id: 2 + name: funcB + processing_time: 3000.415 + parent_id: 1 + - id: 3 + name: funcA + processing_time: 1000.181 + parent_id: 2 + --- + ``` + +- Output (`ros2 topic echo /processing_time_str --field data`) + + ```text + funcC (6000.67ms) + └── funcB (3000.42ms) + └── funcA (1000.19ms) + + --- + ``` + +#### `autoware::universe_utils::ScopedTimeTrack` + +##### Description + +Class for automatically tracking the processing time of a function within a scope. + +##### Constructor + +```cpp +ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper); +``` + +- `func_name`: Name of the function to be tracked. +- `time_keeper`: Reference to the `TimeKeeper` object. + +##### Destructor + +```cpp +~ScopedTimeTrack(); +``` + +- Destroys the `ScopedTimeTrack` object, ending the tracking of the function. + +##### Example + +```cpp +#include "autoware/universe_utils/system/time_keeper.hpp" + +#include + +#include +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared("scoped_time_track_example"); + + auto time_keeper = std::make_shared(); + + time_keeper->add_reporter(&std::cout); + + auto publisher = + node->create_publisher("processing_time", 10); + + time_keeper->add_reporter(publisher); + + auto publisher_str = node->create_publisher("processing_time_str", 10); + + time_keeper->add_reporter(publisher_str); + + auto funcA = [&time_keeper]() { + autoware::universe_utils::ScopedTimeTrack st("funcA", *time_keeper); + std::this_thread::sleep_for(std::chrono::seconds(1)); + }; + + auto funcB = [&time_keeper, &funcA]() { + autoware::universe_utils::ScopedTimeTrack st("funcB", *time_keeper); + std::this_thread::sleep_for(std::chrono::seconds(2)); + funcA(); + }; + + auto funcC = [&time_keeper, &funcB]() { + autoware::universe_utils::ScopedTimeTrack st("funcC", *time_keeper); + std::this_thread::sleep_for(std::chrono::seconds(3)); + funcB(); + }; + + funcC(); + + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} +``` + +- Output (console) + + ```text + ========================== + funcC (6000.7ms) + └── funcB (3000.44ms) + └── funcA (1000.19ms) + ``` + +- Output (`ros2 topic echo /processing_time`) + + ```text + nodes: + - id: 1 + name: funcC + processing_time: 6000.659 + parent_id: 0 + - id: 2 + name: funcB + processing_time: 3000.415 + parent_id: 1 + - id: 3 + name: funcA + processing_time: 1000.181 + parent_id: 2 + --- + ``` + +- Output (`ros2 topic echo /processing_time_str --field data`) + + ```text + funcC (6000.67ms) + └── funcB (3000.42ms) + └── funcA (1000.19ms) + + --- + ``` diff --git a/common/autoware_universe_utils/examples/example_scoped_time_track.cpp b/common/autoware_universe_utils/examples/example_scoped_time_track.cpp new file mode 100644 index 0000000000000..010cc58aba8ae --- /dev/null +++ b/common/autoware_universe_utils/examples/example_scoped_time_track.cpp @@ -0,0 +1,61 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#include "autoware/universe_utils/system/time_keeper.hpp" + +#include + +#include +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared("scoped_time_track_example"); + + auto time_keeper = std::make_shared(); + + time_keeper->add_reporter(&std::cout); + + auto publisher = + node->create_publisher("processing_time", 10); + + time_keeper->add_reporter(publisher); + + auto publisher_str = node->create_publisher("processing_time_str", 10); + + time_keeper->add_reporter(publisher_str); + + auto funcA = [&time_keeper]() { + autoware::universe_utils::ScopedTimeTrack st("funcA", *time_keeper); + std::this_thread::sleep_for(std::chrono::seconds(1)); + }; + + auto funcB = [&time_keeper, &funcA]() { + autoware::universe_utils::ScopedTimeTrack st("funcB", *time_keeper); + std::this_thread::sleep_for(std::chrono::seconds(2)); + funcA(); + }; + + auto funcC = [&time_keeper, &funcB]() { + autoware::universe_utils::ScopedTimeTrack st("funcC", *time_keeper); + std::this_thread::sleep_for(std::chrono::seconds(3)); + funcB(); + }; + + funcC(); + + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/common/autoware_universe_utils/examples/example_time_keeper.cpp b/common/autoware_universe_utils/examples/example_time_keeper.cpp new file mode 100644 index 0000000000000..3f6037e68daac --- /dev/null +++ b/common/autoware_universe_utils/examples/example_time_keeper.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#include "autoware/universe_utils/system/time_keeper.hpp" + +#include + +#include +#include + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared("time_keeper_example"); + + auto time_keeper = std::make_shared(); + + time_keeper->add_reporter(&std::cout); + + auto publisher = + node->create_publisher("processing_time", 10); + + time_keeper->add_reporter(publisher); + + auto publisher_str = node->create_publisher("processing_time_str", 10); + + time_keeper->add_reporter(publisher_str); + + auto funcA = [&time_keeper]() { + time_keeper->start_track("funcA"); + std::this_thread::sleep_for(std::chrono::seconds(1)); + time_keeper->end_track("funcA"); + }; + + auto funcB = [&time_keeper, &funcA]() { + time_keeper->start_track("funcB"); + std::this_thread::sleep_for(std::chrono::seconds(2)); + funcA(); + time_keeper->end_track("funcB"); + }; + + auto funcC = [&time_keeper, &funcB]() { + time_keeper->start_track("funcC"); + std::this_thread::sleep_for(std::chrono::seconds(3)); + funcB(); + time_keeper->end_track("funcC"); + }; + + funcC(); + + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp new file mode 100644 index 0000000000000..96070f0f30b77 --- /dev/null +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp @@ -0,0 +1,202 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE__UNIVERSE_UTILS__SYSTEM__TIME_KEEPER_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__SYSTEM__TIME_KEEPER_HPP_ + +#include "autoware/universe_utils/system/stop_watch.hpp" + +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace autoware::universe_utils +{ +/** + * @brief Class representing a node in the time tracking tree + */ +class ProcessingTimeNode : public std::enable_shared_from_this +{ +public: + /** + * @brief Construct a new ProcessingTimeNode object + * + * @param name Name of the node + */ + explicit ProcessingTimeNode(const std::string & name); + + /** + * @brief Add a child node + * + * @param name Name of the child node + * @return std::shared_ptr Shared pointer to the newly added child node + */ + std::shared_ptr add_child(const std::string & name); + + /** + * @brief Get the result string representing the node and its children in a tree structure + * + * @return std::string Result string representing the node and its children + */ + std::string to_string() const; + + /** + * @brief Construct a ProcessingTimeTree message from the node and its children + * + * @return tier4_debug_msgs::msg::ProcessingTimeTree Constructed ProcessingTimeTree message + */ + tier4_debug_msgs::msg::ProcessingTimeTree to_msg() const; + + /** + * @brief Get the parent node + * + * @return std::shared_ptr Shared pointer to the parent node + */ + std::shared_ptr get_parent_node() const; + + /** + * @brief Get the child nodes + * + * @return std::vector> Vector of shared pointers to the child + * nodes + */ + std::vector> get_child_nodes() const; + + /** + * @brief Set the processing time for the node + * + * @param processing_time Processing time to be set + */ + void set_time(const double processing_time); + + /** + * @brief Get the name of the node + * + * @return std::string Name of the node + */ + std::string get_name() const; + +private: + const std::string name_; //!< Name of the node + double processing_time_{0.0}; //!< Processing time of the node + std::shared_ptr parent_node_{nullptr}; //!< Shared pointer to the parent node + std::vector> + child_nodes_; //!< Vector of shared pointers to the child nodes +}; + +using ProcessingTimeDetail = + tier4_debug_msgs::msg::ProcessingTimeTree; //!< Alias for the ProcessingTimeTree message + +/** + * @brief Class for tracking and reporting the processing time of various functions + */ +class TimeKeeper +{ +public: + template + explicit TimeKeeper(Reporters... reporters) : current_time_node_(nullptr), root_node_(nullptr) + { + reporters_.reserve(sizeof...(Reporters)); + (add_reporter(reporters), ...); + } + + /** + * @brief Add a reporter to output processing times to an ostream + * + * @param os Pointer to the ostream object + */ + void add_reporter(std::ostream * os); + + /** + * @brief Add a reporter to publish processing times to an rclcpp publisher + * + * @param publisher Shared pointer to the rclcpp publisher + */ + void add_reporter(rclcpp::Publisher::SharedPtr publisher); + + /** + * @brief Add a reporter to publish processing times to an rclcpp publisher with + * std_msgs::msg::String + * + * @param publisher Shared pointer to the rclcpp publisher + */ + void add_reporter(rclcpp::Publisher::SharedPtr publisher); + + /** + * @brief Start tracking the processing time of a function + * + * @param func_name Name of the function to be tracked + */ + void start_track(const std::string & func_name); + + /** + * @brief End tracking the processing time of a function + * + * @param func_name Name of the function to end tracking + */ + void end_track(const std::string & func_name); + +private: + /** + * @brief Report the processing times to all registered reporters + */ + void report(); + + std::shared_ptr + current_time_node_; //!< Shared pointer to the current time node + std::shared_ptr root_node_; //!< Shared pointer to the root time node + autoware::universe_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; //!< StopWatch object for tracking the processing time + + std::vector &)>> + reporters_; //!< Vector of functions for reporting the processing times +}; + +/** + * @brief Class for automatically tracking the processing time of a function within a scope + */ +class ScopedTimeTrack +{ +public: + /** + * @brief Construct a new ScopedTimeTrack object + * + * @param func_name Name of the function to be tracked + * @param time_keeper Reference to the TimeKeeper object + */ + ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper); + + /** + * @brief Destroy the ScopedTimeTrack object, ending the tracking of the function + */ + ~ScopedTimeTrack(); + +private: + const std::string func_name_; //!< Name of the function being tracked + TimeKeeper & time_keeper_; //!< Reference to the TimeKeeper object +}; + +} // namespace autoware::universe_utils + +#endif // AUTOWARE__UNIVERSE_UTILS__SYSTEM__TIME_KEEPER_HPP_ diff --git a/common/autoware_universe_utils/src/system/time_keeper.cpp b/common/autoware_universe_utils/src/system/time_keeper.cpp new file mode 100644 index 0000000000000..58bed6677227c --- /dev/null +++ b/common/autoware_universe_utils/src/system/time_keeper.cpp @@ -0,0 +1,175 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/universe_utils/system/time_keeper.hpp" + +#include +#include + +namespace autoware::universe_utils +{ + +ProcessingTimeNode::ProcessingTimeNode(const std::string & name) : name_(name) +{ +} + +std::shared_ptr ProcessingTimeNode::add_child(const std::string & name) +{ + auto new_child_node = std::make_shared(name); + new_child_node->parent_node_ = shared_from_this(); + child_nodes_.push_back(new_child_node); + return new_child_node; +} + +std::string ProcessingTimeNode::to_string() const +{ + std::function + construct_string = [&]( + const ProcessingTimeNode & node, std::ostringstream & oss, + const std::string & prefix, bool is_last, bool is_root) { + if (!is_root) { + oss << prefix << (is_last ? "└── " : "├── "); + } + oss << node.name_ << " (" << node.processing_time_ << "ms)\n"; + for (size_t i = 0; i < node.child_nodes_.size(); ++i) { + const auto & child = node.child_nodes_[i]; + construct_string( + *child, oss, prefix + (is_last ? " " : "│ "), i == node.child_nodes_.size() - 1, + false); + } + }; + + std::ostringstream oss; + construct_string(*this, oss, "", true, true); + return oss.str(); +} + +tier4_debug_msgs::msg::ProcessingTimeTree ProcessingTimeNode::to_msg() const +{ + tier4_debug_msgs::msg::ProcessingTimeTree time_tree_msg; + + std::function + construct_msg = [&]( + const ProcessingTimeNode & node, + tier4_debug_msgs::msg::ProcessingTimeTree & tree_msg, int parent_id) { + tier4_debug_msgs::msg::ProcessingTimeNode time_node_msg; + time_node_msg.name = node.name_; + time_node_msg.processing_time = node.processing_time_; + time_node_msg.id = tree_msg.nodes.size() + 1; + time_node_msg.parent_id = parent_id; + tree_msg.nodes.emplace_back(time_node_msg); + + for (const auto & child : node.child_nodes_) { + construct_msg(*child, tree_msg, time_node_msg.id); + } + }; + construct_msg(*this, time_tree_msg, 0); + + return time_tree_msg; +} + +std::shared_ptr ProcessingTimeNode::get_parent_node() const +{ + return parent_node_; +} +std::vector> ProcessingTimeNode::get_child_nodes() const +{ + return child_nodes_; +} +void ProcessingTimeNode::set_time(const double processing_time) +{ + processing_time_ = processing_time; +} +std::string ProcessingTimeNode::get_name() const +{ + return name_; +} + +void TimeKeeper::add_reporter(std::ostream * os) +{ + reporters_.emplace_back([os](const std::shared_ptr & node) { + *os << "==========================" << std::endl; + *os << node->to_string() << std::endl; + }); +} + +void TimeKeeper::add_reporter(rclcpp::Publisher::SharedPtr publisher) +{ + reporters_.emplace_back([publisher](const std::shared_ptr & node) { + publisher->publish(node->to_msg()); + }); +} + +void TimeKeeper::add_reporter(rclcpp::Publisher::SharedPtr publisher) +{ + reporters_.emplace_back([publisher](const std::shared_ptr & node) { + std_msgs::msg::String msg; + msg.data = node->to_string(); + publisher->publish(msg); + }); +} + +void TimeKeeper::start_track(const std::string & func_name) +{ + if (current_time_node_ == nullptr) { + current_time_node_ = std::make_shared(func_name); + root_node_ = current_time_node_; + } else { + current_time_node_ = current_time_node_->add_child(func_name); + } + stop_watch_.tic(func_name); +} + +void TimeKeeper::end_track(const std::string & func_name) +{ + if (current_time_node_->get_name() != func_name) { + throw std::runtime_error(fmt::format( + "You must call end_track({}) first, but end_track({}) is called", + current_time_node_->get_name(), func_name)); + } + const double processing_time = stop_watch_.toc(func_name); + current_time_node_->set_time(processing_time); + current_time_node_ = current_time_node_->get_parent_node(); + + if (current_time_node_ == nullptr) { + report(); + } +} + +void TimeKeeper::report() +{ + if (current_time_node_ != nullptr) { + throw std::runtime_error(fmt::format( + "You must call end_track({}) first, but report() is called", current_time_node_->get_name())); + } + for (const auto & reporter : reporters_) { + reporter(root_node_); + } + current_time_node_.reset(); + root_node_.reset(); +} + +ScopedTimeTrack::ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper) +: func_name_(func_name), time_keeper_(time_keeper) +{ + time_keeper_.start_track(func_name_); +} + +ScopedTimeTrack::~ScopedTimeTrack() +{ + time_keeper_.end_track(func_name_); +} + +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp new file mode 100644 index 0000000000000..71ca7cc74bec5 --- /dev/null +++ b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp @@ -0,0 +1,53 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/universe_utils/system/time_keeper.hpp" + +#include +#include + +#include + +#include +#include +#include + +TEST(system, TimeKeeper) +{ + using autoware::universe_utils::ScopedTimeTrack; + using autoware::universe_utils::TimeKeeper; + + rclcpp::Node node{"sample_node"}; + + auto publisher = node.create_publisher( + "~/debug/processing_time_tree", 1); + + TimeKeeper time_keeper(&std::cerr, publisher); + + ScopedTimeTrack st{"main_func", time_keeper}; + + { // funcA + ScopedTimeTrack st{"funcA", time_keeper}; + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + + { // funcB + ScopedTimeTrack st{"funcB", time_keeper}; + std::this_thread::sleep_for(std::chrono::seconds(1)); + { // funcC + ScopedTimeTrack st{"funcC", time_keeper}; + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + } +} diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp index 7f2688ffaad95..399262f93e19d 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp @@ -17,7 +17,6 @@ #include "autoware/path_optimizer/type_alias.hpp" #include "autoware/universe_utils/ros/update_param.hpp" -#include "autoware/universe_utils/system/stop_watch.hpp" #include "rclcpp/rclcpp.hpp" #include @@ -43,57 +42,6 @@ struct PlannerData double ego_vel{}; }; -struct TimeKeeper -{ - void init() - { - accumulated_msg = "\n"; - accumulated_time = 0.0; - } - - template - TimeKeeper & operator<<(const T & msg) - { - latest_stream << msg; - return *this; - } - - void endLine() - { - const auto msg = latest_stream.str(); - accumulated_msg += msg + "\n"; - latest_stream.str(""); - - if (enable_calculation_time_info) { - RCLCPP_INFO_STREAM(rclcpp::get_logger("autoware_path_optimizer.time"), msg); - } - } - - void tic(const std::string & func_name) { stop_watch_.tic(func_name); } - - void toc(const std::string & func_name, const std::string & white_spaces) - { - const double elapsed_time = stop_watch_.toc(func_name); - *this << white_spaces << func_name << ":= " << elapsed_time << " [ms]"; - accumulated_time = elapsed_time; - endLine(); - } - - std::string getLog() const { return accumulated_msg; } - - bool enable_calculation_time_info; - std::string accumulated_msg = "\n"; - std::stringstream latest_stream; - - double getAccumulatedTime() const { return accumulated_time; } - - double accumulated_time{0.0}; - - autoware::universe_utils::StopWatch< - std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> - stop_watch_; -}; - struct DebugData { // settting diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp index 4303e5c7e05b4..3443ab663b642 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp @@ -19,6 +19,7 @@ #include "autoware/path_optimizer/state_equation_generator.hpp" #include "autoware/path_optimizer/type_alias.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "gtest/gtest.h" #include "interpolation/linear_interpolation.hpp" @@ -107,7 +108,7 @@ class MPTOptimizer rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const TrajectoryParam & traj_param, const std::shared_ptr debug_data_ptr, - const std::shared_ptr time_keeper_ptr); + const std::shared_ptr time_keeper_); std::vector optimizeTrajectory(const PlannerData & planner_data); std::optional> getPrevOptimizedTrajectoryPoints() const; @@ -222,7 +223,7 @@ class MPTOptimizer autoware::vehicle_info_utils::VehicleInfo vehicle_info_; TrajectoryParam traj_param_; mutable std::shared_ptr debug_data_ptr_; - mutable std::shared_ptr time_keeper_ptr_; + mutable std::shared_ptr time_keeper_; rclcpp::Logger logger_; MPTParam mpt_param_; diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp index 359c20f2a4d29..6f75c649e02b2 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp @@ -22,10 +22,11 @@ #include "autoware/path_optimizer/type_alias.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" -#include "rclcpp/rclcpp.hpp" #include +#include #include #include @@ -65,7 +66,7 @@ class PathOptimizer : public rclcpp::Node // argument variables autoware::vehicle_info_utils::VehicleInfo vehicle_info_{}; mutable std::shared_ptr debug_data_ptr_{nullptr}; - mutable std::shared_ptr time_keeper_ptr_{nullptr}; + mutable std::shared_ptr time_keeper_{nullptr}; // flags for some functions bool enable_pub_debug_marker_; @@ -98,6 +99,8 @@ class PathOptimizer : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_markers_pub_; rclcpp::Publisher::SharedPtr debug_calculation_time_str_pub_; rclcpp::Publisher::SharedPtr debug_calculation_time_float_pub_; + rclcpp::Publisher::SharedPtr + debug_processing_time_detail_pub_; // parameter callback rcl_interfaces::msg::SetParametersResult onParam( diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/state_equation_generator.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/state_equation_generator.hpp index b8162f5ef2d32..1d23d7788dca1 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/state_equation_generator.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/state_equation_generator.hpp @@ -18,6 +18,7 @@ #include "autoware/path_optimizer/common_structs.hpp" #include "autoware/path_optimizer/vehicle_model/vehicle_model_bicycle_kinematics.hpp" #include "autoware/path_optimizer/vehicle_model/vehicle_model_interface.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include #include @@ -39,9 +40,9 @@ class StateEquationGenerator StateEquationGenerator() = default; StateEquationGenerator( const double wheel_base, const double max_steer_rad, - const std::shared_ptr time_keeper_ptr) + const std::shared_ptr time_keeper) : vehicle_model_ptr_(std::make_unique(wheel_base, max_steer_rad)), - time_keeper_ptr_(time_keeper_ptr) + time_keeper_(time_keeper) { } @@ -56,7 +57,7 @@ class StateEquationGenerator private: std::unique_ptr vehicle_model_ptr_; - mutable std::shared_ptr time_keeper_ptr_; + mutable std::shared_ptr time_keeper_; }; } // namespace autoware::path_optimizer #endif // AUTOWARE__PATH_OPTIMIZER__STATE_EQUATION_GENERATOR_HPP_ diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index a5da50862c9fb..1d49b6cb77d59 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -395,13 +395,13 @@ MPTOptimizer::MPTOptimizer( rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const TrajectoryParam & traj_param, const std::shared_ptr debug_data_ptr, - const std::shared_ptr time_keeper_ptr) + const std::shared_ptr time_keeper) : enable_debug_info_(enable_debug_info), ego_nearest_param_(ego_nearest_param), vehicle_info_(vehicle_info), traj_param_(traj_param), debug_data_ptr_(debug_data_ptr), - time_keeper_ptr_(time_keeper_ptr), + time_keeper_(time_keeper), logger_(node->get_logger().get_child("mpt_optimizer")) { // initialize mpt param @@ -411,7 +411,7 @@ MPTOptimizer::MPTOptimizer( // state equation generator state_equation_generator_ = - StateEquationGenerator(vehicle_info_.wheel_base_m, mpt_param_.max_steer_rad, time_keeper_ptr_); + StateEquationGenerator(vehicle_info_.wheel_base_m, mpt_param_.max_steer_rad, time_keeper_); // osqp solver osqp_solver_ptr_ = std::make_unique(osqp_epsilon_); @@ -470,7 +470,7 @@ void MPTOptimizer::onParam(const std::vector & parameters) std::vector MPTOptimizer::optimizeTrajectory(const PlannerData & planner_data) { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & p = planner_data; const auto & traj_points = p.traj_points; @@ -520,8 +520,6 @@ std::vector MPTOptimizer::optimizeTrajectory(const PlannerData // 8. publish trajectories for debug publishDebugTrajectories(p.header, ref_points, *mpt_traj_points); - time_keeper_ptr_->toc(__func__, " "); - debug_data_ptr_->ref_points = ref_points; prev_ref_points_ptr_ = std::make_shared>(ref_points); prev_optimized_traj_points_ptr_ = @@ -541,7 +539,7 @@ std::optional> MPTOptimizer::getPrevOptimizedTrajec std::vector MPTOptimizer::calcReferencePoints( const PlannerData & planner_data, const std::vector & smoothed_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & p = planner_data; @@ -549,14 +547,14 @@ std::vector MPTOptimizer::calcReferencePoints( const double backward_traj_length = traj_param_.output_backward_traj_length; // 1. resample and convert smoothed points type from trajectory points to reference points - time_keeper_ptr_->tic("resampleReferencePoints"); + time_keeper_->start_track("resampleReferencePoints"); auto ref_points = [&]() { const auto resampled_smoothed_points = trajectory_utils::resampleTrajectoryPointsWithoutStopPoint( smoothed_points, mpt_param_.delta_arc_length); return trajectory_utils::convertToReferencePoints(resampled_smoothed_points); }(); - time_keeper_ptr_->toc("resampleReferencePoints", " "); + time_keeper_->end_track("resampleReferencePoints"); // 2. crop forward and backward with margin, and calculate spline interpolation // NOTE: Margin is added to calculate orientation, curvature, etc precisely. @@ -611,8 +609,6 @@ std::vector MPTOptimizer::calcReferencePoints( ref_points.resize(mpt_param_.num_points); } - time_keeper_ptr_->toc(__func__, " "); - return ref_points; } @@ -639,7 +635,7 @@ void MPTOptimizer::updateCurvature( void MPTOptimizer::updateFixedPoint(std::vector & ref_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (!prev_ref_points_ptr_) { // no fixed point @@ -681,8 +677,6 @@ void MPTOptimizer::updateFixedPoint(std::vector & ref_points) co ref_points.front().curvature = front_point.curvature; ref_points.front().fixed_kinematic_state = front_point.optimized_kinematic_state; } - - time_keeper_ptr_->toc(__func__, " "); } void MPTOptimizer::updateDeltaArcLength(std::vector & ref_points) const @@ -697,7 +691,7 @@ void MPTOptimizer::updateDeltaArcLength(std::vector & ref_points void MPTOptimizer::updateExtraPoints(std::vector & ref_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // alpha for (size_t i = 0; i < ref_points.size(); ++i) { @@ -786,8 +780,6 @@ void MPTOptimizer::updateExtraPoints(std::vector & ref_points) c } } } - - time_keeper_ptr_->toc(__func__, " "); } void MPTOptimizer::updateBounds( @@ -796,7 +788,7 @@ void MPTOptimizer::updateBounds( const std::vector & right_bound, const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const double soft_road_clearance = mpt_param_.soft_clearance_from_road + vehicle_info_.vehicle_width_m / 2.0; @@ -844,8 +836,6 @@ void MPTOptimizer::updateBounds( } } */ - - time_keeper_ptr_->toc(__func__, " "); return; } @@ -1106,7 +1096,7 @@ void MPTOptimizer::updateVehicleBounds( std::vector & ref_points, const SplineInterpolationPoints2d & ref_points_spline) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); for (size_t p_idx = 0; p_idx < ref_points.size(); ++p_idx) { const auto & ref_point = ref_points.at(p_idx); @@ -1162,8 +1152,6 @@ void MPTOptimizer::updateVehicleBounds( ref_points.at(p_idx).pose_on_constraints.push_back(vehicle_bounds_pose); } } - - time_keeper_ptr_->toc(__func__, " "); } // cost function: J = x' Q x + u' R u @@ -1171,7 +1159,7 @@ MPTOptimizer::ValueMatrix MPTOptimizer::calcValueMatrix( const std::vector & ref_points, const std::vector & traj_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); @@ -1230,7 +1218,6 @@ MPTOptimizer::ValueMatrix MPTOptimizer::calcValueMatrix( R_sparse_mat.setFromTriplets(R_triplet_vec.begin(), R_triplet_vec.end()); - time_keeper_ptr_->toc(__func__, " "); return ValueMatrix{Q_sparse_mat, R_sparse_mat}; } @@ -1238,7 +1225,7 @@ MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( [[maybe_unused]] const StateEquationGenerator::Matrix & mpt_mat, const ValueMatrix & val_mat, const std::vector & ref_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); @@ -1288,7 +1275,6 @@ MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( obj_matrix.hessian = H; obj_matrix.gradient = g; - time_keeper_ptr_->toc(__func__, " "); return obj_matrix; } @@ -1299,7 +1285,7 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( const StateEquationGenerator::Matrix & mpt_mat, const std::vector & ref_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); @@ -1453,7 +1439,6 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( A_rows_end += N_u; } - time_keeper_ptr_->toc(__func__, " "); return ConstraintMatrix{A, lb, ub}; } @@ -1479,7 +1464,7 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const std::vector & ref_points, const ObjectiveMatrix & obj_mat, const ConstraintMatrix & const_mat) { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); @@ -1512,7 +1497,7 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const auto lower_bound = toStdVector(updated_const_mat.lower_bound); // initialize or update solver according to warm start - time_keeper_ptr_->tic("initOsqp"); + time_keeper_->start_track("initOsqp"); const autoware::common::osqp::CSC_Matrix P_csc = autoware::common::osqp::calCSCMatrixTrapezoidal(H); @@ -1532,13 +1517,12 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( } prev_mat_n_ = H.rows(); prev_mat_m_ = A.rows(); - - time_keeper_ptr_->toc("initOsqp", " "); + time_keeper_->end_track("initOsqp"); // solve qp - time_keeper_ptr_->tic("solveOsqp"); + time_keeper_->start_track("solveOsqp"); const auto result = osqp_solver_ptr_->optimize(); - time_keeper_ptr_->toc("solveOsqp", " "); + time_keeper_->end_track("solveOsqp"); // check solution status const int solution_status = std::get<3>(result); @@ -1565,8 +1549,6 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const Eigen::VectorXd optimized_variables = Eigen::Map(&optimization_result[0], N_v); - time_keeper_ptr_->toc(__func__, " "); - if (u0) { // manual warm start return static_cast(optimized_variables + *u0); } @@ -1649,7 +1631,7 @@ std::optional> MPTOptimizer::calcMPTPoints( std::vector & ref_points, const Eigen::VectorXd & optimized_variables, [[maybe_unused]] const StateEquationGenerator::Matrix & mpt_mat) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); @@ -1702,7 +1684,6 @@ std::optional> MPTOptimizer::calcMPTPoints( traj_points.push_back(traj_point); } - time_keeper_ptr_->toc(__func__, " "); return traj_points; } @@ -1710,7 +1691,7 @@ void MPTOptimizer::publishDebugTrajectories( const std_msgs::msg::Header & header, const std::vector & ref_points, const std::vector & mpt_traj_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // reference points const auto ref_traj = autoware::motion_utils::convertToTrajectory( @@ -1725,8 +1706,6 @@ void MPTOptimizer::publishDebugTrajectories( // mpt points const auto mpt_traj = autoware::motion_utils::convertToTrajectory(mpt_traj_points, header); debug_mpt_traj_pub_->publish(mpt_traj); - - time_keeper_ptr_->toc(__func__, " "); } std::vector MPTOptimizer::extractFixedPoints( diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 3899867a9dcce..7c73d1ad1fee3 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -23,6 +23,7 @@ #include "rclcpp/time.hpp" #include +#include #include namespace autoware::path_optimizer @@ -38,7 +39,8 @@ std::vector concatVectors(const std::vector & prev_vector, const std::vect return concatenated_vector; } -StringStamped createStringStamped(const rclcpp::Time & now, const std::string & data) +[[maybe_unused]] StringStamped createStringStamped( + const rclcpp::Time & now, const std::string & data) { StringStamped msg; msg.stamp = now; @@ -46,7 +48,7 @@ StringStamped createStringStamped(const rclcpp::Time & now, const std::string & return msg; } -Float64Stamped createFloat64Stamped(const rclcpp::Time & now, const float & data) +[[maybe_unused]] Float64Stamped createFloat64Stamped(const rclcpp::Time & now, const float & data) { Float64Stamped msg; msg.stamp = now; @@ -85,8 +87,7 @@ std::vector calcSegmentLengthVector(const std::vector & PathOptimizer::PathOptimizer(const rclcpp::NodeOptions & node_options) : Node("path_optimizer", node_options), vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()), - debug_data_ptr_(std::make_shared()), - time_keeper_ptr_(std::make_shared()) + debug_data_ptr_(std::make_shared()) { // interface publisher traj_pub_ = create_publisher("~/output/path", 1); @@ -102,6 +103,9 @@ PathOptimizer::PathOptimizer(const rclcpp::NodeOptions & node_options) debug_calculation_time_str_pub_ = create_publisher("~/debug/calculation_time", 1); debug_calculation_time_float_pub_ = create_publisher("~/debug/processing_time_ms", 1); + debug_processing_time_detail_pub_ = + create_publisher( + "~/debug/processing_time_detail_ms", 1); { // parameters // parameter for option @@ -120,8 +124,6 @@ PathOptimizer::PathOptimizer(const rclcpp::NodeOptions & node_options) // parameter for debug info enable_debug_info_ = declare_parameter("option.debug.enable_debug_info"); - time_keeper_ptr_->enable_calculation_time_info = - declare_parameter("option.debug.enable_calculation_time_info"); vehicle_stop_margin_outside_drivable_area_ = declare_parameter("common.vehicle_stop_margin_outside_drivable_area"); @@ -133,11 +135,14 @@ PathOptimizer::PathOptimizer(const rclcpp::NodeOptions & node_options) traj_param_ = TrajectoryParam(this); } + time_keeper_ = + std::make_shared(debug_processing_time_detail_pub_); + // create core algorithm pointers with parameter declaration replan_checker_ptr_ = std::make_shared(this, ego_nearest_param_); mpt_optimizer_ptr_ = std::make_shared( this, enable_debug_info_, ego_nearest_param_, vehicle_info_, traj_param_, debug_data_ptr_, - time_keeper_ptr_); + time_keeper_); // reset planners // NOTE: This function must be called after core algorithms (e.g. mpt_optimizer_) have been @@ -177,9 +182,6 @@ rcl_interfaces::msg::SetParametersResult PathOptimizer::onParam( // parameters for debug info updateParam(parameters, "option.debug.enable_debug_info", enable_debug_info_); - updateParam( - parameters, "option.debug.enable_calculation_time_info", - time_keeper_ptr_->enable_calculation_time_info); updateParam( parameters, "common.vehicle_stop_margin_outside_drivable_area", @@ -220,8 +222,7 @@ void PathOptimizer::resetPreviousData() void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) { - time_keeper_ptr_->init(); - time_keeper_ptr_->tic(__func__); + time_keeper_->start_track(__func__); // check if input path is valid if (!checkInputPath(*path_ptr, *get_clock())) { @@ -267,21 +268,21 @@ void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) // 5. publish debug data publishDebugData(planner_data.header); - time_keeper_ptr_->toc(__func__, ""); - *time_keeper_ptr_ << "========================================"; - time_keeper_ptr_->endLine(); - // publish calculation_time // NOTE: This function must be called after measuring onPath calculation time + /* const auto calculation_time_msg = createStringStamped(now(), time_keeper_ptr_->getLog()); debug_calculation_time_str_pub_->publish(calculation_time_msg); debug_calculation_time_float_pub_->publish( createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); + */ const auto output_traj_msg = autoware::motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); published_time_publisher_->publish_if_subscribed(traj_pub_, output_traj_msg.header.stamp); + + time_keeper_->end_track(__func__); } bool PathOptimizer::checkInputPath(const Path & path, rclcpp::Clock clock) const @@ -319,7 +320,7 @@ PlannerData PathOptimizer::createPlannerData( std::vector PathOptimizer::generateOptimizedTrajectory( const PlannerData & planner_data) { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & input_traj_points = planner_data.traj_points; @@ -339,13 +340,12 @@ std::vector PathOptimizer::generateOptimizedTrajectory( // 4. publish debug marker publishDebugMarkerOfOptimization(optimized_traj_points); - time_keeper_ptr_->toc(__func__, " "); return optimized_traj_points; } std::vector PathOptimizer::optimizeTrajectory(const PlannerData & planner_data) { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & p = planner_data; // 1. check if replan (= optimization) is required @@ -372,7 +372,6 @@ std::vector PathOptimizer::optimizeTrajectory(const PlannerData // with model predictive trajectory const auto mpt_traj = mpt_optimizer_ptr_->optimizeTrajectory(planner_data); - time_keeper_ptr_->toc(__func__, " "); return mpt_traj; } @@ -391,7 +390,7 @@ void PathOptimizer::applyInputVelocity( const std::vector & input_traj_points, const geometry_msgs::msg::Pose & ego_pose) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // crop forward for faster calculation const auto forward_cropped_input_traj_points = [&]() { @@ -486,14 +485,12 @@ void PathOptimizer::applyInputVelocity( trajectory_utils::insertStopPoint(output_traj_points, input_stop_pose, *stop_seg_idx); } } - - time_keeper_ptr_->toc(__func__, " "); } void PathOptimizer::insertZeroVelocityOutsideDrivableArea( const PlannerData & planner_data, std::vector & optimized_traj_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (optimized_traj_points.empty()) { return; @@ -553,13 +550,11 @@ void PathOptimizer::insertZeroVelocityOutsideDrivableArea( } else { debug_data_ptr_->stop_pose_by_drivable_area = std::nullopt; } - - time_keeper_ptr_->toc(__func__, " "); } void PathOptimizer::publishVirtualWall(const geometry_msgs::msg::Pose & stop_pose) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( stop_pose, "outside drivable area", now(), 0, vehicle_info_.max_longitudinal_offset_m); @@ -569,36 +564,33 @@ void PathOptimizer::publishVirtualWall(const geometry_msgs::msg::Pose & stop_pos } virtual_wall_pub_->publish(virtual_wall_marker); - time_keeper_ptr_->toc(__func__, " "); } void PathOptimizer::publishDebugMarkerOfOptimization( const std::vector & traj_points) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!enable_pub_debug_marker_) { return; } - time_keeper_ptr_->tic(__func__); - // debug marker - time_keeper_ptr_->tic("getDebugMarker"); + time_keeper_->start_track("getDebugMarker"); const auto debug_marker = getDebugMarker(*debug_data_ptr_, traj_points, vehicle_info_, enable_pub_extra_debug_marker_); - time_keeper_ptr_->toc("getDebugMarker", " "); + time_keeper_->end_track("getDebugMarker"); - time_keeper_ptr_->tic("publishDebugMarker"); + time_keeper_->start_track("publishDebugMarker"); debug_markers_pub_->publish(debug_marker); - time_keeper_ptr_->toc("publishDebugMarker", " "); - - time_keeper_ptr_->toc(__func__, " "); + time_keeper_->end_track("publishDebugMarker"); } std::vector PathOptimizer::extendTrajectory( const std::vector & traj_points, const std::vector & optimized_traj_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & joint_start_pose = optimized_traj_points.back().pose; @@ -654,20 +646,17 @@ std::vector PathOptimizer::extendTrajectory( // debug_data_ptr_->extended_traj_points = // extended_traj_points ? *extended_traj_points : std::vector(); - time_keeper_ptr_->toc(__func__, " "); return resampled_traj_points; } void PathOptimizer::publishDebugData(const Header & header) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // publish trajectories const auto debug_extended_traj = autoware::motion_utils::convertToTrajectory(debug_data_ptr_->extended_traj_points, header); debug_extended_traj_pub_->publish(debug_extended_traj); - - time_keeper_ptr_->toc(__func__, " "); } } // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/state_equation_generator.cpp b/planning/autoware_path_optimizer/src/state_equation_generator.cpp index 5aa2ab4ffbfa8..74033c5834db2 100644 --- a/planning/autoware_path_optimizer/src/state_equation_generator.cpp +++ b/planning/autoware_path_optimizer/src/state_equation_generator.cpp @@ -23,7 +23,7 @@ namespace autoware::path_optimizer StateEquationGenerator::Matrix StateEquationGenerator::calcMatrix( const std::vector & ref_points) const { - time_keeper_ptr_->tic(__func__); + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const size_t D_x = vehicle_model_ptr_->getDimX(); const size_t D_u = vehicle_model_ptr_->getDimU(); @@ -60,7 +60,6 @@ StateEquationGenerator::Matrix StateEquationGenerator::calcMatrix( W.segment(i * D_x, D_x) = Wd; } - time_keeper_ptr_->toc(__func__, " "); return Matrix{A, B, W}; } From fbc6cc34996c3643919a77869f00ca4d3ceb71eb Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 12 Jul 2024 16:26:25 +0900 Subject: [PATCH 019/151] chore(autoware_universe_utils): update document (#7907) * update readme Signed-off-by: Y.Hisaki * refactoring Signed-off-by: Y.Hisaki * remove string reporter Signed-off-by: Y.Hisaki * fix readme.md Signed-off-by: Y.Hisaki * change node name of example Signed-off-by: Y.Hisaki * update readme Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- common/autoware_universe_utils/README.md | 223 ++++++------------ .../examples/example_scoped_time_track.cpp | 61 ----- .../examples/example_time_keeper.cpp | 78 +++--- .../universe_utils/system/time_keeper.hpp | 16 +- .../src/system/time_keeper.cpp | 14 +- 5 files changed, 127 insertions(+), 265 deletions(-) delete mode 100644 common/autoware_universe_utils/examples/example_scoped_time_track.cpp diff --git a/common/autoware_universe_utils/README.md b/common/autoware_universe_utils/README.md index 2d24f84423299..cd5e366c520fc 100644 --- a/common/autoware_universe_utils/README.md +++ b/common/autoware_universe_utils/README.md @@ -49,56 +49,80 @@ explicit TimeKeeper(Reporters... reporters); - Ends tracking the processing time of a function. - `func_name`: Name of the function to end tracking. +##### Note + +- It's possible to start and end time measurements using `start_track` and `end_track` as shown below: + + ```cpp + time_keeper.start_track("example_function"); + // Your function code here + time_keeper.end_track("example_function"); + ``` + +- For safety and to ensure proper tracking, it is recommended to use `ScopedTimeTrack`. + ##### Example ```cpp -#include "autoware/universe_utils/system/time_keeper.hpp" - #include +#include + +#include #include #include +#include + +class ExampleNode : public rclcpp::Node +{ +public: + ExampleNode() : Node("time_keeper_example") + { + publisher_ = + create_publisher("processing_time", 1); + + time_keeper_ = std::make_shared(publisher_, &std::cerr); + // You can also add a reporter later by add_reporter. + // time_keeper_->add_reporter(publisher_); + // time_keeper_->add_reporter(&std::cerr); + + timer_ = create_wall_timer(std::chrono::seconds(1), std::bind(&ExampleNode::func_a, this)); + } + +private: + std::shared_ptr time_keeper_; + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Publisher::SharedPtr publisher_str_; + rclcpp::TimerBase::SharedPtr timer_; + + void func_a() + { + // Start constructing ProcessingTimeTree (because func_a is the root function) + autoware::universe_utils::ScopedTimeTrack st("func_a", *time_keeper_); + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + func_b(); + // End constructing ProcessingTimeTree. After this, the tree will be reported (publishing + // message and outputting to std::cerr) + } + + void func_b() + { + autoware::universe_utils::ScopedTimeTrack st("func_b", *time_keeper_); + std::this_thread::sleep_for(std::chrono::milliseconds(2)); + func_c(); + } + + void func_c() + { + autoware::universe_utils::ScopedTimeTrack st("func_c", *time_keeper_); + std::this_thread::sleep_for(std::chrono::milliseconds(3)); + } +}; int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = std::make_shared("time_keeper_example"); - - auto time_keeper = std::make_shared(); - - time_keeper->add_reporter(&std::cout); - - auto publisher = - node->create_publisher("processing_time", 10); - - time_keeper->add_reporter(publisher); - - auto publisher_str = node->create_publisher("processing_time_str", 10); - - time_keeper->add_reporter(publisher_str); - - auto funcA = [&time_keeper]() { - time_keeper->start_track("funcA"); - std::this_thread::sleep_for(std::chrono::seconds(1)); - time_keeper->end_track("funcA"); - }; - - auto funcB = [&time_keeper, &funcA]() { - time_keeper->start_track("funcB"); - std::this_thread::sleep_for(std::chrono::seconds(2)); - funcA(); - time_keeper->end_track("funcB"); - }; - - auto funcC = [&time_keeper, &funcB]() { - time_keeper->start_track("funcC"); - std::this_thread::sleep_for(std::chrono::seconds(3)); - funcB(); - time_keeper->end_track("funcC"); - }; - - funcC(); - + auto node = std::make_shared(); rclcpp::spin(node); rclcpp::shutdown(); return 0; @@ -109,38 +133,28 @@ int main(int argc, char ** argv) ```text ========================== - funcC (6000.7ms) - └── funcB (3000.44ms) - └── funcA (1000.19ms) + func_a (6.382ms) + └── func_b (5.243ms) + └── func_c (3.146ms) ``` - Output (`ros2 topic echo /processing_time`) ```text + --- nodes: - id: 1 - name: funcC - processing_time: 6000.659 + name: func_a + processing_time: 6.397 parent_id: 0 - id: 2 - name: funcB - processing_time: 3000.415 + name: func_b + processing_time: 5.263 parent_id: 1 - id: 3 - name: funcA - processing_time: 1000.181 + name: func_c + processing_time: 3.129 parent_id: 2 - --- - ``` - -- Output (`ros2 topic echo /processing_time_str --field data`) - - ```text - funcC (6000.67ms) - └── funcB (3000.42ms) - └── funcA (1000.19ms) - - --- ``` #### `autoware::universe_utils::ScopedTimeTrack` @@ -165,94 +179,3 @@ ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper); ``` - Destroys the `ScopedTimeTrack` object, ending the tracking of the function. - -##### Example - -```cpp -#include "autoware/universe_utils/system/time_keeper.hpp" - -#include - -#include -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared("scoped_time_track_example"); - - auto time_keeper = std::make_shared(); - - time_keeper->add_reporter(&std::cout); - - auto publisher = - node->create_publisher("processing_time", 10); - - time_keeper->add_reporter(publisher); - - auto publisher_str = node->create_publisher("processing_time_str", 10); - - time_keeper->add_reporter(publisher_str); - - auto funcA = [&time_keeper]() { - autoware::universe_utils::ScopedTimeTrack st("funcA", *time_keeper); - std::this_thread::sleep_for(std::chrono::seconds(1)); - }; - - auto funcB = [&time_keeper, &funcA]() { - autoware::universe_utils::ScopedTimeTrack st("funcB", *time_keeper); - std::this_thread::sleep_for(std::chrono::seconds(2)); - funcA(); - }; - - auto funcC = [&time_keeper, &funcB]() { - autoware::universe_utils::ScopedTimeTrack st("funcC", *time_keeper); - std::this_thread::sleep_for(std::chrono::seconds(3)); - funcB(); - }; - - funcC(); - - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} -``` - -- Output (console) - - ```text - ========================== - funcC (6000.7ms) - └── funcB (3000.44ms) - └── funcA (1000.19ms) - ``` - -- Output (`ros2 topic echo /processing_time`) - - ```text - nodes: - - id: 1 - name: funcC - processing_time: 6000.659 - parent_id: 0 - - id: 2 - name: funcB - processing_time: 3000.415 - parent_id: 1 - - id: 3 - name: funcA - processing_time: 1000.181 - parent_id: 2 - --- - ``` - -- Output (`ros2 topic echo /processing_time_str --field data`) - - ```text - funcC (6000.67ms) - └── funcB (3000.42ms) - └── funcA (1000.19ms) - - --- - ``` diff --git a/common/autoware_universe_utils/examples/example_scoped_time_track.cpp b/common/autoware_universe_utils/examples/example_scoped_time_track.cpp deleted file mode 100644 index 010cc58aba8ae..0000000000000 --- a/common/autoware_universe_utils/examples/example_scoped_time_track.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -#include "autoware/universe_utils/system/time_keeper.hpp" - -#include - -#include -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared("scoped_time_track_example"); - - auto time_keeper = std::make_shared(); - - time_keeper->add_reporter(&std::cout); - - auto publisher = - node->create_publisher("processing_time", 10); - - time_keeper->add_reporter(publisher); - - auto publisher_str = node->create_publisher("processing_time_str", 10); - - time_keeper->add_reporter(publisher_str); - - auto funcA = [&time_keeper]() { - autoware::universe_utils::ScopedTimeTrack st("funcA", *time_keeper); - std::this_thread::sleep_for(std::chrono::seconds(1)); - }; - - auto funcB = [&time_keeper, &funcA]() { - autoware::universe_utils::ScopedTimeTrack st("funcB", *time_keeper); - std::this_thread::sleep_for(std::chrono::seconds(2)); - funcA(); - }; - - auto funcC = [&time_keeper, &funcB]() { - autoware::universe_utils::ScopedTimeTrack st("funcC", *time_keeper); - std::this_thread::sleep_for(std::chrono::seconds(3)); - funcB(); - }; - - funcC(); - - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} diff --git a/common/autoware_universe_utils/examples/example_time_keeper.cpp b/common/autoware_universe_utils/examples/example_time_keeper.cpp index 3f6037e68daac..c50aa1e1a8342 100644 --- a/common/autoware_universe_utils/examples/example_time_keeper.cpp +++ b/common/autoware_universe_utils/examples/example_time_keeper.cpp @@ -15,49 +15,63 @@ #include +#include + +#include #include #include +#include -int main(int argc, char ** argv) +class ExampleNode : public rclcpp::Node { - rclcpp::init(argc, argv); - auto node = std::make_shared("time_keeper_example"); - - auto time_keeper = std::make_shared(); - - time_keeper->add_reporter(&std::cout); +public: + ExampleNode() : Node("time_keeper_example") + { + publisher_ = + create_publisher("processing_time", 1); - auto publisher = - node->create_publisher("processing_time", 10); + time_keeper_ = std::make_shared(publisher_, &std::cerr); + // You can also add a reporter later by add_reporter. + // time_keeper_->add_reporter(publisher_); + // time_keeper_->add_reporter(&std::cerr); - time_keeper->add_reporter(publisher); + timer_ = create_wall_timer(std::chrono::seconds(1), std::bind(&ExampleNode::func_a, this)); + } - auto publisher_str = node->create_publisher("processing_time_str", 10); +private: + std::shared_ptr time_keeper_; + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Publisher::SharedPtr publisher_str_; + rclcpp::TimerBase::SharedPtr timer_; - time_keeper->add_reporter(publisher_str); + void func_a() + { + // Start constructing ProcessingTimeTree (because func_a is the root function) + autoware::universe_utils::ScopedTimeTrack st("func_a", *time_keeper_); + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + func_b(); + // End constructing ProcessingTimeTree. After this, the tree will be reported (publishing + // message and outputting to std::cerr) + } - auto funcA = [&time_keeper]() { - time_keeper->start_track("funcA"); - std::this_thread::sleep_for(std::chrono::seconds(1)); - time_keeper->end_track("funcA"); - }; + void func_b() + { + autoware::universe_utils::ScopedTimeTrack st("func_b", *time_keeper_); + std::this_thread::sleep_for(std::chrono::milliseconds(2)); + func_c(); + } - auto funcB = [&time_keeper, &funcA]() { - time_keeper->start_track("funcB"); - std::this_thread::sleep_for(std::chrono::seconds(2)); - funcA(); - time_keeper->end_track("funcB"); - }; - - auto funcC = [&time_keeper, &funcB]() { - time_keeper->start_track("funcC"); - std::this_thread::sleep_for(std::chrono::seconds(3)); - funcB(); - time_keeper->end_track("funcC"); - }; - - funcC(); + void func_c() + { + autoware::universe_utils::ScopedTimeTrack st("func_c", *time_keeper_); + std::this_thread::sleep_for(std::chrono::milliseconds(3)); + } +}; +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); rclcpp::spin(node); rclcpp::shutdown(); return 0; diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp index 96070f0f30b77..c635138416aa5 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp @@ -17,14 +17,11 @@ #include "autoware/universe_utils/system/stop_watch.hpp" #include -#include #include #include #include -#include - #include #include #include @@ -134,14 +131,6 @@ class TimeKeeper */ void add_reporter(rclcpp::Publisher::SharedPtr publisher); - /** - * @brief Add a reporter to publish processing times to an rclcpp publisher with - * std_msgs::msg::String - * - * @param publisher Shared pointer to the rclcpp publisher - */ - void add_reporter(rclcpp::Publisher::SharedPtr publisher); - /** * @brief Start tracking the processing time of a function * @@ -187,6 +176,11 @@ class ScopedTimeTrack */ ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper); + ScopedTimeTrack(const ScopedTimeTrack &) = delete; + ScopedTimeTrack & operator=(const ScopedTimeTrack &) = delete; + ScopedTimeTrack(ScopedTimeTrack &&) = delete; + ScopedTimeTrack & operator=(ScopedTimeTrack &&) = delete; + /** * @brief Destroy the ScopedTimeTrack object, ending the tracking of the function */ diff --git a/common/autoware_universe_utils/src/system/time_keeper.cpp b/common/autoware_universe_utils/src/system/time_keeper.cpp index 58bed6677227c..429f063dfc62e 100644 --- a/common/autoware_universe_utils/src/system/time_keeper.cpp +++ b/common/autoware_universe_utils/src/system/time_keeper.cpp @@ -14,7 +14,8 @@ #include "autoware/universe_utils/system/time_keeper.hpp" -#include +#include + #include namespace autoware::universe_utils @@ -67,7 +68,7 @@ tier4_debug_msgs::msg::ProcessingTimeTree ProcessingTimeNode::to_msg() const tier4_debug_msgs::msg::ProcessingTimeNode time_node_msg; time_node_msg.name = node.name_; time_node_msg.processing_time = node.processing_time_; - time_node_msg.id = tree_msg.nodes.size() + 1; + time_node_msg.id = static_cast(tree_msg.nodes.size() + 1); time_node_msg.parent_id = parent_id; tree_msg.nodes.emplace_back(time_node_msg); @@ -112,15 +113,6 @@ void TimeKeeper::add_reporter(rclcpp::Publisher::SharedPtr }); } -void TimeKeeper::add_reporter(rclcpp::Publisher::SharedPtr publisher) -{ - reporters_.emplace_back([publisher](const std::shared_ptr & node) { - std_msgs::msg::String msg; - msg.data = node->to_string(); - publisher->publish(msg); - }); -} - void TimeKeeper::start_track(const std::string & func_name) { if (current_time_node_ == nullptr) { From 5023173eb1bb087def663de88104aa9854808cd6 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 12 Jul 2024 20:06:30 +0900 Subject: [PATCH 020/151] feat(autoware_behavior_path_planner_common,autoware_behavior_path_lane_change_module): add time_keeper to bpp (#8004) * feat(autoware_behavior_path_planner_common,autoware_behavior_path_lane_change_module): add time_keeper to bpp Signed-off-by: Y.Hisaki * update Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../interface.hpp | 2 ++ .../utils/base_class.hpp | 21 +++++++++++++++++-- .../src/interface.cpp | 6 ++++++ .../src/scene.cpp | 17 +++++++++++++++ .../behavior_path_planner/planner_manager.hpp | 2 ++ .../interface/scene_module_interface.hpp | 8 ++++++- .../scene_module_manager_interface.hpp | 5 +++++ 7 files changed, 58 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index 9c014b77a7e82..bd309dd35a260 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -23,6 +23,7 @@ #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include #include #include @@ -108,6 +109,7 @@ class LaneChangeInterface : public SceneModuleInterface const double start_distance, const double finish_distance, const bool safe, const uint8_t & state) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { if (ptr) { ptr->updateCooperateStatus( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index 229f46f89377f..49c8056681e2f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -23,6 +23,7 @@ #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" +#include #include #include @@ -50,7 +51,10 @@ class LaneChangeBase LaneChangeBase( std::shared_ptr parameters, LaneChangeModuleType type, Direction direction) - : lane_change_parameters_{std::move(parameters)}, direction_{direction}, type_{type} + : lane_change_parameters_{std::move(parameters)}, + direction_{direction}, + type_{type}, + time_keeper_(std::make_shared()) { } @@ -151,7 +155,18 @@ class LaneChangeBase bool isValidPath() const { return status_.is_valid_path; } - void setData(const std::shared_ptr & data) { planner_data_ = data; } + void setData(const std::shared_ptr & data) + { + planner_data_ = data; + if (!common_data_ptr_->bpp_param_ptr) { + common_data_ptr_->bpp_param_ptr = + std::make_shared(data->parameters); + } + common_data_ptr_->self_odometry_ptr = data->self_odometry; + common_data_ptr_->route_handler_ptr = data->route_handler; + common_data_ptr_->lc_param_ptr = lane_change_parameters_; + common_data_ptr_->direction = direction_; + } void toNormalState() { current_lane_change_state_ = LaneChangeStates::Normal; } @@ -237,6 +252,8 @@ class LaneChangeBase rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr()); mutable rclcpp::Clock clock_{RCL_ROS_TIME}; + + mutable std::shared_ptr time_keeper_; }; } // namespace autoware::behavior_path_planner #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 0a5b31f9e32d2..b55b41828081e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -21,6 +21,7 @@ #include "autoware/behavior_path_planner_common/marker_utils/utils.hpp" #include +#include #include #include @@ -43,6 +44,7 @@ LaneChangeInterface::LaneChangeInterface( module_type_{std::move(module_type)}, prev_approved_path_{std::make_unique()} { + module_type_->setTimeKeeper(getTimeKeeper()); steering_factor_interface_ptr_ = std::make_unique(&node, name); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } @@ -71,6 +73,7 @@ bool LaneChangeInterface::isExecutionReady() const void LaneChangeInterface::updateData() { + universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper()); module_type_->setPreviousModuleOutput(getPreviousModuleOutput()); module_type_->updateSpecialData(); @@ -94,6 +97,7 @@ void LaneChangeInterface::postProcess() BehaviorModuleOutput LaneChangeInterface::plan() { + universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper()); resetPathCandidate(); resetPathReference(); @@ -165,6 +169,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() CandidateOutput LaneChangeInterface::planCandidate() const { + universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper()); const auto selected_path = module_type_->getLaneChangePath(); if (selected_path.path.points.empty()) { @@ -340,6 +345,7 @@ MarkerArray LaneChangeInterface::getModuleVirtualWall() void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & output) { + universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper()); const auto steering_factor_direction = std::invoke([&]() { if (module_type_->getDirection() == Direction::LEFT) { return SteeringFactor::LEFT; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index ebfa1e7ac260c..3fc64736731f5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -23,6 +23,7 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include +#include #include #include @@ -55,6 +56,7 @@ NormalLaneChange::NormalLaneChange( void NormalLaneChange::updateLaneChangeStatus() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); updateStopTime(); const auto [found_valid_path, found_safe_path] = getSafePath(status_.lane_change_path); @@ -263,6 +265,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const BehaviorModuleOutput NormalLaneChange::generateOutput() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (!status_.is_valid_path) { RCLCPP_DEBUG(logger_, "No valid path found. Returning previous module's path as output."); return prev_module_output_; @@ -308,6 +311,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & dp = planner_data_->drivable_area_expansion_parameters; const auto drivable_lanes = utils::lane_change::generateDrivableLanes( @@ -327,6 +331,7 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) c void NormalLaneChange::insertStopPoint( const lanelet::ConstLanelets & lanelets, PathWithLaneId & path) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (lanelets.empty()) { return; } @@ -468,6 +473,7 @@ void NormalLaneChange::insertStopPoint( PathWithLaneId NormalLaneChange::getReferencePath() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); lanelet::ConstLanelet closest_lanelet; if (!lanelet::utils::query::getClosestLanelet( status_.lane_change_path.info.target_lanes, getEgoPose(), &closest_lanelet)) { @@ -482,6 +488,7 @@ PathWithLaneId NormalLaneChange::getReferencePath() const std::optional NormalLaneChange::extendPath() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto path = status_.lane_change_path.path; const auto lc_start_point = status_.lane_change_path.info.lane_changing_start.position; @@ -560,6 +567,7 @@ void NormalLaneChange::resetParameters() TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & pose = getEgoPose(); const auto & current_lanes = status_.current_lanes; const auto & shift_line = status_.lane_change_path.info.shift_line; @@ -584,6 +592,7 @@ lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const lanelet::ConstLanelets NormalLaneChange::getLaneChangeLanes( const lanelet::ConstLanelets & current_lanes, Direction direction) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (current_lanes.empty()) { return {}; } @@ -1832,6 +1841,7 @@ PathSafetyStatus NormalLaneChange::evaluateApprovedPathWithUnsafeHysteresis( bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & route_handler = planner_data_->route_handler; const auto & dp = planner_data_->drivable_area_expansion_parameters; @@ -1869,6 +1879,7 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto threshold = lane_change_parameters_->backward_length_buffer_for_end_of_lane; if ( isNearEndOfCurrentLanes(status_.current_lanes, status_.target_lanes, threshold) && @@ -1882,6 +1893,7 @@ bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) bool NormalLaneChange::calcAbortPath() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & route_handler = getRouteHandler(); const auto & common_param = getCommonParam(); const auto current_velocity = @@ -2025,6 +2037,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); PathSafetyStatus path_safety_status; if (collision_check_objects.empty()) { @@ -2108,6 +2121,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( bool NormalLaneChange::isVehicleStuck( const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // Ego is still moving, not in stuck if (std::abs(getEgoVelocity()) > lane_change_parameters_->stop_velocity_threshold) { RCLCPP_DEBUG(logger_, "Ego is still moving, not in stuck"); @@ -2163,6 +2177,7 @@ bool NormalLaneChange::isVehicleStuck( double NormalLaneChange::get_max_velocity_for_safety_check() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto external_velocity_limit_ptr = planner_data_->external_limit_max_velocity; if (external_velocity_limit_ptr) { return std::min( @@ -2174,6 +2189,7 @@ double NormalLaneChange::get_max_velocity_for_safety_check() const bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (current_lanes.empty()) { lane_change_debug_.is_stuck = false; return false; // can not check @@ -2208,6 +2224,7 @@ void NormalLaneChange::setStopPose(const Pose & stop_pose) void NormalLaneChange::updateStopTime() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto current_vel = getEgoVelocity(); if (std::abs(current_vel) > lane_change_parameters_->stop_velocity_threshold) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp index a76284b70b7d8..3a9aa9cafbcca 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp @@ -21,6 +21,7 @@ #include "autoware/universe_utils/ros/debug_publisher.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" +#include #include #include @@ -277,6 +278,7 @@ class PlannerManager const SceneModulePtr & module_ptr, const std::shared_ptr & planner_data, const BehaviorModuleOutput & previous_module_output) const { + universe_utils::ScopedTimeTrack st(module_ptr->name() + "=>run", *module_ptr->getTimeKeeper()); stop_watch_.tic(module_ptr->name()); module_ptr->setData(planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index d11c3181526d2..95eb82e0b4c23 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -31,6 +31,7 @@ #include #include #include +#include #include #include @@ -97,7 +98,8 @@ class SceneModuleInterface objects_of_interest_marker_interface_ptr_map_( std::move(objects_of_interest_marker_interface_ptr_map)), steering_factor_interface_ptr_( - std::make_unique(&node, utils::convertToSnakeCase(name))) + std::make_unique(&node, utils::convertToSnakeCase(name))), + time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { uuid_map_.emplace(module_name, generateUUID()); @@ -244,6 +246,8 @@ class SceneModuleInterface previous_module_output_ = previous_module_output; } + std::shared_ptr getTimeKeeper() const { return time_keeper_; } + /** * @brief set planner data */ @@ -641,6 +645,8 @@ class SceneModuleInterface mutable MarkerArray debug_marker_; mutable MarkerArray drivable_lanes_marker_; + + mutable std::shared_ptr time_keeper_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 5b9c0389e29c5..82a364a9c37c7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -85,6 +85,7 @@ class SceneModuleManagerInterface observer.lock()->setData(planner_data_); observer.lock()->setPreviousModuleOutput(previous_module_output); + observer.lock()->getTimeKeeper()->add_reporter(this->pub_processing_time_); observer.lock()->onEntry(); observers_.push_back(observer); @@ -310,6 +311,8 @@ class SceneModuleManagerInterface pub_debug_marker_ = node->create_publisher("~/debug/" + name_, 20); pub_virtual_wall_ = node->create_publisher("~/virtual_wall/" + name_, 20); pub_drivable_lanes_ = node->create_publisher("~/drivable_lanes/" + name_, 20); + pub_processing_time_ = node->create_publisher( + "~/processing_time/" + name_, 20); } // misc @@ -330,6 +333,8 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_drivable_lanes_; + rclcpp::Publisher::SharedPtr pub_processing_time_; + std::string name_; std::shared_ptr planner_data_; From 2d9db5c6ea6885c314ae89d00948f55bbce869dc Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 13 Jul 2024 14:27:11 +0900 Subject: [PATCH 021/151] feat(velocity_smoother): add time_keeper (#8026) Signed-off-by: Takayuki Murooka --- .../autoware/velocity_smoother/node.hpp | 5 +++ .../analytical_jerk_constrained_smoother.hpp | 6 +++- .../smoother/jerk_filtered_smoother.hpp | 5 ++- .../smoother/l2_pseudo_jerk_smoother.hpp | 5 ++- .../smoother/linf_pseudo_jerk_smoother.hpp | 5 ++- .../smoother/smoother_base.hpp | 6 +++- .../autoware_velocity_smoother/src/node.cpp | 35 ++++++++++++++++--- .../analytical_jerk_constrained_smoother.cpp | 5 +-- .../src/smoother/jerk_filtered_smoother.cpp | 20 ++++++++++- .../src/smoother/l2_pseudo_jerk_smoother.cpp | 4 ++- .../smoother/linf_pseudo_jerk_smoother.cpp | 4 ++- .../src/smoother/smoother_base.cpp | 8 ++++- 12 files changed, 93 insertions(+), 15 deletions(-) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index 0dd18615be5ef..26918cce24549 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -23,6 +23,7 @@ #include "autoware/universe_utils/ros/polling_subscriber.hpp" #include "autoware/universe_utils/ros/self_pose_listener.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/resample.hpp" #include "autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" #include "autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp" @@ -260,6 +261,8 @@ class VelocitySmootherNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_closest_jerk_; rclcpp::Publisher::SharedPtr debug_calculation_time_; rclcpp::Publisher::SharedPtr debug_closest_max_velocity_; + rclcpp::Publisher::SharedPtr + debug_processing_time_detail_; // For Jerk Filtered Algorithm Debug rclcpp::Publisher::SharedPtr pub_forward_filtered_trajectory_; @@ -275,6 +278,8 @@ class VelocitySmootherNode : public rclcpp::Node std::unique_ptr logger_configure_; std::unique_ptr published_time_publisher_; + + mutable std::shared_ptr time_keeper_{nullptr}; }; } // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp index 42d5a520c9e44..bbc3828bb1b15 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT #include "autoware/motion_utils/trajectory/trajectory.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp" #include "autoware/velocity_smoother/smoother/smoother_base.hpp" #include "rclcpp/rclcpp.hpp" @@ -24,6 +25,7 @@ #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/pose.hpp" +#include #include #include #include @@ -65,7 +67,9 @@ class AnalyticalJerkConstrainedSmoother : public SmootherBase } backward; }; - explicit AnalyticalJerkConstrainedSmoother(rclcpp::Node & node); + explicit AnalyticalJerkConstrainedSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper = + std::make_shared()); bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp index 14d0d8ab7ff84..06a6f2da7f30a 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp @@ -17,6 +17,7 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/smoother/smoother_base.hpp" #include "osqp_interface/osqp_interface.hpp" @@ -24,6 +25,7 @@ #include "boost/optional.hpp" +#include #include namespace autoware::velocity_smoother @@ -40,7 +42,8 @@ class JerkFilteredSmoother : public SmootherBase double jerk_filter_ds; }; - explicit JerkFilteredSmoother(rclcpp::Node & node); + explicit JerkFilteredSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper); bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp index 1e2918d8e313b..a2a07ec6909aa 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp @@ -17,6 +17,7 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/smoother/smoother_base.hpp" #include "osqp_interface/osqp_interface.hpp" @@ -24,6 +25,7 @@ #include "boost/optional.hpp" +#include #include namespace autoware::velocity_smoother @@ -38,7 +40,8 @@ class L2PseudoJerkSmoother : public SmootherBase double over_a_weight; }; - explicit L2PseudoJerkSmoother(rclcpp::Node & node); + explicit L2PseudoJerkSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper); bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp index b88cd26eb4467..7c46a53431608 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp @@ -17,6 +17,7 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/smoother/smoother_base.hpp" #include "osqp_interface/osqp_interface.hpp" @@ -24,6 +25,7 @@ #include "boost/optional.hpp" +#include #include namespace autoware::velocity_smoother @@ -38,7 +40,8 @@ class LinfPseudoJerkSmoother : public SmootherBase double over_a_weight; }; - explicit LinfPseudoJerkSmoother(rclcpp::Node & node); + explicit LinfPseudoJerkSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper); bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp index be7baf694d361..6671eaa3eabe7 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp @@ -15,12 +15,14 @@ #ifndef AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_ #define AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_ +#include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/resample.hpp" #include "rclcpp/rclcpp.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include +#include #include namespace autoware::velocity_smoother @@ -54,7 +56,8 @@ class SmootherBase resampling::ResampleParam resample_param; }; - explicit SmootherBase(rclcpp::Node & node); + explicit SmootherBase( + rclcpp::Node & node, const std::shared_ptr time_keeper); virtual ~SmootherBase() = default; virtual bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, @@ -85,6 +88,7 @@ class SmootherBase protected: BaseParam base_param_; + mutable std::shared_ptr time_keeper_{nullptr}; }; } // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index aefbd9ef20f84..3640c93d2d807 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -46,6 +46,13 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti initCommonParam(); over_stop_velocity_warn_thr_ = declare_parameter("over_stop_velocity_warn_thr"); + // create time_keeper and its publisher + // NOTE: This has to be called before setupSmoother to pass the time_keeper to the smoother. + debug_processing_time_detail_ = create_publisher( + "~/debug/processing_time_detail_ms", 1); + time_keeper_ = + std::make_shared(debug_processing_time_detail_); + // create smoother setupSmoother(wheelbase_); @@ -99,7 +106,7 @@ void VelocitySmootherNode::setupSmoother(const double wheelbase) { switch (node_param_.algorithm_type) { case AlgorithmType::JERK_FILTERED: { - smoother_ = std::make_shared(*this); + smoother_ = std::make_shared(*this, time_keeper_); // Set Publisher for jerk filtered algorithm pub_forward_filtered_trajectory_ = @@ -113,15 +120,15 @@ void VelocitySmootherNode::setupSmoother(const double wheelbase) break; } case AlgorithmType::L2: { - smoother_ = std::make_shared(*this); + smoother_ = std::make_shared(*this, time_keeper_); break; } case AlgorithmType::LINF: { - smoother_ = std::make_shared(*this); + smoother_ = std::make_shared(*this, time_keeper_); break; } case AlgorithmType::ANALYTICAL: { - smoother_ = std::make_shared(*this); + smoother_ = std::make_shared(*this, time_keeper_); break; } default: @@ -309,6 +316,8 @@ void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory void VelocitySmootherNode::calcExternalVelocityLimit() { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!external_velocity_limit_ptr_) { return; } @@ -414,6 +423,8 @@ bool VelocitySmootherNode::checkData() const void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr msg) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + RCLCPP_DEBUG(get_logger(), "========================= run start ========================="); stop_watch_.tic(); @@ -505,6 +516,8 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr void VelocitySmootherNode::updateDataForExternalVelocityLimit() { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (prev_output_.empty()) { return; } @@ -522,6 +535,8 @@ void VelocitySmootherNode::updateDataForExternalVelocityLimit() TrajectoryPoints VelocitySmootherNode::calcTrajectoryVelocity( const TrajectoryPoints & traj_input) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + TrajectoryPoints output{}; // velocity is optimized by qp solver // Extract trajectory around self-position with desired forward-backward length @@ -569,6 +584,8 @@ bool VelocitySmootherNode::smoothVelocity( const TrajectoryPoints & input, const size_t input_closest, TrajectoryPoints & traj_smoothed) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (input.empty()) { return false; // cannot apply smoothing } @@ -675,6 +692,8 @@ bool VelocitySmootherNode::smoothVelocity( void VelocitySmootherNode::insertBehindVelocity( const size_t output_closest, const InitializeType type, TrajectoryPoints & output) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const bool keep_closest_vel_for_behind = (type == InitializeType::EGO_VELOCITY || type == InitializeType::LARGE_DEVIATION_REPLAN || type == InitializeType::ENGAGING); @@ -737,6 +756,8 @@ void VelocitySmootherNode::publishStopDistance(const TrajectoryPoints & trajecto std::pair VelocitySmootherNode::calcInitialMotion( const TrajectoryPoints & input_traj, const size_t input_closest) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const double vehicle_speed = std::fabs(current_odometry_ptr_->twist.twist.linear.x); const double vehicle_acceleration = current_acceleration_ptr_->accel.accel.linear.x; const double target_vel = std::fabs(input_traj.at(input_closest).longitudinal_velocity_mps); @@ -820,6 +841,8 @@ std::pair VelocitySmootherNode::ca void VelocitySmootherNode::overwriteStopPoint( const TrajectoryPoints & input, TrajectoryPoints & output) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex(input); if (!stop_idx) { return; @@ -866,6 +889,8 @@ void VelocitySmootherNode::overwriteStopPoint( void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (traj.size() < 1) { return; } @@ -905,6 +930,8 @@ void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) c void VelocitySmootherNode::applyStopApproachingVelocity(TrajectoryPoints & traj) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex(traj); if (!stop_idx) { return; // no stop point. diff --git a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp index 7f263fdea5e36..3906222454d35 100644 --- a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp @@ -66,8 +66,9 @@ bool applyMaxVelocity( namespace autoware::velocity_smoother { -AnalyticalJerkConstrainedSmoother::AnalyticalJerkConstrainedSmoother(rclcpp::Node & node) -: SmootherBase(node) +AnalyticalJerkConstrainedSmoother::AnalyticalJerkConstrainedSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper) +: SmootherBase(node, time_keeper) { auto & p = smoother_param_; p.resample.ds_resample = node.declare_parameter("resample.ds_resample"); diff --git a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp index cab8e49a3b45d..d458c688d060c 100644 --- a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -29,7 +29,9 @@ namespace autoware::velocity_smoother { -JerkFilteredSmoother::JerkFilteredSmoother(rclcpp::Node & node) : SmootherBase(node) +JerkFilteredSmoother::JerkFilteredSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper) +: SmootherBase(node, time_keeper) { auto & p = smoother_param_; p.jerk_weight = node.declare_parameter("jerk_weight"); @@ -59,6 +61,8 @@ bool JerkFilteredSmoother::apply( const double v0, const double a0, const TrajectoryPoints & input, TrajectoryPoints & output, std::vector & debug_trajectories) { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + output = input; if (input.empty()) { @@ -102,6 +106,8 @@ bool JerkFilteredSmoother::apply( const auto initial_traj_pose = filtered.front().pose; const auto resample = [&](const auto & trajectory) { + autoware::universe_utils::ScopedTimeTrack st("resample", *time_keeper_); + return resampling::resampleTrajectory( trajectory, v0, initial_traj_pose, std::numeric_limits::max(), std::numeric_limits::max(), base_param_.resample_param); @@ -152,6 +158,7 @@ bool JerkFilteredSmoother::apply( v_max_arr.at(i) = opt_resampled_trajectory.at(i).longitudinal_velocity_mps; } + time_keeper_->start_track("initOptimization"); /* * x = [ * b[0], b[1], ..., b[N], : 0~N @@ -290,9 +297,12 @@ bool JerkFilteredSmoother::apply( lower_bound[constr_idx] = a0; ++constr_idx; } + time_keeper_->end_track("initOptimization"); // execute optimization + time_keeper_->start_track("optimize"); const auto result = qp_solver_.optimize(P, A, q, lower_bound, upper_bound); + time_keeper_->end_track("optimize"); const std::vector optval = std::get<0>(result); const int status_val = std::get<3>(result); if (status_val != 1) { @@ -356,6 +366,8 @@ TrajectoryPoints JerkFilteredSmoother::forwardJerkFilter( const double v0, const double a0, const double a_max, const double a_start, const double j_max, const TrajectoryPoints & input) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + auto applyLimits = [&input, &a_start](double & v, double & a, size_t i) { double v_lim = input.at(i).longitudinal_velocity_mps; static constexpr double ep = 1.0e-5; @@ -408,6 +420,8 @@ TrajectoryPoints JerkFilteredSmoother::backwardJerkFilter( const double v0, const double a0, const double a_min, const double a_stop, const double j_min, const TrajectoryPoints & input) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + auto input_rev = input; std::reverse(input_rev.begin(), input_rev.end()); auto filtered = forwardJerkFilter( @@ -423,6 +437,8 @@ TrajectoryPoints JerkFilteredSmoother::mergeFilteredTrajectory( const double v0, const double a0, const double a_min, const double j_min, const TrajectoryPoints & forward_filtered, const TrajectoryPoints & backward_filtered) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + TrajectoryPoints merged; merged = forward_filtered; @@ -475,6 +491,8 @@ TrajectoryPoints JerkFilteredSmoother::resampleTrajectory( const geometry_msgs::msg::Pose & current_pose, const double nearest_dist_threshold, const double nearest_yaw_threshold) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + return resampling::resampleTrajectory( input, current_pose, nearest_dist_threshold, nearest_yaw_threshold, base_param_.resample_param, smoother_param_.jerk_filter_ds); diff --git a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp index b489c994b0495..f379b217187c9 100644 --- a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp @@ -25,7 +25,9 @@ namespace autoware::velocity_smoother { -L2PseudoJerkSmoother::L2PseudoJerkSmoother(rclcpp::Node & node) : SmootherBase(node) +L2PseudoJerkSmoother::L2PseudoJerkSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper) +: SmootherBase(node, time_keeper) { auto & p = smoother_param_; p.pseudo_jerk_weight = node.declare_parameter("pseudo_jerk_weight"); diff --git a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp index cb8451dba8302..2ab3d6dd80dfc 100644 --- a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp @@ -25,7 +25,9 @@ namespace autoware::velocity_smoother { -LinfPseudoJerkSmoother::LinfPseudoJerkSmoother(rclcpp::Node & node) : SmootherBase(node) +LinfPseudoJerkSmoother::LinfPseudoJerkSmoother( + rclcpp::Node & node, const std::shared_ptr time_keeper) +: SmootherBase(node, time_keeper) { auto & p = smoother_param_; p.pseudo_jerk_weight = node.declare_parameter("pseudo_jerk_weight"); diff --git a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp index 700cf45b7eb9d..46faf10fe4a62 100644 --- a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp @@ -60,7 +60,9 @@ TrajectoryPoints applyPreProcess( } } // namespace -SmootherBase::SmootherBase(rclcpp::Node & node) +SmootherBase::SmootherBase( + rclcpp::Node & node, const std::shared_ptr time_keeper) +: time_keeper_(time_keeper) { auto & p = base_param_; p.max_accel = node.declare_parameter("normal.max_acc"); @@ -130,6 +132,8 @@ TrajectoryPoints SmootherBase::applyLateralAccelerationFilter( [[maybe_unused]] const double a0, [[maybe_unused]] const bool enable_smooth_limit, const bool use_resampling, const double input_points_interval) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (input.size() < 3) { return input; // cannot calculate lateral acc. do nothing. } @@ -198,6 +202,8 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit( const TrajectoryPoints & input, const bool use_resampling, const double input_points_interval) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (input.size() < 3) { return input; // cannot calculate the desired velocity. do nothing. } From 780f9789de715848e57cfe3747fcdc7d81910f95 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 16 Jul 2024 19:30:24 +0900 Subject: [PATCH 022/151] feat(static_obstacle_avoidance): integrate time keeper to major functions (#8044) Signed-off-by: satoshi-ota Signed-off-by: Y.Hisaki --- .../src/scene.cpp | 42 ++++++++++++++++++- 1 file changed, 40 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 824466a1ad3ad..1d8e7ea6ce503 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -24,6 +24,7 @@ #include "autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp" +#include #include #include @@ -194,6 +195,7 @@ bool StaticObstacleAvoidanceModule::canTransitSuccessState() void StaticObstacleAvoidanceModule::fillFundamentalData( AvoidancePlanningData & data, DebugData & debug) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // reference pose data.reference_pose = utils::getUnshiftedEgoPose(getEgoPose(), helper_->getPreviousSplineShiftPath()); @@ -308,8 +310,6 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { - using utils::static_obstacle_avoidance::fillAvoidanceNecessity; - using utils::static_obstacle_avoidance::fillObjectStoppableJudge; using utils::static_obstacle_avoidance::filterTargetObjects; using utils::static_obstacle_avoidance::separateObjectsByPath; using utils::static_obstacle_avoidance::updateRoadShoulderDistance; @@ -371,9 +371,25 @@ void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( } } +void StaticObstacleAvoidanceModule::fillAvoidanceTargetData(ObjectDataArray & objects) const +{ + using utils::static_obstacle_avoidance::fillAvoidanceNecessity; + using utils::static_obstacle_avoidance::fillObjectStoppableJudge; + + // Calculate the distance needed to safely decelerate the ego vehicle to a stop line. + const auto & vehicle_width = planner_data_->parameters.vehicle_width; + const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false); + std::for_each(objects.begin(), objects.end(), [&, this](auto & o) { + fillAvoidanceNecessity(o, registered_objects_, vehicle_width, parameters_); + o.to_stop_line = calcDistanceToStopLine(o); + fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_); + }); +} + ObjectData StaticObstacleAvoidanceModule::createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); using boost::geometry::return_centroid; const auto & path_points = data.reference_path.points; @@ -415,6 +431,7 @@ ObjectData StaticObstacleAvoidanceModule::createObjectData( bool StaticObstacleAvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // transit yield maneuver only when the avoidance maneuver is not initiated. if (helper_->isShifted()) { RCLCPP_DEBUG(getLogger(), "avoidance maneuver already initiated."); @@ -468,6 +485,7 @@ bool StaticObstacleAvoidanceModule::canYieldManeuver(const AvoidancePlanningData void StaticObstacleAvoidanceModule::fillShiftLine( AvoidancePlanningData & data, DebugData & debug) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); auto path_shifter = path_shifter_; /** @@ -520,6 +538,7 @@ void StaticObstacleAvoidanceModule::fillShiftLine( void StaticObstacleAvoidanceModule::fillEgoStatus( AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); data.state = getCurrentModuleState(data); /** @@ -614,6 +633,7 @@ void StaticObstacleAvoidanceModule::fillEgoStatus( void StaticObstacleAvoidanceModule::fillDebugData( const AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (!data.stop_target_object) { return; } @@ -694,6 +714,7 @@ void StaticObstacleAvoidanceModule::updateEgoBehavior( bool StaticObstacleAvoidanceModule::isSafePath( ShiftedPath & shifted_path, [[maybe_unused]] DebugData & debug) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & p = planner_data_->parameters; if (!parameters_->enable_safety_check) { @@ -802,6 +823,7 @@ bool StaticObstacleAvoidanceModule::isSafePath( PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( const PathWithLaneId & original_path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto previous_path = helper_->getPreviousReferencePath(); const auto longest_dist_to_shift_point = [&]() { @@ -864,6 +886,7 @@ PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; resetPathCandidate(); @@ -1021,6 +1044,7 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() CandidateOutput StaticObstacleAvoidanceModule::planCandidate() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; CandidateOutput output; @@ -1060,6 +1084,7 @@ CandidateOutput StaticObstacleAvoidanceModule::planCandidate() const BehaviorModuleOutput StaticObstacleAvoidanceModule::planWaitingApproval() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); BehaviorModuleOutput out = plan(); if (path_shifter_.getShiftLines().empty()) { @@ -1116,6 +1141,7 @@ void StaticObstacleAvoidanceModule::updatePathShifter(const AvoidLineArray & shi void StaticObstacleAvoidanceModule::addNewShiftLines( PathShifter & path_shifter, const AvoidLineArray & new_shift_lines) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); ShiftLineArray future = utils::static_obstacle_avoidance::toShiftLineArray(new_shift_lines); size_t min_start_idx = std::numeric_limits::max(); @@ -1182,6 +1208,7 @@ void StaticObstacleAvoidanceModule::addNewShiftLines( bool StaticObstacleAvoidanceModule::isValidShiftLine( const AvoidLineArray & shift_lines, const PathShifter & shifter) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (shift_lines.empty()) { return true; } @@ -1257,6 +1284,7 @@ bool StaticObstacleAvoidanceModule::isValidShiftLine( void StaticObstacleAvoidanceModule::updateData() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); using utils::static_obstacle_avoidance::toShiftedPath; helper_->setData(planner_data_); @@ -1341,6 +1369,7 @@ void StaticObstacleAvoidanceModule::initRTCStatus() void StaticObstacleAvoidanceModule::updateRTCData() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; updateRegisteredRTCStatus(helper_->getPreviousSplineShiftPath().path); @@ -1376,6 +1405,8 @@ void StaticObstacleAvoidanceModule::updateRTCData() void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { + using utils::static_obstacle_avoidance::createAmbiguousObjectsMarkerArray; + using utils::static_obstacle_avoidance::createStopTargetObjectMarkerArray; using utils::static_obstacle_avoidance::createTargetObjectsMarkerArray; info_marker_.markers.clear(); @@ -1386,6 +1417,7 @@ void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData void StaticObstacleAvoidanceModule::updateDebugMarker( const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); debug_marker_.markers.clear(); debug_marker_ = utils::static_obstacle_avoidance::createDebugMarkerArray(data, shifter, debug, parameters_); @@ -1410,6 +1442,7 @@ void StaticObstacleAvoidanceModule::updateAvoidanceDebugData( double StaticObstacleAvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & p = parameters_; const auto & vehicle_width = planner_data_->parameters.vehicle_width; @@ -1451,6 +1484,7 @@ double StaticObstacleAvoidanceModule::calcDistanceToStopLine(const ObjectData & void StaticObstacleAvoidanceModule::insertReturnDeadLine( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; if (data.to_return_point > planner_data_->parameters.forward_path_length) { @@ -1528,6 +1562,7 @@ void StaticObstacleAvoidanceModule::insertReturnDeadLine( void StaticObstacleAvoidanceModule::insertWaitPoint( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; // If avoidance path is NOT valid, don't insert any stop points. @@ -1576,6 +1611,7 @@ void StaticObstacleAvoidanceModule::insertWaitPoint( void StaticObstacleAvoidanceModule::insertStopPoint( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; if (data.safe) { @@ -1623,6 +1659,7 @@ void StaticObstacleAvoidanceModule::insertStopPoint( void StaticObstacleAvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; // If avoidance path is NOT safe, don't insert any slow down sections. @@ -1735,6 +1772,7 @@ void StaticObstacleAvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_ void StaticObstacleAvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & data = avoid_data_; // do nothing if no shift line is approved. From b49bb5af5a10fd0c813452e62b4c55aae5679b5b Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 17 Jul 2024 16:35:37 +0900 Subject: [PATCH 023/151] feat(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_stop_line_module): add time_keeper to bvp (#8070) Signed-off-by: Y.Hisaki --- .../scene_module_interface.hpp | 14 ++++++++++++++ .../src/scene_module_interface.cpp | 13 ++++++++++++- .../src/scene.cpp | 10 +++++++++- 3 files changed, 35 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index b09f00ce367dc..29f3794516ef5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -42,6 +43,7 @@ #include // Debug +#include #include #include @@ -106,6 +108,13 @@ class SceneModuleInterface infrastructure_command_ = command; } + void setTimeKeeper(const std::shared_ptr & time_keeper) + { + time_keeper_ = time_keeper; + } + + std::shared_ptr getTimeKeeper() { return time_keeper_; } + std::optional getFirstStopPathPointIndex() { return first_stop_path_point_index_; } void setActivation(const bool activated) { activated_ = activated; } @@ -132,6 +141,7 @@ class SceneModuleInterface std::optional first_stop_path_point_index_; autoware::motion_utils::VelocityFactorInterface velocity_factor_; std::vector objects_of_interest_; + mutable std::shared_ptr time_keeper_; void setSafe(const bool safe) { @@ -215,6 +225,10 @@ class SceneModuleManagerInterface pub_infrastructure_commands_; std::shared_ptr processing_time_publisher_; + + rclcpp::Publisher::SharedPtr pub_processing_time_detail_; + + std::shared_ptr time_keeper_; }; class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index a0f30cd3e33cb..350bc439a4a41 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -17,9 +17,11 @@ #include #include #include +#include #include #include +#include namespace autoware::behavior_velocity_planner { @@ -33,7 +35,8 @@ SceneModuleInterface::SceneModuleInterface( safe_(false), distance_(std::numeric_limits::lowest()), logger_(logger), - clock_(clock) + clock_(clock), + time_keeper_(std::shared_ptr()) { } @@ -71,6 +74,11 @@ SceneModuleManagerInterface::SceneModuleManagerInterface( "~/output/infrastructure_commands", 1); processing_time_publisher_ = std::make_shared(&node, "~/debug"); + + pub_processing_time_detail_ = node.create_publisher( + "~/debug/processing_time_detail_ms/" + std::string(module_name), 1); + + time_keeper_ = std::make_shared(pub_processing_time_detail_); } size_t SceneModuleManagerInterface::findEgoSegmentIndex( @@ -94,6 +102,8 @@ void SceneModuleManagerInterface::updateSceneModuleInstances( void SceneModuleManagerInterface::modifyPathVelocity( tier4_planning_msgs::msg::PathWithLaneId * path) { + universe_utils::ScopedTimeTrack st( + "SceneModuleManagerInterface::modifyPathVelocity", *time_keeper_); StopWatch stop_watch; stop_watch.tic("Total"); visualization_msgs::msg::MarkerArray debug_marker_array; @@ -177,6 +187,7 @@ void SceneModuleManagerInterface::registerModule( RCLCPP_DEBUG( logger_, "register task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); registered_module_id_set_.emplace(scene_module->getModuleId()); + scene_module->setTimeKeeper(time_keeper_); scene_modules_.insert(scene_module); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 6075706a672d0..e3b585af4fb8b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -40,6 +41,8 @@ StopLineModule::StopLineModule( bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) { + universe_utils::ScopedTimeTrack st( + std::string(__func__) + " (lane_id:=" + std::to_string(module_id_) + ")", *getTimeKeeper()); debug_data_ = DebugData(); if (path->points.empty()) return true; const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -50,11 +53,12 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop const LineString2d stop_line = planning_utils::extendLine( stop_line_[0], stop_line_[1], planner_data_->stop_line_extend_length); + time_keeper_->start_track("createTargetPoint"); // Calculate stop pose and insert index const auto stop_point = arc_lane_utils::createTargetPoint( *path, stop_line, lane_id_, planner_param_.stop_margin, planner_data_->vehicle_info_.max_longitudinal_offset_m); - + time_keeper_->end_track("createTargetPoint"); // If no collision found, do nothing if (!stop_point) { RCLCPP_DEBUG_THROTTLE(logger_, *clock_, 5000 /* ms */, "is no collision"); @@ -70,12 +74,16 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop * |----------------------------| * s---ego----------x--|--------g */ + time_keeper_->start_track( + "calcSegmentIndexFromPointIndex & findEgoSegmentIndex & calcSignedArcLength"); const size_t stop_line_seg_idx = planning_utils::calcSegmentIndexFromPointIndex( path->points, stop_pose.position, stop_point_idx); const size_t current_seg_idx = findEgoSegmentIndex(path->points); const double signed_arc_dist_to_stop_point = autoware::motion_utils::calcSignedArcLength( path->points, planner_data_->current_odometry->pose.position, current_seg_idx, stop_pose.position, stop_line_seg_idx); + time_keeper_->end_track( + "calcSegmentIndexFromPointIndex & findEgoSegmentIndex & calcSignedArcLength"); switch (state_) { case State::APPROACH: { // Insert stop pose From 843add6a73a6152f0be2e72b4ce31df18dce9e97 Mon Sep 17 00:00:00 2001 From: "Y.Hisaki" Date: Fri, 19 Jul 2024 17:09:59 +0900 Subject: [PATCH 024/151] resolve errors Signed-off-by: Y.Hisaki --- .../utils/base_class.hpp | 14 ++++---------- .../src/scene.cpp | 19 ++----------------- 2 files changed, 6 insertions(+), 27 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index 49c8056681e2f..be1f328fd89df 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -155,17 +155,11 @@ class LaneChangeBase bool isValidPath() const { return status_.is_valid_path; } - void setData(const std::shared_ptr & data) + void setData(const std::shared_ptr & data) { planner_data_ = data; } + + void setTimeKeeper(const std::shared_ptr & time_keeper) { - planner_data_ = data; - if (!common_data_ptr_->bpp_param_ptr) { - common_data_ptr_->bpp_param_ptr = - std::make_shared(data->parameters); - } - common_data_ptr_->self_odometry_ptr = data->self_odometry; - common_data_ptr_->route_handler_ptr = data->route_handler; - common_data_ptr_->lc_param_ptr = lane_change_parameters_; - common_data_ptr_->direction = direction_; + time_keeper_ = time_keeper; } void toNormalState() { current_lane_change_state_ = LaneChangeStates::Normal; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 1d8e7ea6ce503..b7ab41ec99abd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -310,6 +310,8 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { + using utils::static_obstacle_avoidance::fillAvoidanceNecessity; + using utils::static_obstacle_avoidance::fillObjectStoppableJudge; using utils::static_obstacle_avoidance::filterTargetObjects; using utils::static_obstacle_avoidance::separateObjectsByPath; using utils::static_obstacle_avoidance::updateRoadShoulderDistance; @@ -371,21 +373,6 @@ void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( } } -void StaticObstacleAvoidanceModule::fillAvoidanceTargetData(ObjectDataArray & objects) const -{ - using utils::static_obstacle_avoidance::fillAvoidanceNecessity; - using utils::static_obstacle_avoidance::fillObjectStoppableJudge; - - // Calculate the distance needed to safely decelerate the ego vehicle to a stop line. - const auto & vehicle_width = planner_data_->parameters.vehicle_width; - const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false); - std::for_each(objects.begin(), objects.end(), [&, this](auto & o) { - fillAvoidanceNecessity(o, registered_objects_, vehicle_width, parameters_); - o.to_stop_line = calcDistanceToStopLine(o); - fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_); - }); -} - ObjectData StaticObstacleAvoidanceModule::createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const { @@ -1405,8 +1392,6 @@ void StaticObstacleAvoidanceModule::updateRTCData() void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { - using utils::static_obstacle_avoidance::createAmbiguousObjectsMarkerArray; - using utils::static_obstacle_avoidance::createStopTargetObjectMarkerArray; using utils::static_obstacle_avoidance::createTargetObjectsMarkerArray; info_marker_.markers.clear(); From 6ee3d273ef5223ecb6c944d3ffd8eee686de3db0 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 4 Jul 2024 16:50:34 +0900 Subject: [PATCH 025/151] feat(goal_planner): prioritize pull over path by curvature (#7791) * feat(goal_planner): prioritize pull over path by curvature Signed-off-by: kosuke55 fix Signed-off-by: kosuke55 * add comment * pre commit Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Mamoru Sobue --- .../config/goal_planner.param.yaml | 1 + .../goal_planner_parameters.hpp | 1 + .../pull_over_planner_base.hpp | 2 + .../src/goal_planner_module.cpp | 121 +++++++++++++----- .../src/manager.cpp | 1 + 5 files changed, 92 insertions(+), 34 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml index 53e06631a81d5..e6f84e7eece0c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml @@ -22,6 +22,7 @@ lateral_offset_interval: 0.25 ignore_distance_from_lane_start: 0.0 margin_from_boundary: 0.5 + high_curvature_threshold: 0.1 # occupancy grid map occupancy_grid: diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp index bdb267ce223d3..6a10c0fb183f6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp @@ -60,6 +60,7 @@ struct GoalPlannerParameters double lateral_offset_interval{0.0}; double ignore_distance_from_lane_start{0.0}; double margin_from_boundary{0.0}; + double high_curvature_threshold{0.0}; // occupancy grid map bool use_occupancy_grid_for_goal_search{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp index d2ba416c7fa90..05385600926f5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -52,6 +52,7 @@ struct PullOverPath size_t goal_id{}; size_t id{}; bool decided_velocity{false}; + double max_curvature{0.0}; // max curvature of the parking path PathWithLaneId getFullPath() const { @@ -72,6 +73,7 @@ struct PullOverPath return path; } + // path from the pull over start pose to the end pose PathWithLaneId getParkingPath() const { const PathWithLaneId full_path = getFullPath(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 6caeb411f6680..dc7a76031a3c1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -293,9 +293,18 @@ void GoalPlannerModule::onTimer() planner->setPlannerData(local_planner_data); planner->setPreviousModuleOutput(previous_module_output); auto pull_over_path = planner->plan(goal_candidate.goal_pose); - if (pull_over_path) { + if (pull_over_path && pull_over_path->getParkingPath().points.size() >= 3) { pull_over_path->goal_id = goal_candidate.id; pull_over_path->id = path_candidates.size(); + + // calculate absolute maximum curvature of parking path(start pose to end pose) for path + // priority + const std::vector curvatures = + autoware::motion_utils::calcCurvature(pull_over_path->getParkingPath().points); + pull_over_path->max_curvature = std::abs(*std::max_element( + curvatures.begin(), curvatures.end(), + [](const double & a, const double & b) { return std::abs(a) < std::abs(b); })); + path_candidates.push_back(*pull_over_path); // calculate closest pull over start pose for stop path const double start_arc_length = @@ -817,23 +826,37 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri const auto debugPrintPathPriority = [this]( const std::vector & sorted_pull_over_path_candidates, - const std::map & goal_id_to_index, - const std::optional> & path_id_to_margin_map_opt = std::nullopt, - const std::optional> & isSoftMarginOpt = - std::nullopt) { + const std::map & goal_id_to_index, const GoalCandidates & goal_candidates, + const std::map & path_id_to_margin_map, + const std::function & isSoftMargin, + const std::function & isHighCurvature) { std::stringstream ss; - ss << "\n---------------------- path priority ----------------------\n"; - for (const auto & path : sorted_pull_over_path_candidates) { - // clang-format off - ss << "path_type: " << magic_enum::enum_name(path.type) - << ", path_id: " << path.id - << ", goal_id: " << path.goal_id - << ", goal_priority:" << goal_id_to_index.at(path.goal_id); - // clang-format on - if (path_id_to_margin_map_opt && isSoftMarginOpt) { - ss << ", margin: " << path_id_to_margin_map_opt->at(path.id) - << ((*isSoftMarginOpt)(path) ? " (soft)" : " (hard)"); + + // unsafe goal and it's priority are not visible as debug marker in rviz, + // so exclude unsafe goal from goal_priority + std::map goal_id_and_priority; + { + int priority = 0; + for (const auto & goal_candidate : goal_candidates) { + goal_id_and_priority[goal_candidate.id] = goal_candidate.is_safe ? priority++ : -1; } + } + + ss << "\n---------------------- path priority ----------------------\n"; + for (size_t i = 0; i < sorted_pull_over_path_candidates.size(); ++i) { + const auto & path = sorted_pull_over_path_candidates[i]; + + // goal_index is same to goal priority including unsafe goal + const int goal_index = static_cast(goal_id_to_index.at(path.goal_id)); + const bool is_safe_goal = goal_candidates[goal_index].is_safe; + const int goal_priority = goal_id_and_priority[path.goal_id]; + + ss << "path_priority: " << i << ", path_type: " << magic_enum::enum_name(path.type) + << ", path_id: " << path.id << ", goal_id: " << path.goal_id + << ", goal_priority: " << (is_safe_goal ? std::to_string(goal_priority) : "unsafe") + << ", margin: " << path_id_to_margin_map.at(path.id) + << (isSoftMargin(path) ? " (soft)" : " (hard)") << ", curvature: " << path.max_curvature + << (isHighCurvature(path) ? " (high)" : " (low)"); ss << "\n"; } ss << "-----------------------------------------------------------\n"; @@ -844,6 +867,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri const auto & soft_margins = parameters_->object_recognition_collision_check_soft_margins; const auto & hard_margins = parameters_->object_recognition_collision_check_hard_margins; + // (1) Sort pull_over_path_candidates based on the order in goal_candidates // Create a map of goal_id to its index in goal_candidates std::map goal_id_to_index; for (size_t i = 0; i < goal_candidates.size(); ++i) { @@ -868,6 +892,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri // if object recognition is enabled, sort by collision check margin if (parameters_->use_object_recognition) { + // (2) Sort by collision check margins const std::vector margins = std::invoke([&]() { std::vector combined_margins = soft_margins; combined_margins.insert(combined_margins.end(), hard_margins.begin(), hard_margins.end()); @@ -914,23 +939,45 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri return path_id_to_margin_map[a.id] > path_id_to_margin_map[b.id]; }); - // Sort pull_over_path_candidates based on the order in efficient_path_order - if (parameters_->path_priority == "efficient_path") { - const auto isSoftMargin = [&](const PullOverPath & path) -> bool { - const double margin = path_id_to_margin_map[path.id]; - return std::any_of( - soft_margins.begin(), soft_margins.end(), - [margin](const double soft_margin) { return std::abs(margin - soft_margin) < 0.01; }); - }; - const auto isSameHardMargin = [&](const PullOverPath & a, const PullOverPath & b) -> bool { - return !isSoftMargin(a) && !isSoftMargin(b) && - std::abs(path_id_to_margin_map[a.id] - path_id_to_margin_map[b.id]) < 0.01; - }; + // (3) Sort by curvature + // If the curvature is less than the threshold, prioritize the path. + const auto isHighCurvature = [&](const PullOverPath & path) -> bool { + return path.max_curvature >= parameters_->high_curvature_threshold; + }; + const auto isSoftMargin = [&](const PullOverPath & path) -> bool { + const double margin = path_id_to_margin_map[path.id]; + return std::any_of( + soft_margins.begin(), soft_margins.end(), + [margin](const double soft_margin) { return std::abs(margin - soft_margin) < 0.01; }); + }; + const auto isSameHardMargin = [&](const PullOverPath & a, const PullOverPath & b) -> bool { + return !isSoftMargin(a) && !isSoftMargin(b) && + std::abs(path_id_to_margin_map[a.id] - path_id_to_margin_map[b.id]) < 0.01; + }; + + // NOTE: this is just partition sort based on curvature threshold within each sub partitions + std::stable_sort( + sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(), + [&](const PullOverPath & a, const PullOverPath & b) { + // if both are soft margin or both are same hard margin, prioritize the path with lower + // curvature. + if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) { + return !isHighCurvature(a) && isHighCurvature(b); + } + // otherwise, keep the order based on the margin. + return false; + }); + + // (4) Sort pull_over_path_candidates based on the order in efficient_path_order keeping the + // collision check margin and curvature priority. + if (parameters_->path_priority == "efficient_path") { std::stable_sort( sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(), [&](const auto & a, const auto & b) { - // if both are soft margin or both are same hard margin, sort by planner priority + // if any of following conditions are met, sort by path type priority + // - both are soft margin + // - both are same hard margin if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) { return comparePathTypePriority(a, b); } @@ -938,18 +985,24 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri return false; }); - // debug print path priority: sorted by efficient_path_order and collision check margin + // debug print path priority sorted by + // - efficient_path_order + // - collision check margin + // - curvature debugPrintPathPriority( - sorted_pull_over_path_candidates, goal_id_to_index, path_id_to_margin_map, isSoftMargin); + sorted_pull_over_path_candidates, goal_id_to_index, goal_candidates, path_id_to_margin_map, + isSoftMargin, isHighCurvature); } } else { - // Sort pull_over_path_candidates based on the order in efficient_path_order + /** + * NOTE: use_object_recognition=false is not recommended. This option will be deprecated in the + * future. sort by curvature is not implemented yet. + * Sort pull_over_path_candidates based on the order in efficient_path_order + */ if (parameters_->path_priority == "efficient_path") { std::stable_sort( sorted_pull_over_path_candidates.begin(), sorted_pull_over_path_candidates.end(), [&](const auto & a, const auto & b) { return comparePathTypePriority(a, b); }); - // debug print path priority: sorted by efficient_path_order and collision check margin - debugPrintPathPriority(sorted_pull_over_path_candidates, goal_id_to_index); } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index b079db9babf31..b86bbbca7d98b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -61,6 +61,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) p.ignore_distance_from_lane_start = node->declare_parameter(ns + "ignore_distance_from_lane_start"); p.margin_from_boundary = node->declare_parameter(ns + "margin_from_boundary"); + p.high_curvature_threshold = node->declare_parameter(ns + "high_curvature_threshold"); const std::string parking_policy_name = node->declare_parameter(ns + "parking_policy"); From bd9038c3c3102ec309d73283d3aeb2a8afefc0bb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 9 Jul 2024 19:07:17 +0900 Subject: [PATCH 026/151] fix(start/goal_planner): fix addition of duplicate segments in calcBeforeShiftedArcLength (#7902) * fix(start/goal_planner): fix addition of duplicate segments in calcBeforeShiftedArcLength Signed-off-by: kosuke55 * Update trajectory.hpp Co-authored-by: Kyoichi Sugahara * Update trajectory.hpp Co-authored-by: Kyoichi Sugahara --------- Signed-off-by: kosuke55 Co-authored-by: Kyoichi Sugahara --- .../motion_utils/trajectory/trajectory.hpp | 49 +++++++++++++------ .../src/trajectory/trajectory.cpp | 12 ++--- .../src/shift_pull_over.cpp | 15 +++++- .../src/shift_pull_out.cpp | 13 ++++- 4 files changed, 63 insertions(+), 26 deletions(-) diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp index da37d04550f5e..126e66772920a 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp @@ -991,34 +991,51 @@ calcCurvature>( * curvature calculation */ template -std::vector> calcCurvatureAndArcLength(const T & points) +std::vector>> calcCurvatureAndSegmentLength( + const T & points) { - // Note that arclength is for the segment, not the sum. - std::vector> curvature_arc_length_vec; - curvature_arc_length_vec.emplace_back(0.0, 0.0); + // segment length is pair of segment length between {p1, p2} and {p2, p3} + std::vector>> curvature_and_segment_length_vec; + curvature_and_segment_length_vec.reserve(points.size()); + curvature_and_segment_length_vec.emplace_back(0.0, std::make_pair(0.0, 0.0)); for (size_t i = 1; i < points.size() - 1; ++i) { const auto p1 = autoware::universe_utils::getPoint(points.at(i - 1)); const auto p2 = autoware::universe_utils::getPoint(points.at(i)); const auto p3 = autoware::universe_utils::getPoint(points.at(i + 1)); const double curvature = autoware::universe_utils::calcCurvature(p1, p2, p3); - const double arc_length = - autoware::universe_utils::calcDistance2d(points.at(i - 1), points.at(i)) + - autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); - curvature_arc_length_vec.emplace_back(curvature, arc_length); + + // The first point has only the next point, so put the distance to that point. + // In other words, assign the first segment length at the second point to the + // second_segment_length at the first point. + if (i == 1) { + curvature_and_segment_length_vec.at(0).second.second = + autoware::universe_utils::calcDistance2d(p1, p2); + } + + // The second_segment_length of the previous point and the first segment length of the current + // point are equal. + const std::pair arc_length{ + curvature_and_segment_length_vec.back().second.second, + autoware::universe_utils::calcDistance2d(p2, p3)}; + + curvature_and_segment_length_vec.emplace_back(curvature, arc_length); } - curvature_arc_length_vec.emplace_back(0.0, 0.0); - return curvature_arc_length_vec; + // set to the last point + curvature_and_segment_length_vec.emplace_back( + 0.0, std::make_pair(curvature_and_segment_length_vec.back().second.second, 0.0)); + + return curvature_and_segment_length_vec; } -extern template std::vector> -calcCurvatureAndArcLength>( +extern template std::vector>> +calcCurvatureAndSegmentLength>( const std::vector & points); -extern template std::vector> -calcCurvatureAndArcLength>( +extern template std::vector>> +calcCurvatureAndSegmentLength>( const std::vector & points); -extern template std::vector> -calcCurvatureAndArcLength>( +extern template std::vector>> +calcCurvatureAndSegmentLength>( const std::vector & points); /** diff --git a/common/autoware_motion_utils/src/trajectory/trajectory.cpp b/common/autoware_motion_utils/src/trajectory/trajectory.cpp index 5d536c0772fea..ce26952c3d634 100644 --- a/common/autoware_motion_utils/src/trajectory/trajectory.cpp +++ b/common/autoware_motion_utils/src/trajectory/trajectory.cpp @@ -238,14 +238,14 @@ calcCurvature>( const std::vector & points); // -template std::vector> -calcCurvatureAndArcLength>( +template std::vector>> +calcCurvatureAndSegmentLength>( const std::vector & points); -template std::vector> -calcCurvatureAndArcLength>( +template std::vector>> +calcCurvatureAndSegmentLength>( const std::vector & points); -template std::vector> -calcCurvatureAndArcLength>( +template std::vector>> +calcCurvatureAndSegmentLength>( const std::vector & points); // diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp index beb27c67833ea..0690f97900cab 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -308,8 +308,19 @@ double ShiftPullOver::calcBeforeShiftedArcLength( double before_arc_length{0.0}; double after_arc_length{0.0}; - for (const auto & [k, segment_length] : - autoware::motion_utils::calcCurvatureAndArcLength(reversed_path.points)) { + + const auto curvature_and_segment_length = + autoware::motion_utils::calcCurvatureAndSegmentLength(reversed_path.points); + + for (size_t i = 0; i < curvature_and_segment_length.size(); ++i) { + const auto & [k, segment_length_pair] = curvature_and_segment_length[i]; + + // If it is the last point, add the lengths of the previous and next segments. + // For other points, only add the length of the previous segment. + const double segment_length = i == curvature_and_segment_length.size() - 1 + ? segment_length_pair.first + : segment_length_pair.first + segment_length_pair.second; + // after shifted segment length const double after_segment_length = k > 0 ? segment_length * (1 + k * dr) : segment_length / (1 - k * dr); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index 971c9a48e8b40..def7072dc0e71 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -423,8 +423,17 @@ double ShiftPullOut::calcBeforeShiftedArcLength( double before_arc_length{0.0}; double after_arc_length{0.0}; - for (const auto & [k, segment_length] : - autoware::motion_utils::calcCurvatureAndArcLength(path.points)) { + const auto curvatures_and_segment_lengths = + autoware::motion_utils::calcCurvatureAndSegmentLength(path.points); + for (size_t i = 0; i < curvatures_and_segment_lengths.size(); ++i) { + const auto & [k, segment_length_pair] = curvatures_and_segment_lengths.at(i); + + // If it is the last point, add the lengths of the previous and next segments. + // For other points, only add the length of the previous segment. + const double segment_length = i == curvatures_and_segment_lengths.size() - 1 + ? segment_length_pair.first + segment_length_pair.second + : segment_length_pair.first; + // after shifted segment length const double after_segment_length = k < 0 ? segment_length * (1 - k * dr) : segment_length / (1 + k * dr); From e553faaf8206e625b369fce04af620d4da62ef70 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 21 Jul 2024 13:18:58 +0900 Subject: [PATCH 027/151] feat(start_planner): check current_pose and estimated_stop_pose for isPreventingRearVehicleFromPassingThrough (#8112) --- .../data_structs.hpp | 3 ++ .../start_planner_module.hpp | 23 +++++++++ .../src/start_planner_module.cpp | 48 +++++++++++++++++-- 3 files changed, 69 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp index 6eea3e3576732..ebdb0869545ca 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp @@ -90,6 +90,9 @@ struct StartPlannerDebugData std::vector start_pose_candidates; size_t selected_start_pose_candidate_index; double margin_for_start_pose_candidate; + + // for isPreventingRearVehicleFromPassingThrough + std::optional estimated_stop_pose; }; struct StartPlannerParameters diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index b07d6497463ef..bb70ae2638056 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -229,8 +229,31 @@ class StartPlannerModule : public SceneModuleInterface bool isModuleRunning() const; bool isCurrentPoseOnMiddleOfTheRoad() const; + + /** + * @brief Check if the ego vehicle is preventing the rear vehicle from passing through. + * + * This function just call isPreventingRearVehicleFromPassingThrough(const Pose & ego_pose) with + * two poses. If rear vehicle is obstructed by ego vehicle at either of the two poses, it returns + * true. + * + * @return true if the ego vehicle is preventing the rear vehicle from passing through with the + * current pose or the pose if it stops. + */ bool isPreventingRearVehicleFromPassingThrough() const; + /** + * @brief Check if the ego vehicle is preventing the rear vehicle from passing through. + * + * This function measures the distance to the lane boundary from the current pose and the pose if +it stops, and determines whether there is enough space for the rear vehicle to pass through. If + * it is obstructing at either of the two poses, it returns true. + * + * @return true if the ego vehicle is preventing the rear vehicle from passing through with given +ego pose. + */ + bool isPreventingRearVehicleFromPassingThrough(const Pose & ego_pose) const; + bool isCloseToOriginalStartPose() const; bool hasArrivedAtGoal() const; bool isMoving() const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 2d9fbf7355415..e318fbedf3200 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -368,7 +368,35 @@ bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const { + // prepare poses for preventing check + // - current_pose + // - estimated_stop_pose (The position assumed when stopped with the minimum stop distance, + // although it is NOT actually stopped) const auto & current_pose = planner_data_->self_odometry->pose.pose; + std::vector preventing_check_pose{current_pose}; + const auto min_stop_distance = + autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance( + planner_data_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop, + 0.0); + debug_data_.estimated_stop_pose.reset(); // debug + if (min_stop_distance.has_value()) { + const auto current_path = getCurrentPath(); + const auto estimated_stop_pose = calcLongitudinalOffsetPose( + current_path.points, current_pose.position, min_stop_distance.value()); + if (estimated_stop_pose.has_value()) { + preventing_check_pose.push_back(estimated_stop_pose.value()); + debug_data_.estimated_stop_pose = estimated_stop_pose.value(); // debug + } + } + + // check if any of the preventing check poses are preventing rear vehicle from passing through + return std::any_of( + preventing_check_pose.begin(), preventing_check_pose.end(), + [&](const auto & pose) { return isPreventingRearVehicleFromPassingThrough(pose); }); +} + +bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose & ego_pose) const +{ const auto & dynamic_object = planner_data_->dynamic_object; const auto & route_handler = planner_data_->route_handler; const Pose start_pose = planner_data_->route_handler->getOriginalStartPose(); @@ -414,8 +442,8 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const geometry_msgs::msg::Pose & ego_overhang_point_as_pose, const bool ego_is_merging_from_the_left) -> std::optional> { const auto local_vehicle_footprint = vehicle_info_.createFootprint(); - const auto vehicle_footprint = transformVector( - local_vehicle_footprint, autoware::universe_utils::pose2transform(current_pose)); + const auto vehicle_footprint = + transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose)); double smallest_lateral_gap_between_ego_and_border = std::numeric_limits::max(); double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits::max(); @@ -481,7 +509,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const // Check backwards just in case the Vehicle behind ego is in a different lanelet constexpr double backwards_length = 200.0; const auto prev_lanes = autoware::behavior_path_planner::utils::getBackwardLanelets( - *route_handler, target_lanes, current_pose, backwards_length); + *route_handler, target_lanes, ego_pose, backwards_length); // return all the relevant lanelets lanelet::ConstLanelets relevant_lanelets{closest_lanelet_const}; relevant_lanelets.insert(relevant_lanelets.end(), prev_lanes.begin(), prev_lanes.end()); @@ -491,7 +519,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const // filtering objects with velocity, position and class const auto filtered_objects = utils::path_safety_checker::filterObjects( - dynamic_object, route_handler, relevant_lanelets.value(), current_pose.position, + dynamic_object, route_handler, relevant_lanelets.value(), ego_pose.position, objects_filtering_params_); if (filtered_objects.objects.empty()) return false; @@ -508,7 +536,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const target_objects_on_lane.on_current_lane.begin(), target_objects_on_lane.on_current_lane.end(), [&](const auto & o) { const auto arc_length = autoware::motion_utils::calcSignedArcLength( - centerline_path.points, current_pose.position, o.initial_pose.pose.position); + centerline_path.points, ego_pose.position, o.initial_pose.pose.position); if (arc_length > 0.0) return; if (std::abs(arc_length) >= std::abs(arc_length_to_closet_object)) return; arc_length_to_closet_object = arc_length; @@ -1723,6 +1751,16 @@ void StartPlannerModule::setDebugData() info_marker_); add(showPolygon(debug_data_.collision_check, "ego_and_target_polygon_relation"), info_marker_); + // visualize estimated_stop_pose for isPreventingRearVehicleFromPassingThrough() + if (debug_data_.estimated_stop_pose.has_value()) { + auto footprint_marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "estimated_stop_pose", 0, Marker::LINE_STRIP, + createMarkerScale(0.2, 0.2, 0.2), purple_color); + footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5); + addFootprintMarker(footprint_marker, debug_data_.estimated_stop_pose.value(), vehicle_info_); + debug_marker_.markers.push_back(footprint_marker); + } + // set objects of interest for (const auto & [uuid, data] : debug_data_.collision_check) { const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; From a363f9ec562be4d4d37c3c25a40157b4b544cb4b Mon Sep 17 00:00:00 2001 From: Sho Iwasawa <41606073+zusizusi@users.noreply.github.com> Date: Mon, 22 Jul 2024 15:02:18 +0300 Subject: [PATCH 028/151] fix(detected_object_validation): use search for searching intersected lanelet (#1420) fix(detected_object_validation): use search for searching intersected lanelet (#8109) * refactor: use search method of lanelet * rm unuse and mod args * style(pre-commit): autofix --------- Signed-off-by: a-maumau Co-authored-by: Masaki Baba Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../object_lanelet_filter.hpp | 8 +-- .../src/object_lanelet_filter.cpp | 58 ++++++++++++------- 2 files changed, 38 insertions(+), 28 deletions(-) diff --git a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp index 9b9894d56a424..2598f6ec6ca74 100644 --- a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp @@ -55,8 +55,6 @@ class ObjectLaneletFilterNode : public rclcpp::Node std::unique_ptr debug_publisher_{nullptr}; lanelet::LaneletMapPtr lanelet_map_ptr_; - lanelet::ConstLanelets road_lanelets_; - lanelet::ConstLanelets shoulder_lanelets_; std::string lanelet_frame_id_; tf2_ros::Buffer tf_buffer_; @@ -74,12 +72,10 @@ class ObjectLaneletFilterNode : public rclcpp::Node bool filterObject( const autoware_perception_msgs::msg::DetectedObject & transformed_object, const autoware_perception_msgs::msg::DetectedObject & input_object, - const lanelet::ConstLanelets & intersected_road_lanelets, - const lanelet::ConstLanelets & intersected_shoulder_lanelets, + const lanelet::ConstLanelets & intersected_lanelets, autoware_perception_msgs::msg::DetectedObjects & output_object_msg); LinearRing2d getConvexHull(const autoware_perception_msgs::msg::DetectedObjects &); - lanelet::ConstLanelets getIntersectedLanelets( - const LinearRing2d &, const lanelet::ConstLanelets &); + lanelet::ConstLanelets getIntersectedLanelets(const LinearRing2d &); bool isObjectOverlapLanelets( const autoware_perception_msgs::msg::DetectedObject & object, const lanelet::ConstLanelets & intersected_lanelets); diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index cc3a600783a8f..506fefdda1dbb 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -23,6 +23,8 @@ #include #include +#include +#include #include namespace object_lanelet_filter @@ -74,9 +76,6 @@ void ObjectLaneletFilterNode::mapCallback( lanelet_frame_id_ = map_msg->header.frame_id; lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_); - const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); - road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); - shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets); } void ObjectLaneletFilterNode::objectCallback( @@ -101,19 +100,15 @@ void ObjectLaneletFilterNode::objectCallback( // calculate convex hull const auto convex_hull = getConvexHull(transformed_objects); + // get intersected lanelets - lanelet::ConstLanelets intersected_road_lanelets = - getIntersectedLanelets(convex_hull, road_lanelets_); - lanelet::ConstLanelets intersected_shoulder_lanelets = - getIntersectedLanelets(convex_hull, shoulder_lanelets_); + lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull); // filtering process for (size_t index = 0; index < transformed_objects.objects.size(); ++index) { const auto & transformed_object = transformed_objects.objects.at(index); const auto & input_object = input_msg->objects.at(index); - filterObject( - transformed_object, input_object, intersected_road_lanelets, intersected_shoulder_lanelets, - output_object_msg); + filterObject(transformed_object, input_object, intersected_lanelets, output_object_msg); } object_pub_->publish(output_object_msg); published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp); @@ -131,8 +126,7 @@ void ObjectLaneletFilterNode::objectCallback( bool ObjectLaneletFilterNode::filterObject( const autoware_perception_msgs::msg::DetectedObject & transformed_object, const autoware_perception_msgs::msg::DetectedObject & input_object, - const lanelet::ConstLanelets & intersected_road_lanelets, - const lanelet::ConstLanelets & intersected_shoulder_lanelets, + const lanelet::ConstLanelets & intersected_lanelets, autoware_perception_msgs::msg::DetectedObjects & output_object_msg) { const auto & label = transformed_object.classification.front().label; @@ -141,8 +135,7 @@ bool ObjectLaneletFilterNode::filterObject( // 1. is polygon overlap with road lanelets or shoulder lanelets if (filter_settings_.polygon_overlap_filter) { const bool is_polygon_overlap = - isObjectOverlapLanelets(transformed_object, intersected_road_lanelets) || - isObjectOverlapLanelets(transformed_object, intersected_shoulder_lanelets); + isObjectOverlapLanelets(transformed_object, intersected_lanelets); filter_pass = filter_pass && is_polygon_overlap; } @@ -152,8 +145,7 @@ bool ObjectLaneletFilterNode::filterObject( autoware_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE; if (filter_settings_.lanelet_direction_filter && !orientation_not_available) { const bool is_same_direction = - isSameDirectionWithLanelets(intersected_road_lanelets, transformed_object) || - isSameDirectionWithLanelets(intersected_shoulder_lanelets, transformed_object); + isSameDirectionWithLanelets(intersected_lanelets, transformed_object); filter_pass = filter_pass && is_same_direction; } @@ -212,18 +204,40 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull( return convex_hull; } +// fetch the intersected candidate lanelets with bounding box and then +// check the intersections among the lanelets and the convex hull lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets( - const LinearRing2d & convex_hull, const lanelet::ConstLanelets & road_lanelets) + const LinearRing2d & convex_hull) { + namespace bg = boost::geometry; + lanelet::ConstLanelets intersected_lanelets; - // WARNING: This implementation currently iterate all lanelets, which could degrade performance - // when handling large sized map. - for (const auto & road_lanelet : road_lanelets) { - if (boost::geometry::intersects(convex_hull, road_lanelet.polygon2d().basicPolygon())) { - intersected_lanelets.emplace_back(road_lanelet); + // convert convex_hull to a 2D bounding box for searching in the LaneletMap + bg::model::box> bbox2d_convex_hull; + bg::envelope(convex_hull, bbox2d_convex_hull); + lanelet::BoundingBox2d bbox2d( + lanelet::BasicPoint2d( + bg::get(bbox2d_convex_hull), + bg::get(bbox2d_convex_hull)), + lanelet::BasicPoint2d( + bg::get(bbox2d_convex_hull), + bg::get(bbox2d_convex_hull))); + + lanelet::Lanelets candidates_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d); + for (const auto & lanelet : candidates_lanelets) { + // only check the road lanelets and road shoulder lanelets + if ( + lanelet.hasAttribute(lanelet::AttributeName::Subtype) && + (lanelet.attribute(lanelet::AttributeName::Subtype).value() == + lanelet::AttributeValueString::Road || + lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) { + if (boost::geometry::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) { + intersected_lanelets.emplace_back(lanelet); + } } } + return intersected_lanelets; } From 664b2e1bfbdde4c83180ee374a8ede46f0138479 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 23 Jul 2024 16:44:15 +0900 Subject: [PATCH 029/151] fix(autoware_overlay_rviz_plugin): topic type of traffic light (#8098) (#1422) * fix(autoware_overlay_rviz_plugin): topic type of traffic light * style(pre-commit): autofix --------- Signed-off-by: Tomohito Ando Signed-off-by: Tomohito ANDO Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/signal_display.hpp | 5 ++-- .../include/traffic_display.hpp | 5 ++-- .../src/signal_display.cpp | 24 +++++++++---------- .../src/traffic_display.cpp | 6 ++--- 4 files changed, 19 insertions(+), 21 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp index 0831ded468c99..c6921c5ae96b7 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp @@ -102,8 +102,7 @@ private Q_SLOTS: turn_signals_sub_; rclcpp::Subscription::SharedPtr hazard_lights_sub_; - rclcpp::Subscription::SharedPtr - traffic_sub_; + rclcpp::Subscription::SharedPtr traffic_sub_; rclcpp::Subscription::SharedPtr speed_limit_sub_; std::mutex property_mutex_; @@ -117,7 +116,7 @@ private Q_SLOTS: const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & msg); void updateSpeedLimitData(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); void updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr msg); + const autoware_perception_msgs::msg::TrafficLightGroup::ConstSharedPtr msg); void drawWidget(QImage & hud); }; } // namespace autoware_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp index fd15f542021f1..01545bcea6f4e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp @@ -25,7 +25,6 @@ #include #include -#include #include #include @@ -40,8 +39,8 @@ class TrafficDisplay TrafficDisplay(); void drawTrafficLightIndicator(QPainter & painter, const QRectF & backgroundRect); void updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr & msg); - autoware_perception_msgs::msg::TrafficLightGroupArray current_traffic_; + const autoware_perception_msgs::msg::TrafficLightGroup::ConstSharedPtr & msg); + autoware_perception_msgs::msg::TrafficLightGroup current_traffic_; private: QImage traffic_light_image_; diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp index ccfdaa69f5d2a..9cd9e0e0f8e73 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp @@ -109,9 +109,10 @@ void SignalDisplay::onInitialize() speed_limit_topic_property_->initialize(rviz_ros_node); traffic_topic_property_ = std::make_unique( - "Traffic Topic", "/perception/traffic_light_recognition/traffic_signals", - "autoware_perception_msgs/msgs/msg/TrafficLightGroupArray", "Topic for Traffic Light Data", - this, SLOT(topic_updated_traffic())); + "Traffic Topic", + "/planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal", + "autoware_perception_msgs/msgs/msg/TrafficLightGroup", "Topic for Traffic Light Data", this, + SLOT(topic_updated_traffic())); traffic_topic_property_->initialize(rviz_ros_node); } @@ -189,7 +190,7 @@ void SignalDisplay::onDisable() } void SignalDisplay::updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr msg) + const autoware_perception_msgs::msg::TrafficLightGroup::ConstSharedPtr msg) { std::lock_guard lock(property_mutex_); @@ -454,14 +455,13 @@ void SignalDisplay::topic_updated_traffic() // resubscribe to the topic traffic_sub_.reset(); auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); - traffic_sub_ = - rviz_ros_node->get_raw_node() - ->create_subscription( - traffic_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_perception_msgs::msg::TrafficLightGroupArray::SharedPtr msg) { - updateTrafficLightData(msg); - }); + traffic_sub_ = rviz_ros_node->get_raw_node() + ->create_subscription( + traffic_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_perception_msgs::msg::TrafficLightGroup::SharedPtr msg) { + updateTrafficLightData(msg); + }); } } // namespace autoware_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp index 2dc9c23583a52..c3f79f40e2ecd 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp @@ -48,7 +48,7 @@ TrafficDisplay::TrafficDisplay() } void TrafficDisplay::updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr & msg) + const autoware_perception_msgs::msg::TrafficLightGroup::ConstSharedPtr & msg) { current_traffic_ = *msg; } @@ -68,8 +68,8 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF backgroundRect.top() + circleRect.height() / 2)); painter.drawEllipse(circleRect); - if (!current_traffic_.traffic_light_groups.empty()) { - switch (current_traffic_.traffic_light_groups[0].elements[0].color) { + if (!current_traffic_.elements.empty()) { + switch (current_traffic_.elements[0].color) { case 1: painter.setBrush(QBrush(tl_red_)); painter.drawEllipse(circleRect); From 19af48e6fa3a8e4c2858271b6587113df85cb56a Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 25 Jul 2024 09:02:52 +0900 Subject: [PATCH 030/151] feat(pid_long, vehicle_cmd_gate)!: quick pedal change (#1425) * feat(simple_planning_simulator): add new vehicle model with falling down (#7651) * add new vehicle model Signed-off-by: Yuki Takagi * refactor(vehicle_cmd_gate)!: delete rate limit skipping function for vehicle departure (#7720) * delete a fucntion block. More appropriate function can be achieved by the parameter settings. * add notation to readme --------- Signed-off-by: Yuki Takagi * feat(pid_longitudinal_controller): re-organize diff limit structure and fix state change condition (#7718) change diff limit structure change stopped condition define a new param Signed-off-by: Yuki Takagi --------- Signed-off-by: Yuki Takagi --- .../pid_longitudinal_controller.hpp | 4 +- ...ongitudinal_controller_defaults.param.yaml | 6 +- .../src/pid_longitudinal_controller.cpp | 164 ++++++++-------- .../param/longitudinal/pid.param.yaml | 6 +- control/autoware_vehicle_cmd_gate/README.md | 4 + .../config/vehicle_cmd_gate.param.yaml | 16 +- .../src/vehicle_cmd_gate.cpp | 18 -- .../simple_planning_simulator/CMakeLists.txt | 1 + simulator/simple_planning_simulator/README.md | 41 ++-- .../simple_planning_simulator_core.hpp | 3 +- .../vehicle_model/sim_model.hpp | 1 + ...l_delay_steer_acc_geared_wo_fall_guard.hpp | 149 ++++++++++++++ .../simple_planning_simulator_core.cpp | 31 ++- ...l_delay_steer_acc_geared_wo_fall_guard.cpp | 183 ++++++++++++++++++ .../test/test_simple_planning_simulator.cpp | 1 + 15 files changed, 487 insertions(+), 141 deletions(-) create mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp create mode 100644 simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 39c75964dbc72..61c730eb257e7 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -183,7 +183,6 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro { double vel; double acc; - double jerk; }; StoppedStateParams m_stopped_state_params; @@ -203,6 +202,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro // jerk limit double m_max_jerk; double m_min_jerk; + double m_max_acc_cmd_diff; // slope compensation enum class SlopeSource { RAW_PITCH = 0, TRAJECTORY_PITCH, TRAJECTORY_ADAPTIVE }; @@ -291,7 +291,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro * @brief calculate control command in emergency state * @param [in] dt time between previous and current one */ - Motion calcEmergencyCtrlCmd(const double dt) const; + Motion calcEmergencyCtrlCmd(const double dt); /** * @brief update control state according to the current situation diff --git a/control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml b/control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml index ad6217663fbae..5027c94afe7c1 100644 --- a/control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml +++ b/control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml @@ -53,12 +53,11 @@ # stopped state stopped_vel: 0.0 - stopped_acc: -3.4 - stopped_jerk: -5.0 + stopped_acc: -3.4 # denotes pedal position # emergency state emergency_vel: 0.0 - emergency_acc: -5.0 + emergency_acc: -5.0 # denotes acceleration emergency_jerk: -3.0 # acceleration limit @@ -68,6 +67,7 @@ # jerk limit max_jerk: 2.0 min_jerk: -5.0 + max_acc_cmd_diff: 50.0 # [m/s^2 * s^-1] # slope compensation lpf_pitch_gain: 0.95 diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 09f4a90e14898..20f8dfe642cc6 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -150,9 +150,8 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node) // parameters for stop state { auto & p = m_stopped_state_params; - p.vel = node.declare_parameter("stopped_vel"); // [m/s] - p.acc = node.declare_parameter("stopped_acc"); // [m/s^2] - p.jerk = node.declare_parameter("stopped_jerk"); // [m/s^3] + p.vel = node.declare_parameter("stopped_vel"); // [m/s] + p.acc = node.declare_parameter("stopped_acc"); // [m/s^2] } // parameters for emergency state @@ -168,8 +167,9 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node) m_min_acc = node.declare_parameter("min_acc"); // [m/s^2] // parameters for jerk limit - m_max_jerk = node.declare_parameter("max_jerk"); // [m/s^3] - m_min_jerk = node.declare_parameter("min_jerk"); // [m/s^3] + m_max_jerk = node.declare_parameter("max_jerk"); // [m/s^3] + m_min_jerk = node.declare_parameter("min_jerk"); // [m/s^3] + m_max_acc_cmd_diff = node.declare_parameter("max_acc_cmd_diff"); // [m/s^3] // parameters for slope compensation m_adaptive_trajectory_velocity_th = @@ -353,7 +353,6 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac auto & p = m_stopped_state_params; update_param("stopped_vel", p.vel); update_param("stopped_acc", p.acc); - update_param("stopped_jerk", p.jerk); } // emergency state @@ -370,6 +369,7 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac // jerk limit update_param("max_jerk", m_max_jerk); update_param("min_jerk", m_min_jerk); + update_param("max_acc_cmd_diff", m_max_acc_cmd_diff); // slope compensation update_param("max_pitch_rad", m_max_pitch_rad); @@ -565,26 +565,30 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData return control_data; } -PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd( - const double dt) const +PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd(const double dt) { // These accelerations are without slope compensation const auto & p = m_emergency_state_params; - const double vel = - longitudinal_utils::applyDiffLimitFilter(p.vel, m_prev_raw_ctrl_cmd.vel, dt, p.acc); - const double acc = - longitudinal_utils::applyDiffLimitFilter(p.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk); + Motion raw_ctrl_cmd{p.vel, p.acc}; + + raw_ctrl_cmd.vel = + longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.vel, m_prev_raw_ctrl_cmd.vel, dt, p.acc); + raw_ctrl_cmd.acc = std::clamp(raw_ctrl_cmd.acc, m_min_acc, m_max_acc); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, raw_ctrl_cmd.acc); + raw_ctrl_cmd.acc = + longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc); RCLCPP_ERROR_THROTTLE( - logger_, *clock_, 3000, "[Emergency stop] vel: %3.3f, acc: %3.3f", vel, acc); + logger_, *clock_, 3000, "[Emergency stop] vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, + raw_ctrl_cmd.acc); - return Motion{vel, acc}; + return raw_ctrl_cmd; } void PidLongitudinalController::updateControlState(const ControlData & control_data) { const double current_vel = control_data.current_motion.vel; - const double current_acc = control_data.current_motion.acc; const double stop_dist = control_data.stop_dist; // flags for state transition @@ -599,8 +603,8 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d const bool stopping_condition = stop_dist < p.stopping_state_stop_dist; - const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel && - std::abs(current_acc) < p.stopped_state_entry_acc; + const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel; + // Case where the ego slips in the opposite direction of the gear due to e.g. a slope is also // considered as a stop const bool is_not_running = [&]() { @@ -701,7 +705,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_pid_vel.reset(); m_lpf_vel_error->reset(0.0); // prevent the car from taking a long time to start to move - m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_ctrl_cmd.acc); + m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_raw_ctrl_cmd.acc); return changeState(ControlState::DRIVE); } return; @@ -747,8 +751,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_pid_vel.reset(); m_lpf_vel_error->reset(0.0); - // prevent the car from taking a long time to start to move - m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_ctrl_cmd.acc); return changeState(ControlState::DRIVE); } @@ -780,55 +782,85 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd( const size_t target_idx = control_data.target_idx; // velocity and acceleration command - Motion raw_ctrl_cmd{ + Motion ctrl_cmd_as_pedal_pos{ control_data.interpolated_traj.points.at(target_idx).longitudinal_velocity_mps, control_data.interpolated_traj.points.at(target_idx).acceleration_mps2}; - if (m_control_state == ControlState::DRIVE) { - raw_ctrl_cmd.vel = - control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps; - raw_ctrl_cmd.acc = applyVelocityFeedback(control_data); - raw_ctrl_cmd = keepBrakeBeforeStop(control_data, raw_ctrl_cmd, target_idx); + if (m_control_state == ControlState::STOPPED) { + const auto & p = m_stopped_state_params; + ctrl_cmd_as_pedal_pos.vel = p.vel; + ctrl_cmd_as_pedal_pos.acc = p.acc; - RCLCPP_DEBUG( - logger_, - "[feedback control] vel: %3.3f, acc: %3.3f, dt: %3.3f, v_curr: %3.3f, v_ref: %3.3f " - "feedback_ctrl_cmd.ac: %3.3f", - raw_ctrl_cmd.vel, raw_ctrl_cmd.acc, control_data.dt, control_data.current_motion.vel, - control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps, - raw_ctrl_cmd.acc); - } else if (m_control_state == ControlState::STOPPING) { - raw_ctrl_cmd.acc = m_smooth_stop.calculate( - control_data.stop_dist, control_data.current_motion.vel, control_data.current_motion.acc, - m_vel_hist, m_delay_compensation_time); - raw_ctrl_cmd.vel = m_stopped_state_params.vel; + m_prev_raw_ctrl_cmd.vel = 0.0; + m_prev_raw_ctrl_cmd.acc = 0.0; + + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, ctrl_cmd_as_pedal_pos.acc); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, ctrl_cmd_as_pedal_pos.acc); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, ctrl_cmd_as_pedal_pos.acc); RCLCPP_DEBUG( - logger_, "[smooth stop]: Smooth stopping. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, - raw_ctrl_cmd.acc); - } else if (m_control_state == ControlState::STOPPED) { - // This acceleration is without slope compensation - const auto & p = m_stopped_state_params; - raw_ctrl_cmd.vel = p.vel; - raw_ctrl_cmd.acc = longitudinal_utils::applyDiffLimitFilter( - p.acc, m_prev_raw_ctrl_cmd.acc, control_data.dt, p.jerk); + logger_, "[Stopped]. vel: %3.3f, acc: %3.3f", ctrl_cmd_as_pedal_pos.vel, + ctrl_cmd_as_pedal_pos.acc); + } else { + Motion raw_ctrl_cmd{ + control_data.interpolated_traj.points.at(target_idx).longitudinal_velocity_mps, + control_data.interpolated_traj.points.at(target_idx).acceleration_mps2}; + if (m_control_state == ControlState::EMERGENCY) { + raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt); + } else { + if (m_control_state == ControlState::DRIVE) { + raw_ctrl_cmd.vel = control_data.interpolated_traj.points.at(control_data.target_idx) + .longitudinal_velocity_mps; + raw_ctrl_cmd.acc = applyVelocityFeedback(control_data); + raw_ctrl_cmd = keepBrakeBeforeStop(control_data, raw_ctrl_cmd, target_idx); + + RCLCPP_DEBUG( + logger_, + "[feedback control] vel: %3.3f, acc: %3.3f, dt: %3.3f, v_curr: %3.3f, v_ref: %3.3f " + "feedback_ctrl_cmd.ac: %3.3f", + raw_ctrl_cmd.vel, raw_ctrl_cmd.acc, control_data.dt, control_data.current_motion.vel, + control_data.interpolated_traj.points.at(control_data.target_idx) + .longitudinal_velocity_mps, + raw_ctrl_cmd.acc); + } else if (m_control_state == ControlState::STOPPING) { + raw_ctrl_cmd.acc = m_smooth_stop.calculate( + control_data.stop_dist, control_data.current_motion.vel, control_data.current_motion.acc, + m_vel_hist, m_delay_compensation_time); + raw_ctrl_cmd.vel = m_stopped_state_params.vel; + + RCLCPP_DEBUG( + logger_, "[smooth stop]: Smooth stopping. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, + raw_ctrl_cmd.acc); + } + raw_ctrl_cmd.acc = std::clamp(raw_ctrl_cmd.acc, m_min_acc, m_max_acc); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, raw_ctrl_cmd.acc); + raw_ctrl_cmd.acc = longitudinal_utils::applyDiffLimitFilter( + raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, control_data.dt, m_max_jerk, m_min_jerk); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc); + } + + // store acceleration without slope compensation + m_prev_raw_ctrl_cmd = raw_ctrl_cmd; - RCLCPP_DEBUG(logger_, "[Stopped]. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, raw_ctrl_cmd.acc); - } else if (m_control_state == ControlState::EMERGENCY) { - raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt); + ctrl_cmd_as_pedal_pos.acc = + applySlopeCompensation(raw_ctrl_cmd.acc, control_data.slope_angle, control_data.shift); + m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, ctrl_cmd_as_pedal_pos.acc); + ctrl_cmd_as_pedal_pos.vel = raw_ctrl_cmd.vel; } - // store acceleration without slope compensation - m_prev_raw_ctrl_cmd = raw_ctrl_cmd; + storeAccelCmd(m_prev_raw_ctrl_cmd.acc); - // apply slope compensation and filter acceleration and jerk - const double filtered_acc_cmd = calcFilteredAcc(raw_ctrl_cmd.acc, control_data); - const Motion filtered_ctrl_cmd{raw_ctrl_cmd.vel, filtered_acc_cmd}; + ctrl_cmd_as_pedal_pos.acc = longitudinal_utils::applyDiffLimitFilter( + ctrl_cmd_as_pedal_pos.acc, m_prev_ctrl_cmd.acc, control_data.dt, m_max_acc_cmd_diff); // update debug visualization updateDebugVelAcc(control_data); - return filtered_ctrl_cmd; + RCLCPP_DEBUG( + logger_, "[final output]: acc: %3.3f, v_curr: %3.3f", ctrl_cmd_as_pedal_pos.acc, + control_data.current_motion.vel); + + return ctrl_cmd_as_pedal_pos; } // Do not use nearest_idx here @@ -912,28 +944,6 @@ enum PidLongitudinalController::Shift PidLongitudinalController::getCurrentShift return m_prev_shift; } -double PidLongitudinalController::calcFilteredAcc( - const double raw_acc, const ControlData & control_data) -{ - const double acc_max_filtered = std::clamp(raw_acc, m_min_acc, m_max_acc); - m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, acc_max_filtered); - - // store ctrl cmd without slope filter - storeAccelCmd(acc_max_filtered); - - // apply slope compensation - const double acc_slope_filtered = - applySlopeCompensation(acc_max_filtered, control_data.slope_angle, control_data.shift); - m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, acc_slope_filtered); - - // This jerk filter must be applied after slope compensation - const double acc_jerk_filtered = longitudinal_utils::applyDiffLimitFilter( - acc_slope_filtered, m_prev_ctrl_cmd.acc, control_data.dt, m_max_jerk, m_min_jerk); - m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, acc_jerk_filtered); - - return acc_jerk_filtered; -} - void PidLongitudinalController::storeAccelCmd(const double accel) { if (m_control_state == ControlState::DRIVE) { diff --git a/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml b/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml index ad6217663fbae..5027c94afe7c1 100644 --- a/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml +++ b/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml @@ -53,12 +53,11 @@ # stopped state stopped_vel: 0.0 - stopped_acc: -3.4 - stopped_jerk: -5.0 + stopped_acc: -3.4 # denotes pedal position # emergency state emergency_vel: 0.0 - emergency_acc: -5.0 + emergency_acc: -5.0 # denotes acceleration emergency_jerk: -3.0 # acceleration limit @@ -68,6 +67,7 @@ # jerk limit max_jerk: 2.0 min_jerk: -5.0 + max_acc_cmd_diff: 50.0 # [m/s^2 * s^-1] # slope compensation lpf_pitch_gain: 0.95 diff --git a/control/autoware_vehicle_cmd_gate/README.md b/control/autoware_vehicle_cmd_gate/README.md index 2d6f5c5f949af..e46db3c06cfeb 100644 --- a/control/autoware_vehicle_cmd_gate/README.md +++ b/control/autoware_vehicle_cmd_gate/README.md @@ -78,6 +78,10 @@ The limitation values are calculated based on the 1D interpolation of the limita Notation: this filter is not designed to enhance ride comfort. Its main purpose is to detect and remove abnormal values in the control outputs during the final stages of Autoware. If this filter is frequently active, it implies the control module may need tuning. If you're aiming to smoothen the signal via a low-pass filter or similar techniques, that should be handled in the control module. When the filter is activated, the topic `~/is_filter_activated` is published. +Notation 2: If you use vehicles in which the driving force is controlled by the accelerator/brake pedal, the jerk limit, denoting the pedal rate limit, must be sufficiently relaxed at low speeds. +Otherwise, quick pedal changes at start/stop will not be possible, resulting in slow starts and creep down on hills. +This functionality for starting/stopping was embedded in the source code but was removed because it was complex and could be achieved by parameters. + ## Assumptions / Known limits The parameter `check_external_emergency_heartbeat` (true by default) enables an emergency stop request from external modules. diff --git a/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml index 54c87f45b6a96..74affea696893 100644 --- a/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml +++ b/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -16,14 +16,14 @@ stop_check_duration: 1.0 nominal: vel_lim: 25.0 - reference_speed_points: [20.0, 30.0] - steer_lim: [1.0, 0.8] - steer_rate_lim: [1.0, 0.8] - lon_acc_lim: [5.0, 4.0] - lon_jerk_lim: [5.0, 4.0] - lat_acc_lim: [5.0, 4.0] - lat_jerk_lim: [7.0, 6.0] - actual_steer_diff_lim: [1.0, 0.8] + reference_speed_points: [0.1, 0.3, 20.0, 30.0] + steer_lim: [1.0, 1.0, 1.0, 0.8] + steer_rate_lim: [1.0, 1.0, 1.0, 0.8] + lon_acc_lim: [5.0, 5.0, 5.0, 4.0] + lon_jerk_lim: [80.0, 5.0, 5.0, 4.0] # The first element is required for quick pedal changes when stopping and starting. + lat_acc_lim: [5.0, 5.0, 5.0, 4.0] + lat_jerk_lim: [7.0, 7.0, 7.0, 6.0] + actual_steer_diff_lim: [1.0, 1.0, 1.0, 0.8] on_transition: vel_lim: 50.0 reference_speed_points: [20.0, 30.0] diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 87e79f59bc356..dd6e2f0f54aea 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -607,7 +607,6 @@ Control VehicleCmdGate::filterControlCommand(const Control & in) const auto mode = current_operation_mode_; const auto current_status_cmd = getActualStatusAsCommand(); const auto ego_is_stopped = vehicle_stop_checker_->isVehicleStopped(stop_check_duration_); - const auto input_cmd_is_stopping = in.longitudinal.acceleration < 0.0; filter_.setCurrentSpeed(current_kinematics_.twist.twist.linear.x); filter_on_transition_.setCurrentSpeed(current_kinematics_.twist.twist.linear.x); @@ -618,23 +617,6 @@ Control VehicleCmdGate::filterControlCommand(const Control & in) if (mode.is_in_transition) { filter_on_transition_.filterAll(dt, current_steer_, out, is_filter_activated); } else { - // When ego is stopped and the input command is not stopping, - // use the higher of actual vehicle longitudinal state - // and previous longitudinal command for the filtering - // this is to prevent the jerk limits being applied and causing - // a delay when restarting the vehicle. - - if (ego_is_stopped && !input_cmd_is_stopping) { - auto prev_cmd = filter_.getPrevCmd(); - prev_cmd.longitudinal.acceleration = - std::max(prev_cmd.longitudinal.acceleration, current_status_cmd.longitudinal.acceleration); - // consider reverse driving - prev_cmd.longitudinal.velocity = std::fabs(prev_cmd.longitudinal.velocity) > - std::fabs(current_status_cmd.longitudinal.velocity) - ? prev_cmd.longitudinal.velocity - : current_status_cmd.longitudinal.velocity; - filter_.setPrevCmd(prev_cmd); - } filter_.filterAll(dt, current_steer_, out, is_filter_activated); } diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 331d5e819df77..376553aa62917 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -19,6 +19,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp + src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp src/simple_planning_simulator/utils/csv_loader.cpp ) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 4902832f836a9..c3d02da64b882 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -62,6 +62,7 @@ The purpose of this simulator is for the integration test of planning and contro - `DELAY_STEER_VEL` - `DELAY_STEER_ACC` - `DELAY_STEER_ACC_GEARED` +- `DELAY_STEER_ACC_GEARED_WO_FALL_GUARD` - `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. - `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../learning_based_vehicle_model). @@ -69,26 +70,26 @@ The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves base The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_M_ACC_G | L_S_V | Default value | unit | -| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :----------- | :---- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | x | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | x | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | x | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | x | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | x | x | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | x | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | x | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | x | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | x | 5.0 | [rad/s] | -| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | x | 0.0 | [rad] | -| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | x | x | 1.0 | [-] | -| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | x | x | 1.0 | [-] | -| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | o | x | - | [-] | -| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | o | - | [-] | -| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | o | - | [-] | -| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | o | - | [-] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | Default value | unit | +| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------- | :----------- | :---- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | 5.0 | [rad/s] | +| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | 0.0 | [rad] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | 1.0 | [-] | +| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | - | [-] | +| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | - | [-] | +| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | - | [-] | +| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | - | [-] | _Note:_ Parameters `model_module_paths`, `model_param_paths`, and `model_class_names` need to have the same length. diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 18a3a3bae501a..86e4346770f0c 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -205,7 +205,8 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node IDEAL_STEER_VEL = 4, DELAY_STEER_VEL = 5, DELAY_STEER_MAP_ACC_GEARED = 6, - LEARNED_STEER_VEL = 7 + LEARNED_STEER_VEL = 7, + DELAY_STEER_ACC_GEARED_WO_FALL_GUARD = 8 } vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics std::shared_ptr vehicle_model_ptr_; //!< @brief vehicle model pointer diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp index ced7349f28914..2d38ef31498b6 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp @@ -17,6 +17,7 @@ #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp" diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp new file mode 100644 index 0000000000000..d7a6a8284d704 --- /dev/null +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp @@ -0,0 +1,149 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT +#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT + +#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" + +#include +#include + +#include +#include +#include + +class SimModelDelaySteerAccGearedWoFallGuard : public SimModelInterface +{ +public: + /** + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] acc_delay time delay for accel command [s] + * @param [in] acc_time_constant time constant for 1D model of accel dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] steer_dead_band dead band for steering angle [rad] + * @param [in] steer_bias steering bias [rad] + * @param [in] debug_acc_scaling_factor scaling factor for accel command + * @param [in] debug_steer_scaling_factor scaling factor for steering command + */ + SimModelDelaySteerAccGearedWoFallGuard( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double acc_delay, double acc_time_constant, double steer_delay, + double steer_time_constant, double steer_dead_band, double steer_bias, + double debug_acc_scaling_factor, double debug_steer_scaling_factor); + + /** + * @brief default destructor + */ + ~SimModelDelaySteerAccGearedWoFallGuard() = default; + +private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum IDX { + X = 0, + Y, + YAW, + VX, + STEER, + PEDAL_ACCX, + }; + enum IDX_U { PEDAL_ACCX_DES = 0, GEAR, SLOPE_ACCX, STEER_DES }; + + const double vx_lim_; //!< @brief velocity limit [m/s] + const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] + const double steer_lim_; //!< @brief steering limit [rad] + const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_; //!< @brief vehicle wheelbase length [m] + + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for steering dynamics + const double steer_dead_band_; //!< @brief dead band for steering angle [rad] + const double steer_bias_; //!< @brief steering angle bias [rad] + const double debug_acc_scaling_factor_; //!< @brief scaling factor for accel command + const double debug_steer_scaling_factor_; //!< @brief scaling factor for steering command + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double & dt); + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle lateral velocity + */ + double getVy() override; + + /** + * @brief get vehicle longitudinal acceleration + */ + double getAx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double & dt) override; + + /** + * @brief calculate derivative of states with time delay steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; +}; + +// clang-format off +#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT +// clang-format on diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 71c89fcf4df42..7d09aabdc9abd 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -269,6 +269,12 @@ void SimplePlanningSimulator::initialize_vehicle_model() vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, steer_bias, debug_acc_scaling_factor, debug_steer_scaling_factor); + } else if (vehicle_model_type_str == "DELAY_STEER_ACC_GEARED_WO_FALL_GUARD") { + vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC_GEARED_WO_FALL_GUARD; + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, + acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_dead_band, + steer_bias, debug_acc_scaling_factor, debug_steer_scaling_factor); } else if (vehicle_model_type_str == "DELAY_STEER_MAP_ACC_GEARED") { vehicle_model_type_ = VehicleModelType::DELAY_STEER_MAP_ACC_GEARED; const std::string acceleration_map_path = @@ -471,7 +477,7 @@ void SimplePlanningSimulator::set_input(const Control & cmd, const double acc_by { const auto steer = cmd.lateral.steering_tire_angle; const auto vel = cmd.longitudinal.velocity; - const auto accel = cmd.longitudinal.acceleration; + const auto acc_by_cmd = cmd.longitudinal.acceleration; using autoware_vehicle_msgs::msg::GearCommand; Eigen::VectorXd input(vehicle_model_ptr_->getDimU()); @@ -479,12 +485,15 @@ void SimplePlanningSimulator::set_input(const Control & cmd, const double acc_by // TODO(Watanabe): The definition of the sign of acceleration in REVERSE mode is different // between .auto and proposal.iv, and will be discussed later. - float acc = accel + acc_by_slope; - if (gear == GearCommand::NONE) { - acc = 0.0; - } else if (gear == GearCommand::REVERSE || gear == GearCommand::REVERSE_2) { - acc = -accel - acc_by_slope; - } + const float combined_acc = [&] { + if (gear == GearCommand::NONE) { + return 0.0; + } else if (gear == GearCommand::REVERSE || gear == GearCommand::REVERSE_2) { + return -acc_by_cmd + acc_by_slope; + } else { + return acc_by_cmd + acc_by_slope; + } + }(); if ( vehicle_model_type_ == VehicleModelType::IDEAL_STEER_VEL || @@ -494,12 +503,15 @@ void SimplePlanningSimulator::set_input(const Control & cmd, const double acc_by } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC || vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) { - input << acc, steer; + input << combined_acc, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC_GEARED || vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || vehicle_model_type_ == VehicleModelType::DELAY_STEER_MAP_ACC_GEARED) { - input << acc, steer; + input << combined_acc, steer; + } else if ( // NOLINT + vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED_WO_FALL_GUARD) { + input << acc_by_cmd, gear, acc_by_slope, steer; } vehicle_model_ptr_->setInput(input); } @@ -599,6 +611,7 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist & } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC || vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || + vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED_WO_FALL_GUARD || vehicle_model_type_ == VehicleModelType::DELAY_STEER_MAP_ACC_GEARED) { state << x, y, yaw, vx, steer, accx; } diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp new file mode 100644 index 0000000000000..c699d704724f5 --- /dev/null +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp @@ -0,0 +1,183 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp" + +#include "autoware_vehicle_msgs/msg/gear_command.hpp" + +#include + +SimModelDelaySteerAccGearedWoFallGuard::SimModelDelaySteerAccGearedWoFallGuard( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double acc_delay, double acc_time_constant, double steer_delay, + double steer_time_constant, double steer_dead_band, double steer_bias, + double debug_acc_scaling_factor, double debug_steer_scaling_factor) +: SimModelInterface(6 /* dim x */, 4 /* dim u */), + MIN_TIME_CONSTANT(0.03), + vx_lim_(vx_lim), + vx_rate_lim_(vx_rate_lim), + steer_lim_(steer_lim), + steer_rate_lim_(steer_rate_lim), + wheelbase_(wheelbase), + acc_delay_(acc_delay), + acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), + steer_delay_(steer_delay), + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + steer_dead_band_(steer_dead_band), + steer_bias_(steer_bias), + debug_acc_scaling_factor_(std::max(debug_acc_scaling_factor, 0.0)), + debug_steer_scaling_factor_(std::max(debug_steer_scaling_factor, 0.0)) +{ + initializeInputQueue(dt); +} + +double SimModelDelaySteerAccGearedWoFallGuard::getX() +{ + return state_(IDX::X); +} +double SimModelDelaySteerAccGearedWoFallGuard::getY() +{ + return state_(IDX::Y); +} +double SimModelDelaySteerAccGearedWoFallGuard::getYaw() +{ + return state_(IDX::YAW); +} +double SimModelDelaySteerAccGearedWoFallGuard::getVx() +{ + return state_(IDX::VX); +} +double SimModelDelaySteerAccGearedWoFallGuard::getVy() +{ + return 0.0; +} +double SimModelDelaySteerAccGearedWoFallGuard::getAx() +{ + return state_(IDX::PEDAL_ACCX); +} +double SimModelDelaySteerAccGearedWoFallGuard::getWz() +{ + return state_(IDX::VX) * std::tan(state_(IDX::STEER)) / wheelbase_; + ; +} +double SimModelDelaySteerAccGearedWoFallGuard::getSteer() +{ + // return measured values with bias added to actual values + return state_(IDX::STEER) + steer_bias_; +} +void SimModelDelaySteerAccGearedWoFallGuard::update(const double & dt) +{ + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + acc_input_queue_.push_back(input_(IDX_U::PEDAL_ACCX_DES)); + delayed_input(IDX_U::PEDAL_ACCX_DES) = acc_input_queue_.front(); + acc_input_queue_.pop_front(); + steer_input_queue_.push_back(input_(IDX_U::STEER_DES)); + delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front(); + steer_input_queue_.pop_front(); + delayed_input(IDX_U::GEAR) = input_(IDX_U::GEAR); + delayed_input(IDX_U::SLOPE_ACCX) = input_(IDX_U::SLOPE_ACCX); + + const auto prev_state = state_; + updateEuler(dt, delayed_input); + // we cannot use updateRungeKutta() because the differentiability or the continuity condition is + // not satisfied, but we can use Runge-Kutta method with code reconstruction. + + // take velocity limit explicitly + state_(IDX::VX) = std::max(-vx_lim_, std::min(state_(IDX::VX), vx_lim_)); + + if ( + prev_state(IDX::VX) * state_(IDX::VX) <= 0.0 && + -state_(IDX::PEDAL_ACCX) >= std::abs(delayed_input(IDX_U::SLOPE_ACCX))) { + // stop condition is satisfied + state_(IDX::VX) = 0.0; + } +} + +void SimModelDelaySteerAccGearedWoFallGuard::initializeInputQueue(const double & dt) +{ + size_t acc_input_queue_size = static_cast(round(acc_delay_ / dt)); + acc_input_queue_.resize(acc_input_queue_size); + std::fill(acc_input_queue_.begin(), acc_input_queue_.end(), 0.0); + + size_t steer_input_queue_size = static_cast(round(steer_delay_ / dt)); + steer_input_queue_.resize(steer_input_queue_size); + std::fill(steer_input_queue_.begin(), steer_input_queue_.end(), 0.0); +} + +Eigen::VectorXd SimModelDelaySteerAccGearedWoFallGuard::calcModel( + const Eigen::VectorXd & state, const Eigen::VectorXd & input) +{ + auto sat = [](double val, double u, double l) { return std::max(std::min(val, u), l); }; + + const double vel = sat(state(IDX::VX), vx_lim_, -vx_lim_); + const double pedal_acc = sat(state(IDX::PEDAL_ACCX), vx_rate_lim_, -vx_rate_lim_); + const double yaw = state(IDX::YAW); + const double steer = state(IDX::STEER); + const double pedal_acc_des = + sat(input(IDX_U::PEDAL_ACCX_DES), vx_rate_lim_, -vx_rate_lim_) * debug_acc_scaling_factor_; + const double steer_des = + sat(input(IDX_U::STEER_DES), steer_lim_, -steer_lim_) * debug_steer_scaling_factor_; + // NOTE: `steer_des` is calculated by control from measured values. getSteer() also gets the + // measured value. The steer_rate used in the motion calculation is obtained from these + // differences. + const double steer_diff = getSteer() - steer_des; + const double steer_diff_with_dead_band = std::invoke([&]() { + if (steer_diff > steer_dead_band_) { + return steer_diff - steer_dead_band_; + } else if (steer_diff < -steer_dead_band_) { + return steer_diff + steer_dead_band_; + } else { + return 0.0; + } + }); + const double steer_rate = + sat(-steer_diff_with_dead_band / steer_time_constant_, steer_rate_lim_, -steer_rate_lim_); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + + d_state(IDX::X) = vel * cos(yaw); + d_state(IDX::Y) = vel * sin(yaw); + d_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; + d_state(IDX::VX) = [&] { + if (pedal_acc >= 0.0) { + using autoware_vehicle_msgs::msg::GearCommand; + const auto gear = input(IDX_U::GEAR); + if (gear == GearCommand::NONE || gear == GearCommand::PARK) { + return 0.0; + } else if (gear == GearCommand::NEUTRAL) { + return input(IDX_U::SLOPE_ACCX); + } else if (gear == GearCommand::REVERSE || gear == GearCommand::REVERSE_2) { + return -pedal_acc + input(IDX_U::SLOPE_ACCX); + } else { + return pedal_acc + input(IDX_U::SLOPE_ACCX); + } + } else { + constexpr double brake_dead_band = 1e-3; + if (vel > brake_dead_band) { + return pedal_acc + input(IDX_U::SLOPE_ACCX); + } else if (vel < -brake_dead_band) { + return -pedal_acc + input(IDX_U::SLOPE_ACCX); + } else if (-pedal_acc >= std::abs(input(IDX_U::SLOPE_ACCX))) { + return 0.0; + } else { + return input(IDX_U::SLOPE_ACCX); + } + } + }(); + d_state(IDX::STEER) = steer_rate; + d_state(IDX::PEDAL_ACCX) = -(pedal_acc - pedal_acc_des) / acc_time_constant_; + + return d_state; +} diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index dc49bf17a11fc..c61237f83e5bd 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -271,6 +271,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) const std::string VEHICLE_MODEL_LIST[] = { // NOLINT "IDEAL_STEER_VEL", "IDEAL_STEER_ACC", "IDEAL_STEER_ACC_GEARED", "DELAY_STEER_VEL", "DELAY_STEER_ACC", "DELAY_STEER_ACC_GEARED", + "DELAY_STEER_ACC_GEARED_WO_FALL_GUARD" }; // clang-format on From 94c336fdca1a551ebee062758ac9c127814121bd Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 25 Jul 2024 09:57:28 +0900 Subject: [PATCH 031/151] feat(map_based_prediction): add time_keeper (#8176) (#1426) Signed-off-by: Mamoru Sobue --- .../map_based_prediction_node.hpp | 4 ++ .../src/map_based_prediction_node.cpp | 60 +++++++++++++++++++ 2 files changed, 64 insertions(+) diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index ce1c587cc3b01..1c677c9d0f6e4 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -26,6 +26,7 @@ #include #include #include +#include #include #include @@ -222,6 +223,9 @@ class MapBasedPredictionNode : public rclcpp::Node bool remember_lost_crosswalk_users_; std::unique_ptr published_time_publisher_; + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + mutable autoware::universe_utils::TimeKeeper time_keeper_; // Member Functions void mapCallback(const LaneletMapBin::ConstSharedPtr msg); diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index f505cb7cc5592..eaea3c06041b3 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -863,6 +863,11 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ published_time_publisher_ = std::make_unique(this); + detailed_processing_time_publisher_ = + this->create_publisher( + "~/debug/processing_time_detail_ms", 1); + time_keeper_ = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_); + set_param_res_ = this->add_on_set_parameters_callback( std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1)); @@ -922,6 +927,8 @@ PredictedObject MapBasedPredictionNode::convertToPredictedObject( void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Start loading lanelet"); lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg( @@ -938,6 +945,8 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg void MapBasedPredictionNode::trafficSignalsCallback( const TrafficLightGroupArray::ConstSharedPtr msg) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + traffic_signal_id_map_.clear(); for (const auto & signal : msg->traffic_light_groups) { traffic_signal_id_map_[signal.traffic_light_group_id] = signal; @@ -946,6 +955,8 @@ void MapBasedPredictionNode::trafficSignalsCallback( void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + stop_watch_ptr_->toc("processing_time", true); // take traffic_signal @@ -1237,6 +1248,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt void MapBasedPredictionNode::updateCrosswalkUserHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const std::string & object_id) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + CrosswalkUserData crosswalk_user_data; crosswalk_user_data.header = header; crosswalk_user_data.tracked_object = object; @@ -1252,6 +1265,8 @@ void MapBasedPredictionNode::updateCrosswalkUserHistory( std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared( const std::string & object_id, std::unordered_map & current_users) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const auto known_match_opt = [&]() -> std::optional { if (!known_matches_.count(object_id)) { return std::nullopt; @@ -1309,6 +1324,7 @@ std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared( bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); const lanelet::ConstLineStrings3d & all_fences = lanelet::utils::query::getAllFences(lanelet_map_ptr_); for (const auto & fence_line : all_fences) { @@ -1322,6 +1338,8 @@ bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predict bool MapBasedPredictionNode::doesPathCrossFence( const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + // check whether the predicted path cross with fence for (size_t i = 0; i < predicted_path.path.size() - 1; ++i) { for (size_t j = 0; j < fence_line.size() - 1; ++j) { @@ -1350,6 +1368,8 @@ bool MapBasedPredictionNode::isIntersecting( PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( const TrackedObject & object) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + auto predicted_object = convertToPredictedObject(object); { PredictedPath predicted_path = @@ -1482,6 +1502,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( void MapBasedPredictionNode::updateObjectData(TrackedObject & object) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + if ( object.kinematics.orientation_availability == autoware_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE) { @@ -1532,6 +1554,8 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) void MapBasedPredictionNode::removeStaleTrafficLightInfo( const TrackedObjects::ConstSharedPtr in_objects) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + for (auto it = stopped_times_against_green_.begin(); it != stopped_times_against_green_.end();) { const bool isDisappeared = std::none_of( in_objects->objects.begin(), in_objects->objects.end(), @@ -1548,6 +1572,8 @@ void MapBasedPredictionNode::removeStaleTrafficLightInfo( LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & object) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + // obstacle point lanelet::BasicPoint2d search_point( object.kinematics.pose_with_covariance.pose.position.x, @@ -1638,6 +1664,8 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob bool MapBasedPredictionNode::checkCloseLaneletCondition( const std::pair & lanelet, const TrackedObject & object) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + // Step1. If we only have one point in the centerline, we will ignore the lanelet if (lanelet.second.centerline().size() <= 1) { return false; @@ -1684,6 +1712,8 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( float MapBasedPredictionNode::calculateLocalLikelihood( const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const auto & obj_point = object.kinematics.pose_with_covariance.pose.position; // compute yaw difference between the object and lane @@ -1719,6 +1749,8 @@ void MapBasedPredictionNode::updateRoadUsersHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const LaneletsData & current_lanelets_data) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::string object_id = autoware::universe_utils::toHexString(object.object_id); const auto current_lanelets = getLanelets(current_lanelets_data); @@ -1760,6 +1792,8 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); @@ -1921,6 +1955,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuver( const TrackedObject & object, const LaneletData & current_lanelet_data, const double object_detected_time) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + // calculate maneuver const auto current_maneuver = [&]() { if (lane_change_detection_method_ == "time_to_change_lane") { @@ -1971,6 +2007,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByTimeToLaneChange( const TrackedObject & object, const LaneletData & current_lanelet_data, const double /*object_detected_time*/) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + // Step1. Check if we have the object in the buffer const std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { @@ -2042,6 +2080,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance( const TrackedObject & object, const LaneletData & current_lanelet_data, const double /*object_detected_time*/) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + // Step1. Check if we have the object in the buffer const std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { @@ -2185,6 +2225,8 @@ geometry_msgs::msg::Pose MapBasedPredictionNode::compensateTimeDelay( double MapBasedPredictionNode::calcRightLateralOffset( const lanelet::ConstLineString2d & boundary_line, const geometry_msgs::msg::Pose & search_pose) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::vector boundary_path(boundary_line.size()); for (size_t i = 0; i < boundary_path.size(); ++i) { const double x = boundary_line[i].x(); @@ -2204,6 +2246,8 @@ double MapBasedPredictionNode::calcLeftLateralOffset( void MapBasedPredictionNode::updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { return; @@ -2228,6 +2272,8 @@ void MapBasedPredictionNode::addReferencePaths( const Maneuver & maneuver, std::vector & reference_paths, const double speed_limit) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + if (!candidate_paths.empty()) { updateFuturePossibleLanelets(object, candidate_paths); const auto converted_paths = convertPathType(candidate_paths); @@ -2247,6 +2293,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( const lanelet::routing::LaneletPaths & right_paths, const lanelet::routing::LaneletPaths & center_paths) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + float left_lane_change_probability = 0.0; float right_lane_change_probability = 0.0; float lane_follow_probability = 0.0; @@ -2309,6 +2357,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( std::vector MapBasedPredictionNode::convertPathType( const lanelet::routing::LaneletPaths & paths) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::vector converted_paths; for (const auto & path : paths) { PosePath converted_path; @@ -2381,6 +2431,8 @@ bool MapBasedPredictionNode::isDuplicated( const std::pair & target_lanelet, const LaneletsData & lanelets_data) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const double CLOSE_LANELET_THRESHOLD = 0.1; for (const auto & lanelet_data : lanelets_data) { const auto target_lanelet_end_p = target_lanelet.second.centerline2d().back(); @@ -2398,6 +2450,8 @@ bool MapBasedPredictionNode::isDuplicated( bool MapBasedPredictionNode::isDuplicated( const PredictedPath & predicted_path, const std::vector & predicted_paths) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const double CLOSE_PATH_THRESHOLD = 0.1; for (const auto & prev_predicted_path : predicted_paths) { const auto prev_path_end = prev_predicted_path.path.back().position; @@ -2414,6 +2468,8 @@ bool MapBasedPredictionNode::isDuplicated( std::optional MapBasedPredictionNode::getTrafficSignalId( const lanelet::ConstLanelet & way_lanelet) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const auto traffic_light_reg_elems = way_lanelet.regulatoryElementsAs(); if (traffic_light_reg_elems.empty()) { @@ -2430,6 +2486,8 @@ std::optional MapBasedPredictionNode::getTrafficSignalId( std::optional MapBasedPredictionNode::getTrafficSignalElement( const lanelet::Id & id) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + if (traffic_signal_id_map_.count(id) != 0) { const auto & signal_elements = traffic_signal_id_map_.at(id).elements; if (signal_elements.size() > 1) { @@ -2446,6 +2504,8 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal( const TrackedObject & object, const lanelet::ConstLanelet & crosswalk, const lanelet::Id & signal_id) { + autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + const auto signal_color = [&] { const auto elem_opt = getTrafficSignalElement(signal_id); return elem_opt ? elem_opt.value().color : TrafficLightElement::UNKNOWN; From ae7cbfe5159c1b81d134c45dc7edf7697a7f4e6d Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 29 Jul 2024 10:51:42 +0900 Subject: [PATCH 032/151] perf(dynamic_obstacle_avoidance): decrease the computation time with time_keeper (#7986) (#1427) * decrease computation cost * remove TODO * fix --------- Signed-off-by: Takayuki Murooka --- .../scene.hpp | 24 +- .../src/scene.cpp | 299 +++++++++++------- 2 files changed, 200 insertions(+), 123 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 6ea15a9309c3c..8f19613b50e6d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -16,7 +16,6 @@ #define AUTOWARE__BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" -#include "autoware/universe_utils/system/stop_watch.hpp" #include #include @@ -206,20 +205,20 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::optional lat_offset_to_avoid{std::nullopt}; bool is_collision_left{false}; bool should_be_avoided{false}; - std::vector ref_path_points_for_obj_poly; + std::vector ref_points_for_obj_poly; LatFeasiblePaths ego_lat_feasible_paths; // add additional information (not update to the latest data) void update( const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, const bool arg_is_collision_left, const bool arg_should_be_avoided, - const std::vector & arg_ref_path_points_for_obj_poly) + const std::vector & arg_ref_points_for_obj_poly) { lon_offset_to_avoid = arg_lon_offset_to_avoid; lat_offset_to_avoid = arg_lat_offset_to_avoid; is_collision_left = arg_is_collision_left; should_be_avoided = arg_should_be_avoided; - ref_path_points_for_obj_poly = arg_ref_path_points_for_obj_poly; + ref_points_for_obj_poly = arg_ref_points_for_obj_poly; } }; @@ -317,12 +316,12 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface const std::string & uuid, const MinMaxValue & lon_offset_to_avoid, const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left, const bool should_be_avoided, - const std::vector & ref_path_points_for_obj_poly) + const std::vector & ref_points_for_obj_poly) { if (object_map_.count(uuid) != 0) { object_map_.at(uuid).update( lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided, - ref_path_points_for_obj_poly); + ref_points_for_obj_poly); } } @@ -409,24 +408,25 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::optional> calcCollisionSection( const std::vector & ego_path, const PredictedPath & obj_path) const; LatLonOffset getLateralLongitudinalOffset( - const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, + const std::vector & ego_points, + const geometry_msgs::msg::Pose & obj_pose, const size_t obj_seg_idx, const autoware_perception_msgs::msg::Shape & obj_shape) const; double calcValidLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_perception_msgs::msg::Shape & obj_shape, const bool is_object_same_direction) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( - const std::vector & ref_path_points_for_obj_poly, + const std::vector & ref_points_for_obj_poly, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_perception_msgs::msg::Shape & obj_shape, const TimeWhileCollision & time_while_collision) const; std::optional calcMinMaxLateralOffsetToAvoidRegulatedObject( - const std::vector & ref_path_points_for_obj_poly, + const std::vector & ref_points_for_obj_poly, const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel, const bool is_collision_left, const double obj_normal_vel, const std::optional & prev_object) const; std::optional calcMinMaxLateralOffsetToAvoidUnregulatedObject( - const std::vector & ref_path_points_for_obj_poly, + const std::vector & ref_points_for_obj_poly, const std::optional & prev_object, const DynamicAvoidanceObject & object) const; std::pair getAdjacentLanes( @@ -454,10 +454,6 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters_; TargetObjectsManager target_objects_manager_; - - mutable autoware::universe_utils::StopWatch< - std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> - stop_watch_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index 8b411340e4ddc..f195b91a54f21 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -113,11 +113,11 @@ std::optional getObjectFromUuid(const std::vector & objects, const std::st } std::pair projectObstacleVelocityToTrajectory( - const std::vector & path_points, const PredictedObject & object) + const std::vector & path_points, const PredictedObject & object, + const size_t obj_idx) { const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; const double obj_yaw = tf2::getYaw(obj_pose.orientation); - const size_t obj_idx = autoware::motion_utils::findNearestIndex(path_points, obj_pose.position); const double path_yaw = tf2::getYaw(path_points.at(obj_idx).point.pose.orientation); const Eigen::Rotation2Dd R_ego_to_obstacle(obj_yaw - path_yaw); @@ -170,12 +170,9 @@ double calcObstacleWidth(const autoware_perception_msgs::msg::Shape & shape) double calcDiffAngleAgainstPath( const std::vector & path_points, - const geometry_msgs::msg::Pose & target_pose) + const geometry_msgs::msg::Pose & target_pose, const size_t target_idx) { - const size_t nearest_idx = - autoware::motion_utils::findNearestIndex(path_points, target_pose.position); - const double traj_yaw = tf2::getYaw(path_points.at(nearest_idx).point.pose.orientation); - + const double traj_yaw = tf2::getYaw(path_points.at(target_idx).point.pose.orientation); const double target_yaw = tf2::getYaw(target_pose.orientation); const double diff_yaw = autoware::universe_utils::normalizeRadian(target_yaw - traj_yaw); @@ -202,32 +199,30 @@ double calcDiffAngleAgainstPath( } double calcDistanceToPath( - const std::vector & path_points, - const geometry_msgs::msg::Point & target_pos) + const std::vector & points, + const geometry_msgs::msg::Point & target_pos, const size_t target_idx) { - const size_t target_idx = autoware::motion_utils::findNearestIndex(path_points, target_pos); - if (target_idx == 0 || target_idx == path_points.size() - 1) { - const double target_yaw = tf2::getYaw(path_points.at(target_idx).point.pose.orientation); - const double angle_to_target_pos = autoware::universe_utils::calcAzimuthAngle( - path_points.at(target_idx).point.pose.position, target_pos); + if (target_idx == 0 || target_idx == points.size() - 1) { + const double target_yaw = tf2::getYaw(points.at(target_idx).orientation); + const double angle_to_target_pos = + autoware::universe_utils::calcAzimuthAngle(points.at(target_idx).position, target_pos); const double diff_yaw = autoware::universe_utils::normalizeRadian(angle_to_target_pos - target_yaw); if ( (target_idx == 0 && (diff_yaw < -M_PI_2 || M_PI_2 < diff_yaw)) || - (target_idx == path_points.size() - 1 && (-M_PI_2 < diff_yaw && diff_yaw < M_PI_2))) { - return autoware::universe_utils::calcDistance2d(path_points.at(target_idx), target_pos); + (target_idx == points.size() - 1 && (-M_PI_2 < diff_yaw && diff_yaw < M_PI_2))) { + return autoware::universe_utils::calcDistance2d(points.at(target_idx), target_pos); } } - return std::abs(autoware::motion_utils::calcLateralOffset(path_points, target_pos)); + return std::abs(autoware::motion_utils::calcLateralOffset(points, target_pos)); } bool isLeft( const std::vector & path_points, - const geometry_msgs::msg::Point & target_pos) + const geometry_msgs::msg::Point & target_pos, const size_t target_idx) { - const size_t target_idx = autoware::motion_utils::findNearestIndex(path_points, target_pos); const double target_yaw = tf2::getYaw(path_points.at(target_idx).point.pose.orientation); const double angle_to_target_pos = autoware::universe_utils::calcAzimuthAngle( path_points.at(target_idx).point.pose.position, target_pos); @@ -303,6 +298,32 @@ std::vector convertToPoints( } return points; } + +// NOTE: Giving PathPointWithLaneId to autoware_motion_utils functions +// cost a lot. Instead, using Pose is much faster (around x10). +std::vector toGeometryPoints( + const std::vector & path_points) +{ + std::vector geom_points; + for (const auto & path_point : path_points) { + geom_points.push_back(path_point.point.pose); + } + return geom_points; +} + +size_t getNearestIndexFromSegmentIndex( + const std::vector & points, const size_t seg_idx, + const geometry_msgs::msg::Point & target_pos) +{ + const double first_dist = + autoware::universe_utils::calcDistance2d(points.at(seg_idx), target_pos); + const double second_dist = + autoware::universe_utils::calcDistance2d(points.at(seg_idx + 1), target_pos); + if (first_dist < second_dist) { + return seg_idx; + } + return seg_idx + 1; +} } // namespace DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( @@ -351,7 +372,7 @@ bool DynamicObstacleAvoidanceModule::isExecutionReady() const void DynamicObstacleAvoidanceModule::updateData() { - // stop_watch_.tic(std::string(__func__)); + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); info_marker_.markers.clear(); debug_marker_.markers.clear(); @@ -377,11 +398,6 @@ void DynamicObstacleAvoidanceModule::updateData() target_objects_.push_back(target_object_candidate); } } - - // const double calculation_time = stop_watch_.toc(std::string(__func__)); - // RCLCPP_INFO_STREAM_EXPRESSION( - // getLogger(), parameters_->enable_debug_info, __func__ << ":=" << calculation_time << " - // [ms]"); } bool DynamicObstacleAvoidanceModule::canTransitSuccessState() @@ -391,8 +407,6 @@ bool DynamicObstacleAvoidanceModule::canTransitSuccessState() BehaviorModuleOutput DynamicObstacleAvoidanceModule::plan() { - // stop_watch_.tic(std::string(__func__)); - const auto & input_path = getPreviousModuleOutput().path; if (input_path.points.empty()) { throw std::runtime_error("input path is empty"); @@ -440,11 +454,6 @@ BehaviorModuleOutput DynamicObstacleAvoidanceModule::plan() output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; output.modified_goal = getPreviousModuleOutput().modified_goal; - // const double calculation_time = stop_watch_.toc(std::string(__func__)); - // RCLCPP_INFO_STREAM_EXPRESSION( - // getLogger(), parameters_->enable_debug_info, __func__ << ":=" << calculation_time << " - // [ms]"); - return output; } @@ -494,7 +503,10 @@ ObjectType DynamicObstacleAvoidanceModule::getObjectType(const uint8_t label) co void DynamicObstacleAvoidanceModule::registerRegulatedObjects( const std::vector & prev_objects) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto input_path = getPreviousModuleOutput().path; + const auto input_points = toGeometryPoints(input_path.points); // for efficient computation const auto & predicted_objects = planner_data_->dynamic_object->objects; for (const auto & predicted_object : predicted_objects) { @@ -508,6 +520,10 @@ void DynamicObstacleAvoidanceModule::registerRegulatedObjects( predicted_object.kinematics.predicted_paths.begin(), predicted_object.kinematics.predicted_paths.end(), [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(input_points, obj_pose.position); + const size_t obj_idx = + getNearestIndexFromSegmentIndex(input_points, obj_seg_idx, obj_pose.position); // 1.a. check label if (getObjectType(predicted_object.classification.front().label) != ObjectType::REGULATED) { @@ -516,7 +532,7 @@ void DynamicObstacleAvoidanceModule::registerRegulatedObjects( // 1.b. check obstacle velocity const auto [obj_tangent_vel, obj_normal_vel] = - projectObstacleVelocityToTrajectory(input_path.points, predicted_object); + projectObstacleVelocityToTrajectory(input_path.points, predicted_object, obj_idx); if ( std::abs(obj_tangent_vel) < parameters_->min_obstacle_vel || parameters_->max_obstacle_vel < std::abs(obj_tangent_vel)) { @@ -524,7 +540,7 @@ void DynamicObstacleAvoidanceModule::registerRegulatedObjects( } // 1.c. check if object is not crossing ego's path - const double obj_angle = calcDiffAngleAgainstPath(input_path.points, obj_pose); + const double obj_angle = calcDiffAngleAgainstPath(input_path.points, obj_pose, obj_idx); const double max_crossing_object_angle = 0.0 <= obj_tangent_vel ? parameters_->max_overtaking_crossing_object_angle : parameters_->max_oncoming_crossing_object_angle; @@ -544,7 +560,7 @@ void DynamicObstacleAvoidanceModule::registerRegulatedObjects( } // 1.e. check if object lateral offset to ego's path is small enough - const double obj_dist_to_path = calcDistanceToPath(input_path.points, obj_pose.position); + const double obj_dist_to_path = calcDistanceToPath(input_points, obj_pose.position, obj_idx); const bool is_object_far_from_path = isObjectFarFromPath(predicted_object, obj_dist_to_path); if (is_object_far_from_path) { RCLCPP_INFO_EXPRESSION( @@ -582,7 +598,10 @@ void DynamicObstacleAvoidanceModule::registerRegulatedObjects( void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( const std::vector & prev_objects) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto input_path = getPreviousModuleOutput().path; + const auto input_points = toGeometryPoints(input_path.points); // for efficient computation const auto & predicted_objects = planner_data_->dynamic_object->objects; for (const auto & predicted_object : predicted_objects) { @@ -596,6 +615,10 @@ void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( predicted_object.kinematics.predicted_paths.begin(), predicted_object.kinematics.predicted_paths.end(), [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(input_points, obj_pose.position); + const size_t obj_idx = + getNearestIndexFromSegmentIndex(input_points, obj_seg_idx, obj_pose.position); // 1.a. Check if the obstacle is labeled as pedestrians, bicycle or similar. if (getObjectType(predicted_object.classification.front().label) != ObjectType::UNREGULATED) { @@ -604,7 +627,7 @@ void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( // 1.b. Check if the object's velocity is within the module's coverage range. const auto [obj_tangent_vel, obj_normal_vel] = - projectObstacleVelocityToTrajectory(input_path.points, predicted_object); + projectObstacleVelocityToTrajectory(input_path.points, predicted_object, obj_idx); if ( obj_vel_norm < parameters_->min_obstacle_vel || obj_vel_norm > parameters_->max_obstacle_vel) { @@ -626,7 +649,7 @@ void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( // 1.f. calculate the object is on ego's path or not const double dist_obj_center_to_path = - std::abs(autoware::motion_utils::calcLateralOffset(input_path.points, obj_pose.position)); + std::abs(autoware::motion_utils::calcLateralOffset(input_points, obj_pose.position)); const bool is_object_on_ego_path = dist_obj_center_to_path < planner_data_->parameters.vehicle_width / 2.0 + parameters_->min_obj_lat_offset_to_ego_path; @@ -656,7 +679,10 @@ void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObjects( const std::vector & prev_objects) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto & input_path = getPreviousModuleOutput().path; + const auto input_points = toGeometryPoints(input_path.points); // for efficient computation for (const auto & object : target_objects_manager_.getValidObjects()) { if (getObjectType(object.label) != ObjectType::REGULATED) { @@ -668,11 +694,15 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje const auto obj_path = *std::max_element( object.predicted_paths.begin(), object.predicted_paths.end(), [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(input_points, object.pose.position); + const size_t obj_idx = + getNearestIndexFromSegmentIndex(input_points, obj_seg_idx, object.pose.position); - const auto & ref_path_points_for_obj_poly = input_path.points; + const auto & ref_points_for_obj_poly = input_points; // 2.a. check if object is not to be followed by ego - const double obj_angle = calcDiffAngleAgainstPath(input_path.points, object.pose); + const double obj_angle = calcDiffAngleAgainstPath(input_path.points, object.pose, obj_idx); const bool is_object_aligned_to_path = std::abs(obj_angle) < parameters_->max_front_object_angle || M_PI - parameters_->max_front_object_angle < std::abs(obj_angle); @@ -686,9 +716,9 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje } // 2.b. calculate which side object exists against ego's path - const bool is_object_left = isLeft(input_path.points, object.pose.position); + const bool is_object_left = isLeft(input_path.points, object.pose.position, obj_idx); const auto lat_lon_offset = - getLateralLongitudinalOffset(input_path.points, object.pose, object.shape); + getLateralLongitudinalOffset(input_points, object.pose, obj_seg_idx, object.shape); // 2.c. check if object will not cut in const bool will_object_cut_in = @@ -759,7 +789,10 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje } const auto future_obj_pose = object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); - return future_obj_pose ? isLeft(input_path.points, future_obj_pose->position) + const size_t future_obj_idx = + autoware::motion_utils::findNearestIndex(input_path.points, future_obj_pose->position); + + return future_obj_pose ? isLeft(input_path.points, future_obj_pose->position, future_obj_idx) : is_object_left; }(); @@ -790,10 +823,10 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje // "ego_path_base" const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( - ref_path_points_for_obj_poly, object.pose, obj_points, object.vel, obj_path, object.shape, + ref_points_for_obj_poly, object.pose, obj_points, object.vel, obj_path, object.shape, time_while_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoidRegulatedObject( - ref_path_points_for_obj_poly, obj_points, object.pose.position, object.vel, is_collision_left, + ref_points_for_obj_poly, obj_points, object.pose.position, object.vel, is_collision_left, object.lat_vel, prev_object); if (!lat_offset_to_avoid) { @@ -808,7 +841,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje const bool should_be_avoided = true; target_objects_manager_.updateObjectVariables( obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, - ref_path_points_for_obj_poly); + ref_points_for_obj_poly); } // prev_input_ref_path_points_ = input_ref_path_points; } @@ -816,23 +849,31 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedObjects( const std::vector & prev_objects) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto & input_path = getPreviousModuleOutput().path; + const auto input_points = toGeometryPoints(input_path.points); // for efficient computation + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); for (const auto & object : target_objects_manager_.getValidObjects()) { if (getObjectType(object.label) != ObjectType::UNREGULATED) { continue; } + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(input_points, object.pose.position); const auto obj_uuid = object.uuid; - const auto & ref_path_points_for_obj_poly = input_path.points; + const auto & ref_points_for_obj_poly = input_points; // 2.g. check if the ego is not ahead of the object. + time_keeper_->start_track("getLateralLongitudinalOffset"); const auto lat_lon_offset = - getLateralLongitudinalOffset(input_path.points, object.pose, object.shape); + getLateralLongitudinalOffset(input_points, object.pose, obj_seg_idx, object.shape); + time_keeper_->end_track("getLateralLongitudinalOffset"); + const double signed_dist_ego_to_obj = [&]() { - const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); const double lon_offset_ego_to_obj = autoware::motion_utils::calcSignedArcLength( - input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); + input_points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( 0.0, lon_offset_ego_to_obj - planner_data_->parameters.front_overhang + @@ -854,7 +895,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedOb // 2.h. calculate longitudinal and lateral offset to avoid to generate object polygon by // "ego_path_base" const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoidUnregulatedObject( - ref_path_points_for_obj_poly, getObstacleFromUuid(prev_objects, obj_uuid), object); + ref_points_for_obj_poly, getObstacleFromUuid(prev_objects, obj_uuid), object); if (!lat_offset_to_avoid) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -870,7 +911,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedOb const bool should_be_avoided = true; target_objects_manager_.updateObjectVariables( obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, - ref_path_points_for_obj_poly); + ref_points_for_obj_poly); } } @@ -1186,30 +1227,54 @@ DynamicObstacleAvoidanceModule::getAdjacentLanes( DynamicObstacleAvoidanceModule::LatLonOffset DynamicObstacleAvoidanceModule::getLateralLongitudinalOffset( - const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, + const std::vector & ego_points, + const geometry_msgs::msg::Pose & obj_pose, const size_t obj_seg_idx, const autoware_perception_msgs::msg::Shape & obj_shape) const { - const size_t obj_seg_idx = - autoware::motion_utils::findNearestSegmentIndex(ego_path, obj_pose.position); - const auto obj_points = autoware::universe_utils::toPolygon2d(obj_pose, obj_shape); - // TODO(murooka) calculation is not so accurate. std::vector obj_lat_offset_vec; std::vector obj_lon_offset_vec; - for (size_t i = 0; i < obj_points.outer().size(); ++i) { - const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); - const size_t obj_point_seg_idx = - autoware::motion_utils::findNearestSegmentIndex(ego_path, geom_obj_point); + if (obj_shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + // NOTE: efficient calculation for the CYLINDER object. + const double radius = obj_shape.dimensions.x / 2.0; // calculate lateral offset - const double obj_point_lat_offset = - autoware::motion_utils::calcLateralOffset(ego_path, geom_obj_point, obj_point_seg_idx); - obj_lat_offset_vec.push_back(obj_point_lat_offset); + const double obj_lat_offset = + autoware::motion_utils::calcLateralOffset(ego_points, obj_pose.position, obj_seg_idx); + double obj_max_lat_offset = obj_lat_offset + radius; + if (obj_max_lat_offset * obj_lat_offset < 0) { + obj_max_lat_offset = 0.0; + } + double obj_min_lat_offset = obj_lat_offset - radius; + if (obj_min_lat_offset * obj_lat_offset < 0) { + obj_min_lat_offset = 0.0; + } + + obj_lat_offset_vec.push_back(obj_max_lat_offset); + obj_lat_offset_vec.push_back(obj_min_lat_offset); // calculate longitudinal offset - const double lon_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - ego_path, obj_seg_idx, geom_obj_point); - obj_lon_offset_vec.push_back(lon_offset); + const double obj_lon_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( + ego_points, obj_seg_idx, obj_pose.position); + obj_lon_offset_vec.push_back(obj_lon_offset - radius); + obj_lon_offset_vec.push_back(obj_lon_offset + radius); + } else { + const auto obj_points = autoware::universe_utils::toPolygon2d(obj_pose, obj_shape); + for (size_t i = 0; i < obj_points.outer().size(); ++i) { + const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); + const size_t obj_point_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(ego_points, geom_obj_point); + + // calculate lateral offset + const double obj_point_lat_offset = + autoware::motion_utils::calcLateralOffset(ego_points, geom_obj_point, obj_point_seg_idx); + obj_lat_offset_vec.push_back(obj_point_lat_offset); + + // calculate longitudinal offset + const double lon_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( + ego_points, obj_seg_idx, geom_obj_point); + obj_lon_offset_vec.push_back(lon_offset); + } } const auto obj_lat_min_max_offset = getMinMaxValues(obj_lat_offset_vec); @@ -1221,13 +1286,13 @@ DynamicObstacleAvoidanceModule::getLateralLongitudinalOffset( } MinMaxValue DynamicObstacleAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( - const std::vector & ref_path_points_for_obj_poly, + const std::vector & ref_points_for_obj_poly, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_perception_msgs::msg::Shape & obj_shape, const TimeWhileCollision & time_while_collision) const { - const size_t obj_seg_idx = autoware::motion_utils::findNearestSegmentIndex( - ref_path_points_for_obj_poly, obj_pose.position); + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(ref_points_for_obj_poly, obj_pose.position); // calculate min/max longitudinal offset from object to path const auto obj_lon_offset = [&]() { @@ -1235,7 +1300,7 @@ MinMaxValue DynamicObstacleAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); const double lon_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - ref_path_points_for_obj_poly, obj_seg_idx, geom_obj_point); + ref_points_for_obj_poly, obj_seg_idx, geom_obj_point); obj_lon_offset_vec.push_back(lon_offset); } @@ -1388,22 +1453,21 @@ double DynamicObstacleAvoidanceModule::calcValidLengthToAvoid( // min value denotes near side, max value denotes far side std::optional DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( - const std::vector & ref_path_points_for_obj_poly, + const std::vector & ref_points_for_obj_poly, const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel, const bool is_collision_left, const double obj_normal_vel, const std::optional & prev_object) const { const bool enable_lowpass_filter = [&]() { if ( - !prev_object || prev_object->ref_path_points_for_obj_poly.size() < 2 || - ref_path_points_for_obj_poly.size() < 2) { + !prev_object || prev_object->ref_points_for_obj_poly.size() < 2 || + ref_points_for_obj_poly.size() < 2) { return true; } const size_t obj_point_idx = - autoware::motion_utils::findNearestIndex(ref_path_points_for_obj_poly, obj_pos); + autoware::motion_utils::findNearestIndex(ref_points_for_obj_poly, obj_pos); const double paths_lat_diff = std::abs(autoware::motion_utils::calcLateralOffset( - prev_object->ref_path_points_for_obj_poly, - ref_path_points_for_obj_poly.at(obj_point_idx).point.pose.position)); + prev_object->ref_points_for_obj_poly, ref_points_for_obj_poly.at(obj_point_idx).position)); constexpr double min_paths_lat_diff = 0.3; if (paths_lat_diff < min_paths_lat_diff) { @@ -1419,10 +1483,10 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( std::vector obj_lat_abs_offset_vec; for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); - const size_t obj_point_seg_idx = autoware::motion_utils::findNearestSegmentIndex( - ref_path_points_for_obj_poly, geom_obj_point); + const size_t obj_point_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(ref_points_for_obj_poly, geom_obj_point); const double obj_point_lat_offset = autoware::motion_utils::calcLateralOffset( - ref_path_points_for_obj_poly, geom_obj_point, obj_point_seg_idx); + ref_points_for_obj_poly, geom_obj_point, obj_point_seg_idx); obj_lat_abs_offset_vec.push_back(obj_point_lat_offset); } return getMinMaxValues(obj_lat_abs_offset_vec); @@ -1483,21 +1547,28 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( // min value denotes near side, max value denotes far side std::optional DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( - const std::vector & ref_path_points_for_obj_poly, + const std::vector & ref_points_for_obj_poly, const std::optional & prev_object, const DynamicAvoidanceObject & object) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + + time_keeper_->start_track("findNearestSegmentIndex of object position"); + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(ref_points_for_obj_poly, object.pose.position); + time_keeper_->end_track("findNearestSegmentIndex of object position"); + const size_t obj_point_idx = + getNearestIndexFromSegmentIndex(ref_points_for_obj_poly, obj_seg_idx, object.pose.position); + const bool enable_lowpass_filter = [&]() { + universe_utils::ScopedTimeTrack st("calc enable_lowpass_filter", *time_keeper_); if ( - !prev_object || prev_object->ref_path_points_for_obj_poly.size() < 2 || - ref_path_points_for_obj_poly.size() < 2) { + !prev_object || prev_object->ref_points_for_obj_poly.size() < 2 || + ref_points_for_obj_poly.size() < 2) { return true; } - const size_t obj_point_idx = - autoware::motion_utils::findNearestIndex(ref_path_points_for_obj_poly, object.pose.position); const double paths_lat_diff = std::abs(autoware::motion_utils::calcLateralOffset( - prev_object->ref_path_points_for_obj_poly, - ref_path_points_for_obj_poly.at(obj_point_idx).point.pose.position)); + prev_object->ref_points_for_obj_poly, ref_points_for_obj_poly.at(obj_point_idx).position)); constexpr double min_paths_lat_diff = 0.3; if (paths_lat_diff < min_paths_lat_diff) { @@ -1509,15 +1580,33 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( }(); const auto obj_occupancy_region = [&]() { - const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); + universe_utils::ScopedTimeTrack st("calc obj_occupancy_region", *time_keeper_); std::vector lat_pos_vec; - for (size_t i = 0; i < obj_points.outer().size(); ++i) { - const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); - const double obj_point_lat_offset = autoware::motion_utils::calcLateralOffset( - ref_path_points_for_obj_poly, geom_obj_point, - autoware::motion_utils::findNearestSegmentIndex( - ref_path_points_for_obj_poly, geom_obj_point)); - lat_pos_vec.push_back(obj_point_lat_offset); + if (object.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + // NOTE: efficient calculation for the CYLINDER object. + const double radius = object.shape.dimensions.x / 2.0; + + const double obj_lat_offset = autoware::motion_utils::calcLateralOffset( + ref_points_for_obj_poly, object.pose.position, obj_seg_idx); + const double obj_min_lat_offset = [&]() { + if (std::abs(obj_lat_offset) < radius) { + return 0.0; + } + if (0.0 < obj_lat_offset) { + return obj_lat_offset - radius; + } + return obj_lat_offset + radius; + }(); + lat_pos_vec.push_back(obj_min_lat_offset); + } else { + const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); + for (size_t i = 0; i < obj_points.outer().size(); ++i) { + const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); + const double obj_point_lat_offset = autoware::motion_utils::calcLateralOffset( + ref_points_for_obj_poly, geom_obj_point, + autoware::motion_utils::findNearestSegmentIndex(ref_points_for_obj_poly, geom_obj_point)); + lat_pos_vec.push_back(obj_point_lat_offset); + } } const auto current_pos_area = getMinMaxValues(lat_pos_vec); return combineMinMaxValues(current_pos_area, current_pos_area + object.lat_vel * 3.0); @@ -1574,19 +1663,19 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( return std::nullopt; } - auto ref_path_points_for_obj_poly = object.ref_path_points_for_obj_poly; + auto ref_points_for_obj_poly = object.ref_points_for_obj_poly; - const size_t obj_seg_idx = autoware::motion_utils::findNearestSegmentIndex( - ref_path_points_for_obj_poly, object.pose.position); + const size_t obj_seg_idx = + autoware::motion_utils::findNearestSegmentIndex(ref_points_for_obj_poly, object.pose.position); // const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); const auto lon_bound_start_idx_opt = autoware::motion_utils::insertTargetPoint( - obj_seg_idx, object.lon_offset_to_avoid->min_value, ref_path_points_for_obj_poly); + obj_seg_idx, object.lon_offset_to_avoid->min_value, ref_points_for_obj_poly); const size_t updated_obj_seg_idx = (lon_bound_start_idx_opt && lon_bound_start_idx_opt.value() <= obj_seg_idx) ? obj_seg_idx + 1 : obj_seg_idx; const auto lon_bound_end_idx_opt = autoware::motion_utils::insertTargetPoint( - updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, ref_path_points_for_obj_poly); + updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, ref_points_for_obj_poly); if (!lon_bound_start_idx_opt && !lon_bound_end_idx_opt) { // NOTE: The obstacle is longitudinally out of the ego's trajectory. @@ -1596,15 +1685,14 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( lon_bound_start_idx_opt ? lon_bound_start_idx_opt.value() : static_cast(0); const size_t lon_bound_end_idx = lon_bound_end_idx_opt ? lon_bound_end_idx_opt.value() - : static_cast(ref_path_points_for_obj_poly.size() - 1); + : static_cast(ref_points_for_obj_poly.size() - 1); // create inner bound points std::vector obj_inner_bound_poses; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { // NOTE: object.lat_offset_to_avoid->min_value is not the minimum value but the inner value. obj_inner_bound_poses.push_back(autoware::universe_utils::calcOffsetPose( - ref_path_points_for_obj_poly.at(i).point.pose, 0.0, object.lat_offset_to_avoid->min_value, - 0.0)); + ref_points_for_obj_poly.at(i), 0.0, object.lat_offset_to_avoid->min_value, 0.0)); } // calculate start index laterally feasible for ego to shift considering maximum lateral jerk and @@ -1797,9 +1885,6 @@ DynamicObstacleAvoidanceModule::EgoPathReservePoly DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & ego_path) const { // This function require almost 0.5 ms. Should be refactored in the future - // double calculation_time; - // stop_watch_.tic(std::string(__func__)); - namespace strategy = boost::geometry::strategy::buffer; assert(!ego_path.points.empty()); @@ -1862,10 +1947,6 @@ DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & eg strategy::distance_asymmetric(0.0, vehicle_half_width), motion_saturated_outer_paths.left_path); - // calculation_time = stop_watch_.toc(std::string(__func__)); - // RCLCPP_INFO_STREAM_EXPRESSION( - // getLogger(), parameters_->enable_debug_info, __func__ << ":=" << calculation_time << "[ms]"); - return {left_avoid_poly, right_avoid_poly}; } From aad386962821bf4493c96f35f26ba9a169ee256a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 10 Jul 2024 08:13:26 +0900 Subject: [PATCH 033/151] fix(static_obstacle_avoidance): stop position is unstable (#7880) fix(static_obstacle_avoidance): fix stop position Signed-off-by: satoshi-ota --- .../src/scene.cpp | 6 +- .../debug.hpp | 2 + .../scene.hpp | 6 + .../utils.hpp | 11 +- .../src/debug.cpp | 17 +++ .../src/scene.cpp | 46 ++++--- .../src/utils.cpp | 117 +++++++++--------- 7 files changed, 119 insertions(+), 86 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 7571a1f61d1c1..a7a7b30e4eec0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -114,10 +114,8 @@ void AvoidanceByLaneChange::updateSpecialData() : Direction::RIGHT; } - utils::static_obstacle_avoidance::updateRegisteredObject( - registered_objects_, avoidance_data_.target_objects, p); - utils::static_obstacle_avoidance::compensateDetectionLost( - registered_objects_, avoidance_data_.target_objects, avoidance_data_.other_objects); + utils::static_obstacle_avoidance::compensateLostTargetObjects( + registered_objects_, avoidance_data_, clock_.now(), planner_data_, p); std::sort( avoidance_data_.target_objects.begin(), avoidance_data_.target_objects.end(), diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp index 316501fbbd37f..63985e574f3b2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp @@ -47,6 +47,8 @@ MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, cons MarkerArray createOtherObjectsMarkerArray( const ObjectDataArray & objects, const ObjectInfo & info, const bool verbose); +MarkerArray createStopTargetObjectMarkerArray(const AvoidancePlanningData & data); + MarkerArray createDebugMarkerArray( const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug, const std::shared_ptr & parameters); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 635edb7c84f40..34d06a46d9ac8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -266,6 +266,12 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface */ void fillAvoidanceTargetObjects(AvoidancePlanningData & data, DebugData & debug) const; + /** + * @brief fill additional data which are necessary to plan avoidance path/velocity. + * @param avoidance target objects. + */ + void fillAvoidanceTargetData(ObjectDataArray & objects) const; + /** * @brief fill candidate shift lines. * @param avoidance data. diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 1f68ef7d49c47..909d28ed4bab6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -117,15 +117,12 @@ void fillObjectStoppableJudge( ObjectData & object_data, const ObjectDataArray & registered_objects, const double feasible_stop_distance, const std::shared_ptr & parameters); -void updateRegisteredObject( - ObjectDataArray & registered_objects, const ObjectDataArray & now_objects, - const std::shared_ptr & parameters); - void updateClipObject(ObjectDataArray & clip_objects, AvoidancePlanningData & data); -void compensateDetectionLost( - const ObjectDataArray & registered_objects, ObjectDataArray & now_objects, - ObjectDataArray & other_objects); +void compensateLostTargetObjects( + ObjectDataArray & stored_objects, AvoidancePlanningData & data, const rclcpp::Time & now, + const std::shared_ptr & planner_data, + const std::shared_ptr & parameters); void filterTargetObjects( ObjectDataArray & objects, AvoidancePlanningData & data, const double forward_detection_range, diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index e9838eb4a2cfc..8618a1c340004 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -466,6 +466,23 @@ MarkerArray createOtherObjectsMarkerArray( return msg; } +MarkerArray createStopTargetObjectMarkerArray(const AvoidancePlanningData & data) +{ + MarkerArray msg; + + if (!data.stop_target_object.has_value()) { + return msg; + } + + appendMarkerArray( + createObjectsCubeMarkerArray( + {data.stop_target_object.value()}, "stop_target", createMarkerScale(3.4, 1.9, 1.9), + createMarkerColor(1.0, 0.0, 0.42, 0.5)), + &msg); + + return msg; +} + MarkerArray createDrivableBounds( const AvoidancePlanningData & data, std::string && ns, const float & r, const float & g, const float & b) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index b7ab41ec99abd..8452912989c43 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -288,16 +288,22 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( data.to_start_point = utils::static_obstacle_avoidance::calcDistanceToAvoidStartLine( data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); - // target objects for avoidance + // filter only for the latest detected objects. fillAvoidanceTargetObjects(data, debug); - // lost object compensation - utils::static_obstacle_avoidance::updateRegisteredObject( - registered_objects_, data.target_objects, parameters_); - utils::static_obstacle_avoidance::compensateDetectionLost( - registered_objects_, data.target_objects, data.other_objects); + // compensate lost object which was avoidance target. if the time hasn't passed more than + // threshold since perception module lost the target yet, this module keeps it as avoidance + // target. + utils::static_obstacle_avoidance::compensateLostTargetObjects( + registered_objects_, data, clock_->now(), planner_data_, parameters_); + + // once an object filtered for boundary clipping, this module keeps the information until the end + // of execution. utils::static_obstacle_avoidance::updateClipObject(clip_objects_, data); + // calculate various data for each target objects. + fillAvoidanceTargetData(data.target_objects); + // sort object order by longitudinal distance std::sort(data.target_objects.begin(), data.target_objects.end(), [](auto a, auto b) { return a.longitudinal < b.longitudinal; @@ -310,8 +316,6 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { - using utils::static_obstacle_avoidance::fillAvoidanceNecessity; - using utils::static_obstacle_avoidance::fillObjectStoppableJudge; using utils::static_obstacle_avoidance::filterTargetObjects; using utils::static_obstacle_avoidance::separateObjectsByPath; using utils::static_obstacle_avoidance::updateRoadShoulderDistance; @@ -347,15 +351,6 @@ void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( filterTargetObjects(objects, data, forward_detection_range, planner_data_, parameters_); updateRoadShoulderDistance(data, planner_data_, parameters_); - // Calculate the distance needed to safely decelerate the ego vehicle to a stop line. - const auto & vehicle_width = planner_data_->parameters.vehicle_width; - const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false); - std::for_each(data.target_objects.begin(), data.target_objects.end(), [&, this](auto & o) { - fillAvoidanceNecessity(o, registered_objects_, vehicle_width, parameters_); - o.to_stop_line = calcDistanceToStopLine(o); - fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_); - }); - // debug { std::vector debug_info_array; @@ -373,6 +368,21 @@ void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( } } +void StaticObstacleAvoidanceModule::fillAvoidanceTargetData(ObjectDataArray & objects) const +{ + using utils::static_obstacle_avoidance::fillAvoidanceNecessity; + using utils::static_obstacle_avoidance::fillObjectStoppableJudge; + + // Calculate the distance needed to safely decelerate the ego vehicle to a stop line. + const auto & vehicle_width = planner_data_->parameters.vehicle_width; + const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false); + std::for_each(objects.begin(), objects.end(), [&, this](auto & o) { + fillAvoidanceNecessity(o, registered_objects_, vehicle_width, parameters_); + o.to_stop_line = calcDistanceToStopLine(o); + fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_); + }); +} + ObjectData StaticObstacleAvoidanceModule::createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const { @@ -1392,11 +1402,13 @@ void StaticObstacleAvoidanceModule::updateRTCData() void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { + using utils::static_obstacle_avoidance::createStopTargetObjectMarkerArray; using utils::static_obstacle_avoidance::createTargetObjectsMarkerArray; info_marker_.markers.clear(); appendMarkerArray( createTargetObjectsMarkerArray(data.target_objects, "target_objects"), &info_marker_); + appendMarkerArray(createStopTargetObjectMarkerArray(data), &info_marker_); } void StaticObstacleAvoidanceModule::updateDebugMarker( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 016972dccb38e..64831e3b24fff 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1645,31 +1645,39 @@ void fillObjectStoppableJudge( object_data.is_stoppable = same_id_obj->is_stoppable; } -void updateRegisteredObject( - ObjectDataArray & registered_objects, const ObjectDataArray & now_objects, +void compensateLostTargetObjects( + ObjectDataArray & stored_objects, AvoidancePlanningData & data, const rclcpp::Time & now, + const std::shared_ptr & planner_data, const std::shared_ptr & parameters) { - const auto updateIfDetectedNow = [&now_objects](auto & registered_object) { - const auto & n = now_objects; - const auto r_id = registered_object.object.object_id; - const auto same_id_obj = std::find_if( - n.begin(), n.end(), [&r_id](const auto & o) { return o.object.object_id == r_id; }); + const auto include = [](const auto & objects, const auto & search_id) { + return std::all_of(objects.begin(), objects.end(), [&search_id](const auto & o) { + return o.object.object_id != search_id; + }); + }; + + // STEP.1 UPDATE STORED OBJECTS. + const auto match = [&data](auto & object) { + const auto & search_id = object.object.object_id; + const auto same_id_object = std::find_if( + data.target_objects.begin(), data.target_objects.end(), + [&search_id](const auto & o) { return o.object.object_id == search_id; }); // same id object is detected. update registered. - if (same_id_obj != n.end()) { - registered_object = *same_id_obj; + if (same_id_object != data.target_objects.end()) { + object = *same_id_object; return true; } - constexpr auto POS_THR = 1.5; - const auto r_pos = registered_object.getPose(); - const auto similar_pos_obj = std::find_if(n.begin(), n.end(), [&](const auto & o) { - return calcDistance2d(r_pos, o.getPose()) < POS_THR; - }); + const auto similar_pos_obj = std::find_if( + data.target_objects.begin(), data.target_objects.end(), [&object](const auto & o) { + constexpr auto POS_THR = 1.5; + return calcDistance2d(object.getPose(), o.getPose()) < POS_THR; + }); // same id object is not detected, but object is found around registered. update registered. - if (similar_pos_obj != n.end()) { - registered_object = *similar_pos_obj; + if (similar_pos_obj != data.target_objects.end()) { + object = *similar_pos_obj; return true; } @@ -1677,61 +1685,54 @@ void updateRegisteredObject( return false; }; - const rclcpp::Time now = rclcpp::Clock(RCL_ROS_TIME).now(); - - // -- check registered_objects, remove if lost_count exceeds limit. -- - for (int i = static_cast(registered_objects.size()) - 1; i >= 0; --i) { - auto & r = registered_objects.at(i); - - // registered object is not detected this time. lost count up. - if (!updateIfDetectedNow(r)) { - r.lost_time = (now - r.last_seen).seconds(); - } else { - r.last_seen = now; - r.lost_time = 0.0; - } + // STEP1-1: REMOVE EXPIRED OBJECTS. + const auto itr = std::remove_if( + stored_objects.begin(), stored_objects.end(), [&now, &match, ¶meters](auto & o) { + if (!match(o)) { + o.lost_time = (now - o.last_seen).seconds(); + } else { + o.last_seen = now; + o.lost_time = 0.0; + } - // lost count exceeds threshold. remove object from register. - if (r.lost_time > parameters->object_last_seen_threshold) { - registered_objects.erase(registered_objects.begin() + i); - } - } + return o.lost_time > parameters->object_last_seen_threshold; + }); - const auto isAlreadyRegistered = [&](const auto & n_id) { - const auto & r = registered_objects; - return std::any_of( - r.begin(), r.end(), [&n_id](const auto & o) { return o.object.object_id == n_id; }); - }; + stored_objects.erase(itr, stored_objects.end()); - // -- check now_objects, add it if it has new object id -- - for (const auto & now_obj : now_objects) { - if (!isAlreadyRegistered(now_obj.object.object_id)) { - registered_objects.push_back(now_obj); + // STEP1-2: UPDATE STORED OBJECTS IF THERE ARE NEW OBJECTS. + for (const auto & current_object : data.target_objects) { + if (!include(stored_objects, current_object.object.object_id)) { + stored_objects.push_back(current_object); } } -} -void compensateDetectionLost( - const ObjectDataArray & registered_objects, ObjectDataArray & now_objects, - ObjectDataArray & other_objects) -{ - const auto isDetectedNow = [&](const auto & r_id) { - const auto & n = now_objects; + // STEP2: COMPENSATE CURRENT TARGET OBJECTS + const auto is_detected = [&](const auto & object_id) { return std::any_of( - n.begin(), n.end(), [&r_id](const auto & o) { return o.object.object_id == r_id; }); + data.target_objects.begin(), data.target_objects.end(), + [&object_id](const auto & o) { return o.object.object_id == object_id; }); }; - const auto isIgnoreObject = [&](const auto & r_id) { - const auto & n = other_objects; + const auto is_ignored = [&](const auto & object_id) { return std::any_of( - n.begin(), n.end(), [&r_id](const auto & o) { return o.object.object_id == r_id; }); + data.other_objects.begin(), data.other_objects.end(), + [&object_id](const auto & o) { return o.object.object_id == object_id; }); }; - for (const auto & registered : registered_objects) { - if ( - !isDetectedNow(registered.object.object_id) && !isIgnoreObject(registered.object.object_id)) { - now_objects.push_back(registered); + for (auto & stored_object : stored_objects) { + if (is_detected(stored_object.object.object_id)) { + continue; + } + if (is_ignored(stored_object.object.object_id)) { + continue; } + + const auto & ego_pos = planner_data->self_odometry->pose.pose.position; + fillLongitudinalAndLengthByClosestEnvelopeFootprint( + data.reference_path_rough, ego_pos, stored_object); + + data.target_objects.push_back(stored_object); } } From eb123deec9d39a2c035deac4f64fbdbb1f471101 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 10 Jul 2024 19:18:30 +0900 Subject: [PATCH 034/151] fix(static_obstacle_avoidance): don't automatically avoid ambiguous vehicle (#7851) * fix(static_obstacle_avoidance): don't automatically avoid ambiguous vehicle Signed-off-by: satoshi-ota * chore(schema): update schema Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/manager.cpp | 8 ++-- .../static_obstacle_avoidance.param.yaml | 10 +++- .../data_structs.hpp | 5 +- .../helper.hpp | 47 +++++++++++++++++-- .../parameter_helper.hpp | 8 ++-- .../static_obstacle_avoidance.schema.json | 31 ++++++++---- .../src/manager.cpp | 5 +- .../src/utils.cpp | 23 +++------ 8 files changed, 95 insertions(+), 42 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 02b90186d9b2f..8096d2944ee2b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -137,9 +137,11 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) { const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle."; - p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "enable"); - p.closest_distance_to_wait_and_see_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "closest_distance_to_wait_and_see"); + p.policy_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "policy"); + p.wait_and_see_target_behaviors = + getOrDeclareParameter>(*node, ns + "wait_and_see.target_behaviors"); + p.wait_and_see_th_closest_distance = + getOrDeclareParameter(*node, ns + "wait_and_see.th_closest_distance"); p.time_threshold_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); p.distance_threshold_for_ambiguous_vehicle = diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 3087ccc93934b..6bd5e0faf1938 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -138,8 +138,11 @@ # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. avoidance_for_ambiguous_vehicle: - enable: true # [-] - closest_distance_to_wait_and_see: 10.0 # [m] + # policy for ego behavior for ambiguous vehicle. + # "auto" : generate candidate path. if RTC is running as AUTO mode, the ego avoids it automatically. + # "manual" : generate candidate path and wait operator approval even if RTC is running as AUTO mode. + # "ignore" : never avoid it. + policy: "auto" # [-] condition: th_stopped_time: 3.0 # [s] th_moving_distance: 1.0 # [m] @@ -149,6 +152,9 @@ crosswalk: front_distance: 30.0 # [m] behind_distance: 30.0 # [m] + wait_and_see: + target_behaviors: ["MERGING", "DEVIATING"] # [-] + th_closest_distance: 10.0 # [m] # params for filtering objects that are in intersection intersection: diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 49599004e0952..079928a58bd9f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -108,7 +108,7 @@ struct AvoidanceParameters bool enable_cancel_maneuver{false}; // enable avoidance for all parking vehicle - bool enable_avoidance_for_ambiguous_vehicle{false}; + std::string policy_ambiguous_vehicle{"ignore"}; // enable yield maneuver. bool enable_yield_maneuver{false}; @@ -192,7 +192,8 @@ struct AvoidanceParameters double object_check_min_road_shoulder_width{0.0}; // force avoidance - double closest_distance_to_wait_and_see_for_ambiguous_vehicle{0.0}; + std::vector wait_and_see_target_behaviors{"NONE", "MERGING", "DEVIATING"}; + double wait_and_see_th_closest_distance{0.0}; double time_threshold_for_ambiguous_vehicle{0.0}; double distance_threshold_for_ambiguous_vehicle{0.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index 8c46affbc64e3..bfeb942c82be3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -325,10 +326,27 @@ class AvoidanceHelper const auto object = objects.front(); + // if the object is NOT ambiguous, this module doesn't wait operator approval if RTC is running + // as AUTO mode. if (!object.is_ambiguous) { return true; } + // check only front objects. + if (object.longitudinal < 0.0) { + return true; + } + + // if the policy is "manual", this module generates candidate path and waits approval. + if (parameters_->policy_ambiguous_vehicle == "manual") { + return false; + } + + // don't delay avoidance start position if it's not MERGING or DEVIATING vehicle. + if (!isWaitAndSeeTarget(object)) { + return true; + } + if (!object.avoid_margin.has_value()) { return true; } @@ -341,9 +359,32 @@ class AvoidanceHelper const auto constant_distance = getFrontConstantDistance(object); const auto avoidance_distance = getMinAvoidanceDistance(desire_shift_length); - return object.longitudinal < - prepare_distance + constant_distance + avoidance_distance + - parameters_->closest_distance_to_wait_and_see_for_ambiguous_vehicle; + return object.longitudinal < prepare_distance + constant_distance + avoidance_distance + + parameters_->wait_and_see_th_closest_distance; + } + + bool isWaitAndSeeTarget(const ObjectData & object) const + { + const auto & behaviors = parameters_->wait_and_see_target_behaviors; + if (object.behavior == ObjectData::Behavior::MERGING) { + return std::any_of(behaviors.begin(), behaviors.end(), [](const std::string & behavior) { + return behavior == "MERGING"; + }); + } + + if (object.behavior == ObjectData::Behavior::DEVIATING) { + return std::any_of(behaviors.begin(), behaviors.end(), [](const std::string & behavior) { + return behavior == "DEVIATING"; + }); + } + + if (object.behavior == ObjectData::Behavior::NONE) { + return std::any_of(behaviors.begin(), behaviors.end(), [](const std::string & behavior) { + return behavior == "NONE"; + }); + } + + return false; } static bool isAbsolutelyNotAvoidable(const ObjectData & object) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 84cf7c4e33d26..0cea2a4e633c3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -137,9 +137,11 @@ AvoidanceParameters getParameter(rclcpp::Node * node) { const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle."; - p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "enable"); - p.closest_distance_to_wait_and_see_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "closest_distance_to_wait_and_see"); + p.policy_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "policy"); + p.wait_and_see_target_behaviors = + getOrDeclareParameter>(*node, ns + "wait_and_see.target_behaviors"); + p.wait_and_see_th_closest_distance = + getOrDeclareParameter(*node, ns + "wait_and_see.th_closest_distance"); p.time_threshold_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); p.distance_threshold_for_ambiguous_vehicle = diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index db3215fa8d238..246b96ec5440e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -716,9 +716,10 @@ "avoidance_for_ambiguous_vehicle": { "type": "object", "properties": { - "enable": { - "type": "boolean", - "description": "Enable avoidance maneuver for ambiguous vehicles.", + "policy": { + "type": "string", + "enum": ["auto", "manual", "ignore"], + "description": "Ego behavior policy for ambiguous vehicle.", "default": "true" }, "closest_distance_to_wait_and_see": { @@ -778,14 +779,26 @@ }, "required": ["traffic_light", "crosswalk"], "additionalProperties": false + }, + "wait_and_see": { + "type": "object", + "properties": { + "target_behaviors": { + "type": "array", + "default": ["MERGING", "DEVIATING"], + "description": "This module doesn't avoid these behaviors vehicle until it gets closer than threshold." + }, + "th_closest_distance": { + "type": "number", + "default": 10.0, + "description": "Threshold to check whether the ego gets close enough the ambiguous vehicle." + } + }, + "required": ["target_behaviors", "th_closest_distance"], + "additionalProperties": false } }, - "required": [ - "enable", - "closest_distance_to_wait_and_see", - "condition", - "ignore_area" - ], + "required": ["policy", "condition", "ignore_area", "wait_and_see"], "additionalProperties": false }, "intersection": { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index 2d02f33e19870..c5f338e91acbd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -132,10 +132,9 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams( { const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle."; - updateParam(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle); + updateParam(parameters, ns + "policy", p->policy_ambiguous_vehicle); updateParam( - parameters, ns + "closest_distance_to_wait_and_see", - p->closest_distance_to_wait_and_see_for_ambiguous_vehicle); + parameters, ns + "wait_and_see.th_closest_distance", p->wait_and_see_th_closest_distance); updateParam( parameters, ns + "condition.th_stopped_time", p->time_threshold_for_ambiguous_vehicle); updateParam( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 64831e3b24fff..cfd304f1908a1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -880,7 +880,7 @@ bool isSatisfiedWithVehicleCondition( // from here, filtering for ambiguous vehicle. - if (!parameters->enable_avoidance_for_ambiguous_vehicle) { + if (parameters->policy_ambiguous_vehicle == "ignore") { object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; return false; } @@ -889,6 +889,7 @@ bool isSatisfiedWithVehicleCondition( object.stop_time > parameters->time_threshold_for_ambiguous_vehicle; if (!stop_time_longer_than_threshold) { object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; + object.is_ambiguous = false; return false; } @@ -897,6 +898,7 @@ bool isSatisfiedWithVehicleCondition( parameters->distance_threshold_for_ambiguous_vehicle; if (is_moving_distance_longer_than_threshold) { object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; + object.is_ambiguous = false; return false; } @@ -907,22 +909,9 @@ bool isSatisfiedWithVehicleCondition( return true; } } else { - if (object.behavior == ObjectData::Behavior::MERGING) { - object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; - object.is_ambiguous = true; - return true; - } - - if (object.behavior == ObjectData::Behavior::DEVIATING) { - object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; - object.is_ambiguous = true; - return true; - } - - if (object.behavior == ObjectData::Behavior::NONE) { - object.is_ambiguous = false; - return true; - } + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; + object.is_ambiguous = true; + return true; } object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; From 32c41bcefb883c2eccb6a5a3b00973a7d3322406 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 16 Jul 2024 13:34:39 +0900 Subject: [PATCH 035/151] feat(static_obstacle_avoidance): show markers when system requests operator support (#7994) Signed-off-by: satoshi-ota --- .../debug.hpp | 3 + .../src/debug.cpp | 73 ++++++++++++++++++- .../src/scene.cpp | 5 ++ 3 files changed, 80 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp index 63985e574f3b2..b205838896038 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp @@ -47,6 +47,9 @@ MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, cons MarkerArray createOtherObjectsMarkerArray( const ObjectDataArray & objects, const ObjectInfo & info, const bool verbose); +MarkerArray createAmbiguousObjectsMarkerArray( + const ObjectDataArray & objects, const Pose & ego_pose, const std::string & policy); + MarkerArray createStopTargetObjectMarkerArray(const AvoidancePlanningData & data); MarkerArray createDebugMarkerArray( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 8618a1c340004..a542107e890aa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -456,7 +456,7 @@ MarkerArray createOtherObjectsMarkerArray( appendMarkerArray( createObjectsCubeMarkerArray( filtered_objects, "others_" + ns + "_cube", createMarkerScale(3.0, 1.5, 1.5), - createMarkerColor(0.0, 1.0, 0.0, 0.8)), + createMarkerColor(0.5, 0.5, 0.5, 0.8)), &msg); appendMarkerArray( createObjectInfoMarkerArray(filtered_objects, "others_" + ns + "_info", verbose), &msg); @@ -466,6 +466,77 @@ MarkerArray createOtherObjectsMarkerArray( return msg; } +MarkerArray createAmbiguousObjectsMarkerArray( + const ObjectDataArray & objects, const Pose & ego_pose, const std::string & policy) +{ + MarkerArray msg; + + if (policy != "manual") { + return msg; + } + + for (const auto & object : objects) { + if (!object.is_ambiguous || !object.is_avoidable) { + continue; + } + + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "ambiguous_target", 0L, Marker::ARROW, + createMarkerScale(0.5, 1.0, 1.0), createMarkerColor(1.0, 1.0, 0.0, 0.999)); + + Point src, dst; + src = object.getPosition(); + src.z += 4.0; + dst = object.getPosition(); + dst.z += 2.0; + + marker.points.push_back(src); + marker.points.push_back(dst); + marker.id = uuidToInt32(object.object.object_id); + + msg.markers.push_back(marker); + } + + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "ambiguous_target_text", 0L, + Marker::TEXT_VIEW_FACING, createMarkerScale(0.5, 0.5, 0.5), + createMarkerColor(1.0, 1.0, 0.0, 1.0)); + + marker.id = uuidToInt32(object.object.object_id); + marker.pose = object.getPose(); + marker.pose.position.z += 4.5; + std::ostringstream string_stream; + string_stream << "SHOULD AVOID?"; + marker.text = string_stream.str(); + marker.color = createMarkerColor(1.0, 1.0, 0.0, 0.999); + marker.scale = createMarkerScale(0.8, 0.8, 0.8); + msg.markers.push_back(marker); + } + + { + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "request_text", 0L, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.5, 0.5, 0.5), createMarkerColor(1.0, 1.0, 0.0, 1.0)); + + marker.id = uuidToInt32(object.object.object_id); + marker.pose = ego_pose; + marker.pose.position.z += 2.0; + std::ostringstream string_stream; + string_stream << "SYSTEM REQUESTS OPERATOR SUPPORT."; + marker.text = string_stream.str(); + marker.color = createMarkerColor(1.0, 1.0, 0.0, 0.999); + marker.scale = createMarkerScale(0.8, 0.8, 0.8); + msg.markers.push_back(marker); + } + + return msg; + } + + return msg; +} + MarkerArray createStopTargetObjectMarkerArray(const AvoidancePlanningData & data) { MarkerArray msg; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 8452912989c43..324bfdff8d777 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -1402,6 +1402,7 @@ void StaticObstacleAvoidanceModule::updateRTCData() void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { + using utils::static_obstacle_avoidance::createAmbiguousObjectsMarkerArray; using utils::static_obstacle_avoidance::createStopTargetObjectMarkerArray; using utils::static_obstacle_avoidance::createTargetObjectsMarkerArray; @@ -1409,6 +1410,10 @@ void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData appendMarkerArray( createTargetObjectsMarkerArray(data.target_objects, "target_objects"), &info_marker_); appendMarkerArray(createStopTargetObjectMarkerArray(data), &info_marker_); + appendMarkerArray( + createAmbiguousObjectsMarkerArray( + data.target_objects, getEgoPose(), parameters_->policy_ambiguous_vehicle), + &info_marker_); } void StaticObstacleAvoidanceModule::updateDebugMarker( From ed97aff8fe87c17f1f89a060ffd79549156fddf5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 16 Jul 2024 14:34:57 +0900 Subject: [PATCH 036/151] fix(static_obstacle_avoidance): fix issues in target filtiering logic (#7954) * fix: unknown filtering flow Signed-off-by: satoshi-ota * fix: relax target filtering logic for object which is in freespace Signed-off-by: satoshi-ota * docs: update flowchart Signed-off-by: satoshi-ota * fix: check stopped time in freespace Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../README.md | 21 +++++++++ .../static_obstacle_avoidance.param.yaml | 4 ++ .../data_structs.hpp | 3 ++ .../parameter_helper.hpp | 6 +++ .../static_obstacle_avoidance.schema.json | 22 ++++++++- .../src/manager.cpp | 6 +++ .../src/utils.cpp | 46 +++++++++++++++++-- 7 files changed, 103 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index ddd0d473d2cbf..d32ab36301810 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -401,6 +401,15 @@ else (\n no) #00FFB1 :IGNORE; stop endif +if(Is UNKNOWN objects?) then (yes) +if(isSatisfiedWithUnknownTypeObjectCodition) then (yes) +#FF006C :AVOID; +stop +else (\n no) +#00FFB1 :IGNORE; +stop +endif +else (\n no) if(Is vehicle type?) then (yes) if(isSatisfiedWithVehicleCodition()) then (yes) else (\n no) @@ -618,6 +627,18 @@ title Filter vehicle which is obviously an avoidance target start partition isObviousAvoidanceTarget() { +if(Is object within freespace?) then (yes) +if(Is object on ego lane?) then (no) +if(Is object stopping longer than threshold?) then (yes) +#FF006C :return true; +stop +else (\n no) +endif +else (\n yes) +endif +else (\n no) +endif + if(Is object within intersection?) then (yes) else (\n no) if(Is object parallel to ego lane? AND Is object a parked vehicle?) then (yes) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 6bd5e0faf1938..0e60e3216361d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -160,6 +160,10 @@ intersection: yaw_deviation: 0.349 # [rad] (default 20.0deg) + freespace: + condition: + th_stopped_time: 5.0 # [-] + # For safety check safety_check: # safety check target type diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 079928a58bd9f..4e14dc4886768 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -191,6 +191,9 @@ struct AvoidanceParameters // minimum road shoulder width. maybe 0.5 [m] double object_check_min_road_shoulder_width{0.0}; + // time threshold for vehicle in freespace. + double freespace_condition_th_stopped_time{0.0}; + // force avoidance std::vector wait_and_see_target_behaviors{"NONE", "MERGING", "DEVIATING"}; double wait_and_see_th_closest_distance{0.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 0cea2a4e633c3..56ac3d7f4f1bb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -154,6 +154,12 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); } + { + const std::string ns = "avoidance.target_filtering.freespace."; + p.freespace_condition_th_stopped_time = + getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); + } + { const std::string ns = "avoidance.target_filtering.detection_area."; p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index 246b96ec5440e..38a91ac39525b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -812,6 +812,25 @@ }, "required": ["yaw_deviation"], "additionalProperties": false + }, + "freespace": { + "type": "object", + "properties": { + "condition": { + "type": "object", + "properties": { + "th_stopped_time": { + "type": "number", + "description": "This module delays avoidance maneuver to see vehicle behavior in freespace.", + "default": 5.0 + } + }, + "required": ["th_stopped_time"], + "additionalProperties": false + } + }, + "required": ["condition"], + "additionalProperties": false } }, "required": [ @@ -823,7 +842,8 @@ "merging_vehicle", "parked_vehicle", "avoidance_for_ambiguous_vehicle", - "intersection" + "intersection", + "freespace" ], "additionalProperties": false }, diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index c5f338e91acbd..5655696ff086d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -150,6 +150,12 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams( p->object_ignore_section_crosswalk_behind_distance); } + { + const std::string ns = "avoidance.target_filtering.freespace."; + updateParam( + parameters, ns + "condition.th_stopped_time", p->freespace_condition_th_stopped_time); + } + { const std::string ns = "avoidance.target_filtering.intersection."; updateParam(parameters, ns + "yaw_deviation", p->object_check_yaw_deviation); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index cfd304f1908a1..0830c0f10dd4e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -339,6 +339,32 @@ bool isWithinIntersection( lanelet::utils::to2D(polygon.basicPolygon())); } +bool isWithinFreespace( + const ObjectData & object, const std::shared_ptr & route_handler) +{ + auto polygons = lanelet::utils::query::getAllParkingLots(route_handler->getLaneletMapPtr()); + if (polygons.empty()) { + return false; + } + + std::sort(polygons.begin(), polygons.end(), [&object](const auto & a, const auto & b) { + const double a_distance = boost::geometry::distance( + lanelet::utils::to2D(a).basicPolygon(), + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint()); + const double b_distance = boost::geometry::distance( + lanelet::utils::to2D(b).basicPolygon(), + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint()); + return a_distance < b_distance; + }); + + return boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object.getPosition())) + .basicPoint(), + lanelet::utils::to2D(polygons.front().basicPolygon())); +} + bool isOnEgoLane(const ObjectData & object, const std::shared_ptr & route_handler) { if (boost::geometry::within( @@ -708,6 +734,14 @@ bool isObviousAvoidanceTarget( [[maybe_unused]] const std::shared_ptr & planner_data, [[maybe_unused]] const std::shared_ptr & parameters) { + if (isWithinFreespace(object, planner_data->route_handler)) { + if (!object.is_on_ego_lane) { + if (object.stop_time > parameters->freespace_condition_th_stopped_time) { + return true; + } + } + } + if (!object.is_within_intersection) { if (object.is_parked && object.behavior == ObjectData::Behavior::NONE) { RCLCPP_DEBUG(rclcpp::get_logger(logger_namespace), "object is obvious parked vehicle."); @@ -1842,17 +1876,19 @@ void filterTargetObjects( utils::static_obstacle_avoidance::calcEnvelopeOverhangDistance(o, data.reference_path); o.to_road_shoulder_distance = filtering_utils::getRoadShoulderDistance(o, data, planner_data); - // TODO(Satoshi Ota) parametrize stop time threshold if need. - constexpr double STOP_TIME_THRESHOLD = 3.0; // [s] if (filtering_utils::isUnknownTypeObject(o)) { + // TARGET: UNKNOWN + + // TODO(Satoshi Ota) parametrize stop time threshold if need. + constexpr double STOP_TIME_THRESHOLD = 3.0; // [s] if (o.stop_time < STOP_TIME_THRESHOLD) { o.info = ObjectInfo::UNSTABLE_OBJECT; data.other_objects.push_back(o); continue; } - } + } else if (filtering_utils::isVehicleTypeObject(o)) { + // TARGET: CAR, TRUCK, BUS, TRAILER, MOTORCYCLE - if (filtering_utils::isVehicleTypeObject(o)) { o.is_within_intersection = filtering_utils::isWithinIntersection(o, planner_data->route_handler); o.is_parked = @@ -1869,6 +1905,8 @@ void filterTargetObjects( continue; } } else { + // TARGET: PEDESTRIAN, BICYCLE + o.is_within_intersection = filtering_utils::isWithinIntersection(o, planner_data->route_handler); o.is_parked = false; From 433937f8e5d867c74923eb835dc08ec3ac2d56e0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 18 Jul 2024 15:49:25 +0900 Subject: [PATCH 037/151] fix(static_obstacle_avoidance): avoid object behind unavoidance object if unavoidable is not on the path (#8066) Signed-off-by: satoshi-ota --- .../src/shift_line_generator.cpp | 34 +++++++++++++++---- 1 file changed, 27 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index c3a67eb074d73..5e58466fa4229 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -239,10 +239,18 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( const auto is_forward_object = [](const auto & object) { return object.longitudinal > 0.0; }; + const auto is_on_path = [this](const auto & object) { + const auto [overhang, point] = object.overhang_points.front(); + return std::abs(overhang) < 0.5 * data_->parameters.vehicle_width; + }; + const auto is_valid_shift_line = [](const auto & s) { return s.start_longitudinal > 0.0 && s.start_longitudinal < s.end_longitudinal; }; + ObjectDataArray unavoidable_objects; + + // target objects are sorted by longitudinal distance. AvoidOutlines outlines; for (auto & o : data.target_objects) { if (!o.avoid_margin.has_value()) { @@ -253,22 +261,22 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( } else { o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE; } - if (o.avoid_required && is_forward_object(o)) { + if (o.avoid_required && is_forward_object(o) && is_on_path(o)) { break; } else { + unavoidable_objects.push_back(o); continue; } } - const auto is_object_on_right = utils::static_obstacle_avoidance::isOnRight(o); const auto desire_shift_length = - helper_->getShiftLength(o, is_object_on_right, o.avoid_margin.value()); - if (utils::static_obstacle_avoidance::isSameDirectionShift( - is_object_on_right, desire_shift_length)) { + helper_->getShiftLength(o, isOnRight(o), o.avoid_margin.value()); + if (utils::static_obstacle_avoidance::isSameDirectionShift(isOnRight(o), desire_shift_length)) { o.info = ObjectInfo::SAME_DIRECTION_SHIFT; - if (o.avoid_required && is_forward_object(o)) { + if (o.avoid_required && is_forward_object(o) && is_on_path(o)) { break; } else { + unavoidable_objects.push_back(o); continue; } } @@ -276,13 +284,25 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // calculate feasible shift length based on behavior policy const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length); if (!feasible_shift_profile.has_value()) { - if (o.avoid_required && is_forward_object(o)) { + if (o.avoid_required && is_forward_object(o) && is_on_path(o)) { break; } else { + unavoidable_objects.push_back(o); continue; } } + // If there is an object that cannot be avoided, this module only avoids object on the same side + // as unavoidable object. + if (!unavoidable_objects.empty()) { + if (isOnRight(unavoidable_objects.front()) && !isOnRight(o)) { + break; + } + if (!isOnRight(unavoidable_objects.front()) && isOnRight(o)) { + break; + } + } + // use absolute dist for return-to-center, relative dist from current for avoiding. const auto feasible_return_distance = helper_->getMaxAvoidanceDistance(feasible_shift_profile.value().first); From d8d9c19f773a7ad1f8a56637fda61aaad6b00482 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 19 Jul 2024 17:42:38 +0900 Subject: [PATCH 038/151] fix(bpp, rtc_interface): fix state transition (#7743) * fix(rtc_interface): check rtc state Signed-off-by: satoshi-ota * fix(bpp_interface): check rtc state Signed-off-by: satoshi-ota * feat(rtc_interface): print Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../autoware/rtc_interface/rtc_interface.hpp | 2 + .../src/rtc_interface.cpp | 68 +++++++++++++++++-- .../interface/scene_module_interface.hpp | 14 +++- 3 files changed, 75 insertions(+), 9 deletions(-) diff --git a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp index 62f9a55c75455..23f7f0b4b36c5 100644 --- a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp +++ b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp @@ -61,8 +61,10 @@ class RTCInterface bool isActivated(const UUID & uuid) const; bool isRegistered(const UUID & uuid) const; bool isRTCEnabled(const UUID & uuid) const; + bool isTerminated(const UUID & uuid) const; void lockCommandUpdate(); void unlockCommandUpdate(); + void print() const; private: void onCooperateCommandService( diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 985e38b64f2bd..44678077d5dd1 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -20,7 +20,7 @@ namespace { using tier4_rtc_msgs::msg::Module; -std::string to_string(const unique_identifier_msgs::msg::UUID & uuid) +std::string uuid_to_string(const unique_identifier_msgs::msg::UUID & uuid) { std::stringstream ss; for (auto i = 0; i < 16; ++i) { @@ -29,6 +29,34 @@ std::string to_string(const unique_identifier_msgs::msg::UUID & uuid) return ss.str(); } +std::string command_to_string(const uint8_t type) +{ + if (type == tier4_rtc_msgs::msg::Command::ACTIVATE) { + return "ACTIVATE"; + } else if (type == tier4_rtc_msgs::msg::Command::DEACTIVATE) { + return "DEACTIVATE"; + } + + throw std::domain_error("invalid rtc command."); +} + +std::string state_to_string(const uint8_t type) +{ + if (type == tier4_rtc_msgs::msg::State::WAITING_FOR_EXECUTION) { + return "WAITING_FOR_EXECUTION"; + } else if (type == tier4_rtc_msgs::msg::State::RUNNING) { + return "RUNNING"; + } else if (type == tier4_rtc_msgs::msg::State::ABORTING) { + return "ABORTING"; + } else if (type == tier4_rtc_msgs::msg::State::SUCCEEDED) { + return "SUCCEEDED"; + } else if (type == tier4_rtc_msgs::msg::State::FAILED) { + return "FAILED"; + } + + throw std::domain_error("invalid rtc state."); +} + Module getModuleType(const std::string & module_name) { Module module; @@ -158,14 +186,14 @@ std::vector RTCInterface::validateCooperateCommands( } else { RCLCPP_WARN_STREAM( getLogger(), "[validateCooperateCommands] uuid : " - << to_string(command.uuid) + << uuid_to_string(command.uuid) << " state is not WAITING_FOR_EXECUTION or RUNNING. state : " << itr->state.type << std::endl); response.success = false; } } else { RCLCPP_WARN_STREAM( - getLogger(), "[validateCooperateCommands] uuid : " << to_string(command.uuid) + getLogger(), "[validateCooperateCommands] uuid : " << uuid_to_string(command.uuid) << " is not found." << std::endl); response.success = false; } @@ -262,7 +290,7 @@ void RTCInterface::removeCooperateStatus(const UUID & uuid) RCLCPP_WARN_STREAM( getLogger(), - "[removeCooperateStatus] uuid : " << to_string(uuid) << " is not found." << std::endl); + "[removeCooperateStatus] uuid : " << uuid_to_string(uuid) << " is not found." << std::endl); } void RTCInterface::removeStoredCommand(const UUID & uuid) @@ -313,7 +341,7 @@ bool RTCInterface::isActivated(const UUID & uuid) const } RCLCPP_WARN_STREAM( - getLogger(), "[isActivated] uuid : " << to_string(uuid) << " is not found." << std::endl); + getLogger(), "[isActivated] uuid : " << uuid_to_string(uuid) << " is not found." << std::endl); return false; } @@ -338,7 +366,23 @@ bool RTCInterface::isRTCEnabled(const UUID & uuid) const } RCLCPP_WARN_STREAM( - getLogger(), "[isRTCEnabled] uuid : " << to_string(uuid) << " is not found." << std::endl); + getLogger(), "[isRTCEnabled] uuid : " << uuid_to_string(uuid) << " is not found." << std::endl); + return is_auto_mode_enabled_; +} + +bool RTCInterface::isTerminated(const UUID & uuid) const +{ + std::lock_guard lock(mutex_); + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](auto & s) { return s.uuid == uuid; }); + + if (itr != registered_status_.statuses.end()) { + return itr->state.type == State::SUCCEEDED || itr->state.type == State::FAILED; + } + + RCLCPP_WARN_STREAM( + getLogger(), "[isTerminated] uuid : " << uuid_to_string(uuid) << " is not found." << std::endl); return is_auto_mode_enabled_; } @@ -363,4 +407,16 @@ bool RTCInterface::isLocked() const return is_locked_; } +void RTCInterface::print() const +{ + RCLCPP_INFO_STREAM(getLogger(), "---print rtc cooperate statuses---" << std::endl); + for (const auto status : registered_status_.statuses) { + RCLCPP_INFO_STREAM( + getLogger(), "uuid:" << uuid_to_string(status.uuid) + << " command:" << command_to_string(status.command_status.type) + << std::boolalpha << " safe:" << status.safe + << " state:" << state_to_string(status.state.type) << std::endl); + } +} + } // namespace autoware::rtc_interface diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 95eb82e0b4c23..c4a05d171654d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -335,8 +335,15 @@ class SceneModuleInterface { return std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { - return rtc.second->isRegistered(uuid_map_.at(rtc.first)) && - rtc.second->isActivated(uuid_map_.at(rtc.first)); + if (!rtc.second->isRegistered(uuid_map_.at(rtc.first))) { + return false; + } + + if (rtc.second->isTerminated(uuid_map_.at(rtc.first))) { + return true; + } + + return rtc.second->isActivated(uuid_map_.at(rtc.first)); }); } @@ -345,7 +352,8 @@ class SceneModuleInterface return std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isRegistered(uuid_map_.at(rtc.first)) && - !rtc.second->isActivated(uuid_map_.at(rtc.first)); + !rtc.second->isActivated(uuid_map_.at(rtc.first)) && + !rtc.second->isTerminated(uuid_map_.at(rtc.first)); }); } From f0b5d7d791a5bffcbccda7f59b0d31402e70695c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 30 Jul 2024 14:14:40 +0900 Subject: [PATCH 039/151] feat(start_planner): add end_pose_curvature_threshold (#7901) (#1428) * feat(start_planner): add end_pose_curvature_threshold * Update planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md * update max curvature discription * update readme --------- Signed-off-by: kosuke55 Co-authored-by: Kyoichi Sugahara --- .../README.md | 23 ++++---- .../config/start_planner.param.yaml | 1 + .../data_structs.hpp | 1 + .../src/manager.cpp | 4 ++ .../src/shift_pull_out.cpp | 57 +++++++++++++++++-- 5 files changed, 71 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md index dba4a0cfce5e7..5b68b021f99cb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/README.md @@ -469,17 +469,18 @@ Pull out distance is calculated by the speed, lateral deviation, and the lateral #### parameters for shift pull out -| Name | Unit | Type | Description | Default value | -| :--------------------------------------------- | :----- | :----- | :------------------------------------------------------------------------------------------------------------------- | :------------ | -| enable_shift_pull_out | [-] | bool | flag whether to enable shift pull out | true | -| check_shift_path_lane_departure | [-] | bool | flag whether to check if shift path footprints are out of lane | true | -| allow_check_shift_path_lane_departure_override | [-] | bool | flag to override/cancel lane departure check if the ego vehicle's starting pose is already out of lane | false | -| shift_pull_out_velocity | [m/s] | double | velocity of shift pull out | 2.0 | -| pull_out_sampling_num | [-] | int | Number of samplings in the minimum to maximum range of lateral_jerk | 4 | -| maximum_lateral_jerk | [m/s3] | double | maximum lateral jerk | 2.0 | -| minimum_lateral_jerk | [m/s3] | double | minimum lateral jerk | 0.1 | -| minimum_shift_pull_out_distance | [m] | double | minimum shift pull out distance. if calculated pull out distance is shorter than this, use this for path generation. | 0.0 | -| maximum_curvature | [m] | double | maximum curvature. The pull out distance is calculated so that the curvature is smaller than this value. | 0.07 | +| Name | Unit | Type | Description | Default value | +| :--------------------------------------------- | :----- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| enable_shift_pull_out | [-] | bool | flag whether to enable shift pull out | true | +| check_shift_path_lane_departure | [-] | bool | flag whether to check if shift path footprints are out of lane | true | +| allow_check_shift_path_lane_departure_override | [-] | bool | flag to override/cancel lane departure check if the ego vehicle's starting pose is already out of lane | false | +| shift_pull_out_velocity | [m/s] | double | velocity of shift pull out | 2.0 | +| pull_out_sampling_num | [-] | int | Number of samplings in the minimum to maximum range of lateral_jerk | 4 | +| maximum_lateral_jerk | [m/s3] | double | maximum lateral jerk | 2.0 | +| minimum_lateral_jerk | [m/s3] | double | minimum lateral jerk | 0.1 | +| minimum_shift_pull_out_distance | [m] | double | minimum shift pull out distance. if calculated pull out distance is shorter than this, use this for path generation. | 0.0 | +| maximum_curvature | [1/m] | double | maximum curvature. Calculate the required pull out distance from this maximum curvature, assuming the reference path is considered a straight line and shifted by two approximate arcs. This does not compensate for curvature in a shifted path or curve. | 0.07 | +| end_pose_curvature_threshold | [1/m] | double | The curvature threshold which is used for calculating the shift pull out distance. The shift end pose is shifted forward so that curvature on shift end pose is less than this value. This is to prevent the generated path from having a large curvature when the end pose is on a curve. If a shift end pose with a curvature below the threshold is not found, the shift pull out distance is used as the distance to the point with the lowest curvature among the points beyond a certain distance. | 0.01 | ### **geometric pull out** diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml index d39a320a19e14..cb34f9962c479 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml @@ -32,6 +32,7 @@ minimum_lateral_acc: 0.15 maximum_lateral_acc: 0.5 maximum_curvature: 0.07 + end_pose_curvature_threshold: 0.01 # geometric pull out enable_geometric_pull_out: true geometric_collision_check_distance_from_end: 0.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp index ebdb0869545ca..5903a691d60e1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp @@ -122,6 +122,7 @@ struct StartPlannerParameters double maximum_lateral_acc{0.0}; double minimum_lateral_acc{0.0}; double maximum_curvature{0.0}; // maximum curvature considered in the path generation + double end_pose_curvature_threshold{0.0}; double maximum_longitudinal_deviation{0.0}; // geometric pull out bool enable_geometric_pull_out{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp index 873bab1043485..194d75e14228e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp @@ -82,6 +82,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) p.maximum_lateral_acc = node->declare_parameter(ns + "maximum_lateral_acc"); p.minimum_lateral_acc = node->declare_parameter(ns + "minimum_lateral_acc"); p.maximum_curvature = node->declare_parameter(ns + "maximum_curvature"); + p.end_pose_curvature_threshold = + node->declare_parameter(ns + "end_pose_curvature_threshold"); p.maximum_longitudinal_deviation = node->declare_parameter(ns + "maximum_longitudinal_deviation"); // geometric pull out @@ -417,6 +419,8 @@ void StartPlannerModuleManager::updateModuleParams( updateParam(parameters, ns + "maximum_lateral_acc", p->maximum_lateral_acc); updateParam(parameters, ns + "minimum_lateral_acc", p->minimum_lateral_acc); updateParam(parameters, ns + "maximum_curvature", p->maximum_curvature); + updateParam( + parameters, ns + "end_pose_curvature_threshold", p->end_pose_curvature_threshold); updateParam( parameters, ns + "maximum_longitudinal_deviation", p->maximum_longitudinal_deviation); updateParam(parameters, ns + "enable_geometric_pull_out", p->enable_geometric_pull_out); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index def7072dc0e71..a6924cb391bf7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -229,6 +229,7 @@ std::vector ShiftPullOut::calcPullOutPaths( const double minimum_lateral_acc = parameters_.minimum_lateral_acc; const double maximum_lateral_acc = parameters_.maximum_lateral_acc; const double maximum_curvature = parameters_.maximum_curvature; + const double end_pose_curvature_threshold = parameters_.end_pose_curvature_threshold; const double minimum_shift_pull_out_distance = parameters_.minimum_shift_pull_out_distance; const int lateral_acceleration_sampling_num = parameters_.lateral_acceleration_sampling_num; @@ -304,10 +305,58 @@ std::vector ShiftPullOut::calcPullOutPaths( // short length, take maximum with the original distance. // TODO(kosuke55): update the conversion function and get rid of the comparison with original // distance. - const double pull_out_distance_converted = calcBeforeShiftedArcLength( - road_lane_reference_path_from_ego, pull_out_distance, shift_length); - const double before_shifted_pull_out_distance = - std::max(pull_out_distance, pull_out_distance_converted); + const double pull_out_distance_converted = std::max( + pull_out_distance, calcBeforeShiftedArcLength( + road_lane_reference_path_from_ego, pull_out_distance, shift_length)); + + // Calculate the distance until the curvature at end_pose is below a certain threshold. + // This is to prevent the path curvature from becoming unnecessarily large when end_pose is on a + // curve. + const double before_shifted_pull_out_distance = std::invoke([&]() -> double { + double arc_length = 0.0; + + // If a curvature below end_pose_curvature_threshold is not found, return the distance to the + // point with the smallest curvature after pull_out_distance_converted. pull_out_distance is a + // variable to store that distance. + double pull_out_distance = pull_out_distance_converted; + double min_curvature_after_distance_converted = std::numeric_limits::max(); + + const auto curvatures_and_segment_lengths = + autoware::motion_utils::calcCurvatureAndSegmentLength( + road_lane_reference_path_from_ego.points); + + const auto update_arc_length = [&](size_t i, const auto & segment_length) { + arc_length += (i == curvatures_and_segment_lengths.size() - 1) + ? segment_length.first + segment_length.second + : segment_length.first; + }; + + const auto update_min_curvature_and_pull_out_distance = [&](double curvature) { + min_curvature_after_distance_converted = curvature; + pull_out_distance = arc_length; + }; + + for (size_t i = 0; i < curvatures_and_segment_lengths.size(); ++i) { + const auto & [signed_curvature, segment_length] = curvatures_and_segment_lengths[i]; + const double curvature = std::abs(signed_curvature); + update_arc_length(i, segment_length); + if (arc_length > pull_out_distance_converted) { + // update distance with minimum curvature after pull_out_distance_converted + if (curvature < min_curvature_after_distance_converted) { + update_min_curvature_and_pull_out_distance(curvature); + } + // if curvature is smaller than end_pose_curvature_threshold, return the length + if (curvature < end_pose_curvature_threshold) { + return arc_length; + } + } + } + + // if not found point with curvature below end_pose_curvature_threshold + // pull_out_distance_converted, return the distance to the point with the smallest curvature + // after pull_out_distance_converted + return pull_out_distance; + }); // if before_shifted_pull_out_distance is too short, shifting path fails, so add non shifted if ( From 622d6e34ba3840833095e4b1b32dbc373fccc6dc Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Tue, 30 Jul 2024 14:48:39 +0900 Subject: [PATCH 040/151] feat(evalautor): rename evaluator diag topics (#1432) * feat(evalautor): rename evaluator diag topics (#8152) * feat(evalautor): rename evaluator diag topics Signed-off-by: kosuke55 * perception Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 * fix: adapt v0.29.0 control launcher Signed-off-by: Shumpei Wakabayashi --------- Signed-off-by: kosuke55 Signed-off-by: Shumpei Wakabayashi Co-authored-by: Kosuke Takeuchi --- .../launch/control_evaluator.launch.xml | 2 +- .../launch/planning_evaluator.launch.xml | 2 +- .../launch/perception_online_evaluator.launch.xml | 4 ++-- launch/tier4_control_launch/launch/control.launch.py | 2 +- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml index e119f1787d21b..f977916541752 100644 --- a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml +++ b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml @@ -9,7 +9,7 @@ - + diff --git a/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml b/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml index 2e358f6272379..b36e276c06944 100644 --- a/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml +++ b/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml b/evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml index 2ef179dbe3ff9..fc045da0302b7 100644 --- a/evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml +++ b/evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml @@ -6,8 +6,8 @@ - - + + diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a61f29014dcce..c561a8c1b9018 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -381,7 +381,7 @@ def launch_setup(context, *args, **kwargs): ("~/input/diagnostics", "/diagnostics"), ("~/input/odometry", "/localization/kinematic_state"), ("~/input/trajectory", "/planning/scenario_planning/trajectory"), - ("~/metrics", "/diagnostic/control_evaluator/metrics"), + ("~/metrics", "/control/control_evaluator/metrics"), ], ) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 97b07410d108a..8ee3809cb19d2 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -147,7 +147,7 @@ - + From a1e97cbbdbf0e84a841f1549da000520c54170a5 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 30 Jul 2024 15:20:50 +0900 Subject: [PATCH 041/151] perf(autoware_detected_object_validation): reduce lanelet_filter processing time (#8240) (#1433) * add local r-tree for fast searching change to _func__ add more debug use local rtree fix tmp update fix bug clean unused clean up * clean up * style(pre-commit): autofix * chore: Optimize object filtering and improve performance The code changes in `lanelet_filter.cpp` optimize the object filtering process by using the `empty()` function instead of checking the size of the `transformed_objects.objects` vector. This change improves performance and simplifies the code logic. Refactor the code to use `empty()` instead of `size()` for checking if the `transformed_objects.objects` vector is empty. This change improves readability and performance. --------- Signed-off-by: a-maumau Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../object_lanelet_filter.hpp | 27 ++- .../src/object_lanelet_filter.cpp | 158 +++++++++++++----- 2 files changed, 134 insertions(+), 51 deletions(-) diff --git a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp index 2598f6ec6ca74..850de6d4a6f89 100644 --- a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp @@ -26,12 +26,17 @@ #include #include +#include + #include +#include #include #include #include #include +#include +#include namespace object_lanelet_filter { @@ -40,6 +45,13 @@ using autoware::universe_utils::MultiPoint2d; using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; +namespace bg = boost::geometry; +namespace bgi = boost::geometry::index; +using Point2d = bg::model::point; +using Box = boost::geometry::model::box; +using BoxAndLanelet = std::pair; +using RtreeAlgo = bgi::rstar<16>; + class ObjectLaneletFilterNode : public rclcpp::Node { public: @@ -72,17 +84,20 @@ class ObjectLaneletFilterNode : public rclcpp::Node bool filterObject( const autoware_perception_msgs::msg::DetectedObject & transformed_object, const autoware_perception_msgs::msg::DetectedObject & input_object, - const lanelet::ConstLanelets & intersected_lanelets, + const bg::index::rtree & local_rtree, autoware_perception_msgs::msg::DetectedObjects & output_object_msg); LinearRing2d getConvexHull(const autoware_perception_msgs::msg::DetectedObjects &); - lanelet::ConstLanelets getIntersectedLanelets(const LinearRing2d &); + LinearRing2d getConvexHullFromObjectFootprint( + const autoware_perception_msgs::msg::DetectedObject & object); + std::vector getIntersectedLanelets(const LinearRing2d &); bool isObjectOverlapLanelets( const autoware_perception_msgs::msg::DetectedObject & object, - const lanelet::ConstLanelets & intersected_lanelets); - bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &); + const bg::index::rtree & local_rtree); + bool isPolygonOverlapLanelets( + const Polygon2d & polygon, const bgi::rtree & local_rtree); bool isSameDirectionWithLanelets( - const lanelet::ConstLanelets & lanelets, - const autoware_perception_msgs::msg::DetectedObject & object); + const autoware_perception_msgs::msg::DetectedObject & object, + const bgi::rtree & local_rtree); geometry_msgs::msg::Polygon setFootprint(const autoware_perception_msgs::msg::DetectedObject &); std::unique_ptr published_time_publisher_; diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index 506fefdda1dbb..a439c744f9288 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -22,8 +22,10 @@ #include #include #include +#include #include +#include #include #include @@ -98,18 +100,27 @@ void ObjectLaneletFilterNode::objectCallback( return; } - // calculate convex hull - const auto convex_hull = getConvexHull(transformed_objects); + if (!transformed_objects.objects.empty()) { + // calculate convex hull + const auto convex_hull = getConvexHull(transformed_objects); - // get intersected lanelets - lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull); + // get intersected lanelets + std::vector intersected_lanelets_with_bbox = getIntersectedLanelets(convex_hull); - // filtering process - for (size_t index = 0; index < transformed_objects.objects.size(); ++index) { - const auto & transformed_object = transformed_objects.objects.at(index); - const auto & input_object = input_msg->objects.at(index); - filterObject(transformed_object, input_object, intersected_lanelets, output_object_msg); + // create R-Tree with intersected_lanelets for fast search + bgi::rtree local_rtree; + for (const auto & bbox_and_lanelet : intersected_lanelets_with_bbox) { + local_rtree.insert(bbox_and_lanelet); + } + + // filtering process + for (size_t index = 0; index < transformed_objects.objects.size(); ++index) { + const auto & transformed_object = transformed_objects.objects.at(index); + const auto & input_object = input_msg->objects.at(index); + filterObject(transformed_object, input_object, local_rtree, output_object_msg); + } } + object_pub_->publish(output_object_msg); published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp); @@ -126,16 +137,20 @@ void ObjectLaneletFilterNode::objectCallback( bool ObjectLaneletFilterNode::filterObject( const autoware_perception_msgs::msg::DetectedObject & transformed_object, const autoware_perception_msgs::msg::DetectedObject & input_object, - const lanelet::ConstLanelets & intersected_lanelets, + const bgi::rtree & local_rtree, autoware_perception_msgs::msg::DetectedObjects & output_object_msg) { const auto & label = transformed_object.classification.front().label; if (filter_target_.isTarget(label)) { + // no tree, then no intersection + if (local_rtree.empty()) { + return false; + } + bool filter_pass = true; // 1. is polygon overlap with road lanelets or shoulder lanelets if (filter_settings_.polygon_overlap_filter) { - const bool is_polygon_overlap = - isObjectOverlapLanelets(transformed_object, intersected_lanelets); + const bool is_polygon_overlap = isObjectOverlapLanelets(transformed_object, local_rtree); filter_pass = filter_pass && is_polygon_overlap; } @@ -144,8 +159,7 @@ bool ObjectLaneletFilterNode::filterObject( transformed_object.kinematics.orientation_availability == autoware_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE; if (filter_settings_.lanelet_direction_filter && !orientation_not_available) { - const bool is_same_direction = - isSameDirectionWithLanelets(intersected_lanelets, transformed_object); + const bool is_same_direction = isSameDirectionWithLanelets(transformed_object, local_rtree); filter_pass = filter_pass && is_same_direction; } @@ -197,55 +211,75 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull( candidate_points.emplace_back(p.x + pos.x, p.y + pos.y); } } + LinearRing2d convex_hull; + bg::convex_hull(candidate_points, convex_hull); + + return convex_hull; +} + +LinearRing2d ObjectLaneletFilterNode::getConvexHullFromObjectFootprint( + const autoware_perception_msgs::msg::DetectedObject & object) +{ + MultiPoint2d candidate_points; + const auto & pos = object.kinematics.pose_with_covariance.pose.position; + const auto footprint = setFootprint(object); + + for (const auto & p : footprint.points) { + candidate_points.emplace_back(p.x + pos.x, p.y + pos.y); + } LinearRing2d convex_hull; - boost::geometry::convex_hull(candidate_points, convex_hull); + bg::convex_hull(candidate_points, convex_hull); return convex_hull; } // fetch the intersected candidate lanelets with bounding box and then // check the intersections among the lanelets and the convex hull -lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets( +std::vector ObjectLaneletFilterNode::getIntersectedLanelets( const LinearRing2d & convex_hull) { - namespace bg = boost::geometry; - - lanelet::ConstLanelets intersected_lanelets; + std::vector intersected_lanelets_with_bbox; // convert convex_hull to a 2D bounding box for searching in the LaneletMap - bg::model::box> bbox2d_convex_hull; - bg::envelope(convex_hull, bbox2d_convex_hull); - lanelet::BoundingBox2d bbox2d( + bg::model::box> bbox_of_convex_hull; + bg::envelope(convex_hull, bbox_of_convex_hull); + const lanelet::BoundingBox2d bbox2d( lanelet::BasicPoint2d( - bg::get(bbox2d_convex_hull), - bg::get(bbox2d_convex_hull)), + bg::get(bbox_of_convex_hull), + bg::get(bbox_of_convex_hull)), lanelet::BasicPoint2d( - bg::get(bbox2d_convex_hull), - bg::get(bbox2d_convex_hull))); + bg::get(bbox_of_convex_hull), + bg::get(bbox_of_convex_hull))); - lanelet::Lanelets candidates_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d); - for (const auto & lanelet : candidates_lanelets) { + const lanelet::Lanelets candidate_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d); + for (const auto & lanelet : candidate_lanelets) { // only check the road lanelets and road shoulder lanelets if ( lanelet.hasAttribute(lanelet::AttributeName::Subtype) && (lanelet.attribute(lanelet::AttributeName::Subtype).value() == lanelet::AttributeValueString::Road || lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) { - if (boost::geometry::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) { - intersected_lanelets.emplace_back(lanelet); + if (bg::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) { + // create bbox using boost for making the R-tree in later phase + lanelet::BoundingBox2d lanelet_bbox = lanelet::geometry::boundingBox2d(lanelet); + Point2d min_corner(lanelet_bbox.min().x(), lanelet_bbox.min().y()); + Point2d max_corner(lanelet_bbox.max().x(), lanelet_bbox.max().y()); + Box boost_bbox(min_corner, max_corner); + + intersected_lanelets_with_bbox.emplace_back(std::make_pair(boost_bbox, lanelet)); } } } - return intersected_lanelets; + return intersected_lanelets_with_bbox; } bool ObjectLaneletFilterNode::isObjectOverlapLanelets( const autoware_perception_msgs::msg::DetectedObject & object, - const lanelet::ConstLanelets & intersected_lanelets) + const bgi::rtree & local_rtree) { - // if has bounding box, use polygon overlap + // if object has bounding box, use polygon overlap if (utils::hasBoundingBox(object)) { Polygon2d polygon; const auto footprint = setFootprint(object); @@ -256,8 +290,17 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets( polygon.outer().emplace_back(point_transformed.x, point_transformed.y); } polygon.outer().push_back(polygon.outer().front()); - return isPolygonOverlapLanelets(polygon, intersected_lanelets); + + return isPolygonOverlapLanelets(polygon, local_rtree); } else { + const LinearRing2d object_convex_hull = getConvexHullFromObjectFootprint(object); + + // create bounding box to search in the rtree + std::vector candidates; + bg::model::box> bbox; + bg::envelope(object_convex_hull, bbox); + local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates)); + // if object do not have bounding box, check each footprint is inside polygon for (const auto & point : object.shape.footprint.points) { const geometry_msgs::msg::Point32 point_transformed = @@ -266,30 +309,39 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets( geometry_msgs::msg::Pose point2d; point2d.position.x = point_transformed.x; point2d.position.y = point_transformed.y; - for (const auto & lanelet : intersected_lanelets) { - if (lanelet::utils::isInLanelet(point2d, lanelet, 0.0)) { + + for (const auto & candidate : candidates) { + if (lanelet::utils::isInLanelet(point2d, candidate.second, 0.0)) { return true; } } } + return false; } } bool ObjectLaneletFilterNode::isPolygonOverlapLanelets( - const Polygon2d & polygon, const lanelet::ConstLanelets & intersected_lanelets) + const Polygon2d & polygon, const bgi::rtree & local_rtree) { - for (const auto & lanelet : intersected_lanelets) { - if (!boost::geometry::disjoint(polygon, lanelet.polygon2d().basicPolygon())) { + // create a bounding box from polygon for searching the local R-tree + std::vector candidates; + bg::model::box> bbox_of_convex_hull; + bg::envelope(polygon, bbox_of_convex_hull); + local_rtree.query(bgi::intersects(bbox_of_convex_hull), std::back_inserter(candidates)); + + for (const auto & box_and_lanelet : candidates) { + if (!bg::disjoint(polygon, box_and_lanelet.second.polygon2d().basicPolygon())) { return true; } } + return false; } bool ObjectLaneletFilterNode::isSameDirectionWithLanelets( - const lanelet::ConstLanelets & lanelets, - const autoware_perception_msgs::msg::DetectedObject & object) + const autoware_perception_msgs::msg::DetectedObject & object, + const bgi::rtree & local_rtree) { const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); const double object_velocity_norm = std::hypot( @@ -303,14 +355,30 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets( if (object_velocity_norm < filter_settings_.lanelet_direction_filter_object_speed_threshold) { return true; } - for (const auto & lanelet : lanelets) { - const bool is_in_lanelet = - lanelet::utils::isInLanelet(object.kinematics.pose_with_covariance.pose, lanelet, 0.0); + + // we can not query by points, so create a small bounding box + // eps is not determined by any specific criteria; just a guess + constexpr double eps = 1.0e-6; + std::vector candidates; + const Point2d min_corner( + object.kinematics.pose_with_covariance.pose.position.x - eps, + object.kinematics.pose_with_covariance.pose.position.y - eps); + const Point2d max_corner( + object.kinematics.pose_with_covariance.pose.position.x + eps, + object.kinematics.pose_with_covariance.pose.position.y + eps); + const Box bbox(min_corner, max_corner); + + local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates)); + + for (const auto & box_and_lanelet : candidates) { + const bool is_in_lanelet = lanelet::utils::isInLanelet( + object.kinematics.pose_with_covariance.pose, box_and_lanelet.second, 0.0); if (!is_in_lanelet) { continue; } + const double lane_yaw = lanelet::utils::getLaneletAngle( - lanelet, object.kinematics.pose_with_covariance.pose.position); + box_and_lanelet.second, object.kinematics.pose_with_covariance.pose.position); const double delta_yaw = object_velocity_yaw - lane_yaw; const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw); From 3f7060a0c4a0919b0be7127afdbdf8162bbee949 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 16 Jul 2024 19:30:24 +0900 Subject: [PATCH 042/151] feat(static_obstacle_avoidance): integrate time keeper to major functions (#8044) Signed-off-by: satoshi-ota --- .../src/scene.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 324bfdff8d777..d125f043f477b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -316,6 +316,7 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); using utils::static_obstacle_avoidance::filterTargetObjects; using utils::static_obstacle_avoidance::separateObjectsByPath; using utils::static_obstacle_avoidance::updateRoadShoulderDistance; @@ -370,6 +371,7 @@ void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( void StaticObstacleAvoidanceModule::fillAvoidanceTargetData(ObjectDataArray & objects) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); using utils::static_obstacle_avoidance::fillAvoidanceNecessity; using utils::static_obstacle_avoidance::fillObjectStoppableJudge; @@ -1402,6 +1404,7 @@ void StaticObstacleAvoidanceModule::updateRTCData() void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); using utils::static_obstacle_avoidance::createAmbiguousObjectsMarkerArray; using utils::static_obstacle_avoidance::createStopTargetObjectMarkerArray; using utils::static_obstacle_avoidance::createTargetObjectsMarkerArray; From c2fa03815acd30d2ca8dfa477375c960c5de5835 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 31 Jul 2024 14:26:38 +0900 Subject: [PATCH 043/151] fix(tier4_simulator_launch): update diag name (#1435) fix(simulator_launch): update diag name --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 8ee3809cb19d2..3c5fab58212ed 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -147,7 +147,7 @@ - + From 73ed8b8a19c0e11011a1a3a6926bf0e72b433edf Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 31 Jul 2024 23:08:38 +0900 Subject: [PATCH 044/151] fix(autoware_multi_object_tracker): revert latency reduction logic and bring back to timer trigger #8277 (#1436) * fix: revert latency reduction logic and bring back to timer trigger Signed-off-by: Taekjin LEE * style(pre-commit): autofix * chore: remove unused variables Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../multi_object_tracker_core.hpp | 1 - .../src/multi_object_tracker_core.cpp | 26 +------------------ 2 files changed, 1 insertion(+), 26 deletions(-) diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index 4c1ccced1bcf7..d6b79e13f1d3d 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -78,7 +78,6 @@ class MultiObjectTracker : public rclcpp::Node // publish timer rclcpp::TimerBase::SharedPtr publish_timer_; rclcpp::Time last_published_time_; - double publisher_period_; // internal states std::string world_frame_id_; // tracking frame diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 173cec9489f63..94062bcf9cc81 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -153,9 +153,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) // If the delay compensation is enabled, the timer is used to publish the output at the correct // time. if (enable_delay_compensation) { - publisher_period_ = 1.0 / publish_rate; // [s] - constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check - const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period(); + const auto timer_period = rclcpp::Rate(publish_rate).period(); publish_timer_ = rclcpp::create_timer( this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this)); } @@ -210,35 +208,13 @@ void MultiObjectTracker::onTrigger() std::vector> objects_list; const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list); if (!is_objects_ready) return; - onMessage(objects_list); - const rclcpp::Time latest_time(objects_list.back().second.header.stamp); - - // Publish objects if the timer is not enabled - if (publish_timer_ == nullptr) { - // if the delay compensation is disabled, publish the objects in the latest time - publish(latest_time); - } else { - // Publish if the next publish time is close - const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period - const rclcpp::Time publish_time = this->now(); - if ((publish_time - last_published_time_).seconds() > minimum_publish_interval) { - checkAndPublish(publish_time); - } - } } void MultiObjectTracker::onTimer() { const rclcpp::Time current_time = this->now(); - // Check the publish period - const auto elapsed_time = (current_time - last_published_time_).seconds(); - // If the elapsed time is over the period, publish objects with prediction - constexpr double maximum_latency_ratio = 1.11; // 11% margin - const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio; - if (elapsed_time < maximum_publish_latency) return; - // get objects from the input manager and run process ObjectsList objects_list; const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list); From 57279db0646777c8381f428caa89cd302d7a9d23 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 1 Aug 2024 09:24:39 +0900 Subject: [PATCH 045/151] feat(out_of_lane): ignore objects coming from behind ego (#7891) (#1437) Signed-off-by: Maxime CLEMENT --- .../config/out_of_lane.param.yaml | 1 + .../src/filter_predicted_objects.cpp | 8 ++++++++ .../src/out_of_lane_module.cpp | 5 +++-- .../src/types.hpp | 1 + .../autoware_motion_velocity_planner_node/src/node.cpp | 2 +- 5 files changed, 14 insertions(+), 3 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index e57b5a45d8be6..cc8f6f65b272d 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -19,6 +19,7 @@ predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights + ignore_behind_ego: true # if true, objects behind the ego vehicle are ignored overlap: minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index ecc10df43c792..1231bf49759d5 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -111,6 +111,14 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( }) != object.classification.end(); if (is_pedestrian) continue; + const auto is_coming_from_behind = + motion_utils::calcSignedArcLength( + ego_data.trajectory_points, ego_data.first_trajectory_idx, + object.kinematics.initial_pose_with_covariance.pose.position) < 0.0; + if (params.objects_ignore_behind_ego && is_coming_from_behind) { + continue; + } + auto filtered_object = object; const auto is_invalid_predicted_path = [&](const auto & predicted_path) { const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index 8397d0c116090..a7f7cbf5f2242 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -36,7 +36,6 @@ #include #include #include -#include #include namespace autoware::motion_velocity_planner @@ -85,6 +84,8 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) pp.objects_dist_buffer = getOrDeclareParameter(node, ns_ + ".objects.distance_buffer"); pp.objects_cut_predicted_paths_beyond_red_lights = getOrDeclareParameter(node, ns_ + ".objects.cut_predicted_paths_beyond_red_lights"); + pp.objects_ignore_behind_ego = + getOrDeclareParameter(node, ns_ + ".objects.ignore_behind_ego"); pp.overlap_min_dist = getOrDeclareParameter(node, ns_ + ".overlap.minimum_distance"); pp.overlap_extra_length = getOrDeclareParameter(node, ns_ + ".overlap.extra_length"); @@ -132,7 +133,7 @@ void OutOfLaneModule::update_parameters(const std::vector & p updateParam( parameters, ns_ + ".objects.cut_predicted_paths_beyond_red_lights", pp.objects_cut_predicted_paths_beyond_red_lights); - + updateParam(parameters, ns_ + ".objects.ignore_behind_ego", pp.objects_ignore_behind_ego); updateParam(parameters, ns_ + ".overlap.minimum_distance", pp.overlap_min_dist); updateParam(parameters, ns_ + ".overlap.extra_length", pp.overlap_extra_length); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 7a71bb6a7a28a..852d3ab2d2bc1 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -56,6 +56,7 @@ struct PlannerParam double objects_min_confidence; // minimum confidence to consider a predicted path double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in // the other lane + bool objects_ignore_behind_ego; // if true, objects behind the ego vehicle are ignored double overlap_extra_length; // [m] extra length to add around an overlap range double overlap_min_dist; // [m] min distance inside another lane to consider an overlap diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index a8b84fa3dafda..9be416f9e9bb0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -418,7 +418,7 @@ rcl_interfaces::msg::SetParametersResult MotionVelocityPlannerNode::on_set_param updateParam(parameters, "ego_nearest_dist_threshold", planner_data_.ego_nearest_dist_threshold); updateParam(parameters, "ego_nearest_yaw_threshold", planner_data_.ego_nearest_yaw_threshold); - set_velocity_smoother_params(); + // set_velocity_smoother_params(); TODO(Maxime): fix update parameters of the velocity smoother rcl_interfaces::msg::SetParametersResult result; result.successful = true; From 0e539d1999af50b5688b88baad2f22c7e4e1d1ed Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 1 Aug 2024 09:25:27 +0900 Subject: [PATCH 046/151] feat(out_of_lane): also apply lat buffer between the lane and stop pose (#1438) feat(out_of_lane): also apply lat buffer between the lane and stop pose (#7918) Signed-off-by: Maxime CLEMENT --- .../config/out_of_lane.param.yaml | 3 ++- .../src/calculate_slowdown_points.cpp | 6 ++++-- .../src/calculate_slowdown_points.hpp | 2 +- .../src/out_of_lane_module.cpp | 7 +++++-- .../src/types.hpp | 3 ++- 5 files changed, 14 insertions(+), 7 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index cc8f6f65b272d..a0cf69ee71027 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -28,7 +28,8 @@ action: # action to insert in the trajectory if an object causes a conflict at an overlap skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed precision: 0.1 # [m] precision when inserting a stop pose in the trajectory - distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane + longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle + lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled slowdown: distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp index 0c793c9f5798e..8b03fa66eab55 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -70,9 +70,11 @@ std::optional calculate_last_in_lane_pose( std::optional calculate_slowdown_point( const EgoData & ego_data, const std::vector & decisions, - const std::optional prev_slowdown_point, PlannerParam params) + const std::optional & prev_slowdown_point, PlannerParam params) { - params.extra_front_offset += params.dist_buffer; + params.extra_front_offset += params.lon_dist_buffer; + params.extra_right_offset += params.lat_dist_buffer; + params.extra_left_offset += params.lat_dist_buffer; const auto base_footprint = make_base_footprint(params); // search for the first slowdown decision for which a stop point can be inserted diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index ee4897de86c5b..145f21c94c0d0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -53,6 +53,6 @@ std::optional calculate_last_in_lane_pose( /// @return optional slowdown point to insert in the trajectory std::optional calculate_slowdown_point( const EgoData & ego_data, const std::vector & decisions, - const std::optional prev_slowdown_point, PlannerParam params); + const std::optional & prev_slowdown_point, PlannerParam params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index a7f7cbf5f2242..0afedcd7f9c9a 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -94,7 +94,9 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) getOrDeclareParameter(node, ns_ + ".action.skip_if_over_max_decel"); pp.precision = getOrDeclareParameter(node, ns_ + ".action.precision"); pp.min_decision_duration = getOrDeclareParameter(node, ns_ + ".action.min_duration"); - pp.dist_buffer = getOrDeclareParameter(node, ns_ + ".action.distance_buffer"); + pp.lon_dist_buffer = + getOrDeclareParameter(node, ns_ + ".action.longitudinal_distance_buffer"); + pp.lat_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.lateral_distance_buffer"); pp.slow_velocity = getOrDeclareParameter(node, ns_ + ".action.slowdown.velocity"); pp.slow_dist_threshold = getOrDeclareParameter(node, ns_ + ".action.slowdown.distance_threshold"); @@ -140,7 +142,8 @@ void OutOfLaneModule::update_parameters(const std::vector & p updateParam(parameters, ns_ + ".action.skip_if_over_max_decel", pp.skip_if_over_max_decel); updateParam(parameters, ns_ + ".action.precision", pp.precision); updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration); - updateParam(parameters, ns_ + ".action.distance_buffer", pp.dist_buffer); + updateParam(parameters, ns_ + ".action.longitudinal_distance_buffer", pp.lon_dist_buffer); + updateParam(parameters, ns_ + ".action.lateral_distance_buffer", pp.lat_dist_buffer); updateParam(parameters, ns_ + ".action.slowdown.velocity", pp.slow_velocity); updateParam(parameters, ns_ + ".action.slowdown.distance_threshold", pp.slow_dist_threshold); updateParam(parameters, ns_ + ".action.stop.distance_threshold", pp.stop_dist_threshold); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 852d3ab2d2bc1..9c68a0bf23a92 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -62,7 +62,8 @@ struct PlannerParam double overlap_min_dist; // [m] min distance inside another lane to consider an overlap // action to insert in the trajectory if an object causes a conflict at an overlap bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel - double dist_buffer; + double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle + double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle double slow_velocity; double slow_dist_threshold; double stop_dist_threshold; From 34ea4a0635e8d09799e14f5f4972650748670c86 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 7 Jun 2024 18:49:14 +0900 Subject: [PATCH 047/151] feat(motion_velocity_smoother)!: added force acceleration (#1329) * add feature for force acceleration Signed-off-by: Go Sakayori * Add log info when force acceleration is activated/deactivated Signed-off-by: Go Sakayori * fix enagage velocity/acceleration Signed-off-by: Go Sakayori * Update planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp * Update planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> --- .../autoware/velocity_smoother/node.hpp | 20 ++++++ .../smoother/smoother_base.hpp | 3 + .../autoware_velocity_smoother/package.xml | 1 + .../autoware_velocity_smoother/src/node.cpp | 67 +++++++++++++++++++ .../src/smoother/smoother_base.cpp | 15 +++++ 5 files changed, 106 insertions(+) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index 26918cce24549..6584de73d2c84 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -43,6 +43,7 @@ #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" +#include "std_srvs/srv/set_bool.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary #include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary @@ -65,6 +66,7 @@ using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; +using std_srvs::srv::SetBool; using tier4_debug_msgs::msg::Float32Stamped; // temporary using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary using tier4_planning_msgs::msg::VelocityLimit; // temporary @@ -97,6 +99,8 @@ class VelocitySmootherNode : public rclcpp::Node sub_external_velocity_limit_{this, "~/input/external_velocity_limit_mps"}; autoware::universe_utils::InterProcessPollingSubscriber sub_operation_mode_{ this, "~/input/operation_mode_state"}; + rclcpp::Service::SharedPtr srv_force_acceleration_; + rclcpp::Service::SharedPtr srv_slow_driving_; Odometry::ConstSharedPtr current_odometry_ptr_; // current odometry AccelWithCovarianceStamped::ConstSharedPtr current_acceleration_ptr_; @@ -134,6 +138,15 @@ class VelocitySmootherNode : public rclcpp::Node NORMAL = 3, }; + struct ForceAccelerationParam + { + double max_acceleration; + double max_jerk; + double max_lateral_acceleration; + double engage_velocity; + double engage_acceleration; + }; + struct Param { bool enable_lateral_acc_limit; @@ -159,6 +172,8 @@ class VelocitySmootherNode : public rclcpp::Node AlgorithmType algorithm_type; // Option : JerkFiltered, Linf, L2 bool plan_from_ego_speed_on_manual_mode = true; + + ForceAccelerationParam force_acceleration_param; } node_param_{}; struct ExternalVelocityLimit @@ -244,6 +259,11 @@ class VelocitySmootherNode : public rclcpp::Node // parameter handling void initCommonParam(); + void onForceAcceleration( + const std::shared_ptr request, std::shared_ptr response); + bool force_acceleration_mode_; + void onSlowDriving( + const std::shared_ptr request, std::shared_ptr response); // debug autoware::universe_utils::StopWatch stop_watch_; diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp index 6671eaa3eabe7..5efb003db183e 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp @@ -82,6 +82,9 @@ class SmootherBase double getMinJerk() const; void setWheelBase(const double wheel_base); + void setMaxAccel(const double max_accel); + void setMaxJerk(const double max_jerk); + void setMaxLatAccel(const double max_accel); void setParam(const BaseParam & param); BaseParam getBaseParam() const; diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index 997f7b16e5652..37420b534938c 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -30,6 +30,7 @@ nav_msgs osqp_interface rclcpp + std_srvs tf2 tf2_ros tier4_debug_msgs diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 3640c93d2d807..20b98e8f72ea7 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -38,6 +38,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti : Node("velocity_smoother", node_options) { using std::placeholders::_1; + using std::placeholders::_2; // set common params const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); @@ -66,6 +67,13 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti sub_current_trajectory_ = create_subscription( "~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1)); + srv_force_acceleration_ = create_service( + "~/adjust_common_param", + std::bind(&VelocitySmootherNode::onForceAcceleration, this, _1, _2)); + srv_slow_driving_ = create_service( + "~/slow_driving", std::bind(&VelocitySmootherNode::onSlowDriving, this, _1, _2)); + force_acceleration_mode_ = false; + // parameter update set_param_res_ = this->add_on_set_parameters_callback(std::bind(&VelocitySmootherNode::onParameter, this, _1)); @@ -184,6 +192,14 @@ rcl_interfaces::msg::SetParametersResult VelocitySmootherNode::onParameter( update_param("ego_nearest_dist_threshold", p.ego_nearest_dist_threshold); update_param("ego_nearest_yaw_threshold", p.ego_nearest_yaw_threshold); update_param_bool("plan_from_ego_speed_on_manual_mode", p.plan_from_ego_speed_on_manual_mode); + + update_param("force_acceleration.max_acc", p.force_acceleration_param.max_acceleration); + update_param("force_acceleration.max_jerk", p.force_acceleration_param.max_jerk); + update_param( + "force_acceleration.max_lateral_acc", p.force_acceleration_param.max_lateral_acceleration); + update_param("force_acceleration.engage_velocity", p.force_acceleration_param.engage_velocity); + update_param( + "force_acceleration.engage_acceleration", p.force_acceleration_param.engage_acceleration); } { @@ -303,6 +319,16 @@ void VelocitySmootherNode::initCommonParam() p.plan_from_ego_speed_on_manual_mode = declare_parameter("plan_from_ego_speed_on_manual_mode"); + + p.force_acceleration_param.max_acceleration = + declare_parameter("force_acceleration.max_acc"); + p.force_acceleration_param.max_jerk = declare_parameter("force_acceleration.max_jerk"); + p.force_acceleration_param.max_lateral_acceleration = + declare_parameter("force_acceleration.max_lateral_acc"); + p.force_acceleration_param.engage_velocity = + declare_parameter("force_acceleration.engage_velocity"); + p.force_acceleration_param.engage_acceleration = + declare_parameter("force_acceleration.engage_acceleration"); } void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory) const @@ -1116,6 +1142,47 @@ TrajectoryPoint VelocitySmootherNode::calcProjectedTrajectoryPointFromEgo( return calcProjectedTrajectoryPoint(trajectory, current_odometry_ptr_->pose.pose); } +void VelocitySmootherNode::onForceAcceleration( + const std::shared_ptr request, std::shared_ptr response) +{ + std::string message = "default"; + + if (request->data && !force_acceleration_mode_) { + RCLCPP_INFO(get_logger(), "Force acceleration is activated"); + smoother_->setMaxAccel(get_parameter("force_acceleration.max_acc").as_double()); + smoother_->setMaxJerk(get_parameter("force_acceleration.max_jerk").as_double()); + smoother_->setMaxLatAccel(get_parameter("force_acceleration.max_lateral_acc").as_double()); + node_param_.engage_velocity = get_parameter("force_acceleration.engage_velocity").as_double(); + node_param_.engage_acceleration = + get_parameter("force_acceleration.engage_acceleration").as_double(); + + force_acceleration_mode_ = true; + message = "Trigger force acceleration"; + } else if (!request->data && force_acceleration_mode_) { + RCLCPP_INFO(get_logger(), "Force acceleration is deactivated"); + smoother_->setMaxAccel(get_parameter("normal.max_acc").as_double()); + smoother_->setMaxJerk(get_parameter("normal.max_jerk").as_double()); + smoother_->setMaxLatAccel(get_parameter("max_lateral_accel").as_double()); + + node_param_.engage_velocity = get_parameter("engage_velocity").as_double(); + node_param_.engage_acceleration = get_parameter("engage_acceleration").as_double(); + + force_acceleration_mode_ = false; + message = "Trigger normal acceleration"; + } + + response->success = true; +} + +void VelocitySmootherNode::onSlowDriving( + const std::shared_ptr request, std::shared_ptr response) +{ + const std::string message = request->data ? "Slow driving" : "Default"; + + response->success = true; + response->message = message; +} + } // namespace autoware::velocity_smoother #include "rclcpp_components/register_node_macro.hpp" diff --git a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp index 46faf10fe4a62..131327ee9ad0b 100644 --- a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp @@ -97,6 +97,21 @@ void SmootherBase::setWheelBase(const double wheel_base) base_param_.wheel_base = wheel_base; } +void SmootherBase::setMaxAccel(const double max_accel) +{ + base_param_.max_accel = max_accel; +} + +void SmootherBase::setMaxJerk(const double max_jerk) +{ + base_param_.max_jerk = max_jerk; +} + +void SmootherBase::setMaxLatAccel(const double max_accel) +{ + base_param_.max_lateral_accel = max_accel; +} + void SmootherBase::setParam(const BaseParam & param) { base_param_ = param; From e3c1699c97fb31dc610ccb4eb145ae82d1440a04 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Thu, 11 Jul 2024 13:07:15 +0900 Subject: [PATCH 048/151] feat(motion_velocity_smoother): force slow driving (#1409) * add force slow driving function Signed-off-by: Go Sakayori * fix state Signed-off-by: Go Sakayori * erase log info Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../autoware/velocity_smoother/node.hpp | 12 ++++++++ .../autoware_velocity_smoother/src/node.cpp | 30 ++++++++++++++++++- 2 files changed, 41 insertions(+), 1 deletion(-) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index 6584de73d2c84..bcc9338422c9f 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -138,6 +138,12 @@ class VelocitySmootherNode : public rclcpp::Node NORMAL = 3, }; + enum class ForceSlowDrivingType { + DEACTIVATED = 0, + READY = 1, + ACTIVATED = 2, + }; + struct ForceAccelerationParam { double max_acceleration; @@ -174,6 +180,7 @@ class VelocitySmootherNode : public rclcpp::Node bool plan_from_ego_speed_on_manual_mode = true; ForceAccelerationParam force_acceleration_param; + double force_slow_driving_velocity; } node_param_{}; struct ExternalVelocityLimit @@ -259,11 +266,16 @@ class VelocitySmootherNode : public rclcpp::Node // parameter handling void initCommonParam(); + + // Related to force acceleration void onForceAcceleration( const std::shared_ptr request, std::shared_ptr response); bool force_acceleration_mode_; + + // Related to force slow driving void onSlowDriving( const std::shared_ptr request, std::shared_ptr response); + ForceSlowDrivingType force_slow_driving_mode_; // debug autoware::universe_utils::StopWatch stop_watch_; diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 20b98e8f72ea7..eeebc96f1516d 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -73,6 +73,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti srv_slow_driving_ = create_service( "~/slow_driving", std::bind(&VelocitySmootherNode::onSlowDriving, this, _1, _2)); force_acceleration_mode_ = false; + force_slow_driving_mode_ = ForceSlowDrivingType::DEACTIVATED; // parameter update set_param_res_ = @@ -200,6 +201,7 @@ rcl_interfaces::msg::SetParametersResult VelocitySmootherNode::onParameter( update_param("force_acceleration.engage_velocity", p.force_acceleration_param.engage_velocity); update_param( "force_acceleration.engage_acceleration", p.force_acceleration_param.engage_acceleration); + update_param("force_slow_driving.velocity", p.force_slow_driving_velocity); } { @@ -329,6 +331,8 @@ void VelocitySmootherNode::initCommonParam() declare_parameter("force_acceleration.engage_velocity"); p.force_acceleration_param.engage_acceleration = declare_parameter("force_acceleration.engage_acceleration"); + + p.force_slow_driving_velocity = declare_parameter("force_slow_driving.velocity"); } void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory) const @@ -502,6 +506,14 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr flipVelocity(input_points); } + // Only activate slow driving when velocity is below threshold + double slow_driving_vel_threshold = get_parameter("force_slow_driving.velocity").as_double(); + if ( + force_slow_driving_mode_ == ForceSlowDrivingType::READY && + current_odometry_ptr_->twist.twist.linear.x < slow_driving_vel_threshold) { + force_slow_driving_mode_ = ForceSlowDrivingType::ACTIVATED; + } + const auto output = calcTrajectoryVelocity(input_points); if (output.empty()) { RCLCPP_WARN(get_logger(), "Output Point is empty"); @@ -591,6 +603,13 @@ TrajectoryPoints VelocitySmootherNode::calcTrajectoryVelocity( // Apply velocity to approach stop point applyStopApproachingVelocity(traj_extracted); + // Apply force slow driving if activated + if (force_slow_driving_mode_ == ForceSlowDrivingType::ACTIVATED) { + for (auto & tp : traj_extracted) { + tp.longitudinal_velocity_mps = get_parameter("force_slow_driving.velocity").as_double(); + } + } + // Debug if (publish_debug_trajs_) { auto tmp = traj_extracted; @@ -1172,12 +1191,21 @@ void VelocitySmootherNode::onForceAcceleration( } response->success = true; + response->message = message; } void VelocitySmootherNode::onSlowDriving( const std::shared_ptr request, std::shared_ptr response) { - const std::string message = request->data ? "Slow driving" : "Default"; + std::string message = "default"; + if (request->data && force_slow_driving_mode_ == ForceSlowDrivingType::DEACTIVATED) { + force_slow_driving_mode_ = ForceSlowDrivingType::READY; + + message = "Activated force slow drving"; + } else if (!request->data) { + force_slow_driving_mode_ = ForceSlowDrivingType::DEACTIVATED; + message = "Deactivated force slow driving"; + } response->success = true; response->message = message; From def5cadc81177563c515fb82dbacd63cb3552853 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 7 Aug 2024 11:35:15 +0900 Subject: [PATCH 049/151] fix spelling mistake Signed-off-by: Go Sakayori --- planning/autoware_velocity_smoother/src/node.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index eeebc96f1516d..ca0fdc9ca7117 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -68,8 +68,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti "~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1)); srv_force_acceleration_ = create_service( - "~/adjust_common_param", - std::bind(&VelocitySmootherNode::onForceAcceleration, this, _1, _2)); + "~/adjust_common_param", std::bind(&VelocitySmootherNode::onForceAcceleration, this, _1, _2)); srv_slow_driving_ = create_service( "~/slow_driving", std::bind(&VelocitySmootherNode::onSlowDriving, this, _1, _2)); force_acceleration_mode_ = false; @@ -1201,7 +1200,7 @@ void VelocitySmootherNode::onSlowDriving( if (request->data && force_slow_driving_mode_ == ForceSlowDrivingType::DEACTIVATED) { force_slow_driving_mode_ = ForceSlowDrivingType::READY; - message = "Activated force slow drving"; + message = "Activated force slow driving"; } else if (!request->data) { force_slow_driving_mode_ = ForceSlowDrivingType::DEACTIVATED; message = "Deactivated force slow driving"; From c43d7d4e253d66bc9f8ede2c32b1b8c793d48a89 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 7 Aug 2024 18:52:41 +0900 Subject: [PATCH 050/151] fix(autoware_behavior_path_lane_change_module): avoid empty current lanes (#1445) set current_lanes to avoid accessing empty current_lanes Signed-off-by: Kento Yabuuchi --- .../autoware_behavior_path_lane_change_module/src/scene.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 3fc64736731f5..75efc65c2997c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -85,6 +85,7 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); if (target_lanes.empty()) { + safe_path.info.current_lanes = current_lanes; return {false, false}; } From 0c040da2a9e1fbae195f571ec159cf5a5036326d Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 7 Aug 2024 11:25:30 +0900 Subject: [PATCH 051/151] fix(traffic_light_classifier): fix zero size roi bug (#7608) * fix: continue to process when input roi size is zero Signed-off-by: Taekjin LEE * fix: consider when roi size is zero, rois is empty fix Signed-off-by: Taekjin LEE * fix: use emplace_back instead of push_back for adding images and backlight indices The code changes in `traffic_light_classifier_node.cpp` modify the way images and backlight indices are added to the respective vectors. Instead of using `push_back`, the code now uses `emplace_back`. This change improves performance and ensures proper object construction. Signed-off-by: Taekjin LEE * refactor: bring back for loop skim and output_msg filling Signed-off-by: Taekjin LEE * chore: refactor code to handle empty input ROIs in traffic_light_classifier_node.cpp Signed-off-by: Taekjin LEE * refactor: using index instead of vector length Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../traffic_light_classifier/src/nodelet.cpp | 43 ++++++++++++------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index 6378a98fdc8cc..440b5b0dcfb3e 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -84,6 +84,9 @@ void TrafficLightClassifierNodelet::imageRoiCallback( if (classifier_ptr_.use_count() == 0) { return; } + if (input_rois_msg->rois.empty()) { + return; + } cv_bridge::CvImagePtr cv_ptr; try { @@ -95,41 +98,49 @@ void TrafficLightClassifierNodelet::imageRoiCallback( } tier4_perception_msgs::msg::TrafficLightArray output_msg; - output_msg.signals.resize(input_rois_msg->rois.size()); std::vector images; std::vector backlight_indices; - for (size_t i = 0; i < input_rois_msg->rois.size(); i++) { - // skip if the roi is not detected - if (input_rois_msg->rois.at(i).roi.height == 0) { - break; + size_t idx_valid_roi = 0; + for (const auto & input_roi : input_rois_msg->rois) { + // ignore if the roi is not the type to be classified + if (input_roi.traffic_light_type != classify_traffic_light_type_) { + continue; } - if (input_rois_msg->rois.at(i).traffic_light_type != classify_traffic_light_type_) { + // skip if the roi size is zero + if (input_roi.roi.height == 0 || input_roi.roi.width == 0) { continue; } - output_msg.signals[images.size()].traffic_light_id = - input_rois_msg->rois.at(i).traffic_light_id; - output_msg.signals[images.size()].traffic_light_type = - input_rois_msg->rois.at(i).traffic_light_type; - const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi; + // set traffic light id and type + output_msg.signals[idx_valid_roi].traffic_light_id = input_roi.traffic_light_id; + output_msg.signals[idx_valid_roi].traffic_light_type = input_roi.traffic_light_type; + + const sensor_msgs::msg::RegionOfInterest & roi = input_roi.roi; auto roi_img = cv_ptr->image(cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height)); if (is_harsh_backlight(roi_img)) { - backlight_indices.emplace_back(i); + backlight_indices.emplace_back(idx_valid_roi); } images.emplace_back(roi_img); + idx_valid_roi++; } + // classify the images output_msg.signals.resize(images.size()); - if (!classifier_ptr_->getTrafficSignals(images, output_msg)) { - RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); - return; + if (!images.empty()) { + if (!classifier_ptr_->getTrafficSignals(images, output_msg)) { + RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback"); + return; + } } // append the undetected rois as unknown for (const auto & input_roi : input_rois_msg->rois) { - if (input_roi.roi.height == 0 && input_roi.traffic_light_type == classify_traffic_light_type_) { + // if the type is the target type but the roi size is zero, the roi is undetected + if ( + (input_roi.roi.height == 0 || input_roi.roi.width == 0) && + input_roi.traffic_light_type == classify_traffic_light_type_) { tier4_perception_msgs::msg::TrafficLight tlr_sig; tlr_sig.traffic_light_id = input_roi.traffic_light_id; tlr_sig.traffic_light_type = input_roi.traffic_light_type; From 069d98c05ee1d88511668f3881975ab3f4d08fdb Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 7 Aug 2024 20:26:31 +0900 Subject: [PATCH 052/151] feat(map_based_prediction): filter surrounding crosswalks for pedestrians beforehand (#8388) fix withinAnyCroswalk Signed-off-by: Mamoru Sobue --- .../src/map_based_prediction_node.cpp | 65 +++++++++++-------- 1 file changed, 38 insertions(+), 27 deletions(-) diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index eaea3c06041b3..29cfe52855d24 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -410,9 +410,9 @@ bool withinRoadLanelet( } boost::optional isReachableCrosswalkEdgePoints( - const TrackedObject & object, const lanelet::ConstLanelet & target_crosswalk, - const CrosswalkEdgePoints & edge_points, const lanelet::LaneletMapPtr & lanelet_map_ptr, - const double time_horizon, const double min_object_vel) + const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets, + const lanelet::ConstLanelets & external_surrounding_crosswalks, + const CrosswalkEdgePoints & edge_points, const double time_horizon, const double min_object_vel) { using Point = boost::geometry::model::d2::point_xy; @@ -421,9 +421,6 @@ boost::optional isReachableCrosswalkEdgePoints( const auto yaw = autoware::universe_utils::getRPY(object.kinematics.pose_with_covariance.pose).z; lanelet::BasicPoint2d obj_pos_as_lanelet(obj_pos.x, obj_pos.y); - if (boost::geometry::within(obj_pos_as_lanelet, target_crosswalk.polygon2d().basicPolygon())) { - return {}; - } const auto & p1 = edge_points.front_center_point; const auto & p2 = edge_points.back_center_point; @@ -441,17 +438,12 @@ boost::optional isReachableCrosswalkEdgePoints( const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto is_stop_object = estimated_velocity < stop_velocity_th; const auto velocity = std::max(min_object_vel, estimated_velocity); - const auto surrounding_lanelets = lanelet::geometry::findNearest( - lanelet_map_ptr->laneletLayer, obj_pos_as_lanelet, time_horizon * velocity); - const auto isAcrossAnyRoad = [&surrounding_lanelets](const Point & p_src, const Point & p_dst) { - const auto withinAnyCrosswalk = [&surrounding_lanelets](const Point & p) { - for (const auto & lanelet : surrounding_lanelets) { - const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype); - if ( - (attr.value() == lanelet::AttributeValueString::Crosswalk || - attr.value() == lanelet::AttributeValueString::Walkway) && - boost::geometry::within(p, lanelet.second.polygon2d().basicPolygon())) { + const auto isAcrossAnyRoad = [&surrounding_lanelets, &external_surrounding_crosswalks]( + const Point & p_src, const Point & p_dst) { + const auto withinAnyCrosswalk = [&external_surrounding_crosswalks](const Point & p) { + for (const auto & crosswalk : external_surrounding_crosswalks) { + if (boost::geometry::within(p, crosswalk.polygon2d().basicPolygon())) { return true; } } @@ -470,14 +462,13 @@ boost::optional isReachableCrosswalkEdgePoints( std::vector points_of_intersect; const boost::geometry::model::linestring line{p_src, p_dst}; for (const auto & lanelet : surrounding_lanelets) { - const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype); + const lanelet::Attribute attr = lanelet.attribute(lanelet::AttributeName::Subtype); if (attr.value() != lanelet::AttributeValueString::Road) { continue; } std::vector tmp_intersects; - boost::geometry::intersection( - line, lanelet.second.polygon2d().basicPolygon(), tmp_intersects); + boost::geometry::intersection(line, lanelet.polygon2d().basicPolygon(), tmp_intersects); for (const auto & p : tmp_intersects) { if (isExist(p, points_of_intersect) || withinAnyCrosswalk(p)) { continue; @@ -1380,10 +1371,29 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( } boost::optional crossing_crosswalk{boost::none}; - for (const auto & crosswalk : crosswalks_) { - if (withinLanelet(object, crosswalk)) { - crossing_crosswalk = crosswalk; - break; + const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; + const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear; + const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); + const auto velocity = std::max(min_crosswalk_user_velocity_, estimated_velocity); + // TODO(Mamoru Sobue): 3rd argument of findNearest is the number of lanelets, not radius, so past + // implementation has been wrong. + const auto surrounding_lanelets_with_dist = lanelet::geometry::findNearest( + lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y}, + prediction_time_horizon_.pedestrian * velocity); + lanelet::ConstLanelets surrounding_lanelets; + lanelet::ConstLanelets external_surrounding_crosswalks; + for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) { + surrounding_lanelets.push_back(lanelet); + const auto attr = lanelet.attribute(lanelet::AttributeName::Subtype); + if ( + attr.value() == lanelet::AttributeValueString::Crosswalk || + attr.value() == lanelet::AttributeValueString::Walkway) { + const auto & crosswalk = lanelet; + if (withinLanelet(object, crosswalk)) { + crossing_crosswalk = crosswalk; + } else { + external_surrounding_crosswalks.push_back(crosswalk); + } } } @@ -1444,8 +1454,9 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( } } - // try to find the edge points for all crosswalks and generate path to the crosswalk edge - for (const auto & crosswalk : crosswalks_) { + // try to find the edge points for other surrounding crosswalks and generate path to the crosswalk + // edge + for (const auto & crosswalk : external_surrounding_crosswalks) { const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk); if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) { if (!calcIntentionToCrossWithTrafficSignal( @@ -1470,8 +1481,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( } const auto reachable_crosswalk = isReachableCrosswalkEdgePoints( - object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_.pedestrian, - min_crosswalk_user_velocity_); + object, surrounding_lanelets, external_surrounding_crosswalks, edge_points, + prediction_time_horizon_.pedestrian, min_crosswalk_user_velocity_); if (!reachable_crosswalk) { continue; From 55be286ac4e057d95cecf82a50a770927f0b2d52 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 29 Jul 2024 19:59:36 +0900 Subject: [PATCH 053/151] feat(goal_planner): add time keeper (#8194) Signed-off-by: kosuke55 time keeper --- .../src/goal_planner_module.cpp | 63 +++++++++++++++++++ 1 file changed, 63 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index dc7a76031a3c1..73e5cee725054 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -123,6 +123,13 @@ GoalPlannerModule::GoalPlannerModule( if (parameters_->safety_check_params.enable_safety_check) { initializeSafetyCheckParameters(); } + + /** + * NOTE: Add `universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);` to functions called + * from the main thread only. + * If you want to see the processing time tree in console, uncomment the following line + */ + // time_keeper_->add_reporter(&std::cerr); } bool GoalPlannerModule::hasPreviousModulePathShapeChanged( @@ -447,6 +454,8 @@ void GoalPlannerModule::updateObjectsFilteringParams( void GoalPlannerModule::updateData() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // In PlannerManager::run(), it calls SceneModuleInterface::setData and // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). // Then module_ptr->run() invokes GoalPlannerModule::updateData and then @@ -789,6 +798,8 @@ bool GoalPlannerModule::canReturnToLaneParking() GoalCandidates GoalPlannerModule::generateGoalCandidates() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // calculate goal candidates const auto & route_handler = planner_data_->route_handler; if (utils::isAllowedGoalModification(route_handler)) { @@ -809,6 +820,8 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const BehaviorModuleOutput GoalPlannerModule::plan() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { return planPullOver(); } @@ -821,6 +834,8 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // ========================================================================================== // print path priority for debug const auto debugPrintPathPriority = @@ -1013,6 +1028,8 @@ std::optional> GoalPlannerModule::selectP const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates, const double collision_check_margin) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto & goal_pose = planner_data_->route_handler->getOriginalGoalPose(); const double backward_length = parameters_->backward_goal_search_length + parameters_->decide_path_distance; @@ -1072,6 +1089,8 @@ std::optional> GoalPlannerModule::selectP std::vector GoalPlannerModule::generateDrivableLanes() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( planner_data_, parameters_->backward_goal_search_length, parameters_->forward_goal_search_length, @@ -1084,6 +1103,8 @@ std::vector GoalPlannerModule::generateDrivableLanes() const void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + output.reference_path = getPreviousModuleOutput().reference_path; if (!thread_safe_data_.foundPullOverPath()) { @@ -1135,6 +1156,8 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) { const double drivable_area_margin = planner_data_->parameters.vehicle_width; output.drivable_area_info.drivable_margin = @@ -1201,6 +1224,8 @@ bool GoalPlannerModule::hasDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1216,6 +1241,8 @@ bool GoalPlannerModule::hasNotDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1231,6 +1258,8 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; @@ -1345,6 +1374,8 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( void GoalPlannerModule::decideVelocity() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths.front(); @@ -1357,6 +1388,8 @@ void GoalPlannerModule::decideVelocity() BehaviorModuleOutput GoalPlannerModule::planPullOver() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!hasDecidedPath( planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, safety_check_params_, goal_searcher_)) { @@ -1368,6 +1401,8 @@ BehaviorModuleOutput GoalPlannerModule::planPullOver() BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // if pull over path candidates generation is not finished, use previous module output if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); @@ -1398,6 +1433,8 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // if pull over path candidates generation is not finished, use previous module output if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return getPreviousModuleOutput(); @@ -1475,6 +1512,8 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() void GoalPlannerModule::postProcess() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!thread_safe_data_.foundPullOverPath()) { return; } @@ -1502,6 +1541,8 @@ void GoalPlannerModule::postProcess() void GoalPlannerModule::updatePreviousData() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. // TODO(Mamoru Sobue): put prev_data_ out of ThreadSafeData @@ -1537,6 +1578,8 @@ void GoalPlannerModule::updatePreviousData() BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (utils::isAllowedGoalModification(planner_data_->route_handler)) { return planPullOverAsCandidate(); } @@ -1547,6 +1590,8 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() std::pair GoalPlannerModule::calcDistanceToPathChange() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!thread_safe_data_.foundPullOverPath()) { return {std::numeric_limits::max(), std::numeric_limits::max()}; } @@ -1581,6 +1626,8 @@ void GoalPlannerModule::setParameters(const std::shared_ptrroute_handler; const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & common_parameters = planner_data_->parameters; @@ -1688,6 +1735,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const PathWithLaneId GoalPlannerModule::generateFeasibleStopPath(const PathWithLaneId & path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // calc minimum stop distance under maximum deceleration const auto min_stop_distance = calcFeasibleDecelDistance( planner_data_, parameters_->maximum_deceleration, parameters_->maximum_jerk, 0.0); @@ -1784,6 +1833,8 @@ bool GoalPlannerModule::isStuck( bool GoalPlannerModule::hasFinishedCurrentPath() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!last_approval_data_) { return false; } @@ -1834,6 +1885,8 @@ bool GoalPlannerModule::isOnModifiedGoal( TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto path = thread_safe_data_.get_pull_over_path()->getFullPath(); if (path.points.empty()) return getPreviousModuleOutput().turn_signal_info; @@ -2072,6 +2125,8 @@ void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const void GoalPlannerModule::decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const double time = planner_data_->parameters.turn_signal_search_time; const Pose & current_pose = planner_data_->self_odometry->pose.pose; @@ -2111,6 +2166,8 @@ void GoalPlannerModule::decelerateForTurnSignal(const Pose & stop_pose, PathWith void GoalPlannerModule::decelerateBeforeSearchStart( const Pose & search_start_offset_pose, PathWithLaneId & path) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const double pull_over_velocity = parameters_->pull_over_velocity; const Pose & current_pose = planner_data_->self_odometry->pose.pose; @@ -2130,6 +2187,8 @@ void GoalPlannerModule::decelerateBeforeSearchStart( bool GoalPlannerModule::isCrossingPossible( const lanelet::ConstLanelet & start_lane, const lanelet::ConstLanelet & end_lane) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (start_lane.centerline().empty() || end_lane.centerline().empty()) { return false; } @@ -2279,6 +2338,8 @@ std::pair GoalPlannerModule::isSafePath( const std::shared_ptr & objects_filtering_params, const std::shared_ptr & safety_check_params) const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } @@ -2415,6 +2476,8 @@ std::pair GoalPlannerModule::isSafePath( void GoalPlannerModule::setDebugData() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + debug_marker_.markers.clear(); using autoware::motion_utils::createStopVirtualWallMarker; From 38df3659539c629c453945602b13b03877e9e82e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 29 Jul 2024 20:40:29 +0900 Subject: [PATCH 054/151] feat(path_safety_checker): add rough collision check (#8193) * feat(path_safety_checker): add rough collision check Signed-off-by: kosuke55 * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp --------- Signed-off-by: kosuke55 --- .../path_safety_checker/safety_check.hpp | 7 ++ .../path_safety_checker/safety_check.cpp | 98 +++++++++++++++++++ 2 files changed, 105 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index d0d19b6b8fed2..05f7c70fa42c2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -27,6 +27,7 @@ #include #include +#include #include namespace autoware::behavior_path_planner::utils::path_safety_checker @@ -156,6 +157,12 @@ bool checkSafetyWithIntegralPredictedPolygon( const ExtendedPredictedObjects & objects, const bool check_all_predicted_path, const IntegralPredictedPolygonParams & params, CollisionCheckDebugMap & debug_map); +double calcObstacleMinLength(const Shape & shape); +double calcObstacleMaxLength(const Shape & shape); +std::pair checkObjectsCollisionRough( + const PathWithLaneId & path, const PredictedObjects & objects, const double margin, + const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point); + // debug CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj); void updateCollisionCheckDebugMap( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index b05d869cca6b5..8d2dd2fb86e29 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -36,6 +36,12 @@ namespace autoware::behavior_path_planner::utils::path_safety_checker namespace bg = boost::geometry; +using autoware::motion_utils::calcLongitudinalOffsetPoint; +using autoware::motion_utils::calcLongitudinalOffsetToSegment; +using autoware::motion_utils::findNearestIndex; +using autoware::motion_utils::findNearestSegmentIndex; +using autoware::universe_utils::calcDistance2d; + void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) { Point2d point; @@ -722,4 +728,96 @@ void updateCollisionCheckDebugMap( debug_map.insert(object_debug); } +double calcObstacleMinLength(const Shape & shape) +{ + if (shape.type == Shape::BOUNDING_BOX) { + return std::min(shape.dimensions.x / 2.0, shape.dimensions.y / 2.0); + } else if (shape.type == Shape::CYLINDER) { + return shape.dimensions.x / 2.0; + } else if (shape.type == Shape::POLYGON) { + double min_length_to_point = std::numeric_limits::max(); + for (const auto rel_point : shape.footprint.points) { + const double length_to_point = std::hypot(rel_point.x, rel_point.y); + if (min_length_to_point > length_to_point) { + min_length_to_point = length_to_point; + } + } + return min_length_to_point; + } + + throw std::logic_error("The shape type is not supported in obstacle_cruise_planner."); +} + +double calcObstacleMaxLength(const Shape & shape) +{ + if (shape.type == Shape::BOUNDING_BOX) { + return std::hypot(shape.dimensions.x / 2.0, shape.dimensions.y / 2.0); + } else if (shape.type == Shape::CYLINDER) { + return shape.dimensions.x / 2.0; + } else if (shape.type == Shape::POLYGON) { + double max_length_to_point = 0.0; + for (const auto rel_point : shape.footprint.points) { + const double length_to_point = std::hypot(rel_point.x, rel_point.y); + if (max_length_to_point < length_to_point) { + max_length_to_point = length_to_point; + } + } + return max_length_to_point; + } + + throw std::logic_error("The shape type is not supported in obstacle_cruise_planner."); +} + +std::pair checkObjectsCollisionRough( + const PathWithLaneId & path, const PredictedObjects & objects, const double margin, + const BehaviorPathPlannerParameters & parameters, const bool use_offset_ego_point) +{ + const auto & points = path.points; + + std::pair has_collision = {false, false}; // {min_distance, max_distance} + for (const auto & object : objects.objects) { + // calculate distance between object center and ego base_link + const Point & object_point = object.kinematics.initial_pose_with_covariance.pose.position; + const double distance = std::invoke([&]() -> double { + if (use_offset_ego_point) { + const size_t nearest_segment_idx = findNearestSegmentIndex(points, object_point); + const double offset_length = + calcLongitudinalOffsetToSegment(points, nearest_segment_idx, object_point); + const auto offset_point = + calcLongitudinalOffsetPoint(points, nearest_segment_idx, offset_length); + const Point ego_point = + offset_point ? offset_point.value() + : points.at(findNearestIndex(points, object_point)).point.pose.position; + return autoware::universe_utils::calcDistance2d(ego_point, object_point); + } + const Point ego_point = points.at(findNearestIndex(points, object_point)).point.pose.position; + return autoware::universe_utils::calcDistance2d(ego_point, object_point); + }); + + // calculate min and max length from object center to edge + const double object_min_length = calcObstacleMinLength(object.shape); + const double object_max_length = calcObstacleMaxLength(object.shape); + + // calculate min and max length from ego base_link to edge + const auto & p = parameters; + const double ego_min_length = + std::min({p.vehicle_width / 2, p.front_overhang / 2, p.rear_overhang / 2}); + const double ego_max_length = std::max( + std::hypot(p.vehicle_width / 2, p.front_overhang), + std::hypot(p.vehicle_width / 2, p.rear_overhang)); + + // calculate min and max distance between object footprint and ego footprint + const double min_distance = distance - object_max_length - ego_max_length; + const double max_distance = distance - object_min_length - ego_min_length; + + if (min_distance < margin) { + has_collision.first = true; + } + if (max_distance < margin) { + has_collision.second = true; + } + } + return has_collision; +} + } // namespace autoware::behavior_path_planner::utils::path_safety_checker From 4099567eadad586d0845ae7c7fac62f85baae1b8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 30 Jul 2024 11:40:31 +0900 Subject: [PATCH 055/151] perf(goal_planner): reduce processing time (#8195) * perf(goal_palnner): reduce processing time Signed-off-by: kosuke55 * add const& return Signed-off-by: kosuke55 * use copy getter Signed-off-by: kosuke55 * pre commit Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner_module.hpp | 11 +- .../pull_over_planner_base.hpp | 122 +++++++++++++---- .../util.hpp | 1 + .../src/freespace_pull_over.cpp | 4 +- .../src/geometric_pull_over.cpp | 4 +- .../src/goal_planner_module.cpp | 126 +++++++++++------- .../src/shift_pull_over.cpp | 7 +- 7 files changed, 186 insertions(+), 89 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index e34cd202011d0..749ed57f95cc9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -228,6 +228,8 @@ class ThreadSafeData DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, last_previous_module_output) DEFINE_SETTER_GETTER_WITH_MUTEX(PreviousPullOverData, prev_data) DEFINE_SETTER_GETTER_WITH_MUTEX(CollisionCheckDebugMap, collision_check) + DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, static_target_objects) + DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, dynamic_target_objects) private: std::shared_ptr pull_over_path_{nullptr}; @@ -241,6 +243,8 @@ class ThreadSafeData std::optional last_previous_module_output_{}; PreviousPullOverData prev_data_{}; CollisionCheckDebugMap collision_check_{}; + PredictedObjects static_target_objects_{}; + PredictedObjects dynamic_target_objects_{}; std::recursive_mutex & mutex_; rclcpp::Clock::SharedPtr clock_; @@ -520,9 +524,10 @@ class GoalPlannerModule : public SceneModuleInterface const PathWithLaneId & path, const std::shared_ptr occupancy_grid_map) const; bool checkObjectsCollision( - const PathWithLaneId & path, const std::shared_ptr planner_data, - const GoalPlannerParameters & parameters, const double collision_check_margin, - const bool extract_static_objects, const bool update_debug_data = false) const; + const PathWithLaneId & path, const std::vector & curvatures, + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const double collision_check_margin, const bool extract_static_objects, + const bool update_debug_data = false) const; // goal seach Pose calcRefinedGoal(const Pose & goal_pose) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp index 05385600926f5..9899f4a5fad1e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -52,41 +52,29 @@ struct PullOverPath size_t goal_id{}; size_t id{}; bool decided_velocity{false}; - double max_curvature{0.0}; // max curvature of the parking path - PathWithLaneId getFullPath() const + /** + * @brief Set paths and start/end poses + * By setting partial_paths, full_path, parking_path and curvature are also set at the same time + * @param input_partial_paths partial paths + * @param input_start_pose start pose + * @param input_end_pose end pose + */ + void setPaths( + const std::vector input_partial_paths, const Pose & input_start_pose, + const Pose & input_end_pose) { - PathWithLaneId path{}; - for (size_t i = 0; i < partial_paths.size(); ++i) { - if (i == 0) { - path.points.insert( - path.points.end(), partial_paths.at(i).points.begin(), partial_paths.at(i).points.end()); - } else { - // skip overlapping point - path.points.insert( - path.points.end(), next(partial_paths.at(i).points.begin()), - partial_paths.at(i).points.end()); - } - } - path.points = autoware::motion_utils::removeOverlapPoints(path.points); + partial_paths = input_partial_paths; + start_pose = input_start_pose; + end_pose = input_end_pose; - return path; + updatePathData(); } - // path from the pull over start pose to the end pose - PathWithLaneId getParkingPath() const - { - const PathWithLaneId full_path = getFullPath(); - const size_t start_idx = - autoware::motion_utils::findNearestIndex(full_path.points, start_pose.position); + // Note: return copy value (not const&) because the value is used in multi threads + PathWithLaneId getFullPath() const { return full_path; } - PathWithLaneId parking_path{}; - std::copy( - full_path.points.begin() + start_idx, full_path.points.end(), - std::back_inserter(parking_path.points)); - - return parking_path; - } + PathWithLaneId getParkingPath() const { return parking_path; } PathWithLaneId getCurrentPath() const { @@ -108,6 +96,82 @@ struct PullOverPath } bool isValidPath() const { return type != PullOverPlannerType::NONE; } + + std::vector getFullPathCurvatures() const { return full_path_curvatures; } + std::vector getParkingPathCurvatures() const { return parking_path_curvatures; } + double getFullPathMaxCurvature() const { return full_path_max_curvature; } + double getParkingPathMaxCurvature() const { return parking_path_max_curvature; } + +private: + void updatePathData() + { + updateFullPath(); + updateParkingPath(); + updateCurvatures(); + } + + void updateFullPath() + { + PathWithLaneId path{}; + for (size_t i = 0; i < partial_paths.size(); ++i) { + if (i == 0) { + path.points.insert( + path.points.end(), partial_paths.at(i).points.begin(), partial_paths.at(i).points.end()); + } else { + // skip overlapping point + path.points.insert( + path.points.end(), next(partial_paths.at(i).points.begin()), + partial_paths.at(i).points.end()); + } + } + full_path.points = autoware::motion_utils::removeOverlapPoints(path.points); + } + + void updateParkingPath() + { + if (full_path.points.empty()) { + updateFullPath(); + } + const size_t start_idx = + autoware::motion_utils::findNearestIndex(full_path.points, start_pose.position); + + PathWithLaneId path{}; + std::copy( + full_path.points.begin() + start_idx, full_path.points.end(), + std::back_inserter(path.points)); + parking_path = path; + } + + void updateCurvatures() + { + const auto calculateCurvaturesAndMax = + [](const auto & path) -> std::pair, double> { + std::vector curvatures = autoware::motion_utils::calcCurvature(path.points); + double max_curvature = 0.0; + if (!curvatures.empty()) { + max_curvature = std::abs(*std::max_element( + curvatures.begin(), curvatures.end(), + [](const double & a, const double & b) { return std::abs(a) < std::abs(b); })); + } + return std::make_pair(curvatures, max_curvature); + }; + std::tie(full_path_curvatures, full_path_max_curvature) = + calculateCurvaturesAndMax(getFullPath()); + std::tie(parking_path_curvatures, parking_path_max_curvature) = + calculateCurvaturesAndMax(getParkingPath()); + } + + // curvatures + std::vector full_path_curvatures{}; + std::vector parking_path_curvatures{}; + std::vector current_path_curvatures{}; + double parking_path_max_curvature{0.0}; + double full_path_max_curvature{0.0}; + double current_path_max_curvature{0.0}; + + // path + PathWithLaneId full_path{}; + PathWithLaneId parking_path{}; }; class PullOverPlannerBase diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp index 98a513d519b43..3c717a90c93ef 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp @@ -42,6 +42,7 @@ using geometry_msgs::msg::Twist; using tier4_planning_msgs::msg::PathWithLaneId; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; +using Shape = autoware_perception_msgs::msg::Shape; using Polygon2d = autoware::universe_utils::Polygon2d; lanelet::ConstLanelets getPullOverLanes( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp index ee35790ee2ab1..8ea33af375052 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -129,10 +129,8 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) } PullOverPath pull_over_path{}; - pull_over_path.partial_paths = partial_paths; pull_over_path.pairs_terminal_velocity_and_accel = pairs_terminal_velocity_and_accel; - pull_over_path.start_pose = current_pose; - pull_over_path.end_pose = goal_pose; + pull_over_path.setPaths(partial_paths, current_pose, goal_pose); pull_over_path.type = getPlannerType(); return pull_over_path; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp index 50cb090ca04d8..62c51408a000b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -72,10 +72,8 @@ std::optional GeometricPullOver::plan(const Pose & goal_pose) PullOverPath pull_over_path{}; pull_over_path.type = getPlannerType(); - pull_over_path.partial_paths = planner_.getPaths(); pull_over_path.pairs_terminal_velocity_and_accel = planner_.getPairsTerminalVelocityAndAccel(); - pull_over_path.start_pose = planner_.getStartPose(); - pull_over_path.end_pose = planner_.getArcEndPose(); + pull_over_path.setPaths(planner_.getPaths(), planner_.getStartPose(), planner_.getArcEndPose()); return pull_over_path; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 73e5cee725054..2f8372def8c55 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -306,12 +306,6 @@ void GoalPlannerModule::onTimer() // calculate absolute maximum curvature of parking path(start pose to end pose) for path // priority - const std::vector curvatures = - autoware::motion_utils::calcCurvature(pull_over_path->getParkingPath().points); - pull_over_path->max_curvature = std::abs(*std::max_element( - curvatures.begin(), curvatures.end(), - [](const double & a, const double & b) { return std::abs(a) < std::abs(b); })); - path_candidates.push_back(*pull_over_path); // calculate closest pull over start pose for stop path const double start_arc_length = @@ -456,6 +450,22 @@ void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + // extract static and dynamic objects in expanded pull over lanes + { + const auto & p = parameters_; + const auto & rh = *(planner_data_->route_handler); + const auto objects = *(planner_data_->dynamic_object); + const auto static_target_objects = + goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( + rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, + p->detection_bound_offset, objects, p->th_moving_object_velocity); + const auto dynamic_target_objects = goal_planner_utils::extractObjectsInExpandedPullOverLanes( + rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, + p->detection_bound_offset, objects); + thread_safe_data_.set_static_target_objects(static_target_objects); + thread_safe_data_.set_dynamic_target_objects(dynamic_target_objects); + } + // In PlannerManager::run(), it calls SceneModuleInterface::setData and // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). // Then module_ptr->run() invokes GoalPlannerModule::updateData and then @@ -764,16 +774,17 @@ bool GoalPlannerModule::canReturnToLaneParking() return false; } - if (!thread_safe_data_.get_lane_parking_pull_over_path()) { + const auto lane_parking_path = thread_safe_data_.get_lane_parking_pull_over_path(); + if (!lane_parking_path) { return false; } - const PathWithLaneId path = thread_safe_data_.get_lane_parking_pull_over_path()->getFullPath(); - + const PathWithLaneId path = lane_parking_path->getFullPath(); + const std::vector curvatures = lane_parking_path->getFullPathCurvatures(); if ( parameters_->use_object_recognition && checkObjectsCollision( - path, planner_data_, *parameters_, + path, curvatures, planner_data_, *parameters_, parameters_->object_recognition_collision_check_hard_margins.back(), /*extract_static_objects=*/false)) { return false; @@ -870,7 +881,8 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri << ", path_id: " << path.id << ", goal_id: " << path.goal_id << ", goal_priority: " << (is_safe_goal ? std::to_string(goal_priority) : "unsafe") << ", margin: " << path_id_to_margin_map.at(path.id) - << (isSoftMargin(path) ? " (soft)" : " (hard)") << ", curvature: " << path.max_curvature + << (isSoftMargin(path) ? " (soft)" : " (hard)") + << ", curvature: " << path.getParkingPathMaxCurvature() << (isHighCurvature(path) ? " (high)" : " (low)"); ss << "\n"; } @@ -926,11 +938,11 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri return 0.0; } // check path collision margin - const auto resampled_path = - utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); + const PathWithLaneId parking_path = pull_over_path.getParkingPath(); + const std::vector parking_path_curvatures = pull_over_path.getParkingPathCurvatures(); for (const auto & margin : margins) { if (!checkObjectsCollision( - resampled_path, planner_data_, *parameters_, margin, + parking_path, parking_path_curvatures, planner_data_, *parameters_, margin, /*extract_static_objects=*/true)) { return margin; } @@ -957,7 +969,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri // (3) Sort by curvature // If the curvature is less than the threshold, prioritize the path. const auto isHighCurvature = [&](const PullOverPath & path) -> bool { - return path.max_curvature >= parameters_->high_curvature_threshold; + return path.getParkingPathMaxCurvature() >= parameters_->high_curvature_threshold; }; const auto isSoftMargin = [&](const PullOverPath & path) -> bool { @@ -1065,11 +1077,14 @@ std::optional> GoalPlannerModule::selectP continue; } - const auto resampled_path = utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); + // const auto resampled_path = utils::resamplePathWithSpline(pull_over_path.getParkingPath(), + // 0.5); + const PathWithLaneId parking_path = pull_over_path.getParkingPath(); + const std::vector parking_path_curvatures = pull_over_path.getParkingPathCurvatures(); if ( parameters_->use_object_recognition && checkObjectsCollision( - resampled_path, planner_data_, *parameters_, collision_check_margin, + parking_path, parking_path_curvatures, planner_data_, *parameters_, collision_check_margin, /*extract_static_objects=*/true, /*update_debug_data=*/true)) { continue; @@ -1077,7 +1092,7 @@ std::optional> GoalPlannerModule::selectP if ( parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(resampled_path, occupancy_grid_map_)) { + checkOccupancyGridCollision(parking_path, occupancy_grid_map_)) { continue; } @@ -1307,11 +1322,13 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( } // check current parking path collision - const auto parking_path = utils::resamplePathWithSpline(pull_over_path->getParkingPath(), 0.5); + const auto parking_path = pull_over_path->getParkingPath(); + const std::vector parking_path_curvatures = pull_over_path->getParkingPathCurvatures(); const double margin = parameters.object_recognition_collision_check_hard_margins.back() * hysteresis_factor; if (checkObjectsCollision( - parking_path, planner_data, parameters, margin, /*extract_static_objects=*/false)) { + parking_path, parking_path_curvatures, planner_data, parameters, margin, + /*extract_static_objects=*/false)) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects"); @@ -1812,13 +1829,16 @@ bool GoalPlannerModule::isStuck( return false; } - if ( - parameters.use_object_recognition && - checkObjectsCollision( - thread_safe_data_.get_pull_over_path()->getCurrentPath(), planner_data, parameters, - /*extract_static_objects=*/false, - parameters.object_recognition_collision_check_hard_margins.back())) { - return true; + const auto pull_over_path = thread_safe_data_.get_pull_over_path(); + if (parameters.use_object_recognition) { + const auto path = pull_over_path->getCurrentPath(); + const auto curvatures = autoware::motion_utils::calcCurvature(path.points); + if (checkObjectsCollision( + path, curvatures, planner_data, parameters, + parameters.object_recognition_collision_check_hard_margins.back(), + /*extract_static_objects=*/false)) { + return true; + } } if ( @@ -1966,23 +1986,29 @@ bool GoalPlannerModule::checkOccupancyGridCollision( } bool GoalPlannerModule::checkObjectsCollision( - const PathWithLaneId & path, const std::shared_ptr planner_data, - const GoalPlannerParameters & parameters, const double collision_check_margin, - const bool extract_static_objects, const bool update_debug_data) const -{ - const auto target_objects = std::invoke([&]() { - const auto & p = parameters; - const auto & rh = *(planner_data->route_handler); - const auto objects = *(planner_data->dynamic_object); - if (extract_static_objects) { - return goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, - p.detection_bound_offset, objects, p.th_moving_object_velocity); - } - return goal_planner_utils::extractObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, - p.detection_bound_offset, objects); - }); + const PathWithLaneId & path, const std::vector & curvatures, + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const double collision_check_margin, const bool extract_static_objects, + const bool update_debug_data) const +{ + const auto target_objects = extract_static_objects + ? thread_safe_data_.get_static_target_objects() + : thread_safe_data_.get_dynamic_target_objects(); + if (target_objects.objects.empty()) { + return false; + } + + // check collision roughly with {min_distance, max_distance} between ego footprint and objects + // footprint + std::pair has_collision_rough = + utils::path_safety_checker::checkObjectsCollisionRough( + path, target_objects, collision_check_margin, planner_data_->parameters, false); + if (!has_collision_rough.first) { + return false; + } + if (has_collision_rough.second) { + return true; + } std::vector obj_polygons; for (const auto & object : target_objects.objects) { @@ -1994,18 +2020,22 @@ bool GoalPlannerModule::checkObjectsCollision( * - `extra_stopping_margin` adds stopping margin under deceleration constraints forward. * - `extra_lateral_margin` adds the lateral margin on curves. */ + if (path.points.size() != curvatures.size()) { + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, + "path.points.size() != curvatures.size() in checkObjectsCollision(). judge as non collision"); + return false; + } std::vector ego_polygons_expanded{}; - const auto curvatures = autoware::motion_utils::calcCurvature(path.points); for (size_t i = 0; i < path.points.size(); ++i) { const auto p = path.points.at(i); - const double extra_stopping_margin = std::min( std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters.maximum_deceleration, parameters.object_recognition_collision_check_max_extra_stopping_margin); // The square is meant to imply centrifugal force, but it is not a very well-founded formula. - // TODO(kosuke55): It is needed to consider better way because there is an inherently different - // conception of the inside and outside margins. + // TODO(kosuke55): It is needed to consider better way because there is an inherently + // different conception of the inside and outside margins. const double extra_lateral_margin = std::min( extra_stopping_margin, std::abs(curvatures.at(i) * std::pow(p.point.longitudinal_velocity_mps, 2))); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp index 0690f97900cab..ba1ebfade0127 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -246,10 +246,11 @@ std::optional ShiftPullOver::generatePullOverPath( // set pull over path PullOverPath pull_over_path{}; pull_over_path.type = getPlannerType(); - pull_over_path.partial_paths.push_back(shifted_path.path); + std::vector partial_paths{shifted_path.path}; + pull_over_path.setPaths( + partial_paths, path_shifter.getShiftLines().front().start, + path_shifter.getShiftLines().front().end); pull_over_path.pairs_terminal_velocity_and_accel.push_back(std::make_pair(pull_over_velocity, 0)); - pull_over_path.start_pose = path_shifter.getShiftLines().front().start; - pull_over_path.end_pose = path_shifter.getShiftLines().front().end; pull_over_path.debug_poses.push_back(shift_end_pose_prev_module_path); pull_over_path.debug_poses.push_back(actual_shift_end_pose); pull_over_path.debug_poses.push_back(goal_pose); From 913d199ce487437802ba1714dcddf3903d1f063b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 8 Aug 2024 21:37:26 +0900 Subject: [PATCH 056/151] fix(static_obstacle_avoidance): remove invalid small shift lines (#8344) (#1451) Signed-off-by: satoshi-ota --- .../src/shift_line_generator.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 5e58466fa4229..57a6e340bf853 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -827,6 +827,8 @@ AvoidLineArray ShiftLineGenerator::applyFillGapProcess( utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal( data, debug.step1_front_shift_line); + applySmallShiftFilter(ret, 1e-3); + return ret; } From 1a60db7a61b2cde7dc9f45054f957f5a09c39115 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 9 Aug 2024 01:29:28 +0900 Subject: [PATCH 057/151] fix(autoware_mpc_lateral_controller): add timestamp and frame ID to published trajectory (#8164) (#1452) add timestamp and frame ID to published trajectory Signed-off-by: kyoichi-sugahara Co-authored-by: Kyoichi Sugahara --- control/autoware_mpc_lateral_controller/src/mpc.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 79748f23e7aa0..c42072a186f4d 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -804,8 +804,10 @@ Trajectory MPC::calculatePredictedTrajectory( const auto frenet = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate( mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory, dt); - const auto frenet_clipped = MPCUtils::convertToAutowareTrajectory( + auto frenet_clipped = MPCUtils::convertToAutowareTrajectory( MPCUtils::clipTrajectoryByLength(frenet, predicted_length)); + frenet_clipped.header.stamp = m_clock->now(); + frenet_clipped.header.frame_id = "map"; m_debug_frenet_predicted_trajectory_pub->publish(frenet_clipped); } From fd6d09802b8e328460889af3cd9ad1c392724d23 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 23 Jul 2024 19:16:33 +0900 Subject: [PATCH 058/151] fix(velocity_smoother, obstacle_cruise_planner ): float type of processing time was wrong (#8161) fix(velocity_smoother): float type of processing time was wrong Signed-off-by: Takayuki Murooka --- .../include/autoware/obstacle_cruise_planner/node.hpp | 2 +- .../include/autoware/obstacle_cruise_planner/type_alias.hpp | 2 ++ planning/autoware_obstacle_cruise_planner/src/node.cpp | 4 ++-- .../include/autoware/velocity_smoother/node.hpp | 4 +++- planning/autoware_velocity_smoother/src/node.cpp | 4 ++-- 5 files changed, 10 insertions(+), 6 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp index dd9a6c3880672..b5728fd3bd3d9 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp @@ -141,7 +141,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_stop_planning_info_pub_; rclcpp::Publisher::SharedPtr debug_cruise_planning_info_pub_; rclcpp::Publisher::SharedPtr debug_slow_down_planning_info_pub_; - rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; + rclcpp::Publisher::SharedPtr debug_calculation_time_pub_; // subscriber rclcpp::Subscription::SharedPtr traj_sub_; diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index 5721efd051f63..9eeb97d74ef04 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -28,6 +28,7 @@ #include "geometry_msgs/msg/twist_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" +#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_planning_msgs/msg/stop_factor.hpp" #include "tier4_planning_msgs/msg/stop_reason_array.hpp" #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" @@ -51,6 +52,7 @@ using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Twist; using nav_msgs::msg::Odometry; using tier4_debug_msgs::msg::Float32Stamped; +using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::StopFactor; using tier4_planning_msgs::msg::StopReason; using tier4_planning_msgs::msg::StopReasonArray; diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index 9682ac63104c8..df46fd086c9c3 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -374,7 +374,7 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & "~/output/clear_velocity_limit", rclcpp::QoS{1}.transient_local()); // debug publisher - debug_calculation_time_pub_ = create_publisher("~/debug/processing_time_ms", 1); + debug_calculation_time_pub_ = create_publisher("~/debug/processing_time_ms", 1); debug_cruise_wall_marker_pub_ = create_publisher("~/debug/cruise/virtual_wall", 1); debug_stop_wall_marker_pub_ = create_publisher("~/virtual_wall", 1); debug_slow_down_wall_marker_pub_ = @@ -1645,7 +1645,7 @@ void ObstacleCruisePlannerNode::publishDebugInfo() const void ObstacleCruisePlannerNode::publishCalculationTime(const double calculation_time) const { - Float32Stamped calculation_time_msg; + Float64Stamped calculation_time_msg; calculation_time_msg.stamp = now(); calculation_time_msg.data = calculation_time; debug_calculation_time_pub_->publish(calculation_time_msg); diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index bcc9338422c9f..655632f14d207 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -45,6 +45,7 @@ #include "nav_msgs/msg/odometry.hpp" #include "std_srvs/srv/set_bool.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary +#include "tier4_debug_msgs/msg/float64_stamped.hpp" // temporary #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary #include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary #include "visualization_msgs/msg/marker_array.hpp" @@ -68,6 +69,7 @@ using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; using std_srvs::srv::SetBool; using tier4_debug_msgs::msg::Float32Stamped; // temporary +using tier4_debug_msgs::msg::Float64Stamped; // temporary using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary using tier4_planning_msgs::msg::VelocityLimit; // temporary using visualization_msgs::msg::MarkerArray; @@ -291,7 +293,7 @@ class VelocitySmootherNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_closest_velocity_; rclcpp::Publisher::SharedPtr debug_closest_acc_; rclcpp::Publisher::SharedPtr debug_closest_jerk_; - rclcpp::Publisher::SharedPtr debug_calculation_time_; + rclcpp::Publisher::SharedPtr debug_calculation_time_; rclcpp::Publisher::SharedPtr debug_closest_max_velocity_; rclcpp::Publisher::SharedPtr debug_processing_time_detail_; diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index ca0fdc9ca7117..23dee0019bf94 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -84,7 +84,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti debug_closest_acc_ = create_publisher("~/closest_acceleration", 1); debug_closest_jerk_ = create_publisher("~/closest_jerk", 1); debug_closest_max_velocity_ = create_publisher("~/closest_max_velocity", 1); - debug_calculation_time_ = create_publisher("~/debug/processing_time_ms", 1); + debug_calculation_time_ = create_publisher("~/debug/processing_time_ms", 1); pub_trajectory_raw_ = create_publisher("~/debug/trajectory_raw", 1); pub_trajectory_vel_lim_ = create_publisher("~/debug/trajectory_external_velocity_limited", 1); @@ -1138,7 +1138,7 @@ void VelocitySmootherNode::flipVelocity(TrajectoryPoints & points) const void VelocitySmootherNode::publishStopWatchTime() { - Float32Stamped calculation_time_data{}; + Float64Stamped calculation_time_data{}; calculation_time_data.stamp = this->now(); calculation_time_data.data = stop_watch_.toc(); debug_calculation_time_->publish(calculation_time_data); From a196826671b48149297d0633d62736d865d5da21 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 13 Jul 2024 14:56:46 +0900 Subject: [PATCH 059/151] refactor(qp_interface): clean up the code (#8029) * refactor qp_interface Signed-off-by: Takayuki Murooka * variable names: m_XXX -> XXX_ Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../qp_interface/osqp_csc_matrix_conv.hpp | 10 +- .../include/qp_interface/osqp_interface.hpp | 42 ++-- .../include/qp_interface/proxqp_interface.hpp | 18 +- .../include/qp_interface/qp_interface.hpp | 18 +- .../qp_interface/src/osqp_csc_matrix_conv.cpp | 10 +- common/qp_interface/src/osqp_interface.cpp | 236 +++++++++--------- common/qp_interface/src/proxqp_interface.cpp | 84 +++++-- common/qp_interface/src/qp_interface.cpp | 8 +- .../test/test_csc_matrix_conv.cpp | 210 ++++++++-------- .../qp_interface/test/test_osqp_interface.cpp | 64 ++--- .../test/test_proxqp_interface.cpp | 21 +- 11 files changed, 377 insertions(+), 344 deletions(-) diff --git a/common/qp_interface/include/qp_interface/osqp_csc_matrix_conv.hpp b/common/qp_interface/include/qp_interface/osqp_csc_matrix_conv.hpp index 74ec4c1282f46..8ec7280cfc100 100644 --- a/common/qp_interface/include/qp_interface/osqp_csc_matrix_conv.hpp +++ b/common/qp_interface/include/qp_interface/osqp_csc_matrix_conv.hpp @@ -21,17 +21,17 @@ #include -namespace qp +namespace autoware::common { /// \brief Compressed-Column-Sparse Matrix struct CSC_Matrix { /// Vector of non-zero values. Ex: [4,1,1,2] - std::vector m_vals; + std::vector vals_; /// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner') - std::vector m_row_idxs; + std::vector row_idxs_; /// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer') - std::vector m_col_idxs; + std::vector col_idxs_; }; /// \brief Calculate CSC matrix from Eigen matrix @@ -41,6 +41,6 @@ CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat); /// \brief Print the given CSC matrix to the standard output void printCSCMatrix(const CSC_Matrix & csc_mat); -} // namespace qp +} // namespace autoware::common #endif // QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ diff --git a/common/qp_interface/include/qp_interface/osqp_interface.hpp b/common/qp_interface/include/qp_interface/osqp_interface.hpp index ef2c3bd17c89e..14c03a91d8fa1 100644 --- a/common/qp_interface/include/qp_interface/osqp_interface.hpp +++ b/common/qp_interface/include/qp_interface/osqp_interface.hpp @@ -24,9 +24,9 @@ #include #include -namespace qp +namespace autoware::common { -constexpr c_float INF = 1e30; +constexpr c_float OSQP_INF = 1e30; class OSQPInterface : public QPInterface { @@ -34,7 +34,9 @@ class OSQPInterface : public QPInterface /// \brief Constructor without problem formulation OSQPInterface( const bool enable_warm_start = false, - const c_float eps_abs = std::numeric_limits::epsilon(), const bool polish = true); + const c_float eps_abs = std::numeric_limits::epsilon(), + const c_float eps_rel = std::numeric_limits::epsilon(), const bool polish = true, + const bool verbose = false); /// \brief Constructor with problem setup /// \param P: (n,n) matrix defining relations between parameters. /// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound. @@ -60,8 +62,10 @@ class OSQPInterface : public QPInterface CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, const std::vector & u); - int getIteration() const override; - int getStatus() const override; + int getIterationNumber() const override; + bool isSolved() const override; + std::string getStatus() const override; + int getPolishStatus() const; std::vector getDualSolution() const; @@ -96,20 +100,18 @@ class OSQPInterface : public QPInterface void updateCheckTermination(const int check_termination); /// \brief Get the number of iteration taken to solve the problem - inline int64_t getTakenIter() const { return static_cast(m_latest_work_info.iter); } + inline int64_t getTakenIter() const { return static_cast(latest_work_info_.iter); } /// \brief Get the status message for the latest problem solved inline std::string getStatusMessage() const { - return static_cast(m_latest_work_info.status); + return static_cast(latest_work_info_.status); } /// \brief Get the runtime of the latest problem solved - inline double getRunTime() const { return m_latest_work_info.run_time; } + inline double getRunTime() const { return latest_work_info_.run_time; } /// \brief Get the objective value the latest problem solved - inline double getObjVal() const { return m_latest_work_info.obj_val; } + inline double getObjVal() const { return latest_work_info_.obj_val; } /// \brief Returns flag asserting interface condition (Healthy condition: 0). - inline int64_t getExitFlag() const { return m_exitflag; } - - void logUnsolvedStatus(const std::string & prefix_message = "") const; + inline int64_t getExitFlag() const { return exitflag_; } // Setter functions for warm start bool setWarmStart( @@ -118,17 +120,17 @@ class OSQPInterface : public QPInterface bool setDualVariables(const std::vector & dual_variables); private: - std::unique_ptr> m_work; - std::unique_ptr m_settings; - std::unique_ptr m_data; + std::unique_ptr> work_; + std::unique_ptr settings_; + std::unique_ptr data_; // store last work info since work is cleaned up at every execution to prevent memory leak. - OSQPInfo m_latest_work_info; + OSQPInfo latest_work_info_; // Number of parameters to optimize - int64_t m_param_n; + int64_t param_n_; // Flag to check if the current work exists - bool m_work_initialized = false; + bool work__initialized = false; // Exitflag - int64_t m_exitflag; + int64_t exitflag_; void initializeProblemImpl( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, @@ -140,6 +142,6 @@ class OSQPInterface : public QPInterface std::vector optimizeImpl() override; }; -} // namespace qp +} // namespace autoware::common #endif // QP_INTERFACE__OSQP_INTERFACE_HPP_ diff --git a/common/qp_interface/include/qp_interface/proxqp_interface.hpp b/common/qp_interface/include/qp_interface/proxqp_interface.hpp index a940262d5f6da..f75fb3da5954c 100644 --- a/common/qp_interface/include/qp_interface/proxqp_interface.hpp +++ b/common/qp_interface/include/qp_interface/proxqp_interface.hpp @@ -22,27 +22,29 @@ #include #include +#include #include -namespace qp +namespace autoware::common { class ProxQPInterface : public QPInterface { public: explicit ProxQPInterface( - const bool enable_warm_start = false, - const double eps_abs = std::numeric_limits::epsilon()); + const bool enable_warm_start, const double eps_abs, const double eps_rel, + const bool verbose = false); - int getIteration() const override; - int getStatus() const override; + int getIterationNumber() const override; + bool isSolved() const override; + std::string getStatus() const override; void updateEpsAbs(const double eps_abs) override; void updateEpsRel(const double eps_rel) override; void updateVerbose(const bool verbose) override; private: - proxsuite::proxqp::Settings m_settings; - std::shared_ptr> m_qp_ptr; + proxsuite::proxqp::Settings settings_{}; + std::shared_ptr> qp_ptr_{nullptr}; void initializeProblemImpl( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, @@ -50,6 +52,6 @@ class ProxQPInterface : public QPInterface std::vector optimizeImpl() override; }; -} // namespace qp +} // namespace autoware::common #endif // QP_INTERFACE__PROXQP_INTERFACE_HPP_ diff --git a/common/qp_interface/include/qp_interface/qp_interface.hpp b/common/qp_interface/include/qp_interface/qp_interface.hpp index 026c0fe413b71..85e2d103cde7a 100644 --- a/common/qp_interface/include/qp_interface/qp_interface.hpp +++ b/common/qp_interface/include/qp_interface/qp_interface.hpp @@ -18,28 +18,30 @@ #include #include +#include #include -namespace qp +namespace autoware::common { class QPInterface { public: - explicit QPInterface(const bool enable_warm_start) : m_enable_warm_start(enable_warm_start) {} + explicit QPInterface(const bool enable_warm_start) : enable_warm_start_(enable_warm_start) {} std::vector optimize( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u); - virtual int getIteration() const = 0; - virtual int getStatus() const = 0; + virtual bool isSolved() const = 0; + virtual int getIterationNumber() const = 0; + virtual std::string getStatus() const = 0; virtual void updateEpsAbs([[maybe_unused]] const double eps_abs) = 0; virtual void updateEpsRel([[maybe_unused]] const double eps_rel) = 0; virtual void updateVerbose([[maybe_unused]] const bool verbose) {} protected: - bool m_enable_warm_start; + bool enable_warm_start_{false}; void initializeProblem( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, @@ -51,9 +53,9 @@ class QPInterface virtual std::vector optimizeImpl() = 0; - std::optional m_variables_num; - std::optional m_constraints_num; + std::optional variables_num_{std::nullopt}; + std::optional constraints_num_{std::nullopt}; }; -} // namespace qp +} // namespace autoware::common #endif // QP_INTERFACE__QP_INTERFACE_HPP_ diff --git a/common/qp_interface/src/osqp_csc_matrix_conv.cpp b/common/qp_interface/src/osqp_csc_matrix_conv.cpp index 0faf7586463fd..77a481f442000 100644 --- a/common/qp_interface/src/osqp_csc_matrix_conv.cpp +++ b/common/qp_interface/src/osqp_csc_matrix_conv.cpp @@ -21,7 +21,7 @@ #include #include -namespace qp +namespace autoware::common { CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat) { @@ -114,21 +114,21 @@ CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat) void printCSCMatrix(const CSC_Matrix & csc_mat) { std::cout << "["; - for (const c_float & val : csc_mat.m_vals) { + for (const c_float & val : csc_mat.vals_) { std::cout << val << ", "; } std::cout << "]\n"; std::cout << "["; - for (const c_int & row : csc_mat.m_row_idxs) { + for (const c_int & row : csc_mat.row_idxs_) { std::cout << row << ", "; } std::cout << "]\n"; std::cout << "["; - for (const c_int & col : csc_mat.m_col_idxs) { + for (const c_int & col : csc_mat.col_idxs_) { std::cout << col << ", "; } std::cout << "]\n"; } -} // namespace qp +} // namespace autoware::common diff --git a/common/qp_interface/src/osqp_interface.cpp b/common/qp_interface/src/osqp_interface.cpp index 81d2ffeeaaed5..0e8cb7e13988a 100644 --- a/common/qp_interface/src/osqp_interface.cpp +++ b/common/qp_interface/src/osqp_interface.cpp @@ -18,27 +18,29 @@ #include -namespace qp -{ -OSQPInterface::OSQPInterface(const bool enable_warm_start, const c_float eps_abs, const bool polish) -: QPInterface(enable_warm_start), m_work{nullptr, OSQPWorkspaceDeleter} -{ - m_settings = std::make_unique(); - m_data = std::make_unique(); - - if (m_settings) { - osqp_set_default_settings(m_settings.get()); - m_settings->alpha = 1.6; // Change alpha parameter - m_settings->eps_rel = 1.0E-4; - m_settings->eps_abs = eps_abs; - m_settings->eps_prim_inf = 1.0E-4; - m_settings->eps_dual_inf = 1.0E-4; - m_settings->warm_start = true; - m_settings->max_iter = 4000; - m_settings->verbose = false; - m_settings->polish = polish; +namespace autoware::common +{ +OSQPInterface::OSQPInterface( + const bool enable_warm_start, const c_float eps_abs, const c_float eps_rel, const bool polish, + const bool verbose) +: QPInterface(enable_warm_start), work_{nullptr, OSQPWorkspaceDeleter} +{ + settings_ = std::make_unique(); + data_ = std::make_unique(); + + if (settings_) { + osqp_set_default_settings(settings_.get()); + settings_->alpha = 1.6; // Change alpha parameter + settings_->eps_rel = eps_rel; + settings_->eps_abs = eps_abs; + settings_->eps_prim_inf = 1.0E-4; + settings_->eps_dual_inf = 1.0E-4; + settings_->warm_start = true; + settings_->max_iter = 4000; + settings_->verbose = verbose; + settings_->polish = polish; } - m_exitflag = 0; + exitflag_ = 0; } OSQPInterface::OSQPInterface( @@ -61,8 +63,8 @@ OSQPInterface::OSQPInterface( OSQPInterface::~OSQPInterface() { - if (m_data->P) free(m_data->P); - if (m_data->A) free(m_data->A); + if (data_->P) free(data_->P); + if (data_->A) free(data_->A); } void OSQPInterface::initializeProblemImpl( @@ -89,30 +91,30 @@ void OSQPInterface::initializeCSCProblemImpl( /********************** * OBJECTIVE FUNCTION **********************/ - m_param_n = static_cast(q.size()); - m_data->m = static_cast(l.size()); + param_n_ = static_cast(q.size()); + data_->m = static_cast(l.size()); /***************** * POPULATE DATA *****************/ - m_data->n = m_param_n; - if (m_data->P) free(m_data->P); - m_data->P = csc_matrix( - m_data->n, m_data->n, static_cast(P_csc.m_vals.size()), P_csc.m_vals.data(), - P_csc.m_row_idxs.data(), P_csc.m_col_idxs.data()); - m_data->q = q_dyn; - if (m_data->A) free(m_data->A); - m_data->A = csc_matrix( - m_data->m, m_data->n, static_cast(A_csc.m_vals.size()), A_csc.m_vals.data(), - A_csc.m_row_idxs.data(), A_csc.m_col_idxs.data()); - m_data->l = l_dyn; - m_data->u = u_dyn; + data_->n = param_n_; + if (data_->P) free(data_->P); + data_->P = csc_matrix( + data_->n, data_->n, static_cast(P_csc.vals_.size()), P_csc.vals_.data(), + P_csc.row_idxs_.data(), P_csc.col_idxs_.data()); + data_->q = q_dyn; + if (data_->A) free(data_->A); + data_->A = csc_matrix( + data_->m, data_->n, static_cast(A_csc.vals_.size()), A_csc.vals_.data(), + A_csc.row_idxs_.data(), A_csc.col_idxs_.data()); + data_->l = l_dyn; + data_->u = u_dyn; // Setup workspace OSQPWorkspace * workspace; - m_exitflag = osqp_setup(&workspace, m_data.get(), m_settings.get()); - m_work.reset(workspace); - m_work_initialized = true; + exitflag_ = osqp_setup(&workspace, data_.get(), settings_.get()); + work_.reset(workspace); + work__initialized = true; } void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept @@ -124,67 +126,67 @@ void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept void OSQPInterface::updateEpsAbs(const double eps_abs) { - m_settings->eps_abs = eps_abs; // for default setting - if (m_work_initialized) { - osqp_update_eps_abs(m_work.get(), eps_abs); // for current work + settings_->eps_abs = eps_abs; // for default setting + if (work__initialized) { + osqp_update_eps_abs(work_.get(), eps_abs); // for current work } } void OSQPInterface::updateEpsRel(const double eps_rel) { - m_settings->eps_rel = eps_rel; // for default setting - if (m_work_initialized) { - osqp_update_eps_rel(m_work.get(), eps_rel); // for current work + settings_->eps_rel = eps_rel; // for default setting + if (work__initialized) { + osqp_update_eps_rel(work_.get(), eps_rel); // for current work } } void OSQPInterface::updateMaxIter(const int max_iter) { - m_settings->max_iter = max_iter; // for default setting - if (m_work_initialized) { - osqp_update_max_iter(m_work.get(), max_iter); // for current work + settings_->max_iter = max_iter; // for default setting + if (work__initialized) { + osqp_update_max_iter(work_.get(), max_iter); // for current work } } void OSQPInterface::updateVerbose(const bool is_verbose) { - m_settings->verbose = is_verbose; // for default setting - if (m_work_initialized) { - osqp_update_verbose(m_work.get(), is_verbose); // for current work + settings_->verbose = is_verbose; // for default setting + if (work__initialized) { + osqp_update_verbose(work_.get(), is_verbose); // for current work } } void OSQPInterface::updateRhoInterval(const int rho_interval) { - m_settings->adaptive_rho_interval = rho_interval; // for default setting + settings_->adaptive_rho_interval = rho_interval; // for default setting } void OSQPInterface::updateRho(const double rho) { - m_settings->rho = rho; - if (m_work_initialized) { - osqp_update_rho(m_work.get(), rho); + settings_->rho = rho; + if (work__initialized) { + osqp_update_rho(work_.get(), rho); } } void OSQPInterface::updateAlpha(const double alpha) { - m_settings->alpha = alpha; - if (m_work_initialized) { - osqp_update_alpha(m_work.get(), alpha); + settings_->alpha = alpha; + if (work__initialized) { + osqp_update_alpha(work_.get(), alpha); } } void OSQPInterface::updateScaling(const int scaling) { - m_settings->scaling = scaling; + settings_->scaling = scaling; } void OSQPInterface::updatePolish(const bool polish) { - m_settings->polish = polish; - if (m_work_initialized) { - osqp_update_polish(m_work.get(), polish); + settings_->polish = polish; + if (work__initialized) { + osqp_update_polish(work_.get(), polish); } } @@ -195,9 +197,9 @@ void OSQPInterface::updatePolishRefinementIteration(const int polish_refine_iter return; } - m_settings->polish_refine_iter = polish_refine_iter; - if (m_work_initialized) { - osqp_update_polish_refine_iter(m_work.get(), polish_refine_iter); + settings_->polish_refine_iter = polish_refine_iter; + if (work__initialized) { + osqp_update_polish_refine_iter(work_.get(), polish_refine_iter); } } @@ -208,9 +210,9 @@ void OSQPInterface::updateCheckTermination(const int check_termination) return; } - m_settings->check_termination = check_termination; - if (m_work_initialized) { - osqp_update_check_termination(m_work.get(), check_termination); + settings_->check_termination = check_termination; + if (work__initialized) { + osqp_update_check_termination(work_.get(), check_termination); } } @@ -222,11 +224,11 @@ bool OSQPInterface::setWarmStart( bool OSQPInterface::setPrimalVariables(const std::vector & primal_variables) { - if (!m_work_initialized) { + if (!work__initialized) { return false; } - const auto result = osqp_warm_start_x(m_work.get(), primal_variables.data()); + const auto result = osqp_warm_start_x(work_.get(), primal_variables.data()); if (result != 0) { std::cerr << "Failed to set primal variables for warm start" << std::endl; return false; @@ -237,11 +239,11 @@ bool OSQPInterface::setPrimalVariables(const std::vector & primal_variab bool OSQPInterface::setDualVariables(const std::vector & dual_variables) { - if (!m_work_initialized) { + if (!work__initialized) { return false; } - const auto result = osqp_warm_start_y(m_work.get(), dual_variables.data()); + const auto result = osqp_warm_start_y(work_.get(), dual_variables.data()); if (result != 0) { std::cerr << "Failed to set dual variables for warm start" << std::endl; return false; @@ -250,27 +252,6 @@ bool OSQPInterface::setDualVariables(const std::vector & dual_variables) return true; } -void OSQPInterface::logUnsolvedStatus(const std::string & prefix_message) const -{ - const int status = getStatus(); - if (status == 1) { - // No need to log since optimization was solved. - return; - } - - // create message - std::string output_message = ""; - if (prefix_message != "") { - output_message = prefix_message + " "; - } - - const auto status_message = getStatusMessage(); - output_message += "Optimization failed due to " + status_message; - - // log with warning - RCLCPP_WARN(rclcpp::get_logger("osqp_interface"), output_message.c_str()); -} - void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) { /* @@ -283,14 +264,12 @@ void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) c_int P_elem_N = P_sparse.nonZeros(); */ CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P_new); - osqp_update_P( - m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); + osqp_update_P(work_.get(), P_csc.vals_.data(), OSQP_NULL, static_cast(P_csc.vals_.size())); } void OSQPInterface::updateCscP(const CSC_Matrix & P_csc) { - osqp_update_P( - m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); + osqp_update_P(work_.get(), P_csc.vals_.data(), OSQP_NULL, static_cast(P_csc.vals_.size())); } void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) @@ -303,36 +282,34 @@ void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) c_int A_elem_N = A_sparse.nonZeros(); */ CSC_Matrix A_csc = calCSCMatrix(A_new); - osqp_update_A( - m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); + osqp_update_A(work_.get(), A_csc.vals_.data(), OSQP_NULL, static_cast(A_csc.vals_.size())); return; } void OSQPInterface::updateCscA(const CSC_Matrix & A_csc) { - osqp_update_A( - m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); + osqp_update_A(work_.get(), A_csc.vals_.data(), OSQP_NULL, static_cast(A_csc.vals_.size())); } void OSQPInterface::updateQ(const std::vector & q_new) { std::vector q_tmp(q_new.begin(), q_new.end()); double * q_dyn = q_tmp.data(); - osqp_update_lin_cost(m_work.get(), q_dyn); + osqp_update_lin_cost(work_.get(), q_dyn); } void OSQPInterface::updateL(const std::vector & l_new) { std::vector l_tmp(l_new.begin(), l_new.end()); double * l_dyn = l_tmp.data(); - osqp_update_lower_bound(m_work.get(), l_dyn); + osqp_update_lower_bound(work_.get(), l_dyn); } void OSQPInterface::updateU(const std::vector & u_new) { std::vector u_tmp(u_new.begin(), u_new.end()); double * u_dyn = u_tmp.data(); - osqp_update_upper_bound(m_work.get(), u_dyn); + osqp_update_upper_bound(work_.get(), u_dyn); } void OSQPInterface::updateBounds( @@ -342,45 +319,50 @@ void OSQPInterface::updateBounds( std::vector u_tmp(u_new.begin(), u_new.end()); double * l_dyn = l_tmp.data(); double * u_dyn = u_tmp.data(); - osqp_update_bounds(m_work.get(), l_dyn, u_dyn); + osqp_update_bounds(work_.get(), l_dyn, u_dyn); +} + +int OSQPInterface::getIterationNumber() const +{ + return work_->info->iter; } -int OSQPInterface::getIteration() const +std::string OSQPInterface::getStatus() const { - return m_work->info->iter; + return "OSQP_SOLVED"; } -int OSQPInterface::getStatus() const +bool OSQPInterface::isSolved() const { - return static_cast(m_latest_work_info.status_val); + return latest_work_info_.status_val == 1; } int OSQPInterface::getPolishStatus() const { - return static_cast(m_latest_work_info.status_polish); + return static_cast(latest_work_info_.status_polish); } std::vector OSQPInterface::getDualSolution() const { - double * sol_y = m_work->solution->y; - std::vector dual_solution(sol_y, sol_y + m_data->m); + double * sol_y = work_->solution->y; + std::vector dual_solution(sol_y, sol_y + data_->m); return dual_solution; } std::vector OSQPInterface::optimizeImpl() { - osqp_solve(m_work.get()); + osqp_solve(work_.get()); - double * sol_x = m_work->solution->x; - double * sol_y = m_work->solution->y; - std::vector sol_primal(sol_x, sol_x + m_param_n); - std::vector sol_lagrange_multiplier(sol_y, sol_y + m_data->m); + double * sol_x = work_->solution->x; + double * sol_y = work_->solution->y; + std::vector sol_primal(sol_x, sol_x + param_n_); + std::vector sol_lagrange_multiplier(sol_y, sol_y + data_->m); - m_latest_work_info = *(m_work->info); + latest_work_info_ = *(work_->info); - if (!m_enable_warm_start) { - m_work.reset(); - m_work_initialized = false; + if (!enable_warm_start_) { + work_.reset(); + work__initialized = false; } return sol_primal; @@ -393,7 +375,17 @@ std::vector OSQPInterface::optimize( initializeCSCProblemImpl(P, A, q, l, u); const auto result = optimizeImpl(); + // show polish status if not successful + const int status_polish = static_cast(latest_work_info_.status_polish); + if (status_polish != 1) { + const auto msg = status_polish == 0 ? "unperformed" + : status_polish == -1 ? "unsuccessful" + : "unknown"; + std::cerr << "osqp polish process failed : " << msg << ". The result may be inaccurate" + << std::endl; + } + return result; } -} // namespace qp +} // namespace autoware::common diff --git a/common/qp_interface/src/proxqp_interface.cpp b/common/qp_interface/src/proxqp_interface.cpp index bf1f0229e1e21..507f3858cbf1b 100644 --- a/common/qp_interface/src/proxqp_interface.cpp +++ b/common/qp_interface/src/proxqp_interface.cpp @@ -14,12 +14,17 @@ #include "qp_interface/proxqp_interface.hpp" -namespace qp +namespace autoware::common { -ProxQPInterface::ProxQPInterface(const bool enable_warm_start, const double eps_abs) +using proxsuite::proxqp::QPSolverOutput; + +ProxQPInterface::ProxQPInterface( + const bool enable_warm_start, const double eps_abs, const double eps_rel, const bool verbose) : QPInterface(enable_warm_start) { - m_settings.eps_abs = eps_abs; + settings_.eps_abs = eps_abs; + settings_.eps_rel = eps_rel; + settings_.verbose = verbose; } void ProxQPInterface::initializeProblemImpl( @@ -31,28 +36,28 @@ void ProxQPInterface::initializeProblemImpl( const bool enable_warm_start = [&]() { if ( - !m_enable_warm_start // Warm start is designated - || !m_qp_ptr // QP pointer is initialized + !enable_warm_start_ // Warm start is designated + || !qp_ptr_ // QP pointer is initialized // The number of variables is the same as the previous one. - || !m_variables_num || - *m_variables_num != variables_num + || !variables_num_ || + *variables_num_ != variables_num // The number of constraints is the same as the previous one - || !m_constraints_num || *m_constraints_num != constraints_num) { + || !constraints_num_ || *constraints_num_ != constraints_num) { return false; } return true; }(); if (!enable_warm_start) { - m_qp_ptr = std::make_shared>( + qp_ptr_ = std::make_shared>( variables_num, 0, constraints_num); } - m_settings.initial_guess = + settings_.initial_guess = enable_warm_start ? proxsuite::proxqp::InitialGuessStatus::WARM_START_WITH_PREVIOUS_RESULT : proxsuite::proxqp::InitialGuessStatus::NO_INITIAL_GUESS; - m_qp_ptr->settings = m_settings; + qp_ptr_->settings = settings_; Eigen::SparseMatrix P_sparse(variables_num, constraints_num); P_sparse = P.sparseView(); @@ -69,53 +74,78 @@ void ProxQPInterface::initializeProblemImpl( Eigen::Map(u_std_vec.data(), u_std_vec.size()); if (enable_warm_start) { - m_qp_ptr->update( + qp_ptr_->update( P_sparse, eigen_q, proxsuite::nullopt, proxsuite::nullopt, A.sparseView(), eigen_l, eigen_u); } else { - m_qp_ptr->init( + qp_ptr_->init( P_sparse, eigen_q, proxsuite::nullopt, proxsuite::nullopt, A.sparseView(), eigen_l, eigen_u); } } void ProxQPInterface::updateEpsAbs(const double eps_abs) { - m_settings.eps_abs = eps_abs; + settings_.eps_abs = eps_abs; } void ProxQPInterface::updateEpsRel(const double eps_rel) { - m_settings.eps_rel = eps_rel; + settings_.eps_rel = eps_rel; } void ProxQPInterface::updateVerbose(const bool is_verbose) { - m_settings.verbose = is_verbose; + settings_.verbose = is_verbose; } -int ProxQPInterface::getIteration() const +bool ProxQPInterface::isSolved() const { - if (m_qp_ptr) { - return m_qp_ptr->results.info.iter; + if (qp_ptr_) { + return qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED; } - return 0; + return false; } -int ProxQPInterface::getStatus() const +int ProxQPInterface::getIterationNumber() const { - if (m_qp_ptr) { - return static_cast(m_qp_ptr->results.info.status); + if (qp_ptr_) { + return qp_ptr_->results.info.iter; } return 0; } +std::string ProxQPInterface::getStatus() const +{ + if (qp_ptr_) { + if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED) { + return "PROXQP_SOLVED"; + } + if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_MAX_ITER_REACHED) { + return "PROXQP_MAX_ITER_REACHED"; + } + if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_PRIMAL_INFEASIBLE) { + return "PROXQP_PRIMAL_INFEASIBLE"; + } + // if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED_CLOSEST_PRIMAL_FEASIBLE) { + // return "PROXQP_SOLVED_CLOSEST_PRIMAL_FEASIBLE"; + // } + if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_DUAL_INFEASIBLE) { + return "PROXQP_DUAL_INFEASIBLE"; + } + if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_NOT_RUN) { + return "PROXQP_NOT_RUN"; + } + } + return "None"; +} + std::vector ProxQPInterface::optimizeImpl() { - m_qp_ptr->solve(); + qp_ptr_->solve(); std::vector result; - for (Eigen::Index i = 0; i < m_qp_ptr->results.x.size(); ++i) { - result.push_back(m_qp_ptr->results.x[i]); + for (Eigen::Index i = 0; i < qp_ptr_->results.x.size(); ++i) { + result.push_back(qp_ptr_->results.x[i]); } return result; } -} // namespace qp +} // namespace autoware::common diff --git a/common/qp_interface/src/qp_interface.cpp b/common/qp_interface/src/qp_interface.cpp index e7a69bac0c67c..afd26132d7769 100644 --- a/common/qp_interface/src/qp_interface.cpp +++ b/common/qp_interface/src/qp_interface.cpp @@ -18,7 +18,7 @@ #include #include -namespace qp +namespace autoware::common { void QPInterface::initializeProblem( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, @@ -54,8 +54,8 @@ void QPInterface::initializeProblem( initializeProblemImpl(P, A, q, l, u); - m_variables_num = q.size(); - m_constraints_num = l.size(); + variables_num_ = q.size(); + constraints_num_ = l.size(); } std::vector QPInterface::optimize( @@ -67,4 +67,4 @@ std::vector QPInterface::optimize( return result; } -} // namespace qp +} // namespace autoware::common diff --git a/common/qp_interface/test/test_csc_matrix_conv.cpp b/common/qp_interface/test/test_csc_matrix_conv.cpp index fc604d762d2c4..a6bd5e3df0be1 100644 --- a/common/qp_interface/test/test_csc_matrix_conv.cpp +++ b/common/qp_interface/test/test_csc_matrix_conv.cpp @@ -23,42 +23,42 @@ TEST(TestCscMatrixConv, Nominal) { - using qp::calCSCMatrix; - using qp::CSC_Matrix; + using autoware::common::calCSCMatrix; + using autoware::common::CSC_Matrix; Eigen::MatrixXd rect1(1, 2); rect1 << 0.0, 1.0; const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - ASSERT_EQ(rect_m1.m_vals.size(), size_t(1)); - EXPECT_EQ(rect_m1.m_vals[0], 1.0); - ASSERT_EQ(rect_m1.m_row_idxs.size(), size_t(1)); - EXPECT_EQ(rect_m1.m_row_idxs[0], c_int(0)); - ASSERT_EQ(rect_m1.m_col_idxs.size(), size_t(3)); // nb of columns + 1 - EXPECT_EQ(rect_m1.m_col_idxs[0], c_int(0)); - EXPECT_EQ(rect_m1.m_col_idxs[1], c_int(0)); - EXPECT_EQ(rect_m1.m_col_idxs[2], c_int(1)); + ASSERT_EQ(rect_m1.vals_.size(), size_t(1)); + EXPECT_EQ(rect_m1.vals_[0], 1.0); + ASSERT_EQ(rect_m1.row_idxs_.size(), size_t(1)); + EXPECT_EQ(rect_m1.row_idxs_[0], c_int(0)); + ASSERT_EQ(rect_m1.col_idxs_.size(), size_t(3)); // nb of columns + 1 + EXPECT_EQ(rect_m1.col_idxs_[0], c_int(0)); + EXPECT_EQ(rect_m1.col_idxs_[1], c_int(0)); + EXPECT_EQ(rect_m1.col_idxs_[2], c_int(1)); Eigen::MatrixXd rect2(2, 4); rect2 << 1.0, 0.0, 3.0, 0.0, 0.0, 6.0, 7.0, 0.0; const CSC_Matrix rect_m2 = calCSCMatrix(rect2); - ASSERT_EQ(rect_m2.m_vals.size(), size_t(4)); - EXPECT_EQ(rect_m2.m_vals[0], 1.0); - EXPECT_EQ(rect_m2.m_vals[1], 6.0); - EXPECT_EQ(rect_m2.m_vals[2], 3.0); - EXPECT_EQ(rect_m2.m_vals[3], 7.0); - ASSERT_EQ(rect_m2.m_row_idxs.size(), size_t(4)); - EXPECT_EQ(rect_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(rect_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(rect_m2.m_row_idxs[2], c_int(0)); - EXPECT_EQ(rect_m2.m_row_idxs[3], c_int(1)); - ASSERT_EQ(rect_m2.m_col_idxs.size(), size_t(5)); // nb of columns + 1 - EXPECT_EQ(rect_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(rect_m2.m_col_idxs[1], c_int(1)); - EXPECT_EQ(rect_m2.m_col_idxs[2], c_int(2)); - EXPECT_EQ(rect_m2.m_col_idxs[3], c_int(4)); - EXPECT_EQ(rect_m2.m_col_idxs[4], c_int(4)); + ASSERT_EQ(rect_m2.vals_.size(), size_t(4)); + EXPECT_EQ(rect_m2.vals_[0], 1.0); + EXPECT_EQ(rect_m2.vals_[1], 6.0); + EXPECT_EQ(rect_m2.vals_[2], 3.0); + EXPECT_EQ(rect_m2.vals_[3], 7.0); + ASSERT_EQ(rect_m2.row_idxs_.size(), size_t(4)); + EXPECT_EQ(rect_m2.row_idxs_[0], c_int(0)); + EXPECT_EQ(rect_m2.row_idxs_[1], c_int(1)); + EXPECT_EQ(rect_m2.row_idxs_[2], c_int(0)); + EXPECT_EQ(rect_m2.row_idxs_[3], c_int(1)); + ASSERT_EQ(rect_m2.col_idxs_.size(), size_t(5)); // nb of columns + 1 + EXPECT_EQ(rect_m2.col_idxs_[0], c_int(0)); + EXPECT_EQ(rect_m2.col_idxs_[1], c_int(1)); + EXPECT_EQ(rect_m2.col_idxs_[2], c_int(2)); + EXPECT_EQ(rect_m2.col_idxs_[3], c_int(4)); + EXPECT_EQ(rect_m2.col_idxs_[4], c_int(4)); // Example from http://netlib.org/linalg/html_templates/node92.html Eigen::MatrixXd square2(6, 6); @@ -66,59 +66,59 @@ TEST(TestCscMatrixConv, Nominal) 0.0, 3.0, 0.0, 8.0, 7.0, 5.0, 0.0, 0.0, 8.0, 0.0, 9.0, 9.0, 13.0, 0.0, 4.0, 0.0, 0.0, 2.0, -1.0; const CSC_Matrix square_m2 = calCSCMatrix(square2); - ASSERT_EQ(square_m2.m_vals.size(), size_t(19)); - EXPECT_EQ(square_m2.m_vals[0], 10.0); - EXPECT_EQ(square_m2.m_vals[1], 3.0); - EXPECT_EQ(square_m2.m_vals[2], 3.0); - EXPECT_EQ(square_m2.m_vals[3], 9.0); - EXPECT_EQ(square_m2.m_vals[4], 7.0); - EXPECT_EQ(square_m2.m_vals[5], 8.0); - EXPECT_EQ(square_m2.m_vals[6], 4.0); - EXPECT_EQ(square_m2.m_vals[7], 8.0); - EXPECT_EQ(square_m2.m_vals[8], 8.0); - EXPECT_EQ(square_m2.m_vals[9], 7.0); - EXPECT_EQ(square_m2.m_vals[10], 7.0); - EXPECT_EQ(square_m2.m_vals[11], 9.0); - EXPECT_EQ(square_m2.m_vals[12], -2.0); - EXPECT_EQ(square_m2.m_vals[13], 5.0); - EXPECT_EQ(square_m2.m_vals[14], 9.0); - EXPECT_EQ(square_m2.m_vals[15], 2.0); - EXPECT_EQ(square_m2.m_vals[16], 3.0); - EXPECT_EQ(square_m2.m_vals[17], 13.0); - EXPECT_EQ(square_m2.m_vals[18], -1.0); - ASSERT_EQ(square_m2.m_row_idxs.size(), size_t(19)); - EXPECT_EQ(square_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[2], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[3], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[4], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[5], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[6], c_int(5)); - EXPECT_EQ(square_m2.m_row_idxs[7], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[8], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[9], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[10], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[11], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[12], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[13], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[14], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[15], c_int(5)); - EXPECT_EQ(square_m2.m_row_idxs[16], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[17], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[18], c_int(5)); - ASSERT_EQ(square_m2.m_col_idxs.size(), size_t(7)); // nb of columns + 1 - EXPECT_EQ(square_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[1], c_int(3)); - EXPECT_EQ(square_m2.m_col_idxs[2], c_int(7)); - EXPECT_EQ(square_m2.m_col_idxs[3], c_int(9)); - EXPECT_EQ(square_m2.m_col_idxs[4], c_int(12)); - EXPECT_EQ(square_m2.m_col_idxs[5], c_int(16)); - EXPECT_EQ(square_m2.m_col_idxs[6], c_int(19)); + ASSERT_EQ(square_m2.vals_.size(), size_t(19)); + EXPECT_EQ(square_m2.vals_[0], 10.0); + EXPECT_EQ(square_m2.vals_[1], 3.0); + EXPECT_EQ(square_m2.vals_[2], 3.0); + EXPECT_EQ(square_m2.vals_[3], 9.0); + EXPECT_EQ(square_m2.vals_[4], 7.0); + EXPECT_EQ(square_m2.vals_[5], 8.0); + EXPECT_EQ(square_m2.vals_[6], 4.0); + EXPECT_EQ(square_m2.vals_[7], 8.0); + EXPECT_EQ(square_m2.vals_[8], 8.0); + EXPECT_EQ(square_m2.vals_[9], 7.0); + EXPECT_EQ(square_m2.vals_[10], 7.0); + EXPECT_EQ(square_m2.vals_[11], 9.0); + EXPECT_EQ(square_m2.vals_[12], -2.0); + EXPECT_EQ(square_m2.vals_[13], 5.0); + EXPECT_EQ(square_m2.vals_[14], 9.0); + EXPECT_EQ(square_m2.vals_[15], 2.0); + EXPECT_EQ(square_m2.vals_[16], 3.0); + EXPECT_EQ(square_m2.vals_[17], 13.0); + EXPECT_EQ(square_m2.vals_[18], -1.0); + ASSERT_EQ(square_m2.row_idxs_.size(), size_t(19)); + EXPECT_EQ(square_m2.row_idxs_[0], c_int(0)); + EXPECT_EQ(square_m2.row_idxs_[1], c_int(1)); + EXPECT_EQ(square_m2.row_idxs_[2], c_int(3)); + EXPECT_EQ(square_m2.row_idxs_[3], c_int(1)); + EXPECT_EQ(square_m2.row_idxs_[4], c_int(2)); + EXPECT_EQ(square_m2.row_idxs_[5], c_int(4)); + EXPECT_EQ(square_m2.row_idxs_[6], c_int(5)); + EXPECT_EQ(square_m2.row_idxs_[7], c_int(2)); + EXPECT_EQ(square_m2.row_idxs_[8], c_int(3)); + EXPECT_EQ(square_m2.row_idxs_[9], c_int(2)); + EXPECT_EQ(square_m2.row_idxs_[10], c_int(3)); + EXPECT_EQ(square_m2.row_idxs_[11], c_int(4)); + EXPECT_EQ(square_m2.row_idxs_[12], c_int(0)); + EXPECT_EQ(square_m2.row_idxs_[13], c_int(3)); + EXPECT_EQ(square_m2.row_idxs_[14], c_int(4)); + EXPECT_EQ(square_m2.row_idxs_[15], c_int(5)); + EXPECT_EQ(square_m2.row_idxs_[16], c_int(1)); + EXPECT_EQ(square_m2.row_idxs_[17], c_int(4)); + EXPECT_EQ(square_m2.row_idxs_[18], c_int(5)); + ASSERT_EQ(square_m2.col_idxs_.size(), size_t(7)); // nb of columns + 1 + EXPECT_EQ(square_m2.col_idxs_[0], c_int(0)); + EXPECT_EQ(square_m2.col_idxs_[1], c_int(3)); + EXPECT_EQ(square_m2.col_idxs_[2], c_int(7)); + EXPECT_EQ(square_m2.col_idxs_[3], c_int(9)); + EXPECT_EQ(square_m2.col_idxs_[4], c_int(12)); + EXPECT_EQ(square_m2.col_idxs_[5], c_int(16)); + EXPECT_EQ(square_m2.col_idxs_[6], c_int(19)); } TEST(TestCscMatrixConv, Trapezoidal) { - using qp::calCSCMatrixTrapezoidal; - using qp::CSC_Matrix; + using autoware::common::calCSCMatrixTrapezoidal; + using autoware::common::CSC_Matrix; Eigen::MatrixXd square1(2, 2); Eigen::MatrixXd square2(3, 3); @@ -129,33 +129,33 @@ TEST(TestCscMatrixConv, Trapezoidal) const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); // Trapezoidal: skip the lower left triangle (2.0 in this example) - ASSERT_EQ(square_m1.m_vals.size(), size_t(3)); - EXPECT_EQ(square_m1.m_vals[0], 1.0); - EXPECT_EQ(square_m1.m_vals[1], 2.0); - EXPECT_EQ(square_m1.m_vals[2], 4.0); - ASSERT_EQ(square_m1.m_row_idxs.size(), size_t(3)); - EXPECT_EQ(square_m1.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m1.m_row_idxs[1], c_int(0)); - EXPECT_EQ(square_m1.m_row_idxs[2], c_int(1)); - ASSERT_EQ(square_m1.m_col_idxs.size(), size_t(3)); - EXPECT_EQ(square_m1.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m1.m_col_idxs[1], c_int(1)); - EXPECT_EQ(square_m1.m_col_idxs[2], c_int(3)); + ASSERT_EQ(square_m1.vals_.size(), size_t(3)); + EXPECT_EQ(square_m1.vals_[0], 1.0); + EXPECT_EQ(square_m1.vals_[1], 2.0); + EXPECT_EQ(square_m1.vals_[2], 4.0); + ASSERT_EQ(square_m1.row_idxs_.size(), size_t(3)); + EXPECT_EQ(square_m1.row_idxs_[0], c_int(0)); + EXPECT_EQ(square_m1.row_idxs_[1], c_int(0)); + EXPECT_EQ(square_m1.row_idxs_[2], c_int(1)); + ASSERT_EQ(square_m1.col_idxs_.size(), size_t(3)); + EXPECT_EQ(square_m1.col_idxs_[0], c_int(0)); + EXPECT_EQ(square_m1.col_idxs_[1], c_int(1)); + EXPECT_EQ(square_m1.col_idxs_[2], c_int(3)); const CSC_Matrix square_m2 = calCSCMatrixTrapezoidal(square2); - ASSERT_EQ(square_m2.m_vals.size(), size_t(3)); - EXPECT_EQ(square_m2.m_vals[0], 2.0); - EXPECT_EQ(square_m2.m_vals[1], 5.0); - EXPECT_EQ(square_m2.m_vals[2], 6.0); - ASSERT_EQ(square_m2.m_row_idxs.size(), size_t(3)); - EXPECT_EQ(square_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[2], c_int(1)); - ASSERT_EQ(square_m2.m_col_idxs.size(), size_t(4)); - EXPECT_EQ(square_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[1], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[2], c_int(2)); - EXPECT_EQ(square_m2.m_col_idxs[3], c_int(3)); + ASSERT_EQ(square_m2.vals_.size(), size_t(3)); + EXPECT_EQ(square_m2.vals_[0], 2.0); + EXPECT_EQ(square_m2.vals_[1], 5.0); + EXPECT_EQ(square_m2.vals_[2], 6.0); + ASSERT_EQ(square_m2.row_idxs_.size(), size_t(3)); + EXPECT_EQ(square_m2.row_idxs_[0], c_int(0)); + EXPECT_EQ(square_m2.row_idxs_[1], c_int(1)); + EXPECT_EQ(square_m2.row_idxs_[2], c_int(1)); + ASSERT_EQ(square_m2.col_idxs_.size(), size_t(4)); + EXPECT_EQ(square_m2.col_idxs_[0], c_int(0)); + EXPECT_EQ(square_m2.col_idxs_[1], c_int(0)); + EXPECT_EQ(square_m2.col_idxs_[2], c_int(2)); + EXPECT_EQ(square_m2.col_idxs_[3], c_int(3)); try { const CSC_Matrix rect_m1 = calCSCMatrixTrapezoidal(rect1); @@ -166,10 +166,10 @@ TEST(TestCscMatrixConv, Trapezoidal) } TEST(TestCscMatrixConv, Print) { - using qp::calCSCMatrix; - using qp::calCSCMatrixTrapezoidal; - using qp::CSC_Matrix; - using qp::printCSCMatrix; + using autoware::common::calCSCMatrix; + using autoware::common::calCSCMatrixTrapezoidal; + using autoware::common::CSC_Matrix; + using autoware::common::printCSCMatrix; Eigen::MatrixXd square1(2, 2); Eigen::MatrixXd rect1(1, 2); square1 << 1.0, 2.0, 2.0, 4.0; diff --git a/common/qp_interface/test/test_osqp_interface.cpp b/common/qp_interface/test/test_osqp_interface.cpp index e5d7041469289..eddc8a452fe35 100644 --- a/common/qp_interface/test/test_osqp_interface.cpp +++ b/common/qp_interface/test/test_osqp_interface.cpp @@ -40,44 +40,44 @@ namespace // cppcheck-suppress syntaxError TEST(TestOsqpInterface, BasicQp) { - using qp::calCSCMatrix; - using qp::calCSCMatrixTrapezoidal; - using qp::CSC_Matrix; + using autoware::common::calCSCMatrix; + using autoware::common::calCSCMatrixTrapezoidal; + using autoware::common::CSC_Matrix; - auto check_result = []( - const auto & solution, const int solution_status, const int polish_status) { - EXPECT_EQ(solution_status, 1); - EXPECT_EQ(polish_status, 1); + auto check_result = + [](const auto & solution, const std::string & status, const int polish_status) { + EXPECT_EQ(status, "OSQP_SOLVED"); + EXPECT_EQ(polish_status, 1); - static const auto ep = 1.0e-8; + static const auto ep = 1.0e-8; - ASSERT_EQ(solution.size(), size_t(2)); - EXPECT_NEAR(solution[0], 0.3, ep); - EXPECT_NEAR(solution[1], 0.7, ep); - }; + ASSERT_EQ(solution.size(), size_t(2)); + EXPECT_NEAR(solution[0], 0.3, ep); + EXPECT_NEAR(solution[1], 0.7, ep); + }; const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -qp::INF}; - const std::vector u = {1.0, 0.7, 0.7, qp::INF}; + const std::vector l = {1.0, 0.0, 0.0, -autoware::common::OSQP_INF}; + const std::vector u = {1.0, 0.7, 0.7, autoware::common::OSQP_INF}; { // Define problem during optimization - qp::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 1e-6); const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); - const auto solution_status = osqp.getStatus(); + const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); - check_result(solution, solution_status, polish_status); + check_result(solution, status, polish_status); } { // Define problem during initialization - qp::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 1e-6); const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); - const auto solution_status = osqp.getStatus(); + const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); - check_result(solution, solution_status, polish_status); + check_result(solution, status, polish_status); } { @@ -88,7 +88,7 @@ TEST(TestOsqpInterface, BasicQp) std::vector q_ini(2, 0.0); std::vector l_ini(4, 0.0); std::vector u_ini(4, 0.0); - qp::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 1e-6); osqp.QPInterface::optimize(P_ini, A_ini, q_ini, l_ini, u_ini); } @@ -96,12 +96,12 @@ TEST(TestOsqpInterface, BasicQp) // Define problem during initialization with csc matrix CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); CSC_Matrix A_csc = calCSCMatrix(A); - qp::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 1e-6); const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto solution_status = osqp.getStatus(); + const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); - check_result(solution, solution_status, polish_status); + check_result(solution, status, polish_status); } { @@ -112,7 +112,7 @@ TEST(TestOsqpInterface, BasicQp) std::vector q_ini(2, 0.0); std::vector l_ini(4, 0.0); std::vector u_ini(4, 0.0); - qp::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 1e-6); osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); // Redefine problem before optimization @@ -120,9 +120,9 @@ TEST(TestOsqpInterface, BasicQp) CSC_Matrix A_csc = calCSCMatrix(A); const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto solution_status = osqp.getStatus(); + const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); - check_result(solution, solution_status, polish_status); + check_result(solution, status, polish_status); } // add warm startup @@ -133,7 +133,7 @@ TEST(TestOsqpInterface, BasicQp) std::vector q_ini(2, 0.0); std::vector l_ini(4, 0.0); std::vector u_ini(4, 0.0); - qp::OSQPInterface osqp(true, 1e-6); // enable warm start + autoware::common::OSQPInterface osqp(true, 1e-6); // enable warm start osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); // Redefine problem before optimization @@ -141,9 +141,9 @@ TEST(TestOsqpInterface, BasicQp) CSC_Matrix A_csc = calCSCMatrix(A); { const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto solution_status = osqp.getStatus(); + const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); - check_result(solution, solution_status, polish_status); + check_result(solution, status, polish_status); osqp.updateCheckTermination(1); const auto primal_val = solution; @@ -156,9 +156,9 @@ TEST(TestOsqpInterface, BasicQp) { const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto solution_status = osqp.getStatus(); + const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); - check_result(solution, solution_status, polish_status); + check_result(solution, status, polish_status); } // NOTE: This should be true, but currently optimize function reset the workspace, which diff --git a/common/qp_interface/test/test_proxqp_interface.cpp b/common/qp_interface/test/test_proxqp_interface.cpp index 96466665d5172..34d23f15e4a0b 100644 --- a/common/qp_interface/test/test_proxqp_interface.cpp +++ b/common/qp_interface/test/test_proxqp_interface.cpp @@ -41,7 +41,9 @@ namespace // cppcheck-suppress syntaxError TEST(TestProxqpInterface, BasicQp) { - auto check_result = [](const auto & solution) { + auto check_result = [](const auto & solution, const std::string & status) { + EXPECT_EQ(status, "PROXQP_SOLVED"); + static const auto ep = 1.0e-8; ASSERT_EQ(solution.size(), size_t(2)); EXPECT_NEAR(solution[0], 0.3, ep); @@ -56,23 +58,26 @@ TEST(TestProxqpInterface, BasicQp) { // Define problem during optimization - qp::ProxQPInterface proxqp(false, 1e-9); + autoware::common::ProxQPInterface proxqp(false, 1e-9, 1e-9, false); const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - check_result(solution); + const auto status = proxqp.getStatus(); + check_result(solution, status); } { // Define problem during optimization with warm start - qp::ProxQPInterface proxqp(true, 1e-9); + autoware::common::ProxQPInterface proxqp(true, 1e-9, 1e-9, false); { const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - check_result(solution); - EXPECT_NE(proxqp.getIteration(), 1); + const auto status = proxqp.getStatus(); + check_result(solution, status); + EXPECT_NE(proxqp.getIterationNumber(), 1); } { const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - check_result(solution); - EXPECT_EQ(proxqp.getIteration(), 0); + const auto status = proxqp.getStatus(); + check_result(solution, status); + EXPECT_EQ(proxqp.getIterationNumber(), 0); } } } From 8311f5ad7c45b617b30750b35472d0b9b142345f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 30 Jul 2024 15:59:48 +0900 Subject: [PATCH 060/151] perf(velocity_smoother): use ProxQP for faster optimization (#8028) * perf(velocity_smoother): use ProxQP for faster optimization Signed-off-by: Takayuki Murooka * consider max_iteration Signed-off-by: Takayuki Murooka * disable warm start Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/qp_interface/osqp_interface.hpp | 2 +- .../include/qp_interface/proxqp_interface.hpp | 4 +-- common/qp_interface/src/osqp_interface.cpp | 8 +++--- common/qp_interface/src/proxqp_interface.cpp | 4 ++- .../qp_interface/test/test_osqp_interface.cpp | 12 ++++----- .../test/test_proxqp_interface.cpp | 4 +-- .../smoother/jerk_filtered_smoother.hpp | 4 +-- .../autoware_velocity_smoother/package.xml | 1 + .../src/smoother/jerk_filtered_smoother.cpp | 27 +++++-------------- 9 files changed, 28 insertions(+), 38 deletions(-) diff --git a/common/qp_interface/include/qp_interface/osqp_interface.hpp b/common/qp_interface/include/qp_interface/osqp_interface.hpp index 14c03a91d8fa1..55792beaaff11 100644 --- a/common/qp_interface/include/qp_interface/osqp_interface.hpp +++ b/common/qp_interface/include/qp_interface/osqp_interface.hpp @@ -33,7 +33,7 @@ class OSQPInterface : public QPInterface public: /// \brief Constructor without problem formulation OSQPInterface( - const bool enable_warm_start = false, + const bool enable_warm_start = false, const int max_iteration = 20000, const c_float eps_abs = std::numeric_limits::epsilon(), const c_float eps_rel = std::numeric_limits::epsilon(), const bool polish = true, const bool verbose = false); diff --git a/common/qp_interface/include/qp_interface/proxqp_interface.hpp b/common/qp_interface/include/qp_interface/proxqp_interface.hpp index f75fb3da5954c..775ba0fcc42b8 100644 --- a/common/qp_interface/include/qp_interface/proxqp_interface.hpp +++ b/common/qp_interface/include/qp_interface/proxqp_interface.hpp @@ -31,8 +31,8 @@ class ProxQPInterface : public QPInterface { public: explicit ProxQPInterface( - const bool enable_warm_start, const double eps_abs, const double eps_rel, - const bool verbose = false); + const bool enable_warm_start, const int max_iteration, const double eps_abs, + const double eps_rel, const bool verbose = false); int getIterationNumber() const override; bool isSolved() const override; diff --git a/common/qp_interface/src/osqp_interface.cpp b/common/qp_interface/src/osqp_interface.cpp index 0e8cb7e13988a..3ada25e8fa023 100644 --- a/common/qp_interface/src/osqp_interface.cpp +++ b/common/qp_interface/src/osqp_interface.cpp @@ -21,8 +21,8 @@ namespace autoware::common { OSQPInterface::OSQPInterface( - const bool enable_warm_start, const c_float eps_abs, const c_float eps_rel, const bool polish, - const bool verbose) + const bool enable_warm_start, const int max_iteration, const c_float eps_abs, + const c_float eps_rel, const bool polish, const bool verbose) : QPInterface(enable_warm_start), work_{nullptr, OSQPWorkspaceDeleter} { settings_ = std::make_unique(); @@ -35,8 +35,8 @@ OSQPInterface::OSQPInterface( settings_->eps_abs = eps_abs; settings_->eps_prim_inf = 1.0E-4; settings_->eps_dual_inf = 1.0E-4; - settings_->warm_start = true; - settings_->max_iter = 4000; + settings_->warm_start = enable_warm_start; + settings_->max_iter = max_iteration; settings_->verbose = verbose; settings_->polish = polish; } diff --git a/common/qp_interface/src/proxqp_interface.cpp b/common/qp_interface/src/proxqp_interface.cpp index 507f3858cbf1b..d26543f907e62 100644 --- a/common/qp_interface/src/proxqp_interface.cpp +++ b/common/qp_interface/src/proxqp_interface.cpp @@ -19,9 +19,11 @@ namespace autoware::common using proxsuite::proxqp::QPSolverOutput; ProxQPInterface::ProxQPInterface( - const bool enable_warm_start, const double eps_abs, const double eps_rel, const bool verbose) + const bool enable_warm_start, const int max_iteration, const double eps_abs, const double eps_rel, + const bool verbose) : QPInterface(enable_warm_start) { + settings_.max_iter = max_iteration; settings_.eps_abs = eps_abs; settings_.eps_rel = eps_rel; settings_.verbose = verbose; diff --git a/common/qp_interface/test/test_osqp_interface.cpp b/common/qp_interface/test/test_osqp_interface.cpp index eddc8a452fe35..980a85b384747 100644 --- a/common/qp_interface/test/test_osqp_interface.cpp +++ b/common/qp_interface/test/test_osqp_interface.cpp @@ -64,7 +64,7 @@ TEST(TestOsqpInterface, BasicQp) { // Define problem during optimization - autoware::common::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 4000, 1e-6); const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); @@ -73,7 +73,7 @@ TEST(TestOsqpInterface, BasicQp) { // Define problem during initialization - autoware::common::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 4000, 1e-6); const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); const auto status = osqp.getStatus(); const auto polish_status = osqp.getPolishStatus(); @@ -88,7 +88,7 @@ TEST(TestOsqpInterface, BasicQp) std::vector q_ini(2, 0.0); std::vector l_ini(4, 0.0); std::vector u_ini(4, 0.0); - autoware::common::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 4000, 1e-6); osqp.QPInterface::optimize(P_ini, A_ini, q_ini, l_ini, u_ini); } @@ -96,7 +96,7 @@ TEST(TestOsqpInterface, BasicQp) // Define problem during initialization with csc matrix CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); CSC_Matrix A_csc = calCSCMatrix(A); - autoware::common::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 4000, 1e-6); const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); const auto status = osqp.getStatus(); @@ -112,7 +112,7 @@ TEST(TestOsqpInterface, BasicQp) std::vector q_ini(2, 0.0); std::vector l_ini(4, 0.0); std::vector u_ini(4, 0.0); - autoware::common::OSQPInterface osqp(false, 1e-6); + autoware::common::OSQPInterface osqp(false, 4000, 1e-6); osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); // Redefine problem before optimization @@ -133,7 +133,7 @@ TEST(TestOsqpInterface, BasicQp) std::vector q_ini(2, 0.0); std::vector l_ini(4, 0.0); std::vector u_ini(4, 0.0); - autoware::common::OSQPInterface osqp(true, 1e-6); // enable warm start + autoware::common::OSQPInterface osqp(true, 4000, 1e-6); // enable warm start osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); // Redefine problem before optimization diff --git a/common/qp_interface/test/test_proxqp_interface.cpp b/common/qp_interface/test/test_proxqp_interface.cpp index 34d23f15e4a0b..a19c673b52f4d 100644 --- a/common/qp_interface/test/test_proxqp_interface.cpp +++ b/common/qp_interface/test/test_proxqp_interface.cpp @@ -58,7 +58,7 @@ TEST(TestProxqpInterface, BasicQp) { // Define problem during optimization - autoware::common::ProxQPInterface proxqp(false, 1e-9, 1e-9, false); + autoware::common::ProxQPInterface proxqp(false, 4000, 1e-9, 1e-9, false); const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); const auto status = proxqp.getStatus(); check_result(solution, status); @@ -66,7 +66,7 @@ TEST(TestProxqpInterface, BasicQp) { // Define problem during optimization with warm start - autoware::common::ProxQPInterface proxqp(true, 1e-9, 1e-9, false); + autoware::common::ProxQPInterface proxqp(true, 4000, 1e-9, 1e-9, false); { const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); const auto status = proxqp.getStatus(); diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp index 06a6f2da7f30a..cc8b4f95ccbdc 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp @@ -19,7 +19,7 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/system/time_keeper.hpp" #include "autoware/velocity_smoother/smoother/smoother_base.hpp" -#include "osqp_interface/osqp_interface.hpp" +#include "qp_interface/qp_interface.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -59,7 +59,7 @@ class JerkFilteredSmoother : public SmootherBase private: Param smoother_param_; - autoware::common::osqp::OSQPInterface qp_solver_; + std::shared_ptr qp_interface_; rclcpp::Logger logger_{rclcpp::get_logger("smoother").get_child("jerk_filtered_smoother")}; TrajectoryPoints forwardJerkFilter( diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index 37420b534938c..5ddbe3aa20ead 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -29,6 +29,7 @@ interpolation nav_msgs osqp_interface + qp_interface rclcpp std_srvs tf2 diff --git a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp index d458c688d060c..ecb67338fb1c4 100644 --- a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -15,6 +15,7 @@ #include "autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp" #include "autoware/velocity_smoother/trajectory_utils.hpp" +#include "qp_interface/proxqp_interface.hpp" #include @@ -40,11 +41,8 @@ JerkFilteredSmoother::JerkFilteredSmoother( p.over_j_weight = node.declare_parameter("over_j_weight"); p.jerk_filter_ds = node.declare_parameter("jerk_filter_ds"); - qp_solver_.updateMaxIter(20000); - qp_solver_.updateRhoInterval(0); // 0 means automatic - qp_solver_.updateEpsRel(1.0e-6); // def: 1.0e-4 - qp_solver_.updateEpsAbs(1.0e-8); // def: 1.0e-4 - qp_solver_.updateVerbose(false); + qp_interface_ = + std::make_shared(false, 20000, 1.0e-8, 1.0e-6, false); } void JerkFilteredSmoother::setParam(const Param & smoother_param) @@ -301,14 +299,13 @@ bool JerkFilteredSmoother::apply( // execute optimization time_keeper_->start_track("optimize"); - const auto result = qp_solver_.optimize(P, A, q, lower_bound, upper_bound); + const auto optval = qp_interface_->optimize(P, A, q, lower_bound, upper_bound); time_keeper_->end_track("optimize"); - const std::vector optval = std::get<0>(result); - const int status_val = std::get<3>(result); - if (status_val != 1) { - RCLCPP_WARN(logger_, "optimization failed : %s", qp_solver_.getStatusMessage().c_str()); + if (!qp_interface_->isSolved()) { + RCLCPP_WARN(logger_, "optimization failed : %s", qp_interface_->getStatus().c_str()); return false; } + const auto has_nan = std::any_of(optval.begin(), optval.end(), [](const auto v) { return std::isnan(v); }); if (has_nan) { @@ -332,16 +329,6 @@ bool JerkFilteredSmoother::apply( output.at(i).acceleration_mps2 = a_stop_decel; } - qp_solver_.logUnsolvedStatus("[autoware_velocity_smoother]"); - - const int status_polish = std::get<2>(result); - if (status_polish != 1) { - const auto msg = status_polish == 0 ? "unperformed" - : status_polish == -1 ? "unsuccessful" - : "unknown"; - RCLCPP_DEBUG(logger_, "osqp polish process failed : %s. The result may be inaccurate", msg); - } - if (VERBOSE_TRAJECTORY_VELOCITY) { const auto s_output = trajectory_utils::calcArclengthArray(output); From c74c9ca4ac5321219258dcb2dfb8351e504701e5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 30 Jul 2024 19:38:55 +0900 Subject: [PATCH 061/151] perf(velocity_smoother): not resample debug_trajectories is not used (#8030) * not resample debug_trajectories if not published Signed-off-by: Takayuki Murooka * update dependant packages Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../analytical_jerk_constrained_smoother.hpp | 3 ++- .../smoother/jerk_filtered_smoother.hpp | 3 ++- .../smoother/l2_pseudo_jerk_smoother.hpp | 3 ++- .../smoother/linf_pseudo_jerk_smoother.hpp | 3 ++- .../smoother/smoother_base.hpp | 3 ++- .../autoware_velocity_smoother/src/node.cpp | 19 ++++++++--------- .../analytical_jerk_constrained_smoother.cpp | 3 ++- .../src/smoother/jerk_filtered_smoother.cpp | 21 ++++++++++++------- .../src/smoother/l2_pseudo_jerk_smoother.cpp | 3 ++- .../smoother/linf_pseudo_jerk_smoother.cpp | 3 ++- .../src/utilization/trajectory_utils.cpp | 2 +- .../src/node.cpp | 2 +- 12 files changed, 40 insertions(+), 28 deletions(-) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp index bbc3828bb1b15..bfcd7db6b9c43 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp @@ -73,7 +73,8 @@ class AnalyticalJerkConstrainedSmoother : public SmootherBase bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) override; + TrajectoryPoints & output, std::vector & debug_trajectories, + const bool publish_debug_trajs) override; TrajectoryPoints resampleTrajectory( const TrajectoryPoints & input, [[maybe_unused]] const double v0, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp index cc8b4f95ccbdc..79dd5cda20d4b 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp @@ -47,7 +47,8 @@ class JerkFilteredSmoother : public SmootherBase bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) override; + TrajectoryPoints & output, std::vector & debug_trajectories, + const bool publish_debug_trajs) override; TrajectoryPoints resampleTrajectory( const TrajectoryPoints & input, [[maybe_unused]] const double v0, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp index a2a07ec6909aa..8f6bbc2236eb6 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp @@ -45,7 +45,8 @@ class L2PseudoJerkSmoother : public SmootherBase bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) override; + TrajectoryPoints & output, std::vector & debug_trajectories, + const bool publish_debug_trajs) override; TrajectoryPoints resampleTrajectory( const TrajectoryPoints & input, const double v0, const geometry_msgs::msg::Pose & current_pose, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp index 7c46a53431608..e27a4db10e748 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp @@ -45,7 +45,8 @@ class LinfPseudoJerkSmoother : public SmootherBase bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) override; + TrajectoryPoints & output, std::vector & debug_trajectories, + const bool publish_debug_trajs) override; TrajectoryPoints resampleTrajectory( const TrajectoryPoints & input, const double v0, const geometry_msgs::msg::Pose & current_pose, diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp index 5efb003db183e..893a66f7eb7fa 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp @@ -61,7 +61,8 @@ class SmootherBase virtual ~SmootherBase() = default; virtual bool apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) = 0; + TrajectoryPoints & output, std::vector & debug_trajectories, + const bool publish_debug_trajs) = 0; virtual TrajectoryPoints resampleTrajectory( const TrajectoryPoints & input, const double v0, const geometry_msgs::msg::Pose & current_pose, diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 23dee0019bf94..a8a3a847adec3 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -676,7 +676,8 @@ bool VelocitySmootherNode::smoothVelocity( std::vector debug_trajectories; if (!smoother_->apply( - initial_motion.vel, initial_motion.acc, clipped, traj_smoothed, debug_trajectories)) { + initial_motion.vel, initial_motion.acc, clipped, traj_smoothed, debug_trajectories, + publish_debug_trajs_)) { RCLCPP_WARN(get_logger(), "Fail to solve optimization."); } @@ -716,15 +717,13 @@ bool VelocitySmootherNode::smoothVelocity( pub_trajectory_steering_rate_limited_->publish(toTrajectoryMsg(tmp)); } - if (!debug_trajectories.empty()) { - for (auto & debug_trajectory : debug_trajectories) { - debug_trajectory.insert( - debug_trajectory.begin(), traj_resampled.begin(), - traj_resampled.begin() + traj_resampled_closest); - for (size_t i = 0; i < traj_resampled_closest; ++i) { - debug_trajectory.at(i).longitudinal_velocity_mps = - debug_trajectory.at(traj_resampled_closest).longitudinal_velocity_mps; - } + for (auto & debug_trajectory : debug_trajectories) { + debug_trajectory.insert( + debug_trajectory.begin(), traj_resampled.begin(), + traj_resampled.begin() + traj_resampled_closest); + for (size_t i = 0; i < traj_resampled_closest; ++i) { + debug_trajectory.at(i).longitudinal_velocity_mps = + debug_trajectory.at(traj_resampled_closest).longitudinal_velocity_mps; } } publishDebugTrajectories(debug_trajectories); diff --git a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp index 3906222454d35..43b03748133e6 100644 --- a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp @@ -103,7 +103,8 @@ AnalyticalJerkConstrainedSmoother::Param AnalyticalJerkConstrainedSmoother::getP bool AnalyticalJerkConstrainedSmoother::apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, [[maybe_unused]] std::vector & debug_trajectories) + TrajectoryPoints & output, [[maybe_unused]] std::vector & debug_trajectories, + [[maybe_unused]] const bool publish_debug_trajs) { RCLCPP_DEBUG(logger_, "-------------------- Start --------------------"); diff --git a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp index ecb67338fb1c4..3e363b8bcbab9 100644 --- a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -57,7 +57,7 @@ JerkFilteredSmoother::Param JerkFilteredSmoother::getParam() const bool JerkFilteredSmoother::apply( const double v0, const double a0, const TrajectoryPoints & input, TrajectoryPoints & output, - std::vector & debug_trajectories) + std::vector & debug_trajectories, const bool publish_debug_trajs) { autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -114,10 +114,12 @@ bool JerkFilteredSmoother::apply( auto opt_resampled_trajectory = resample(filtered); // Set debug trajectories - debug_trajectories.resize(3); - debug_trajectories[0] = resample(forward_filtered); - debug_trajectories[1] = resample(backward_filtered); - debug_trajectories[2] = resample(filtered); + if (publish_debug_trajs) { + debug_trajectories.resize(3); + debug_trajectories[0] = resample(forward_filtered); + debug_trajectories[1] = resample(backward_filtered); + debug_trajectories[2] = resample(filtered); + } // Ensure terminal velocity is zero opt_resampled_trajectory.back().longitudinal_velocity_mps = 0.0; @@ -127,9 +129,12 @@ bool JerkFilteredSmoother::apply( // No need to do optimization output.front().longitudinal_velocity_mps = v0; output.front().acceleration_mps2 = a0; - debug_trajectories[0] = output; - debug_trajectories[1] = output; - debug_trajectories[2] = output; + if (publish_debug_trajs) { + debug_trajectories.resize(3); + debug_trajectories[0] = output; + debug_trajectories[1] = output; + debug_trajectories[2] = output; + } return true; } diff --git a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp index f379b217187c9..678c8e01bf67e 100644 --- a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp @@ -53,7 +53,8 @@ L2PseudoJerkSmoother::Param L2PseudoJerkSmoother::getParam() const bool L2PseudoJerkSmoother::apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) + TrajectoryPoints & output, std::vector & debug_trajectories, + [[maybe_unused]] const bool publish_debug_trajs) { debug_trajectories.clear(); diff --git a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp index 2ab3d6dd80dfc..60345ff0fa6f4 100644 --- a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp @@ -53,7 +53,8 @@ LinfPseudoJerkSmoother::Param LinfPseudoJerkSmoother::getParam() const bool LinfPseudoJerkSmoother::apply( const double initial_vel, const double initial_acc, const TrajectoryPoints & input, - TrajectoryPoints & output, std::vector & debug_trajectories) + TrajectoryPoints & output, std::vector & debug_trajectories, + [[maybe_unused]] const bool publish_debug_trajs) { debug_trajectories.clear(); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 5900bd3531266..6815ca3ff8cb4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -76,7 +76,7 @@ bool smoothPath( TrajectoryPoints traj_smoothed; clipped.insert( clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); - if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories)) { + if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { std::cerr << "[behavior_velocity][trajectory_utils]: failed to smooth" << std::endl; return false; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 9be416f9e9bb0..76b64c0a4d5e2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -361,7 +361,7 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware::motion_velocity_planner::TrajectoryPoints traj_smoothed; clipped.insert( clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); - if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories)) { + if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { RCLCPP_ERROR(get_logger(), "failed to smooth"); } traj_smoothed.insert( From ec3ad51ae66aeebc7843622ce22607a80db87978 Mon Sep 17 00:00:00 2001 From: Shohei Sakai Date: Fri, 9 Aug 2024 13:11:16 +0900 Subject: [PATCH 062/151] fix(tier4_perception_launch): radar_lanelet_filtering_range_param_path (#1440) fix radar_lanelet_filtering_range_param_path --- .../detection/filter/radar_filter.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/filter/radar_filter.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/filter/radar_filter.launch.xml index d837505649cf1..c878dccc106fc 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/filter/radar_filter.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/filter/radar_filter.launch.xml @@ -4,7 +4,7 @@ - + @@ -36,7 +36,7 @@ - + From 49231bcd6fcebddd20266a4e31ab5fdab1790f7d Mon Sep 17 00:00:00 2001 From: Sho Iwasawa <41606073+zusizusi@users.noreply.github.com> Date: Fri, 9 Aug 2024 10:12:41 +0300 Subject: [PATCH 063/151] fix(traffic_light_classifier): fix traffic light monitor warning (#8412) (#1455) fix traffic light monitor warning Signed-off-by: Sho Iwasawa Co-authored-by: Naophis --- perception/traffic_light_classifier/src/nodelet.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/perception/traffic_light_classifier/src/nodelet.cpp b/perception/traffic_light_classifier/src/nodelet.cpp index 440b5b0dcfb3e..a076ea984daf3 100644 --- a/perception/traffic_light_classifier/src/nodelet.cpp +++ b/perception/traffic_light_classifier/src/nodelet.cpp @@ -84,7 +84,10 @@ void TrafficLightClassifierNodelet::imageRoiCallback( if (classifier_ptr_.use_count() == 0) { return; } + tier4_perception_msgs::msg::TrafficLightArray output_msg; if (input_rois_msg->rois.empty()) { + output_msg.header = input_image_msg->header; + traffic_signal_array_pub_->publish(output_msg); return; } @@ -97,7 +100,6 @@ void TrafficLightClassifierNodelet::imageRoiCallback( input_image_msg->encoding.c_str()); } - tier4_perception_msgs::msg::TrafficLightArray output_msg; output_msg.signals.resize(input_rois_msg->rois.size()); std::vector images; From 91d0e856035df0e78cfc8fb23a0fa6e2ef9a98f1 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 9 Aug 2024 18:23:52 +0900 Subject: [PATCH 064/151] fix(autoware_universe_utils): fix memory leak of time_keeper (#1456) fix bug of time_keeper Signed-off-by: Y.Hisaki --- .../autoware/universe_utils/system/time_keeper.hpp | 11 ++++++----- .../src/system/time_keeper.cpp | 6 +++--- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp index c635138416aa5..b6c12714c5daf 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/time_keeper.hpp @@ -67,9 +67,9 @@ class ProcessingTimeNode : public std::enable_shared_from_this Shared pointer to the parent node + * @return std::weak_ptr Weak pointer to the parent node */ - std::shared_ptr get_parent_node() const; + std::weak_ptr get_parent_node() const; /** * @brief Get the child nodes @@ -94,9 +94,10 @@ class ProcessingTimeNode : public std::enable_shared_from_this parent_node_{nullptr}; //!< Shared pointer to the parent node + const std::string name_; //!< Name of the node + double processing_time_{0.0}; //!< Processing time of the node + std::string comment_; //!< Comment for the node + std::weak_ptr parent_node_; //!< Weak pointer to the parent node std::vector> child_nodes_; //!< Vector of shared pointers to the child nodes }; diff --git a/common/autoware_universe_utils/src/system/time_keeper.cpp b/common/autoware_universe_utils/src/system/time_keeper.cpp index 429f063dfc62e..fa73c57369d94 100644 --- a/common/autoware_universe_utils/src/system/time_keeper.cpp +++ b/common/autoware_universe_utils/src/system/time_keeper.cpp @@ -28,7 +28,7 @@ ProcessingTimeNode::ProcessingTimeNode(const std::string & name) : name_(name) std::shared_ptr ProcessingTimeNode::add_child(const std::string & name) { auto new_child_node = std::make_shared(name); - new_child_node->parent_node_ = shared_from_this(); + new_child_node->parent_node_ = weak_from_this(); child_nodes_.push_back(new_child_node); return new_child_node; } @@ -81,7 +81,7 @@ tier4_debug_msgs::msg::ProcessingTimeTree ProcessingTimeNode::to_msg() const return time_tree_msg; } -std::shared_ptr ProcessingTimeNode::get_parent_node() const +std::weak_ptr ProcessingTimeNode::get_parent_node() const { return parent_node_; } @@ -133,7 +133,7 @@ void TimeKeeper::end_track(const std::string & func_name) } const double processing_time = stop_watch_.toc(func_name); current_time_node_->set_time(processing_time); - current_time_node_ = current_time_node_->get_parent_node(); + current_time_node_ = current_time_node_->get_parent_node().lock(); if (current_time_node_ == nullptr) { report(); From f1f8029b62e59f17812d3190ee7bf0686b2e2c4a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 21 Jun 2024 17:59:05 +0900 Subject: [PATCH 065/151] refactor(lane_change): use lane change namespace for structs (#7508) * refactor(lane_change): use lane change namespace for structs Signed-off-by: Zulfaqar Azmi * Move lane change namespace to bottom level Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_lane_change_module/scene.hpp | 2 +- .../utils/base_class.hpp | 6 +++--- .../utils/data_structs.hpp | 11 ++--------- .../utils/debug_structs.hpp | 4 ++-- .../utils/markers.hpp | 2 +- .../behavior_path_lane_change_module/utils/utils.hpp | 4 ++-- 6 files changed, 11 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index 69e9e90a236b9..be62492b7c2cc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -31,10 +31,10 @@ using autoware::behavior_path_planner::utils::path_safety_checker:: using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using autoware::behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; using autoware::route_handler::Direction; -using data::lane_change::LanesPolygon; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; +using lane_change::LanesPolygon; using tier4_planning_msgs::msg::PathWithLaneId; using utils::path_safety_checker::ExtendedPredictedObjects; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index be1f328fd89df..cb5746d60c1d3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -39,10 +39,10 @@ namespace autoware::behavior_path_planner { using autoware::route_handler::Direction; using autoware::universe_utils::StopWatch; -using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; +using lane_change::PathSafetyStatus; using tier4_planning_msgs::msg::PathWithLaneId; class LaneChangeBase @@ -130,7 +130,7 @@ class LaneChangeBase const LaneChangeStatus & getLaneChangeStatus() const { return status_; } - const data::lane_change::Debug & getDebugData() const { return lane_change_debug_; } + const lane_change::Debug & getDebugData() const { return lane_change_debug_; } const Pose & getEgoPose() const { return planner_data_->self_odometry->pose.pose; } @@ -242,7 +242,7 @@ class LaneChangeBase LaneChangeModuleType type_{LaneChangeModuleType::NORMAL}; mutable StopWatch stop_watch_; - mutable data::lane_change::Debug lane_change_debug_; + mutable lane_change::Debug lane_change_debug_; rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr()); mutable rclcpp::Clock clock_{RCL_ROS_TIME}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index a65f3baff01d7..ffd2754acc38f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -190,13 +190,6 @@ struct LaneChangeInfo double terminal_lane_changing_velocity{0.0}; }; -struct LaneChangeTargetObjectIndices -{ - std::vector current_lane{}; - std::vector target_lane{}; - std::vector other_lane{}; -}; - struct LaneChangeLanesFilteredObjects { utils::path_safety_checker::ExtendedPredictedObjects current_lane{}; @@ -211,7 +204,7 @@ enum class LaneChangeModuleType { }; } // namespace autoware::behavior_path_planner -namespace autoware::behavior_path_planner::data::lane_change +namespace autoware::behavior_path_planner::lane_change { struct PathSafetyStatus { @@ -225,6 +218,6 @@ struct LanesPolygon std::optional target; std::vector target_backward; }; -} // namespace autoware::behavior_path_planner::data::lane_change +} // namespace autoware::behavior_path_planner::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp index 3b8159dc3ad47..1890b9f308e8e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp @@ -26,7 +26,7 @@ #include #include -namespace autoware::behavior_path_planner::data::lane_change +namespace autoware::behavior_path_planner::lane_change { using utils::path_safety_checker::CollisionCheckDebugMap; struct Debug @@ -71,6 +71,6 @@ struct Debug is_abort = false; } }; -} // namespace autoware::behavior_path_planner::data::lane_change +} // namespace autoware::behavior_path_planner::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index c40db47adf280..91d1f1db15cbc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -30,7 +30,7 @@ namespace marker_utils::lane_change_markers { using autoware::behavior_path_planner::LaneChangePath; -using autoware::behavior_path_planner::data::lane_change::Debug; +using autoware::behavior_path_planner::lane_change::Debug; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; using visualization_msgs::msg::MarkerArray; MarkerArray showAllValidLaneChangePath( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 4071c39568987..e25b67bdb73d8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -48,8 +48,8 @@ using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; -using data::lane_change::LanesPolygon; -using data::lane_change::PathSafetyStatus; +using behavior_path_planner::lane_change::LanesPolygon; +using behavior_path_planner::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; From ccd4ffbb62af319d4732d6fbdb175fc5de70f06d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 24 Jun 2024 09:57:02 +0900 Subject: [PATCH 066/151] feat(route_handler): add unit test for lane change related functions (#7504) * RT1-6230 feat(route_handler): add unit test for lane change related functions Signed-off-by: Zulfaqar Azmi * fix spell check Signed-off-by: Zulfaqar Azmi * fix spellcheck Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/autoware_test_utils.cpp | 30 ++- .../test/test_route_handler.cpp | 238 +++++++++++++----- .../test/test_route_handler.hpp | 43 +++- 3 files changed, 234 insertions(+), 77 deletions(-) diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index 563350dbe53cc..d870bcf9974a1 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -19,6 +19,8 @@ #include #include +#include + #include namespace autoware::test_utils @@ -54,14 +56,32 @@ lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename) lanelet::ErrorMessages errors{}; lanelet::projection::MGRSProjector projector{}; lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); - if (errors.empty()) { - return map; + if (!errors.empty()) { + for (const auto & error : errors) { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); + } + return nullptr; } - for (const auto & error : errors) { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); + for (lanelet::Point3d point : map->pointLayer) { + if (point.hasAttribute("local_x")) { + point.x() = point.attribute("local_x").asDouble().value(); + } + if (point.hasAttribute("local_y")) { + point.y() = point.attribute("local_y").asDouble().value(); + } } - return nullptr; + + // realign lanelet borders using updated points + for (lanelet::Lanelet lanelet : map->laneletLayer) { + auto left = lanelet.leftBound(); + auto right = lanelet.rightBound(); + std::tie(left, right) = lanelet::geometry::align(left, right); + lanelet.setLeftBound(left); + lanelet.setRightBound(right); + } + + return map; } LaneletMapBin convertToMapBinMsg( diff --git a/planning/autoware_route_handler/test/test_route_handler.cpp b/planning/autoware_route_handler/test/test_route_handler.cpp index 35a2fe3ef45da..9a4081c51be3b 100644 --- a/planning/autoware_route_handler/test/test_route_handler.cpp +++ b/planning/autoware_route_handler/test/test_route_handler.cpp @@ -49,10 +49,11 @@ TEST_F(TestRouteHandler, getGoalLaneId) TEST_F(TestRouteHandler, getLaneletSequenceWhenOverlappingRoute) { - set_route_handler("/test_map/overlap_map.osm"); + set_route_handler("overlap_map.osm"); ASSERT_FALSE(route_handler_->isHandlerReady()); - geometry_msgs::msg::Pose start_pose, goal_pose; + geometry_msgs::msg::Pose start_pose; + geometry_msgs::msg::Pose goal_pose; start_pose.position = autoware::universe_utils::createPoint(3728.870361, 73739.281250, 0); start_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, -0.513117, 0.858319); goal_pose.position = autoware::universe_utils::createPoint(3729.961182, 73727.328125, 0); @@ -79,11 +80,12 @@ TEST_F(TestRouteHandler, getLaneletSequenceWhenOverlappingRoute) TEST_F(TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute) { - set_route_handler("/test_map/overlap_map.osm"); - set_test_route("/test_route/overlap_test_route.yaml"); + set_route_handler("overlap_map.osm"); + set_test_route("overlap_test_route.yaml"); ASSERT_TRUE(route_handler_->isHandlerReady()); - geometry_msgs::msg::Pose reference_pose, search_pose; + geometry_msgs::msg::Pose reference_pose; + geometry_msgs::msg::Pose search_pose; lanelet::ConstLanelet reference_lanelet; reference_pose.position = autoware::universe_utils::createPoint(3730.88, 73735.3, 0); @@ -102,71 +104,189 @@ TEST_F(TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute) ASSERT_EQ(closest_lanelet.id(), 345); found_lanelet = route_handler_->getClosestRouteLaneletFromLanelet( - search_pose, reference_lanelet, &closest_lanelet, 3.0, 1.046); + search_pose, reference_lanelet, &closest_lanelet, dist_threshold, yaw_threshold); ASSERT_TRUE(found_lanelet); ASSERT_EQ(closest_lanelet.id(), 277); } -// TEST_F(TestRouteHandler, getClosestLaneletWithinRouteWhenPointsInRoute) -// { -// lanelet::ConstLanelet closest_lane; - -// Pose search_pose; - -// search_pose.position = autoware::universe_utils::createPoint(-1.0, 1.75, 0); -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// const auto closest_lane_obtained7 = -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); - -// ASSERT_TRUE(closest_lane_obtained7); -// ASSERT_EQ(closest_lane.id(), 4775); - -// search_pose.position = autoware::universe_utils::createPoint(-0.5, 1.75, 0); -// const auto closest_lane_obtained = -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); - -// ASSERT_TRUE(closest_lane_obtained); -// ASSERT_EQ(closest_lane.id(), 4775); - -// search_pose.position = autoware::universe_utils::createPoint(-.01, 1.75, 0); -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// const auto closest_lane_obtained3 = -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); +TEST_F(TestRouteHandler, CheckLaneIsInGoalRouteSection) +{ + const auto lane = route_handler_->getLaneletsFromId(4785); + const auto is_lane_in_goal_route_section = route_handler_->isInGoalRouteSection(lane); + ASSERT_TRUE(is_lane_in_goal_route_section); +} -// ASSERT_TRUE(closest_lane_obtained3); -// ASSERT_EQ(closest_lane.id(), 4775); +TEST_F(TestRouteHandler, CheckLaneIsNotInGoalRouteSection) +{ + const auto lane = route_handler_->getLaneletsFromId(4780); + const auto is_lane_in_goal_route_section = route_handler_->isInGoalRouteSection(lane); + ASSERT_FALSE(is_lane_in_goal_route_section); +} -// search_pose.position = autoware::universe_utils::createPoint(0.0, 1.75, 0); -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// const auto closest_lane_obtained1 = -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); +TEST_F(TestRouteHandler, checkGetLaneletSequence) +{ + const auto current_pose = autoware::test_utils::createPose(-50.0, 1.75, 0.0, 0.0, 0.0, 0.0); -// ASSERT_TRUE(closest_lane_obtained1); -// ASSERT_EQ(closest_lane.id(), 4775); + lanelet::ConstLanelet closest_lanelet; + const auto found_closest_lanelet = route_handler_->getClosestLaneletWithConstrainsWithinRoute( + current_pose, &closest_lanelet, dist_threshold, yaw_threshold); + ASSERT_TRUE(found_closest_lanelet); + ASSERT_EQ(closest_lanelet.id(), 4765ul); + + const auto current_lanes = route_handler_->getLaneletSequence( + closest_lanelet, current_pose, backward_path_length, forward_path_length); + + ASSERT_EQ(current_lanes.size(), 6ul); + ASSERT_EQ(current_lanes.at(0).id(), 4765ul); + ASSERT_EQ(current_lanes.at(1).id(), 4770ul); + ASSERT_EQ(current_lanes.at(2).id(), 4775ul); + ASSERT_EQ(current_lanes.at(3).id(), 4424ul); + ASSERT_EQ(current_lanes.at(4).id(), 4780ul); + ASSERT_EQ(current_lanes.at(5).id(), 4785ul); +} -// search_pose.position = autoware::universe_utils::createPoint(0.01, 1.75, 0); -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// const auto closest_lane_obtained2 = -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); +TEST_F(TestRouteHandler, checkLateralIntervalToPreferredLaneWhenLaneChangeToRight) +{ + const auto current_lanes = get_current_lanes(); + + // The input is within expectation. + // this lane is of preferred lane type + std::for_each(current_lanes.begin(), current_lanes.begin() + 3, [&](const auto & lane) { + const auto result = route_handler_->getLateralIntervalsToPreferredLane(lane, Direction::RIGHT); + ASSERT_EQ(result.size(), 0ul); + }); + + // The input is within expectation. + // this alternative lane is a subset of preferred lane route section + std::for_each(current_lanes.begin() + 3, current_lanes.end(), [&](const auto & lane) { + const auto result = route_handler_->getLateralIntervalsToPreferredLane(lane, Direction::RIGHT); + ASSERT_EQ(result.size(), 1ul); + EXPECT_DOUBLE_EQ(result.at(0), -3.5); + }); + + // The input is within expectation. + // Although Direction::NONE, the function should still return result similar to + // Direction::RIGHT. + std::for_each(current_lanes.begin(), current_lanes.begin() + 3, [&](const auto & lane) { + const auto result = route_handler_->getLateralIntervalsToPreferredLane(lane, Direction::NONE); + ASSERT_EQ(result.size(), 0ul); + }); + + // The input is within expectation. + // Although Direction::NONE is provided, the function should behave similarly to + // Direction::RIGHT. + std::for_each(current_lanes.begin() + 3, current_lanes.end(), [&](const auto & lane) { + const auto result = route_handler_->getLateralIntervalsToPreferredLane(lane, Direction::NONE); + ASSERT_EQ(result.size(), 1ul); + EXPECT_DOUBLE_EQ(result.at(0), -3.5); + }); +} -// ASSERT_TRUE(closest_lane_obtained2); -// ASSERT_EQ(closest_lane.id(), 4424); +TEST_F(TestRouteHandler, checkLateralIntervalToPreferredLaneUsingUnexpectedResults) +{ + const auto current_lanes = get_current_lanes(); -// search_pose.position = autoware::universe_utils::createPoint(0.5, 1.75, 0); -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// const auto closest_lane_obtained4 = -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + std::for_each(current_lanes.begin(), current_lanes.end(), [&](const auto & lane) { + const auto result = route_handler_->getLateralIntervalsToPreferredLane(lane, Direction::LEFT); + ASSERT_EQ(result.size(), 0ul); + }); +} -// ASSERT_TRUE(closest_lane_obtained4); -// ASSERT_EQ(closest_lane.id(), 4424); +TEST_F(TestRouteHandler, testGetCenterLinePath) +{ + const auto current_lanes = route_handler_->getLaneletsFromIds({4424, 4780, 4785}); + { + // The input is within expectation. + const auto center_line_path = route_handler_->getCenterLinePath(current_lanes, 0.0, 50.0); + ASSERT_EQ(center_line_path.points.size(), 51); // 26 + 26 - 1(overlapped) + ASSERT_EQ(center_line_path.points.back().lane_ids.size(), 2); + ASSERT_EQ(center_line_path.points.back().lane_ids.at(0), 4780); + ASSERT_EQ(center_line_path.points.back().lane_ids.at(1), 4785); + } + { + // The input is broken. + // s_start is negative, and s_end is over the boundary. + const auto center_line_path = route_handler_->getCenterLinePath(current_lanes, -1.0, 200.0); + ASSERT_EQ(center_line_path.points.size(), 76); // 26 + 26 + 26 - 2(overlapped) + ASSERT_EQ(center_line_path.points.front().lane_ids.size(), 1); + ASSERT_EQ(center_line_path.points.front().lane_ids.at(0), 4424); + ASSERT_EQ(center_line_path.points.back().lane_ids.size(), 1); + ASSERT_EQ(center_line_path.points.back().lane_ids.at(0), 4785); + } +} +TEST_F(TestRouteHandler, DISABLED_testGetCenterLinePathWhenLanesIsNotConnected) +{ + // broken current lanes. 4424 and 4785 are not connected directly. + const auto current_lanes = route_handler_->getLaneletsFromIds({4424, 4780, 4785}); + + // The input is broken. Test is disabled because it doesn't pass. + const auto center_line_path = route_handler_->getCenterLinePath(current_lanes, 0.0, 75.0); + ASSERT_EQ(center_line_path.points.size(), 26); // 26 + 26 + 26 - 2(overlapped) + ASSERT_EQ(center_line_path.points.front().lane_ids.size(), 1); + ASSERT_EQ(center_line_path.points.front().lane_ids.at(0), 4424); + ASSERT_EQ(center_line_path.points.back().lane_ids.size(), 1); + ASSERT_EQ(center_line_path.points.back().lane_ids.at(0), 4424); +} -// search_pose.position = autoware::universe_utils::createPoint(1.0, 1.75, 0); -// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); -// const auto closest_lane_obtained5 = -// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); +TEST_F(TestRouteHandler, getClosestLaneletWithinRouteWhenPointsInRoute) +{ + auto get_closest_lanelet_within_route = + [&](double x, double y, double z) -> std::optional { + const auto pose = autoware::test_utils::createPose(x, y, z, 0.0, 0.0, 0.0); + lanelet::ConstLanelet closest_lanelet; + const auto closest_lane_obtained = + route_handler_->getClosestLaneletWithinRoute(pose, &closest_lanelet); + if (!closest_lane_obtained) { + return std::nullopt; + } + return closest_lanelet.id(); + }; + + ASSERT_TRUE(get_closest_lanelet_within_route(-0.5, 1.75, 0).has_value()); + ASSERT_EQ(get_closest_lanelet_within_route(-0.5, 1.75, 0).value(), 4775ul); + + ASSERT_TRUE(get_closest_lanelet_within_route(-0.01, 1.75, 0).has_value()); + ASSERT_EQ(get_closest_lanelet_within_route(-0.01, 1.75, 0).value(), 4775ul); + + ASSERT_TRUE(get_closest_lanelet_within_route(0.0, 1.75, 0).has_value()); + ASSERT_EQ(get_closest_lanelet_within_route(0.0, 1.75, 0).value(), 4775ul); + + ASSERT_TRUE(get_closest_lanelet_within_route(0.01, 1.75, 0).has_value()); + ASSERT_EQ(get_closest_lanelet_within_route(0.01, 1.75, 0).value(), 4424ul); + + ASSERT_TRUE(get_closest_lanelet_within_route(0.5, 1.75, 0).has_value()); + ASSERT_EQ(get_closest_lanelet_within_route(0.5, 1.75, 0).value(), 4424ul); +} -// ASSERT_TRUE(closest_lane_obtained5); -// ASSERT_EQ(closest_lane.id(), 4424); -// } +TEST_F(TestRouteHandler, testGetLaneChangeTargetLanes) +{ + { + // The input is within expectation. + // There exist no lane changing lane since both 4770 and 4775 are preferred lane. + const auto current_lanes = route_handler_->getLaneletsFromIds({4770, 4775}); + const auto lane_change_lane = + route_handler_->getLaneChangeTarget(current_lanes, Direction::RIGHT); + ASSERT_FALSE(lane_change_lane.has_value()); + } + + { + // The input is within expectation. + // There exist lane changing lane since 4424 is subset of preferred lane 9598. + const auto current_lanes = route_handler_->getLaneletsFromIds({4775, 4424}); + const auto lane_change_lane = + route_handler_->getLaneChangeTarget(current_lanes, Direction::RIGHT); + EXPECT_TRUE(lane_change_lane.has_value()); + ASSERT_EQ(lane_change_lane.value().id(), 9598ul); + } + + { + // The input is within expectation. + // There is a lane-changing lane. Within the maximum current lanes, there is an alternative lane + // to the preferred lane. Therefore, the lane-changing lane exists. + const auto current_lanes = get_current_lanes(); + const auto lane_change_lane = route_handler_->getLaneChangeTarget(current_lanes); + ASSERT_TRUE(lane_change_lane.has_value()); + ASSERT_EQ(lane_change_lane.value().id(), 9598ul); + } +} } // namespace autoware::route_handler::test diff --git a/planning/autoware_route_handler/test/test_route_handler.hpp b/planning/autoware_route_handler/test/test_route_handler.hpp index 86f7461fc7538..ec3368809df99 100644 --- a/planning/autoware_route_handler/test/test_route_handler.hpp +++ b/planning/autoware_route_handler/test/test_route_handler.hpp @@ -15,7 +15,6 @@ #ifndef TEST_ROUTE_HANDLER_HPP_ #define TEST_ROUTE_HANDLER_HPP_ -#include "ament_index_cpp/get_package_share_directory.hpp" #include "autoware_test_utils/autoware_test_utils.hpp" #include "autoware_test_utils/mock_data_parser.hpp" #include "gtest/gtest.h" @@ -37,16 +36,16 @@ namespace autoware::route_handler::test { +using autoware::test_utils::get_absolute_path_to_lanelet_map; +using autoware::test_utils::get_absolute_path_to_route; using autoware_map_msgs::msg::LaneletMapBin; - class TestRouteHandler : public ::testing::Test { public: TestRouteHandler() { - autoware_test_utils_dir = ament_index_cpp::get_package_share_directory("autoware_test_utils"); - set_route_handler("/test_map/2km_test.osm"); - set_test_route("/test_route/lane_change_test_route.yaml"); + set_route_handler("2km_test.osm"); + set_test_route(lane_change_right_test_route_filename); } TestRouteHandler(const TestRouteHandler &) = delete; @@ -55,26 +54,44 @@ class TestRouteHandler : public ::testing::Test TestRouteHandler & operator=(TestRouteHandler &&) = delete; ~TestRouteHandler() override = default; - void set_route_handler(const std::string & relative_path) + void set_route_handler(const std::string & lanelet_map_filename) { route_handler_.reset(); - const auto lanelet2_path = autoware_test_utils_dir + relative_path; + const auto lanelet2_path = + get_absolute_path_to_lanelet_map(autoware_test_utils_dir, lanelet_map_filename); const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(lanelet2_path, center_line_resolution); route_handler_ = std::make_shared(map_bin_msg); } - void set_test_route(const std::string & route_path) + void set_test_route(const std::string & route_filename) { - const auto route_handler_dir = - ament_index_cpp::get_package_share_directory("autoware_route_handler"); - const auto rh_test_route = route_handler_dir + route_path; + const auto rh_test_route = + get_absolute_path_to_route(autoware_route_handler_dir, route_filename); route_handler_->setRoute(autoware::test_utils::parse_lanelet_route_file(rh_test_route)); } + lanelet::ConstLanelets get_current_lanes() + { + const auto current_pose = autoware::test_utils::createPose(-50.0, 1.75, 0.0, 0.0, 0.0, 0.0); + lanelet::ConstLanelet closest_lanelet; + [[maybe_unused]] const auto found_closest_lanelet = + route_handler_->getClosestLaneletWithConstrainsWithinRoute( + current_pose, &closest_lanelet, dist_threshold, yaw_threshold); + return route_handler_->getLaneletSequence( + closest_lanelet, current_pose, backward_path_length, forward_path_length); + } + std::shared_ptr route_handler_; - std::string autoware_test_utils_dir; - static constexpr double center_line_resolution = 5.0; + std::string autoware_test_utils_dir{"autoware_test_utils"}; + std::string autoware_route_handler_dir{"autoware_route_handler"}; + std::string lane_change_right_test_route_filename{"lane_change_test_route.yaml"}; + + static constexpr double center_line_resolution{5.0}; + static constexpr double dist_threshold{3.0}; + static constexpr double yaw_threshold{1.045}; + static constexpr double backward_path_length{5.0}; + static constexpr double forward_path_length{300.0}; }; } // namespace autoware::route_handler::test From 1000fe036cf5ae2a83da0402bb0c065294e4a540 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 5 Jul 2024 11:37:50 +0900 Subject: [PATCH 067/151] refactor(lane_change): move struct to lane change namespace (#7841) * move struct to lane change namespace Signed-off-by: Muhammad Zulfaqar Azmi * Revert "move struct to lane change namespace" This reverts commit 306984a76103c427732f170a6f7eb5f94e895b0b. Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../utils/base_class.hpp | 15 ++- .../utils/data_structs.hpp | 102 ++++++++++++++---- .../utils/path.hpp | 4 +- 3 files changed, 96 insertions(+), 25 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index cb5746d60c1d3..cbd3a81827948 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -52,6 +52,7 @@ class LaneChangeBase std::shared_ptr parameters, LaneChangeModuleType type, Direction direction) : lane_change_parameters_{std::move(parameters)}, + common_data_ptr_{std::make_shared()}, direction_{direction}, type_{type}, time_keeper_(std::make_shared()) @@ -155,7 +156,18 @@ class LaneChangeBase bool isValidPath() const { return status_.is_valid_path; } - void setData(const std::shared_ptr & data) { planner_data_ = data; } + void setData(const std::shared_ptr & data) + { + planner_data_ = data; + if (!common_data_ptr_->bpp_param_ptr) { + common_data_ptr_->bpp_param_ptr = + std::make_shared(data->parameters); + } + common_data_ptr_->self_odometry_ptr = data->self_odometry; + common_data_ptr_->route_handler_ptr = data->route_handler; + common_data_ptr_->lc_param_ptr = lane_change_parameters_; + common_data_ptr_->direction = direction_; + } void setTimeKeeper(const std::shared_ptr & time_keeper) { @@ -228,6 +240,7 @@ class LaneChangeBase std::shared_ptr lane_change_parameters_{}; std::shared_ptr abort_path_{}; std::shared_ptr planner_data_{}; + lane_change::CommonDataPtr common_data_ptr_{}; BehaviorModuleOutput prev_module_output_{}; std::optional lane_change_stop_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index ffd2754acc38f..2fdf7c6b550a3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -17,16 +17,28 @@ #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include +#include #include +#include + #include #include +#include #include #include -namespace autoware::behavior_path_planner +namespace autoware::behavior_path_planner::lane_change { +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::Twist; +using nav_msgs::msg::Odometry; +using route_handler::Direction; +using route_handler::RouteHandler; +using utils::path_safety_checker::ExtendedPredictedObjects; + struct LateralAccelerationMap { std::vector base_vel; @@ -68,7 +80,7 @@ struct LateralAccelerationMap } }; -struct LaneChangeCancelParameters +struct CancelParameters { bool enable_on_prepare_phase{true}; bool enable_on_lane_changing_phase{false}; @@ -83,7 +95,7 @@ struct LaneChangeCancelParameters int unsafe_hysteresis_threshold{2}; }; -struct LaneChangeParameters +struct Parameters { // trajectory generation double backward_lane_length{200.0}; @@ -92,8 +104,8 @@ struct LaneChangeParameters int lateral_acc_sampling_num{10}; // lane change parameters - double backward_length_buffer_for_end_of_lane; - double backward_length_buffer_for_blocking_object; + double backward_length_buffer_for_end_of_lane{0.0}; + double backward_length_buffer_for_blocking_object{0.0}; double lane_changing_lateral_jerk{0.5}; double minimum_lane_changing_velocity{5.6}; double lane_change_prepare_duration{4.0}; @@ -143,7 +155,7 @@ struct LaneChangeParameters utils::path_safety_checker::RSSparams rss_params_for_stuck{}; // abort - LaneChangeCancelParameters cancel{}; + CancelParameters cancel{}; double finish_judge_lateral_threshold{0.2}; @@ -151,32 +163,32 @@ struct LaneChangeParameters bool publish_debug_marker{false}; }; -enum class LaneChangeStates { +enum class States { Normal = 0, Cancel, Abort, Stop, }; -struct LaneChangePhaseInfo +struct PhaseInfo { double prepare{0.0}; double lane_changing{0.0}; [[nodiscard]] double sum() const { return prepare + lane_changing; } - LaneChangePhaseInfo(const double _prepare, const double _lane_changing) + PhaseInfo(const double _prepare, const double _lane_changing) : prepare(_prepare), lane_changing(_lane_changing) { } }; -struct LaneChangeInfo +struct Info { - LaneChangePhaseInfo longitudinal_acceleration{0.0, 0.0}; - LaneChangePhaseInfo velocity{0.0, 0.0}; - LaneChangePhaseInfo duration{0.0, 0.0}; - LaneChangePhaseInfo length{0.0, 0.0}; + PhaseInfo longitudinal_acceleration{0.0, 0.0}; + PhaseInfo velocity{0.0, 0.0}; + PhaseInfo duration{0.0, 0.0}; + PhaseInfo length{0.0, 0.0}; lanelet::ConstLanelets current_lanes{}; lanelet::ConstLanelets target_lanes{}; @@ -190,22 +202,19 @@ struct LaneChangeInfo double terminal_lane_changing_velocity{0.0}; }; -struct LaneChangeLanesFilteredObjects +struct LanesObjects { - utils::path_safety_checker::ExtendedPredictedObjects current_lane{}; - utils::path_safety_checker::ExtendedPredictedObjects target_lane{}; - utils::path_safety_checker::ExtendedPredictedObjects other_lane{}; + ExtendedPredictedObjects current_lane{}; + ExtendedPredictedObjects target_lane{}; + ExtendedPredictedObjects other_lane{}; }; -enum class LaneChangeModuleType { +enum class ModuleType { NORMAL = 0, EXTERNAL_REQUEST, AVOIDANCE_BY_LANE_CHANGE, }; -} // namespace autoware::behavior_path_planner -namespace autoware::behavior_path_planner::lane_change -{ struct PathSafetyStatus { bool is_safe{true}; @@ -218,6 +227,55 @@ struct LanesPolygon std::optional target; std::vector target_backward; }; + +struct Lanes +{ + lanelet::ConstLanelets current; + lanelet::ConstLanelets target; + std::vector preceding_target; +}; + +struct CommonData +{ + std::shared_ptr route_handler_ptr; + Odometry::ConstSharedPtr self_odometry_ptr; + std::shared_ptr bpp_param_ptr; + std::shared_ptr lc_param_ptr; + Lanes lanes; + Direction direction; + + [[nodiscard]] Pose get_ego_pose() const { return self_odometry_ptr->pose.pose; } + + [[nodiscard]] Twist get_ego_twist() const { return self_odometry_ptr->twist.twist; } + + [[nodiscard]] double get_ego_speed(bool use_norm = false) const + { + if (!use_norm) { + return get_ego_twist().linear.x; + } + + const auto x = get_ego_twist().linear.x; + const auto y = get_ego_twist().linear.y; + return std::hypot(x, y); + } +}; + +using RouteHandlerPtr = std::shared_ptr; +using BppParamPtr = std::shared_ptr; +using LCParamPtr = std::shared_ptr; +using CommonDataPtr = std::shared_ptr; +using LanesPtr = std::shared_ptr; } // namespace autoware::behavior_path_planner::lane_change +namespace autoware::behavior_path_planner +{ +using LaneChangeModuleType = lane_change::ModuleType; +using LaneChangeParameters = lane_change::Parameters; +using LaneChangeStates = lane_change::States; +using LaneChangePhaseInfo = lane_change::PhaseInfo; +using LaneChangeInfo = lane_change::Info; +using LaneChangeLanesFilteredObjects = lane_change::LanesObjects; +using LateralAccelerationMap = lane_change::LateralAccelerationMap; +} // namespace autoware::behavior_path_planner + #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp index 77c603e3bd975..97b5c621deea5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -31,8 +31,8 @@ struct LaneChangePath { PathWithLaneId path{}; ShiftedPath shifted_path{}; - PathWithLaneId prev_path{}; - LaneChangeInfo info{}; + LaneChangeInfo info; + bool is_safe{false}; }; using LaneChangePaths = std::vector; From 2cd660176df341aa06e1c67641867693f1690a82 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 11 Jul 2024 17:39:49 +0900 Subject: [PATCH 068/151] fix(autoware_behavior_path_lane_change_module): fix shadowVariable (#7964) fix:shadowVariable Signed-off-by: kobayu858 Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/scene.cpp | 32 +++++++++---------- .../src/utils/utils.cpp | 8 ++--- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 75efc65c2997c..c26f54e905b47 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1455,7 +1455,7 @@ bool NormalLaneChange::getLaneChangePaths( RCLCPP_DEBUG(logger_, " - sampling num for lat_acc: %lu", sample_lat_acc.size()); for (const auto & lateral_acc : sample_lat_acc) { - const auto debug_print = [&](const auto & s) { + const auto debug_print_lat = [&](const auto & s) { RCLCPP_DEBUG_STREAM( logger_, " - " << s << " : prep_time = " << prepare_duration << ", lon_acc = " << sampled_longitudinal_acc << ", lat_acc = " << lateral_acc); @@ -1477,7 +1477,7 @@ bool NormalLaneChange::getLaneChangePaths( prepare_segment, current_velocity, terminal_lane_changing_velocity); if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) { - debug_print("Reject: length of lane changing path is longer than length to goal!!"); + debug_print_lat("Reject: length of lane changing path is longer than length to goal!!"); continue; } @@ -1496,7 +1496,7 @@ bool NormalLaneChange::getLaneChangePaths( s_start + lane_changing_length + finish_judge_buffer + backward_buffer + next_lane_change_buffer > s_goal) { - debug_print("Reject: length of lane changing path is longer than length to goal!!"); + debug_print_lat("Reject: length of lane changing path is longer than length to goal!!"); continue; } } @@ -1506,7 +1506,7 @@ bool NormalLaneChange::getLaneChangePaths( initial_lane_changing_velocity, next_lane_change_buffer); if (target_segment.points.empty()) { - debug_print("Reject: target segment is empty!! something wrong..."); + debug_print_lat("Reject: target segment is empty!! something wrong..."); continue; } @@ -1537,7 +1537,7 @@ bool NormalLaneChange::getLaneChangePaths( lane_change_info.terminal_lane_changing_velocity = terminal_lane_changing_velocity; if (!is_valid_start_point) { - debug_print( + debug_print_lat( "Reject: lane changing points are not inside of the target preferred lanes or its " "neighbors"); continue; @@ -1551,7 +1551,7 @@ bool NormalLaneChange::getLaneChangePaths( next_lane_change_buffer); if (target_lane_reference_path.points.empty()) { - debug_print("Reject: target_lane_reference_path is empty!!"); + debug_print_lat("Reject: target_lane_reference_path is empty!!"); continue; } @@ -1563,12 +1563,12 @@ bool NormalLaneChange::getLaneChangePaths( sorted_lane_ids); if (!candidate_path) { - debug_print("Reject: failed to generate candidate path!!"); + debug_print_lat("Reject: failed to generate candidate path!!"); continue; } if (!hasEnoughLength(*candidate_path, current_lanes, target_lanes, direction)) { - debug_print("Reject: invalid candidate path!!"); + debug_print_lat("Reject: invalid candidate path!!"); continue; } @@ -1576,7 +1576,7 @@ bool NormalLaneChange::getLaneChangePaths( lane_change_parameters_->regulate_on_crosswalk && !hasEnoughLengthToCrosswalk(*candidate_path, current_lanes)) { if (getStopTime() < lane_change_parameters_->stop_time_threshold) { - debug_print("Reject: including crosswalk!!"); + debug_print_lat("Reject: including crosswalk!!"); continue; } RCLCPP_INFO_THROTTLE( @@ -1587,7 +1587,7 @@ bool NormalLaneChange::getLaneChangePaths( lane_change_parameters_->regulate_on_intersection && !hasEnoughLengthToIntersection(*candidate_path, current_lanes)) { if (getStopTime() < lane_change_parameters_->stop_time_threshold) { - debug_print("Reject: including intersection!!"); + debug_print_lat("Reject: including intersection!!"); continue; } RCLCPP_WARN_STREAM( @@ -1597,14 +1597,14 @@ bool NormalLaneChange::getLaneChangePaths( if ( lane_change_parameters_->regulate_on_traffic_light && !hasEnoughLengthToTrafficLight(*candidate_path, current_lanes)) { - debug_print("Reject: regulate on traffic light!!"); + debug_print_lat("Reject: regulate on traffic light!!"); continue; } if (utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance( lane_change_info.current_lanes, candidate_path.value().path, planner_data_, lane_change_info.length.sum())) { - debug_print("Ego is stopping near traffic light. Do not allow lane change"); + debug_print_lat("Ego is stopping near traffic light. Do not allow lane change"); continue; } candidate_paths->push_back(*candidate_path); @@ -1614,14 +1614,14 @@ bool NormalLaneChange::getLaneChangePaths( route_handler, *candidate_path, filtered_objects.target_lane, lane_change_buffer, is_goal_in_route, *lane_change_parameters_, lane_change_debug_.collision_check_objects)) { - debug_print( + debug_print_lat( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " "lane change."); return false; } if (!check_safety) { - debug_print("ACCEPT!!!: it is valid (and safety check is skipped)."); + debug_print_lat("ACCEPT!!!: it is valid (and safety check is skipped)."); return false; } @@ -1629,11 +1629,11 @@ bool NormalLaneChange::getLaneChangePaths( *candidate_path, target_objects, rss_params, lane_change_debug_.collision_check_objects); if (is_safe) { - debug_print("ACCEPT!!!: it is valid and safe!"); + debug_print_lat("ACCEPT!!!: it is valid and safe!"); return true; } - debug_print("Reject: sampled path is not safe."); + debug_print_lat("Reject: sampled path is not safe."); } } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index d989a1e6d301d..9568f803773c4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -888,7 +888,7 @@ bool isParkedObject( const auto most_left_lanelet_candidates = route_handler.getLaneletMapPtr()->laneletLayer.findUsages(most_left_road_lanelet.leftBound()); lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet; - const lanelet::Attribute sub_type = + const lanelet::Attribute most_left_sub_type = most_left_lanelet.attribute(lanelet::AttributeName::Subtype); for (const auto & ll : most_left_lanelet_candidates) { @@ -898,7 +898,7 @@ bool isParkedObject( } } bound = most_left_lanelet.leftBound2d().basicLineString(); - if (sub_type.value() != "road_shoulder") { + if (most_left_sub_type.value() != "road_shoulder") { center_to_bound_buffer = object_check_min_road_shoulder_width; } } else { @@ -909,7 +909,7 @@ bool isParkedObject( most_right_road_lanelet.rightBound()); lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet; - const lanelet::Attribute sub_type = + const lanelet::Attribute most_right_sub_type = most_right_lanelet.attribute(lanelet::AttributeName::Subtype); for (const auto & ll : most_right_lanelet_candidates) { @@ -919,7 +919,7 @@ bool isParkedObject( } } bound = most_right_lanelet.rightBound2d().basicLineString(); - if (sub_type.value() != "road_shoulder") { + if (most_right_sub_type.value() != "road_shoulder") { center_to_bound_buffer = object_check_min_road_shoulder_width; } } From 3e4d2d0310cf358ca9ab5797adeaf0f45a224642 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 12 Jul 2024 22:32:34 +0900 Subject: [PATCH 069/151] refactor(lane_change): update lanes and its polygons only when it's updated (#7989) * refactor(lane_change): compute lanes and polygon only when updated Signed-off-by: Zulfaqar Azmi * Revert accidental changesd This reverts commit cbfd9ae8a88b2d6c3b27b35c9a08bb824ecd5011. Signed-off-by: Zulfaqar Azmi * fix spell check Signed-off-by: Zulfaqar Azmi * Make a common getter for current lanes Signed-off-by: Zulfaqar Azmi * add target lanes getter Signed-off-by: Zulfaqar Azmi * some minor function refactoring Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/scene.cpp | 4 +- .../scene.hpp | 13 +- .../utils/base_class.hpp | 19 +- .../utils/data_structs.hpp | 40 ++-- .../utils/path.hpp | 24 +- .../utils/utils.hpp | 22 +- .../src/interface.cpp | 3 +- .../src/scene.cpp | 218 ++++++++++-------- .../src/utils/utils.cpp | 76 ++++-- 9 files changed, 246 insertions(+), 173 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp index a7a7b30e4eec0..2c3e716151df8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -135,7 +135,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( const auto resample_interval = avoidance_parameters_->resample_interval_for_planning; data.reference_path = utils::resamplePathWithSpline(data.reference_path_rough, resample_interval); - data.current_lanelets = getCurrentLanes(); + data.current_lanelets = get_current_lanes(); fillAvoidanceTargetObjects(data, debug); @@ -275,7 +275,7 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_ double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const { - const auto current_lanes = getCurrentLanes(); + const auto current_lanes = get_current_lanes(); if (current_lanes.empty()) { RCLCPP_DEBUG(logger_, "no empty lanes"); return std::numeric_limits::infinity(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index be62492b7c2cc..dad96d5f7371a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -51,6 +51,8 @@ class NormalLaneChange : public LaneChangeBase NormalLaneChange & operator=(NormalLaneChange &&) = delete; ~NormalLaneChange() override = default; + void update_lanes(const bool is_approved) final; + void updateLaneChangeStatus() override; std::pair getSafePath(LaneChangePath & safe_path) const override; @@ -105,8 +107,6 @@ class NormalLaneChange : public LaneChangeBase TurnSignalInfo get_current_turn_signal_info() override; protected: - lanelet::ConstLanelets getCurrentLanes() const override; - lanelet::ConstLanelets getLaneChangeLanes( const lanelet::ConstLanelets & current_lanes, Direction direction) const override; @@ -124,9 +124,7 @@ class NormalLaneChange : public LaneChangeBase const LaneChangeLanesFilteredObjects & predicted_objects, const lanelet::ConstLanelets & current_lanes) const; - LaneChangeLanesFilteredObjects filterObjects( - const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes) const; + LaneChangeLanesFilteredObjects filterObjects() const; void filterOncomingObjects(PredictedObjects & objects) const; @@ -203,6 +201,11 @@ class NormalLaneChange : public LaneChangeBase double getStopTime() const { return stop_time_; } + const lanelet::ConstLanelets & get_target_lanes() const + { + return common_data_ptr_->lanes_ptr->target; + } + double stop_time_{0.0}; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index cbd3a81827948..c1cc14d98a7c7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -65,6 +65,8 @@ class LaneChangeBase LaneChangeBase & operator=(LaneChangeBase &&) = delete; virtual ~LaneChangeBase() = default; + virtual void update_lanes(const bool is_approved) = 0; + virtual void updateLaneChangeStatus() = 0; virtual std::pair getSafePath(LaneChangePath & safe_path) const = 0; @@ -139,6 +141,11 @@ class LaneChangeBase const Twist & getEgoTwist() const { return planner_data_->self_odometry->twist.twist; } + const lanelet::ConstLanelets & get_current_lanes() const + { + return common_data_ptr_->lanes_ptr->current; + } + const BehaviorPathPlannerParameters & getCommonParam() const { return planner_data_->parameters; } LaneChangeParameters getLaneChangeParam() const { return *lane_change_parameters_; } @@ -163,9 +170,19 @@ class LaneChangeBase common_data_ptr_->bpp_param_ptr = std::make_shared(data->parameters); } + + if (!common_data_ptr_->lanes_ptr) { + common_data_ptr_->lanes_ptr = std::make_shared(); + } + + if (!common_data_ptr_->lanes_polygon_ptr) { + common_data_ptr_->lanes_polygon_ptr = std::make_shared(); + } + common_data_ptr_->self_odometry_ptr = data->self_odometry; common_data_ptr_->route_handler_ptr = data->route_handler; common_data_ptr_->lc_param_ptr = lane_change_parameters_; + common_data_ptr_->lc_type = type_; common_data_ptr_->direction = direction_; } @@ -211,8 +228,6 @@ class LaneChangeBase virtual TurnSignalInfo get_current_turn_signal_info() = 0; protected: - virtual lanelet::ConstLanelets getCurrentLanes() const = 0; - virtual int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const = 0; virtual PathWithLaneId getPrepareSegment( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 2fdf7c6b550a3..1bb4dfdeb59dc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -183,6 +183,13 @@ struct PhaseInfo } }; +struct Lanes +{ + lanelet::ConstLanelets current; + lanelet::ConstLanelets target; + std::vector preceding_target; +}; + struct Info { PhaseInfo longitudinal_acceleration{0.0, 0.0}; @@ -190,9 +197,6 @@ struct Info PhaseInfo duration{0.0, 0.0}; PhaseInfo length{0.0, 0.0}; - lanelet::ConstLanelets current_lanes{}; - lanelet::ConstLanelets target_lanes{}; - Pose lane_changing_start{}; Pose lane_changing_end{}; @@ -225,23 +229,26 @@ struct LanesPolygon { std::optional current; std::optional target; - std::vector target_backward; + std::optional expanded_target; + lanelet::BasicPolygon2d target_neighbor; + std::vector preceding_target; }; -struct Lanes -{ - lanelet::ConstLanelets current; - lanelet::ConstLanelets target; - std::vector preceding_target; -}; +using RouteHandlerPtr = std::shared_ptr; +using BppParamPtr = std::shared_ptr; +using LCParamPtr = std::shared_ptr; +using LanesPtr = std::shared_ptr; +using LanesPolygonPtr = std::shared_ptr; struct CommonData { - std::shared_ptr route_handler_ptr; + RouteHandlerPtr route_handler_ptr; Odometry::ConstSharedPtr self_odometry_ptr; - std::shared_ptr bpp_param_ptr; - std::shared_ptr lc_param_ptr; - Lanes lanes; + BppParamPtr bpp_param_ptr; + LCParamPtr lc_param_ptr; + LanesPtr lanes_ptr; + LanesPolygonPtr lanes_polygon_ptr; + ModuleType lc_type; Direction direction; [[nodiscard]] Pose get_ego_pose() const { return self_odometry_ptr->pose.pose; } @@ -259,12 +266,7 @@ struct CommonData return std::hypot(x, y); } }; - -using RouteHandlerPtr = std::shared_ptr; -using BppParamPtr = std::shared_ptr; -using LCParamPtr = std::shared_ptr; using CommonDataPtr = std::shared_ptr; -using LanesPtr = std::shared_ptr; } // namespace autoware::behavior_path_planner::lane_change namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp index 97b5c621deea5..5623f03a22eb3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -23,31 +23,31 @@ #include -namespace autoware::behavior_path_planner +namespace autoware::behavior_path_planner::lane_change { using autoware::behavior_path_planner::TurnSignalInfo; using tier4_planning_msgs::msg::PathWithLaneId; -struct LaneChangePath +struct Path { PathWithLaneId path{}; ShiftedPath shifted_path{}; - LaneChangeInfo info; - bool is_safe{false}; + Info info{}; }; -using LaneChangePaths = std::vector; -struct LaneChangeStatus +struct Status { - PathWithLaneId lane_follow_path{}; - LaneChangePath lane_change_path{}; - lanelet::ConstLanelets current_lanes{}; - lanelet::ConstLanelets target_lanes{}; - std::vector lane_follow_lane_ids{}; - std::vector lane_change_lane_ids{}; + Path lane_change_path{}; bool is_safe{false}; bool is_valid_path{false}; double start_distance{0.0}; }; +} // namespace autoware::behavior_path_planner::lane_change + +namespace autoware::behavior_path_planner +{ +using LaneChangePath = lane_change::Path; +using LaneChangePaths = std::vector; +using LaneChangeStatus = lane_change::Status; } // namespace autoware::behavior_path_planner #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index e25b67bdb73d8..17eaceb055fc1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -48,6 +48,7 @@ using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; +using behavior_path_planner::lane_change::CommonDataPtr; using behavior_path_planner::lane_change::LanesPolygon; using behavior_path_planner::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; @@ -114,8 +115,9 @@ bool isPathInLanelets( const lanelet::ConstLanelets & target_lanes); std::optional constructCandidatePath( - const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, - const PathWithLaneId & target_segment, const PathWithLaneId & target_lane_reference_path, + const CommonDataPtr & common_data_ptr, const LaneChangeInfo & lane_change_info, + const PathWithLaneId & prepare_segment, const PathWithLaneId & target_segment, + const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids); ShiftLine getLaneChangingShiftLine( @@ -177,10 +179,9 @@ bool isParkedObject( const double ratio_threshold); bool passParkedObject( - const RouteHandler & route_handler, const LaneChangePath & lane_change_path, + const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, const std::vector & objects, const double minimum_lane_change_length, - const bool is_goal_in_route, const LaneChangeParameters & lane_change_parameters, - CollisionCheckDebugMap & object_debug); + const bool is_goal_in_route, CollisionCheckDebugMap & object_debug); std::optional getLeadingStaticObjectIdx( const RouteHandler & route_handler, const LaneChangePath & lane_change_path, @@ -195,7 +196,8 @@ ExtendedPredictedObject transform( const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase); bool isCollidedPolygonsInLanelet( - const std::vector & collided_polygons, const lanelet::ConstLanelets & lanes); + const std::vector & collided_polygons, + const std::optional & lanes_polygon); /** * @brief Generates expanded lanelets based on the given direction and offsets. @@ -295,9 +297,11 @@ double calcPhaseLength( const double velocity, const double maximum_velocity, const double acceleration, const double time); -LanesPolygon createLanesPolygon( - const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, - const std::vector & target_backward_lanes); +LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr); + +bool is_same_lane_with_prev_iteration( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes); } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index b55b41828081e..4823cb0bfec22 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -75,6 +75,7 @@ void LaneChangeInterface::updateData() { universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper()); module_type_->setPreviousModuleOutput(getPreviousModuleOutput()); + module_type_->update_lanes(getCurrentStatus() == ModuleStatus::RUNNING); module_type_->updateSpecialData(); if (isWaitingApproval() || module_type_->isAbortState()) { @@ -136,7 +137,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() *prev_approved_path_ = getPreviousModuleOutput().path; BehaviorModuleOutput out = getPreviousModuleOutput(); - module_type_->insertStopPoint(module_type_->getLaneChangeStatus().current_lanes, out.path); + module_type_->insertStopPoint(module_type_->get_current_lanes(), out.path); out.turn_signal_info = module_type_->get_current_turn_signal_info(); const auto & lane_change_debug = module_type_->getDebugData(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index c26f54e905b47..659e5b78bf577 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -41,7 +41,7 @@ namespace autoware::behavior_path_planner { using autoware::motion_utils::calcSignedArcLength; using utils::lane_change::calcMinimumLaneChangeLength; -using utils::lane_change::createLanesPolygon; +using utils::lane_change::create_lanes_polygon; using utils::path_safety_checker::isPolygonOverlapLanelet; using utils::traffic_light::getDistanceToNextTrafficLight; @@ -54,6 +54,42 @@ NormalLaneChange::NormalLaneChange( stop_watch_.tic("stop_time"); } +void NormalLaneChange::update_lanes(const bool is_approved) +{ + if (is_approved) { + return; + } + + const auto current_lanes = + utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); + + if (current_lanes.empty()) { + return; + } + + const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); + if (target_lanes.empty()) { + return; + } + + const auto is_same_lanes_with_prev_iteration = + utils::lane_change::is_same_lane_with_prev_iteration( + common_data_ptr_, current_lanes, target_lanes); + + if (is_same_lanes_with_prev_iteration) { + return; + } + + common_data_ptr_->lanes_ptr->current = current_lanes; + common_data_ptr_->lanes_ptr->target = target_lanes; + + common_data_ptr_->lanes_ptr->preceding_target = utils::getPrecedingLanelets( + *common_data_ptr_->route_handler_ptr, get_target_lanes(), common_data_ptr_->get_ego_pose(), + common_data_ptr_->lc_param_ptr->backward_lane_length); + + *common_data_ptr_->lanes_polygon_ptr = create_lanes_polygon(common_data_ptr_); +} + void NormalLaneChange::updateLaneChangeStatus() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -61,35 +97,23 @@ void NormalLaneChange::updateLaneChangeStatus() const auto [found_valid_path, found_safe_path] = getSafePath(status_.lane_change_path); // Update status - status_.current_lanes = status_.lane_change_path.info.current_lanes; - status_.target_lanes = status_.lane_change_path.info.target_lanes; status_.is_valid_path = found_valid_path; status_.is_safe = found_safe_path; - status_.lane_follow_lane_ids = utils::getIds(status_.current_lanes); - status_.lane_change_lane_ids = utils::getIds(status_.target_lanes); - const auto arclength_start = - lanelet::utils::getArcCoordinates(status_.target_lanes, getEgoPose()); + const auto arclength_start = lanelet::utils::getArcCoordinates(get_target_lanes(), getEgoPose()); status_.start_distance = arclength_start.length; status_.lane_change_path.path.header = getRouteHeader(); } std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) const { - const auto current_lanes = getCurrentLanes(); - - if (current_lanes.empty()) { - return {false, false}; - } + const auto & current_lanes = get_current_lanes(); + const auto & target_lanes = get_target_lanes(); - const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); - - if (target_lanes.empty()) { - safe_path.info.current_lanes = current_lanes; + if (current_lanes.empty() || target_lanes.empty()) { return {false, false}; } - // find candidate paths LaneChangePaths valid_paths{}; const bool is_stuck = isVehicleStuck(current_lanes); bool found_safe_path = getLaneChangePaths( @@ -105,8 +129,6 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) lane_change_debug_.valid_paths = valid_paths; if (valid_paths.empty()) { - safe_path.info.current_lanes = current_lanes; - safe_path.info.target_lanes = target_lanes; return {false, false}; } @@ -122,21 +144,22 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) bool NormalLaneChange::isLaneChangeRequired() { - status_.current_lanes = getCurrentLanes(); + const auto current_lanes = + utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); - if (status_.current_lanes.empty()) { + if (current_lanes.empty()) { return false; } - status_.target_lanes = getLaneChangeLanes(status_.current_lanes, direction_); + const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); - return !status_.target_lanes.empty(); + return !target_lanes.empty(); } bool NormalLaneChange::isStoppedAtRedTrafficLight() const { return utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance( - status_.current_lanes, status_.lane_change_path.path, planner_data_, + get_current_lanes(), status_.lane_change_path.path, planner_data_, status_.lane_change_path.info.length.sum()); } @@ -144,7 +167,7 @@ TurnSignalInfo NormalLaneChange::get_current_turn_signal_info() { const auto original_turn_signal_info = prev_module_output_.turn_signal_info; - const auto & current_lanes = getLaneChangeStatus().current_lanes; + const auto & current_lanes = get_current_lanes(); const auto is_valid = getLaneChangeStatus().is_valid_path; const auto & lane_change_path = getLaneChangeStatus().lane_change_path; const auto & lane_change_param = getLaneChangeParam(); @@ -237,7 +260,7 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const return output; } - const auto current_lanes = getCurrentLanes(); + const auto & current_lanes = get_current_lanes(); if (current_lanes.empty()) { RCLCPP_DEBUG(logger_, "Current lanes not found. Returning previous module's path as output."); return prev_module_output_; @@ -275,7 +298,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() auto output = prev_module_output_; if (isAbortState() && abort_path_) { output.path = abort_path_->path; - insertStopPoint(status_.current_lanes, output.path); + insertStopPoint(get_current_lanes(), output.path); } else { output.path = getLaneChangePath().path; @@ -295,7 +318,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, output.path); setStopPose(stop_point.point.pose); } else { - insertStopPoint(status_.target_lanes, output.path); + insertStopPoint(get_target_lanes(), output.path); } } @@ -316,7 +339,7 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) c const auto & dp = planner_data_->drivable_area_expansion_parameters; const auto drivable_lanes = utils::lane_change::generateDrivableLanes( - *getRouteHandler(), status_.current_lanes, status_.target_lanes); + *getRouteHandler(), get_current_lanes(), get_target_lanes()); const auto shorten_lanes = utils::cutOverlappedLanes(output.path, drivable_lanes); const auto expanded_lanes = utils::expandLanelets( shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, @@ -362,15 +385,14 @@ void NormalLaneChange::insertStopPoint( } const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; - const auto target_objects = filterObjects(status_.current_lanes, status_.target_lanes); + const auto target_objects = filterObjects(); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; const auto is_valid_start_point = std::invoke([&]() -> bool { auto lc_start_point = lanelet::utils::conversion::toLaneletPoint( status_.lane_change_path.info.lane_changing_start.position); - const auto target_neighbor_preferred_lane_poly_2d = - utils::lane_change::getTargetNeighborLanesPolygon( - *route_handler, status_.current_lanes, type_); + const auto & target_neighbor_preferred_lane_poly_2d = + common_data_ptr_->lanes_polygon_ptr->target_neighbor; return boost::geometry::covered_by( lanelet::traits::to2D(lc_start_point), target_neighbor_preferred_lane_poly_2d); }); @@ -450,7 +472,7 @@ void NormalLaneChange::insertStopPoint( // target_objects includes objects out of target lanes, so filter them out if (!boost::geometry::intersects( autoware::universe_utils::toPolygon2d(o.initial_pose.pose, o.shape).outer(), - lanelet::utils::combineLaneletsShape(status_.target_lanes) + lanelet::utils::combineLaneletsShape(get_target_lanes()) .polygon2d() .basicPolygon())) { return false; @@ -477,7 +499,7 @@ PathWithLaneId NormalLaneChange::getReferencePath() const universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); lanelet::ConstLanelet closest_lanelet; if (!lanelet::utils::query::getClosestLanelet( - status_.lane_change_path.info.target_lanes, getEgoPose(), &closest_lanelet)) { + get_target_lanes(), getEgoPose(), &closest_lanelet)) { return prev_module_output_.reference_path; } const auto reference_path = utils::getCenterLinePathFromLanelet(closest_lanelet, planner_data_); @@ -499,7 +521,7 @@ std::optional NormalLaneChange::extendPath() return std::nullopt; } - auto & target_lanes = status_.target_lanes; + auto & target_lanes = common_data_ptr_->lanes_ptr->target; const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes); const auto dist_in_target = lanelet::utils::getArcCoordinates(target_lanes, getEgoPose()); @@ -570,7 +592,7 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & pose = getEgoPose(); - const auto & current_lanes = status_.current_lanes; + const auto & current_lanes = get_current_lanes(); const auto & shift_line = status_.lane_change_path.info.shift_line; const auto & shift_path = status_.lane_change_path.shifted_path; const auto current_shift_length = lanelet::utils::getArcCoordinates(current_lanes, pose).distance; @@ -585,11 +607,6 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const return new_signal; } -lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const -{ - return utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); -} - lanelet::ConstLanelets NormalLaneChange::getLaneChangeLanes( const lanelet::ConstLanelets & current_lanes, Direction direction) const { @@ -667,8 +684,9 @@ bool NormalLaneChange::hasFinishedLaneChange() const { const auto & current_pose = getEgoPose(); const auto & lane_change_end = status_.lane_change_path.info.shift_line.end; - const double dist_to_lane_change_end = utils::getSignedDistance( - current_pose, lane_change_end, status_.lane_change_path.info.target_lanes); + const auto & target_lanes = get_target_lanes(); + const double dist_to_lane_change_end = + utils::getSignedDistance(current_pose, lane_change_end, get_target_lanes()); double finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer; // If ego velocity is low, relax finish judge buffer @@ -686,7 +704,7 @@ bool NormalLaneChange::hasFinishedLaneChange() const return false; } - const auto arc_length = lanelet::utils::getArcCoordinates(status_.target_lanes, current_pose); + const auto arc_length = lanelet::utils::getArcCoordinates(target_lanes, current_pose); const auto reach_target_lane = std::abs(arc_length.distance) < lane_change_parameters_->finish_judge_lateral_threshold; @@ -703,7 +721,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const } if (!utils::isEgoWithinOriginalLane( - status_.current_lanes, getEgoPose(), planner_data_->parameters, + get_current_lanes(), getEgoPose(), planner_data_->parameters, lane_change_parameters_->cancel.overhang_tolerance)) { lane_change_debug_.is_able_to_return_to_current_lane = false; return false; @@ -724,7 +742,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const if (dist > estimated_travel_dist) { const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose; auto is_ego_within_original_lane = utils::isEgoWithinOriginalLane( - status_.current_lanes, estimated_pose, planner_data_->parameters, + get_current_lanes(), estimated_pose, planner_data_->parameters, lane_change_parameters_->cancel.overhang_tolerance); lane_change_debug_.is_able_to_return_to_current_lane = is_ego_within_original_lane; return is_ego_within_original_lane; @@ -763,7 +781,7 @@ bool NormalLaneChange::isAbleToStopSafely() const if (dist > stop_dist) { const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose; return utils::isEgoWithinOriginalLane( - status_.current_lanes, estimated_pose, planner_data_->parameters); + get_current_lanes(), estimated_pose, planner_data_->parameters); } } return true; @@ -963,8 +981,7 @@ ExtendedPredictedObjects NormalLaneChange::getTargetObjects( return target_objects; } -LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects( - const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const +LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const { const auto & current_pose = getEgoPose(); const auto & route_handler = getRouteHandler(); @@ -983,6 +1000,12 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects( return {}; } + const auto & current_lanes = get_current_lanes(); + + if (current_lanes.empty()) { + return {}; + } + filterAheadTerminalObjects(objects, current_lanes); if (objects.objects.empty()) { @@ -993,6 +1016,12 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects( std::vector current_lane_objects; std::vector other_lane_objects; + const auto & target_lanes = get_target_lanes(); + + if (target_lanes.empty()) { + return {}; + } + filterObjectsByLanelets( objects, current_lanes, target_lanes, current_lane_objects, target_lane_objects, other_lane_objects); @@ -1133,9 +1162,7 @@ void NormalLaneChange::filterObjectsByLanelets( }; // get backward lanes - const auto backward_length = lane_change_parameters_->backward_lane_length; - const auto target_backward_lanes = - utils::getPrecedingLanelets(*route_handler, target_lanes, current_pose, backward_length); + const auto & target_backward_lanes = common_data_ptr_->lanes_ptr->preceding_target; { lane_change_debug_.current_lanes = current_lanes; @@ -1152,12 +1179,7 @@ void NormalLaneChange::filterObjectsByLanelets( }); } - const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( - target_lanes, direction_, lane_change_parameters_->lane_expansion_left_offset, - lane_change_parameters_->lane_expansion_right_offset); - - const auto lanes_polygon = - createLanesPolygon(current_lanes, expanded_target_lanes, target_backward_lanes); + const auto & lanes_polygon = *common_data_ptr_->lanes_polygon_ptr; const auto dist_ego_to_current_lanes_center = lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); @@ -1177,7 +1199,7 @@ void NormalLaneChange::filterObjectsByLanelets( return std::abs(lateral) > (common_parameters.vehicle_width / 2); }); - if (check_optional_polygon(object, lanes_polygon.target) && is_lateral_far) { + if (check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far) { target_lane_objects.push_back(object); continue; } @@ -1187,7 +1209,7 @@ void NormalLaneChange::filterObjectsByLanelets( return isPolygonOverlapLanelet(object, target_backward_polygon); }; return std::any_of( - lanes_polygon.target_backward.begin(), lanes_polygon.target_backward.end(), + lanes_polygon.preceding_target.begin(), lanes_polygon.preceding_target.end(), check_backward_polygon); }); @@ -1377,14 +1399,14 @@ bool NormalLaneChange::getLaneChangePaths( const auto sorted_lane_ids = utils::lane_change::getSortedLaneIds(route_handler, getEgoPose(), current_lanes, target_lanes); - const auto target_neighbor_preferred_lane_poly_2d = - utils::lane_change::getTargetNeighborLanesPolygon(route_handler, current_lanes, type_); + const auto & target_neighbor_preferred_lane_poly_2d = + common_data_ptr_->lanes_polygon_ptr->target_neighbor; if (target_neighbor_preferred_lane_poly_2d.empty()) { RCLCPP_WARN(logger_, "target_neighbor_preferred_lane_poly_2d is empty. Not expected."); return false; } - const auto filtered_objects = filterObjects(current_lanes, target_lanes); + const auto filtered_objects = filterObjects(); const auto target_objects = getTargetObjects(filtered_objects, current_lanes); const auto prepare_durations = calcPrepareDuration(current_lanes, target_lanes); @@ -1514,9 +1536,7 @@ bool NormalLaneChange::getLaneChangePaths( prepare_segment.points.back().point.pose.position.x, prepare_segment.points.back().point.pose.position.y); - const auto target_lane_polygon = lanelet::utils::getPolygonFromArcLength( - target_lanes, 0, std::numeric_limits::max()); - const auto target_lane_poly_2d = lanelet::utils::to2D(target_lane_polygon).basicPolygon(); + const auto target_lane_poly_2d = common_data_ptr_->lanes_polygon_ptr->target.value(); const auto is_valid_start_point = boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) || @@ -1529,8 +1549,6 @@ bool NormalLaneChange::getLaneChangePaths( lane_change_info.velocity = LaneChangePhaseInfo{prepare_velocity, initial_lane_changing_velocity}; lane_change_info.length = LaneChangePhaseInfo{prepare_length, lane_changing_length}; - lane_change_info.current_lanes = current_lanes; - lane_change_info.target_lanes = target_lanes; lane_change_info.lane_changing_start = prepare_segment.points.back().point.pose; lane_change_info.lane_changing_end = target_segment.points.front().point.pose; lane_change_info.lateral_acceleration = lateral_acc; @@ -1559,8 +1577,8 @@ bool NormalLaneChange::getLaneChangePaths( prepare_segment, target_segment, target_lane_reference_path, shift_length); const auto candidate_path = utils::lane_change::constructCandidatePath( - lane_change_info, prepare_segment, target_segment, target_lane_reference_path, - sorted_lane_ids); + common_data_ptr_, lane_change_info, prepare_segment, target_segment, + target_lane_reference_path, sorted_lane_ids); if (!candidate_path) { debug_print_lat("Reject: failed to generate candidate path!!"); @@ -1602,7 +1620,7 @@ bool NormalLaneChange::getLaneChangePaths( } if (utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance( - lane_change_info.current_lanes, candidate_path.value().path, planner_data_, + get_current_lanes(), candidate_path.value().path, planner_data_, lane_change_info.length.sum())) { debug_print_lat("Ego is stopping near traffic light. Do not allow lane change"); continue; @@ -1610,10 +1628,10 @@ bool NormalLaneChange::getLaneChangePaths( candidate_paths->push_back(*candidate_path); if ( - !is_stuck && utils::lane_change::passParkedObject( - route_handler, *candidate_path, filtered_objects.target_lane, - lane_change_buffer, is_goal_in_route, *lane_change_parameters_, - lane_change_debug_.collision_check_objects)) { + !is_stuck && + utils::lane_change::passParkedObject( + common_data_ptr_, *candidate_path, filtered_objects.target_lane, lane_change_buffer, + is_goal_in_route, lane_change_debug_.collision_check_objects)) { debug_print_lat( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " "lane change."); @@ -1671,7 +1689,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( utils::lane_change::getSortedLaneIds(route_handler, getEgoPose(), current_lanes, target_lanes); const auto target_neighbor_preferred_lane_poly_2d = - utils::lane_change::getTargetNeighborLanesPolygon(route_handler, current_lanes, type_); + common_data_ptr_->lanes_polygon_ptr->target_neighbor; if (target_neighbor_preferred_lane_poly_2d.empty()) { RCLCPP_WARN(logger_, "target_neighbor_preferred_lane_poly_2d is empty. Not expected."); return {}; @@ -1726,9 +1744,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( const lanelet::BasicPoint2d lc_start_point( lane_changing_start_pose->position.x, lane_changing_start_pose->position.y); - const auto target_lane_polygon = - lanelet::utils::getPolygonFromArcLength(target_lanes, 0, std::numeric_limits::max()); - const auto target_lane_poly_2d = lanelet::utils::to2D(target_lane_polygon).basicPolygon(); + const auto & target_lane_poly_2d = common_data_ptr_->lanes_polygon_ptr->target.value(); const auto is_valid_start_point = boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) || @@ -1740,8 +1756,6 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( lane_change_info.velocity = LaneChangePhaseInfo{minimum_lane_changing_velocity, minimum_lane_changing_velocity}; lane_change_info.length = LaneChangePhaseInfo{0.0, lane_change_buffer}; - lane_change_info.current_lanes = current_lanes; - lane_change_info.target_lanes = target_lanes; lane_change_info.lane_changing_start = lane_changing_start_pose.value(); lane_change_info.lane_changing_end = target_segment.points.front().point.pose; lane_change_info.lateral_acceleration = max_lateral_acc; @@ -1781,8 +1795,8 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( reference_segment.points.back().point.longitudinal_velocity_mps = minimum_lane_changing_velocity; const auto terminal_lane_change_path = utils::lane_change::constructCandidatePath( - lane_change_info, reference_segment, target_segment, target_lane_reference_path, - sorted_lane_ids); + common_data_ptr_, lane_change_info, reference_segment, target_segment, + target_lane_reference_path, sorted_lane_ids); return terminal_lane_change_path; } @@ -1790,10 +1804,14 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const { const auto & path = status_.lane_change_path; - const auto & current_lanes = status_.current_lanes; - const auto & target_lanes = status_.target_lanes; + const auto & current_lanes = get_current_lanes(); + const auto & target_lanes = get_target_lanes(); + + if (current_lanes.empty() || target_lanes.empty()) { + return {true, true}; + } - const auto filtered_objects = filterObjects(current_lanes, target_lanes); + const auto filtered_objects = filterObjects(); const auto target_objects = getTargetObjects(filtered_objects, current_lanes); CollisionCheckDebugMap debug_data; @@ -1848,8 +1866,8 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const // check lane departure const auto drivable_lanes = utils::lane_change::generateDrivableLanes( - *route_handler, utils::extendLanes(route_handler, status_.current_lanes), - utils::extendLanes(route_handler, status_.target_lanes)); + *route_handler, utils::extendLanes(route_handler, get_current_lanes()), + utils::extendLanes(route_handler, get_target_lanes())); const auto expanded_lanes = utils::expandLanelets( drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); @@ -1883,7 +1901,7 @@ bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto threshold = lane_change_parameters_->backward_length_buffer_for_end_of_lane; if ( - isNearEndOfCurrentLanes(status_.current_lanes, status_.target_lanes, threshold) && + isNearEndOfCurrentLanes(get_current_lanes(), get_target_lanes(), threshold) && isAbleToStopSafely() && is_object_coming_from_rear) { current_lane_change_state_ = LaneChangeStates::Stop; return true; @@ -1901,16 +1919,16 @@ bool NormalLaneChange::calcAbortPath() std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()); const auto current_pose = getEgoPose(); const auto & selected_path = status_.lane_change_path; - const auto reference_lanelets = selected_path.info.current_lanes; const auto ego_nearest_dist_threshold = common_param.ego_nearest_dist_threshold; const auto ego_nearest_yaw_threshold = common_param.ego_nearest_yaw_threshold; const auto direction = getDirection(); const auto minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( - route_handler, selected_path.info.current_lanes.back(), *lane_change_parameters_, direction); + route_handler, get_current_lanes().back(), *lane_change_parameters_, direction); const auto & lane_changing_path = selected_path.path; + const auto & reference_lanelets = get_current_lanes(); const auto lane_changing_end_pose_idx = std::invoke([&]() { constexpr double s_start = 0.0; const double s_end = std::max( @@ -1999,7 +2017,7 @@ bool NormalLaneChange::calcAbortPath() auto reference_lane_segment = prev_module_output_.path; { // const auto terminal_path = - // calcTerminalLaneChangePath(reference_lanelets, selected_path.info.target_lanes); + // calcTerminalLaneChangePath(reference_lanelets, get_target_lanes()); // if (terminal_path) { // reference_lane_segment = terminal_path->path; // } @@ -2064,12 +2082,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const auto debug_predicted_path = utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); - const auto current_lanes = getCurrentLanes(); - - const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( - lane_change_path.info.target_lanes, direction_, - lane_change_parameters_->lane_expansion_left_offset, - lane_change_parameters_->lane_expansion_right_offset); + const auto & current_lanes_polygon = common_data_ptr_->lanes_polygon_ptr->current; + const auto & expanded_target_polygon = common_data_ptr_->lanes_polygon_ptr->expanded_target; constexpr double collision_check_yaw_diff_threshold{M_PI}; @@ -2090,10 +2104,10 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( continue; } - const auto collision_in_current_lanes = utils::lane_change::isCollidedPolygonsInLanelet( - collided_polygons, lane_change_path.info.current_lanes); + const auto collision_in_current_lanes = + utils::lane_change::isCollidedPolygonsInLanelet(collided_polygons, current_lanes_polygon); const auto collision_in_target_lanes = - utils::lane_change::isCollidedPolygonsInLanelet(collided_polygons, expanded_target_lanes); + utils::lane_change::isCollidedPolygonsInLanelet(collided_polygons, expanded_target_polygon); if (!collision_in_current_lanes && !collision_in_target_lanes) { utils::path_safety_checker::updateCollisionCheckDebugMap( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 9568f803773c4..20610380a0a5b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -330,13 +330,12 @@ bool isPathInLanelets( } std::optional constructCandidatePath( - const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, - const PathWithLaneId & target_segment, const PathWithLaneId & target_lane_reference_path, + const CommonDataPtr & common_data_ptr, const LaneChangeInfo & lane_change_info, + const PathWithLaneId & prepare_segment, const PathWithLaneId & target_segment, + const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids) { const auto & shift_line = lane_change_info.shift_line; - const auto & original_lanes = lane_change_info.current_lanes; - const auto & target_lanes = lane_change_info.target_lanes; const auto terminal_lane_changing_velocity = lane_change_info.terminal_lane_changing_velocity; const auto longitudinal_acceleration = lane_change_info.longitudinal_acceleration; const auto lane_change_velocity = lane_change_info.velocity; @@ -393,9 +392,11 @@ std::optional constructCandidatePath( const bool enable_path_check_in_lanelet = false; // check candidate path is in lanelet + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; if ( enable_path_check_in_lanelet && - !isPathInLanelets(shifted_path.path, original_lanes, target_lanes)) { + !isPathInLanelets(shifted_path.path, current_lanes, target_lanes)) { return std::nullopt; } @@ -968,17 +969,18 @@ bool isParkedObject( } bool passParkedObject( - const RouteHandler & route_handler, const LaneChangePath & lane_change_path, + const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, const std::vector & objects, const double minimum_lane_change_length, - const bool is_goal_in_route, const LaneChangeParameters & lane_change_parameters, - CollisionCheckDebugMap & object_debug) + const bool is_goal_in_route, CollisionCheckDebugMap & object_debug) { + const auto route_handler = *common_data_ptr->route_handler_ptr; + const auto lane_change_parameters = *common_data_ptr->lc_param_ptr; const auto & object_check_min_road_shoulder_width = lane_change_parameters.object_check_min_road_shoulder_width; const auto & object_shiftable_ratio_threshold = lane_change_parameters.object_shiftable_ratio_threshold; const auto & path = lane_change_path.path; - const auto & current_lanes = lane_change_path.info.current_lanes; + const auto & current_lanes = common_data_ptr->lanes_ptr->current; const auto current_lane_path = route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); @@ -1135,10 +1137,9 @@ ExtendedPredictedObject transform( } bool isCollidedPolygonsInLanelet( - const std::vector & collided_polygons, const lanelet::ConstLanelets & lanes) + const std::vector & collided_polygons, + const std::optional & lanes_polygon) { - const auto lanes_polygon = createPolygon(lanes, 0.0, std::numeric_limits::max()); - const auto is_in_lanes = [&](const auto & collided_polygon) { return lanes_polygon && boost::geometry::intersects(lanes_polygon.value(), collided_polygon); }; @@ -1207,27 +1208,60 @@ double calcPhaseLength( return std::min(length_with_acceleration, length_with_max_velocity); } -LanesPolygon createLanesPolygon( - const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, - const std::vector & target_backward_lanes) +LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr) { + const auto & lanes = common_data_ptr->lanes_ptr; LanesPolygon lanes_polygon; lanes_polygon.current = - utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); + utils::lane_change::createPolygon(lanes->current, 0.0, std::numeric_limits::max()); lanes_polygon.target = - utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + utils::lane_change::createPolygon(lanes->target, 0.0, std::numeric_limits::max()); + + const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; + const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( + lanes->target, common_data_ptr->direction, lc_param_ptr->lane_expansion_left_offset, + lc_param_ptr->lane_expansion_right_offset); + lanes_polygon.expanded_target = utils::lane_change::createPolygon( + expanded_target_lanes, 0.0, std::numeric_limits::max()); + + const auto & route_handler = *common_data_ptr->route_handler_ptr; + lanes_polygon.target_neighbor = + getTargetNeighborLanesPolygon(route_handler, lanes->current, common_data_ptr->lc_type); - for (const auto & target_backward_lane : target_backward_lanes) { - auto lane_polygon = utils::lane_change::createPolygon( - target_backward_lane, 0.0, std::numeric_limits::max()); + lanes_polygon.preceding_target.reserve(lanes->preceding_target.size()); + for (const auto & preceding_lane : lanes->preceding_target) { + auto lane_polygon = + utils::lane_change::createPolygon(preceding_lane, 0.0, std::numeric_limits::max()); if (lane_polygon) { - lanes_polygon.target_backward.push_back(*lane_polygon); + lanes_polygon.preceding_target.push_back(*lane_polygon); } } return lanes_polygon; } + +bool is_same_lane_with_prev_iteration( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes) +{ + if (current_lanes.empty() || target_lanes.empty()) { + return false; + } + const auto & prev_current_lanes = common_data_ptr->lanes_ptr->current; + const auto & prev_target_lanes = common_data_ptr->lanes_ptr->target; + if (prev_current_lanes.empty() || prev_target_lanes.empty()) { + return false; + } + + if ( + (prev_current_lanes.front().id() != current_lanes.front().id()) || + (prev_current_lanes.back().id() != prev_current_lanes.back().id())) { + return false; + } + return (prev_target_lanes.front().id() == target_lanes.front().id()) && + (prev_target_lanes.back().id() == prev_target_lanes.back().id()); +} } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug From ab60a5b9add673d6187c12fd009ba6a497008d63 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 23 Jul 2024 11:40:00 +0900 Subject: [PATCH 070/151] fix(lane_change): delay lane change cancel (#8048) RT1-6955: delay lane change cancel Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../utils/utils.hpp | 4 ++-- .../src/scene.cpp | 20 +++++++++++++++---- .../src/utils/utils.cpp | 19 +++++++++--------- 3 files changed, 28 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 17eaceb055fc1..703d882794ee4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -178,10 +178,10 @@ bool isParkedObject( const ExtendedPredictedObject & object, const double buffer_to_bound, const double ratio_threshold); -bool passParkedObject( +bool passed_parked_objects( const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, const std::vector & objects, const double minimum_lane_change_length, - const bool is_goal_in_route, CollisionCheckDebugMap & object_debug); + CollisionCheckDebugMap & object_debug); std::optional getLeadingStaticObjectIdx( const RouteHandler & route_handler, const LaneChangePath & lane_change_path, diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 659e5b78bf577..7a4b72631629d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1628,10 +1628,9 @@ bool NormalLaneChange::getLaneChangePaths( candidate_paths->push_back(*candidate_path); if ( - !is_stuck && - utils::lane_change::passParkedObject( - common_data_ptr_, *candidate_path, filtered_objects.target_lane, lane_change_buffer, - is_goal_in_route, lane_change_debug_.collision_check_objects)) { + !is_stuck && !utils::lane_change::passed_parked_objects( + common_data_ptr_, *candidate_path, filtered_objects.target_lane, + lane_change_buffer, lane_change_debug_.collision_check_objects)) { debug_print_lat( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " "lane change."); @@ -1815,6 +1814,19 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const const auto target_objects = getTargetObjects(filtered_objects, current_lanes); CollisionCheckDebugMap debug_data; + + const auto min_lc_length = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, + common_data_ptr_->route_handler_ptr->getLateralIntervalsToPreferredLane(current_lanes.back())); + + const auto has_passed_parked_objects = utils::lane_change::passed_parked_objects( + common_data_ptr_, path, filtered_objects.target_lane, min_lc_length, debug_data); + + if (!has_passed_parked_objects) { + RCLCPP_DEBUG(logger_, "Lane change has been delayed."); + return {false, false}; + } + const auto safety_status = isLaneChangePathSafe( path, target_objects, lane_change_parameters_->rss_params_for_abort, debug_data); { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 20610380a0a5b..6ea280817f39b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -968,10 +968,10 @@ bool isParkedObject( return clamped_ratio > ratio_threshold; } -bool passParkedObject( +bool passed_parked_objects( const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, const std::vector & objects, const double minimum_lane_change_length, - const bool is_goal_in_route, CollisionCheckDebugMap & object_debug) + CollisionCheckDebugMap & object_debug) { const auto route_handler = *common_data_ptr->route_handler_ptr; const auto lane_change_parameters = *common_data_ptr->lc_param_ptr; @@ -979,20 +979,19 @@ bool passParkedObject( lane_change_parameters.object_check_min_road_shoulder_width; const auto & object_shiftable_ratio_threshold = lane_change_parameters.object_shiftable_ratio_threshold; - const auto & path = lane_change_path.path; const auto & current_lanes = common_data_ptr->lanes_ptr->current; const auto current_lane_path = route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); - if (objects.empty() || path.points.empty() || current_lane_path.points.empty()) { - return false; + if (objects.empty() || lane_change_path.path.points.empty() || current_lane_path.points.empty()) { + return true; } const auto leading_obj_idx = getLeadingStaticObjectIdx( route_handler, lane_change_path, objects, object_check_min_road_shoulder_width, object_shiftable_ratio_threshold); if (!leading_obj_idx) { - return false; + return true; } const auto & leading_obj = objects.at(*leading_obj_idx); @@ -1000,11 +999,13 @@ bool passParkedObject( const auto leading_obj_poly = autoware::universe_utils::toPolygon2d(leading_obj.initial_pose.pose, leading_obj.shape); if (leading_obj_poly.outer().empty()) { - return false; + return true; } const auto & current_path_end = current_lane_path.points.back().point.pose.position; double min_dist_to_end_of_current_lane = std::numeric_limits::max(); + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); for (const auto & point : leading_obj_poly.outer()) { const auto obj_p = autoware::universe_utils::createPoint(point.x(), point.y(), 0.0); const double dist = autoware::motion_utils::calcSignedArcLength( @@ -1022,10 +1023,10 @@ bool passParkedObject( if (min_dist_to_end_of_current_lane > minimum_lane_change_length) { debug.second.unsafe_reason = "delay lane change"; utils::path_safety_checker::updateCollisionCheckDebugMap(object_debug, debug, false); - return true; + return false; } - return false; + return true; } std::optional getLeadingStaticObjectIdx( From 6d38b7f37f6ff6cbc384a221691db601469c112c Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 25 Jul 2024 12:14:25 +0900 Subject: [PATCH 071/151] fix(lane_change): filtering object ahead of terminal (#8093) * employ lanelet based filtering before distance based filtering Signed-off-by: Zulfaqar Azmi * use distance based to terminal check instead Signed-off-by: Zulfaqar Azmi * remove RCLCPP INFO Signed-off-by: Muhammad Zulfaqar Azmi * update flow chart Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../README.md | 84 +++++----------- .../scene.hpp | 6 +- .../utils/data_structs.hpp | 1 + .../utils/utils.hpp | 12 +++ .../src/scene.cpp | 99 ++++++------------- .../src/utils/utils.cpp | 80 +++++++++++++++ 6 files changed, 153 insertions(+), 129 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 5790be377b7aa..63f5a2ec05bf1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -331,8 +331,7 @@ title NormalLaneChange::filterObjects Method Execution Flow start group "Filter Objects by Class" { -:Iterate through each object in objects list; -while (has not finished iterating through object list) is (TRUE) +while (has not finished iterating through predicted object list) is (TRUE) if (current object type != param.object_types_to_check?) then (TRUE) #LightPink:Remove current object; else (FALSE) @@ -341,17 +340,15 @@ endif end while end group -if (object list is empty?) then (TRUE) +if (predicted object list is empty?) then (TRUE) :Return empty result; stop else (FALSE) endif group "Filter Oncoming Objects" #PowderBlue { -:Iterate through each object in target lane objects list; -while (has not finished iterating through object list?) is (TRUE) -:check object's yaw with reference to ego's yaw.; -if (yaw difference < 90 degree?) then (TRUE) +while (has not finished iterating through predicted object list?) is (TRUE) +if (object's yaw with reference to ego's yaw difference < 90 degree?) then (TRUE) :Keep current object; else (FALSE) if (object is stopping?) then (TRUE) @@ -363,31 +360,7 @@ endif endwhile end group -if (object list is empty?) then (TRUE) - :Return empty result; - stop -else (FALSE) -endif - -group "Filter Objects Ahead Terminal" #Beige { -:Calculate lateral distance from ego to current lanes center; - -:Iterate through each object in objects list; -while (has not finished iterating through object list) is (TRUE) - :Get current object's polygon; - :Initialize distance to terminal from object to max; - while (has not finished iterating through object polygon's vertices) is (TRUE) - :Calculate object's lateral distance to end of lane; - :Update minimum distance to terminal from object; - end while - if (Is object's distance to terminal exceeds minimum lane change length?) then (TRUE) - #LightPink:Remove current object; - else (FALSE) - endif -end while -end group - -if (object list is empty?) then (TRUE) +if (predicted object list is empty?) then (TRUE) :Return empty result; stop else (FALSE) @@ -395,21 +368,27 @@ endif group "Filter Objects By Lanelets" #LightGreen { -:Iterate through each object in objects list; -while (has not finished iterating through object list) is (TRUE) - :lateral distance diff = difference between object's lateral distance and ego's lateral distance to the current lanes' centerline.; - if (Object in target lane polygon, and lateral distance diff is more than half of ego's width?) then (TRUE) - :Add to target_lane_objects; - else (FALSE) - if (Object overlaps with backward target lanes?) then (TRUE) +while (has not finished iterating through predicted object list) is (TRUE) + :Calculate lateral distance diff; + if (Object in target lane polygon?) then (TRUE) + if (lateral distance diff > half of ego's width?) then (TRUE) + if (Object's physical position is before terminal point?) then (TRUE) :Add to target_lane_objects; else (FALSE) - if (Object in current lane polygon?) then (TRUE) - :Add to current_lane_objects; - else (FALSE) - :Add to other_lane_objects; - endif endif + else (FALSE) + endif + else (FALSE) + endif + + if (Object overlaps with backward target lanes?) then (TRUE) + :Add to target_lane_objects; + else (FALSE) + if (Object in current lane polygon?) then (TRUE) + :Add to current_lane_objects; + else (FALSE) + :Add to other_lane_objects; + endif endif end while @@ -426,13 +405,10 @@ endif group "Filter Target Lanes' objects" #LightCyan { -:Iterate through each object in target lane objects list; -while (has not finished iterating through object list) is (TRUE) - :check object's velocity; +while (has not finished iterating through target lanes' object list) is (TRUE) if(velocity is within threshold?) then (TRUE) :Keep current object; else (FALSE) - :check whether object is ahead of ego; if(object is ahead of ego?) then (TRUE) :keep current object; else (FALSE) @@ -444,11 +420,8 @@ end group group "Filter Current Lanes' objects" #LightYellow { -:Iterate through each object in current lane objects list; -while (has not finished iterating through object list) is (TRUE) - :check object's velocity; +while (has not finished iterating through current lanes' object list) is (TRUE) if(velocity is within threshold?) then (TRUE) - :check whether object is ahead of ego; if(object is ahead of ego?) then (TRUE) :keep current object; else (FALSE) @@ -462,11 +435,8 @@ end group group "Filter Other Lanes' objects" #Lavender { -:Iterate through each object in other lane objects list; -while (has not finished iterating through object list) is (TRUE) - :check object's velocity; +while (has not finished iterating through other lanes' object list) is (TRUE) if(velocity is within threshold?) then (TRUE) - :check whether object is ahead of ego; if(object is ahead of ego?) then (TRUE) :keep current object; else (FALSE) @@ -478,7 +448,7 @@ while (has not finished iterating through object list) is (TRUE) endwhile end group -:Trasform the objects into extended predicted object and return them as lane_change_target_objects; +:Transform the objects into extended predicted object and return them as lane_change_target_objects; stop @enduml diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index dad96d5f7371a..a1284f355a87d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -128,12 +128,8 @@ class NormalLaneChange : public LaneChangeBase void filterOncomingObjects(PredictedObjects & objects) const; - void filterAheadTerminalObjects( - PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes) const; - void filterObjectsByLanelets( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, + const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path, std::vector & current_lane_objects, std::vector & target_lane_objects, std::vector & other_lane_objects) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 1bb4dfdeb59dc..495fe9012ecd0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -185,6 +185,7 @@ struct PhaseInfo struct Lanes { + bool current_lane_in_goal_section{false}; lanelet::ConstLanelets current; lanelet::ConstLanelets target; std::vector preceding_target; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 703d882794ee4..6dbed08ea651d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -302,6 +302,18 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr); bool is_same_lane_with_prev_iteration( const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes); + +Pose to_pose( + const autoware::universe_utils::Point2d & point, + const geometry_msgs::msg::Quaternion & orientation); + +bool is_ahead_of_ego( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, + const PredictedObject & object); + +bool is_before_terminal( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, + const PredictedObject & object); } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 7a4b72631629d..0969103ff585b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -83,8 +83,11 @@ void NormalLaneChange::update_lanes(const bool is_approved) common_data_ptr_->lanes_ptr->current = current_lanes; common_data_ptr_->lanes_ptr->target = target_lanes; + const auto & route_handler_ptr = common_data_ptr_->route_handler_ptr; + common_data_ptr_->lanes_ptr->current_lane_in_goal_section = + route_handler_ptr->isInGoalRouteSection(current_lanes.back()); common_data_ptr_->lanes_ptr->preceding_target = utils::getPrecedingLanelets( - *common_data_ptr_->route_handler_ptr, get_target_lanes(), common_data_ptr_->get_ego_pose(), + *route_handler_ptr, get_target_lanes(), common_data_ptr_->get_ego_pose(), common_data_ptr_->lc_param_ptr->backward_lane_length); *common_data_ptr_->lanes_polygon_ptr = create_lanes_polygon(common_data_ptr_); @@ -983,7 +986,6 @@ ExtendedPredictedObjects NormalLaneChange::getTargetObjects( LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const { - const auto & current_pose = getEgoPose(); const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; auto objects = *planner_data_->dynamic_object; @@ -1006,12 +1008,6 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const return {}; } - filterAheadTerminalObjects(objects, current_lanes); - - if (objects.objects.empty()) { - return {}; - } - std::vector target_lane_objects; std::vector current_lane_objects; std::vector other_lane_objects; @@ -1022,9 +1018,11 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const return {}; } + const auto path = + route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + filterObjectsByLanelets( - objects, current_lanes, target_lanes, current_lane_objects, target_lane_objects, - other_lane_objects); + objects, path, current_lane_objects, target_lane_objects, other_lane_objects); const auto is_within_vel_th = [](const auto & object) -> bool { constexpr double min_vel_th = 1.0; @@ -1032,38 +1030,25 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); }; - const auto path = - route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); - - if (path.points.empty()) { - return {}; - } - - const auto is_ahead_of_ego = [&path, ¤t_pose](const auto & object) { - const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); - - double max_dist_ego_to_obj = std::numeric_limits::lowest(); - for (const auto & polygon_p : obj_polygon) { - const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - const auto dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p); - max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); - } - return max_dist_ego_to_obj >= 0.0; - }; - utils::path_safety_checker::filterObjects( target_lane_objects, [&](const PredictedObject & object) { - return (is_within_vel_th(object) || is_ahead_of_ego(object)); + const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); + return is_within_vel_th(object) || ahead_of_ego; }); - utils::path_safety_checker::filterObjects( - other_lane_objects, [&](const PredictedObject & object) { - return is_within_vel_th(object) && is_ahead_of_ego(object); - }); + if (lane_change_parameters_->check_objects_on_other_lanes) { + utils::path_safety_checker::filterObjects( + other_lane_objects, [&](const PredictedObject & object) { + const auto ahead_of_ego = + utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); + return is_within_vel_th(object) && ahead_of_ego; + }); + } utils::path_safety_checker::filterObjects( current_lane_objects, [&](const PredictedObject & object) { - return is_within_vel_th(object) && is_ahead_of_ego(object); + const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); + return is_within_vel_th(object) && ahead_of_ego; }); LaneChangeLanesFilteredObjects lane_change_target_objects; @@ -1119,42 +1104,15 @@ void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const }); } -void NormalLaneChange::filterAheadTerminalObjects( - PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes) const -{ - const auto & current_pose = getEgoPose(); - const auto & route_handler = getRouteHandler(); - const auto minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( - route_handler, current_lanes.back(), *lane_change_parameters_, direction_); - - const auto dist_ego_to_current_lanes_center = - lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); - - // ignore object that are ahead of terminal lane change start - utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { - const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); - // ignore object that are ahead of terminal lane change start - auto distance_to_terminal_from_object = std::numeric_limits::max(); - for (const auto & polygon_p : obj_polygon) { - const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - Pose polygon_pose; - polygon_pose.position = obj_p; - polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation; - const auto dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes); - distance_to_terminal_from_object = std::min(dist_ego_to_current_lanes_center, dist); - } - - return (minimum_lane_change_length > distance_to_terminal_from_object); - }); -} - void NormalLaneChange::filterObjectsByLanelets( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, std::vector & current_lane_objects, + const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path, + std::vector & current_lane_objects, std::vector & target_lane_objects, std::vector & other_lane_objects) const { const auto & current_pose = getEgoPose(); + const auto & current_lanes = common_data_ptr_->lanes_ptr->current; + const auto & target_lanes = common_data_ptr_->lanes_ptr->target; const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; const auto check_optional_polygon = [](const auto & object, const auto & polygon) { @@ -1199,7 +1157,14 @@ void NormalLaneChange::filterObjectsByLanelets( return std::abs(lateral) > (common_parameters.vehicle_width / 2); }); - if (check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far) { + const auto is_before_terminal = [&]() { + return utils::lane_change::is_before_terminal( + common_data_ptr_, current_lanes_ref_path, object); + }; + + if ( + check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far && + is_before_terminal()) { target_lane_objects.push_back(object); continue; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 6ea280817f39b..2ef7bd0a41cc3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -1216,6 +1216,7 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr) lanes_polygon.current = utils::lane_change::createPolygon(lanes->current, 0.0, std::numeric_limits::max()); + lanes_polygon.target = utils::lane_change::createPolygon(lanes->target, 0.0, std::numeric_limits::max()); @@ -1263,6 +1264,85 @@ bool is_same_lane_with_prev_iteration( return (prev_target_lanes.front().id() == target_lanes.front().id()) && (prev_target_lanes.back().id() == prev_target_lanes.back().id()); } + +Pose to_pose( + const autoware::universe_utils::Point2d & point, + const geometry_msgs::msg::Quaternion & orientation) +{ + Pose pose; + pose.position = autoware::universe_utils::createPoint(point.x(), point.y(), 0.0); + pose.orientation = orientation; + return pose; +} + +bool is_ahead_of_ego( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, + const PredictedObject & object) +{ + const auto & current_ego_pose = common_data_ptr->get_ego_pose(); + + const auto & obj_position = object.kinematics.initial_pose_with_covariance.pose.position; + + const auto dist_to_base_link = autoware::motion_utils::calcSignedArcLength( + path.points, current_ego_pose.position, obj_position); + const auto & ego_info = common_data_ptr->bpp_param_ptr->vehicle_info; + const auto lon_dev = std::max( + ego_info.max_longitudinal_offset_m + ego_info.rear_overhang_m, object.shape.dimensions.x); + + // we don't always have to check the distance accurately. + if (std::abs(dist_to_base_link) > lon_dev) { + return dist_to_base_link >= 0.0; + } + + const auto ego_polygon = getEgoCurrentFootprint(current_ego_pose, ego_info).outer(); + auto ego_min_dist_to_end = std::numeric_limits::max(); + for (const auto & ego_edge_point : ego_polygon) { + const auto ego_edge = + autoware::universe_utils::createPoint(ego_edge_point.x(), ego_edge_point.y(), 0.0); + const auto dist_to_end = autoware::motion_utils::calcSignedArcLength( + path.points, ego_edge, path.points.back().point.pose.position); + ego_min_dist_to_end = std::min(dist_to_end, ego_min_dist_to_end); + } + + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); + auto current_min_dist_to_end = std::numeric_limits::max(); + for (const auto & polygon_p : obj_polygon) { + const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto dist_ego_to_obj = autoware::motion_utils::calcSignedArcLength( + path.points, obj_p, path.points.back().point.pose.position); + current_min_dist_to_end = std::min(dist_ego_to_obj, current_min_dist_to_end); + } + return ego_min_dist_to_end - current_min_dist_to_end >= 0.0; +} + +bool is_before_terminal( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, + const PredictedObject & object) +{ + const auto & route_handler_ptr = common_data_ptr->route_handler_ptr; + const auto & lanes_ptr = common_data_ptr->lanes_ptr; + const auto terminal_position = (lanes_ptr->current_lane_in_goal_section) + ? route_handler_ptr->getGoalPose().position + : path.points.back().point.pose.position; + double current_max_dist = std::numeric_limits::lowest(); + + const auto & obj_position = object.kinematics.initial_pose_with_covariance.pose.position; + const auto dist_to_base_link = + autoware::motion_utils::calcSignedArcLength(path.points, obj_position, terminal_position); + // we don't always have to check the distance accurately. + if (std::abs(dist_to_base_link) > object.shape.dimensions.x) { + return dist_to_base_link >= 0.0; + } + + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); + for (const auto & polygon_p : obj_polygon) { + const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto dist_obj_to_terminal = + autoware::motion_utils::calcSignedArcLength(path.points, obj_p, terminal_position); + current_max_dist = std::max(dist_obj_to_terminal, current_max_dist); + } + return current_max_dist >= 0.0; +} } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug From a4563aa739a0a7be6de34e6d205dbfac64f95ba9 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 13 Aug 2024 10:23:39 +0900 Subject: [PATCH 072/151] perf(static_obstacle_avoidance): improve logic to reduce computational cost (#8432) * perf(safety_check): check within first Signed-off-by: satoshi-ota * perf(static_obstacle_avoidance): remove duplicated process Signed-off-by: satoshi-ota * perf(static_obstacle_avoidance): remove heavy process Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../path_safety_checker/objects_filtering.cpp | 28 +++++++++---------- .../src/scene.cpp | 5 ---- .../src/utils.cpp | 5 ++-- 3 files changed, 15 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 95a498b7b8475..1de55dca29347 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -61,32 +61,30 @@ bool isCentroidWithinLanelet( const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold) { const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position); - if ( - std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) > - yaw_threshold) { + if (!boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pose.position)) + .basicPoint(), + lanelet.polygon2d().basicPolygon())) { return false; } - return boost::geometry::within( - lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pose.position)) - .basicPoint(), - lanelet.polygon2d().basicPolygon()); + const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position); + return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) < + yaw_threshold; } bool isPolygonOverlapLanelet( const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold) { - const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position); - if ( - std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) > - yaw_threshold) { + const auto lanelet_polygon = utils::toPolygon2d(lanelet); + if (!isPolygonOverlapLanelet(object, lanelet_polygon)) { return false; } - const auto lanelet_polygon = utils::toPolygon2d(lanelet); - return isPolygonOverlapLanelet(object, lanelet_polygon); + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; + const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position); + return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) < + yaw_threshold; } bool isPolygonOverlapLanelet( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index d125f043f477b..39a8d1b853e47 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -926,11 +926,6 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() spline_shift_path = helper_->getPreviousSplineShiftPath(); } - // post processing - { - postProcess(); // remove old shift points - } - BehaviorModuleOutput output; const auto is_ignore_signal = [this](const UUID & uuid) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 0830c0f10dd4e..f7bda56150b49 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -2253,10 +2253,9 @@ std::pair separateObjectsByPath( Pose p_reference_ego_front = reference_path.points.front().point.pose; Pose p_spline_ego_front = spline_path.points.front().point.pose; double next_longitudinal_distance = parameters->resample_interval_for_output; + const auto offset = arc_length_array.at(ego_idx); for (size_t i = 0; i < points_size; ++i) { - const auto distance_from_ego = - autoware::motion_utils::calcSignedArcLength(reference_path.points, ego_idx, i); - if (distance_from_ego > object_check_forward_distance) { + if (arc_length_array.at(i) > object_check_forward_distance + offset) { break; } From 8a3411a4d3bcf07259370a9ea362090ca4606cb5 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 26 Jul 2024 16:34:56 +0900 Subject: [PATCH 073/151] fix(autoware_behavior_path_lane_change_module): fix passedByValue (#8208) fix:passedByValue Signed-off-by: kobayu858 --- .../autoware/behavior_path_lane_change_module/utils/utils.hpp | 2 +- .../src/utils/utils.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 6dbed08ea651d..7bb6a06116a53 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -136,7 +136,7 @@ PathWithLaneId getReferencePathFromTargetLane( const double next_lane_change_buffer); std::vector generateDrivableLanes( - const std::vector original_drivable_lanes, const RouteHandler & route_handler, + const std::vector & original_drivable_lanes, const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes); std::vector generateDrivableLanes( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 2ef7bd0a41cc3..94b477d3e5737 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -527,7 +527,7 @@ std::vector generateDrivableLanes( } std::vector generateDrivableLanes( - const std::vector original_drivable_lanes, const RouteHandler & route_handler, + const std::vector & original_drivable_lanes, const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes) { const auto has_same_lane = From 4a1864a4354813b5407c9c9957b8fda73690da78 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 2 Aug 2024 16:22:40 +0900 Subject: [PATCH 074/151] fix(lane_change): relax finish judge (#8133) * fix(lane_change): relax finish judge Signed-off-by: Muhammad Zulfaqar Azmi * documentation update Signed-off-by: Zulfaqar Azmi * update readme explanations Signed-off-by: Zulfaqar Azmi * update config Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../README.md | 66 ++++++++++++++++++- .../config/lane_change.param.yaml | 5 +- .../utils/data_structs.hpp | 5 +- .../utils/utils.hpp | 2 + .../src/manager.cpp | 9 ++- .../src/scene.cpp | 31 ++++++--- .../src/utils/utils.cpp | 11 ++++ 7 files changed, 114 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 63f5a2ec05bf1..967e8352b830a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -618,6 +618,61 @@ The last behavior will also occur if the ego vehicle has departed from the curre ![stop](./images/lane_change-cant_cancel_no_abort.png) +## Lane change completion checks + +To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. + +For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. + +If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. + +The process of determining lane change completion is shown in the following diagram. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title Lane change completion judge + +start + +:Calculate distance from current ego pose to lane change end pose; + +if (Is ego velocity < 1.0?) then (YES) + :Set finish_judge_buffer to 0.0; +else (NO) + :Set finish_judge_buffer to lane_change_finish_judge_buffer; +endif + +if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) + if (Current ego pose is in target lanes' polygon?) then (YES) + :Lane change is completed; + stop + else (NO) +:Lane change is NOT completed; +stop + endif +else (NO) +endif + +if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) + :Lane change is NOT completed; + stop +else (NO) + :Calculate distance to the target lanes' centerline; + if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) + :Lane change is completed; + stop + else (NO) + :Lane change is NOT completed; + stop + endif +endif + +@enduml +``` + ## Parameters ### Essential lane change parameters @@ -631,7 +686,6 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | | `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | | `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 2.0 | -| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | | `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | | `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | | `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | @@ -647,6 +701,16 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | | `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.65, 0.65, 0.65] | +### Parameter to judge if lane change is completed + +The following parameters are used to judge lane change completion. + +| Name | Unit | Type | Description | Default value | +| :------------------------------------- | ----- | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------- | +| `lane_change_finish_judge_buffer` | [m] | double | The longitudinal distance starting from the lane change end pose. | 2.0 | +| `finish_judge_lateral_threshold` | [m] | double | The lateral distance from targets lanes' centerline. Used in addition with `finish_judge_lateral_angle_deviation` | 0.1 | +| `finish_judge_lateral_angle_deviation` | [deg] | double | Ego angle deviation with reference to target lanes' centerline. Used in addition with `finish_judge_lateral_threshold` | 2.0 | + ### Lane change regulations | Name | Unit | Type | Description | Default value | diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index d2f695071649a..77cf9b7b11cbe 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -6,7 +6,6 @@ backward_length_buffer_for_end_of_lane: 3.0 # [m] backward_length_buffer_for_blocking_object: 3.0 # [m] - lane_change_finish_judge_buffer: 2.0 # [m] lane_changing_lateral_jerk: 0.5 # [m/s3] @@ -109,7 +108,9 @@ overhang_tolerance: 0.0 # [m] unsafe_hysteresis_threshold: 10 # [/] - finish_judge_lateral_threshold: 0.2 # [m] + lane_change_finish_judge_buffer: 2.0 # [m] + finish_judge_lateral_threshold: 0.1 # [m] + finish_judge_lateral_angle_deviation: 1.0 # [deg] # debug publish_debug_marker: false diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 495fe9012ecd0..696cf4bd58d32 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -109,7 +110,6 @@ struct Parameters double lane_changing_lateral_jerk{0.5}; double minimum_lane_changing_velocity{5.6}; double lane_change_prepare_duration{4.0}; - double lane_change_finish_judge_buffer{3.0}; LateralAccelerationMap lane_change_lat_acc_map; // parked vehicle @@ -157,7 +157,10 @@ struct Parameters // abort CancelParameters cancel{}; + // finish judge parameter + double lane_change_finish_judge_buffer{3.0}; double finish_judge_lateral_threshold{0.2}; + double finish_judge_lateral_angle_deviation{autoware::universe_utils::deg2rad(3.0)}; // debug marker bool publish_debug_marker{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 7bb6a06116a53..d566aceba413b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -314,6 +314,8 @@ bool is_ahead_of_ego( bool is_before_terminal( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const PredictedObject & object); + +double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose); } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 22c93f7d4bfd5..16c4058bb3911 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -166,8 +166,6 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) getOrDeclareParameter(*node, parameter("minimum_lane_changing_velocity")); p.minimum_lane_changing_velocity = std::min(p.minimum_lane_changing_velocity, max_acc * p.lane_change_prepare_duration); - p.lane_change_finish_judge_buffer = - getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer")); if (p.backward_length_buffer_for_end_of_lane < 1.0) { RCLCPP_WARN_STREAM( @@ -224,8 +222,15 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) p.cancel.unsafe_hysteresis_threshold = getOrDeclareParameter(*node, parameter("cancel.unsafe_hysteresis_threshold")); + // finish judge parameters + p.lane_change_finish_judge_buffer = + getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer")); p.finish_judge_lateral_threshold = getOrDeclareParameter(*node, parameter("finish_judge_lateral_threshold")); + const auto finish_judge_lateral_angle_deviation = + getOrDeclareParameter(*node, parameter("finish_judge_lateral_angle_deviation")); + p.finish_judge_lateral_angle_deviation = + autoware::universe_utils::deg2rad(finish_judge_lateral_angle_deviation); // debug marker p.publish_debug_marker = getOrDeclareParameter(*node, parameter("publish_debug_marker")); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 0969103ff585b..655fa4f8320e2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -23,6 +23,7 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include +#include #include #include #include @@ -689,21 +690,33 @@ bool NormalLaneChange::hasFinishedLaneChange() const const auto & lane_change_end = status_.lane_change_path.info.shift_line.end; const auto & target_lanes = get_target_lanes(); const double dist_to_lane_change_end = - utils::getSignedDistance(current_pose, lane_change_end, get_target_lanes()); - double finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer; + utils::getSignedDistance(current_pose, lane_change_end, target_lanes); - // If ego velocity is low, relax finish judge buffer - const double ego_velocity = getEgoVelocity(); - if (std::abs(ego_velocity) < 1.0) { - finish_judge_buffer = 0.0; - } + const auto finish_judge_buffer = std::invoke([&]() { + const double ego_velocity = getEgoVelocity(); + // If ego velocity is low, relax finish judge buffer + if (std::abs(ego_velocity) < 1.0) { + return 0.0; + } + return lane_change_parameters_->lane_change_finish_judge_buffer; + }); - const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0; + const auto has_passed_end_pose = dist_to_lane_change_end + finish_judge_buffer < 0.0; lane_change_debug_.distance_to_lane_change_finished = dist_to_lane_change_end + finish_judge_buffer; - if (!reach_lane_change_end) { + if (has_passed_end_pose) { + const auto & lanes_polygon = common_data_ptr_->lanes_polygon_ptr->target; + return !boost::geometry::disjoint( + lanes_polygon.value(), + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(current_pose.position))); + } + + const auto yaw_deviation_to_centerline = + utils::lane_change::calc_angle_to_lanelet_segment(target_lanes, current_pose); + + if (yaw_deviation_to_centerline > lane_change_parameters_->finish_judge_lateral_angle_deviation) { return false; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 94b477d3e5737..915864c597882 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -1343,6 +1343,17 @@ bool is_before_terminal( } return current_max_dist >= 0.0; } + +double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose) +{ + lanelet::ConstLanelet closest_lanelet; + + if (!lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) { + return autoware::universe_utils::deg2rad(180); + } + const auto closest_pose = lanelet::utils::getClosestCenterPose(closest_lanelet, pose.position); + return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, pose)); +} } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug From dde26ce72e73936b05fd3637f63bb3d204acef67 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 2 Aug 2024 17:24:57 +0900 Subject: [PATCH 075/151] feat(lane_change): use different rss param to deal with parked vehicle (#8316) * different rss value for parked vehicle Signed-off-by: Muhammad Zulfaqar Azmi * Documentation and config file update Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../README.md | 12 ++++++++++++ .../config/lane_change.param.yaml | 8 ++++++++ .../utils/data_structs.hpp | 1 + .../src/manager.cpp | 17 +++++++++++++++++ .../src/scene.cpp | 7 ++++++- 5 files changed, 44 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 967e8352b830a..e42e6e2d47738 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -773,6 +773,18 @@ The following parameters are used to judge lane change completion. | `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | | `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | +#### safety constraints specifically for stopped or parked vehicles + +| Name | Unit | Type | Description | Default value | +| :-------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.parked.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.parked.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.0 | +| `safety_check.parked.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.0 | +| `safety_check.parked.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 | +| `safety_check.parked.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 | +| `safety_check.parked.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.parked.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | + ##### safety constraints to cancel lane change path | Name | Unit | Type | Description | Default value | diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 77cf9b7b11cbe..7a9c466fec260 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -38,6 +38,14 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 longitudinal_velocity_delta_time: 0.8 + parked: + expected_front_deceleration: -1.0 + expected_rear_deceleration: -2.0 + rear_vehicle_reaction_time: 1.0 + rear_vehicle_safety_time_margin: 0.8 + lateral_distance_max_threshold: 1.0 + longitudinal_distance_min_threshold: 3.0 + longitudinal_velocity_delta_time: 0.0 cancel: expected_front_deceleration: -1.0 expected_rear_deceleration: -2.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 696cf4bd58d32..7962c878d7d64 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -151,6 +151,7 @@ struct Parameters bool allow_loose_check_for_cancel{true}; double collision_check_yaw_diff_threshold{3.1416}; utils::path_safety_checker::RSSparams rss_params{}; + utils::path_safety_checker::RSSparams rss_params_for_parked{}; utils::path_safety_checker::RSSparams rss_params_for_abort{}; utils::path_safety_checker::RSSparams rss_params_for_stuck{}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 16c4058bb3911..f3f371ec02a9b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -122,6 +122,23 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) p.rss_params.lateral_distance_max_threshold = getOrDeclareParameter( *node, parameter("safety_check.execution.lateral_distance_max_threshold")); + p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter( + *node, parameter("safety_check.parked.longitudinal_distance_min_threshold")); + p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter( + *node, parameter("safety_check.parked.longitudinal_distance_min_threshold")); + p.rss_params_for_parked.longitudinal_velocity_delta_time = getOrDeclareParameter( + *node, parameter("safety_check.parked.longitudinal_velocity_delta_time")); + p.rss_params_for_parked.front_vehicle_deceleration = getOrDeclareParameter( + *node, parameter("safety_check.parked.expected_front_deceleration")); + p.rss_params_for_parked.rear_vehicle_deceleration = getOrDeclareParameter( + *node, parameter("safety_check.parked.expected_rear_deceleration")); + p.rss_params_for_parked.rear_vehicle_reaction_time = getOrDeclareParameter( + *node, parameter("safety_check.parked.rear_vehicle_reaction_time")); + p.rss_params_for_parked.rear_vehicle_safety_time_margin = getOrDeclareParameter( + *node, parameter("safety_check.parked.rear_vehicle_safety_time_margin")); + p.rss_params_for_parked.lateral_distance_max_threshold = getOrDeclareParameter( + *node, parameter("safety_check.parked.lateral_distance_max_threshold")); + p.rss_params_for_abort.longitudinal_distance_min_threshold = getOrDeclareParameter( *node, parameter("safety_check.cancel.longitudinal_distance_min_threshold")); p.rss_params_for_abort.longitudinal_velocity_delta_time = getOrDeclareParameter( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 655fa4f8320e2..eda0c4024a934 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -2082,9 +2082,14 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( obj, lane_change_parameters_->use_all_predicted_path); auto is_safe = true; + const auto selected_rss_param = + (obj.initial_twist.twist.linear.x <= + lane_change_parameters_->prepare_segment_ignore_object_velocity_thresh) + ? lane_change_parameters_->rss_params_for_parked + : rss_params; for (const auto & obj_path : obj_predicted_paths) { const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons( - path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0, + path, ego_predicted_path, obj, obj_path, common_parameters, selected_rss_param, 1.0, get_max_velocity_for_safety_check(), collision_check_yaw_diff_threshold, current_debug_data.second); From 70425d535dc32299b79c04ec78e0542b2049be7f Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 7 Aug 2024 12:07:45 +0900 Subject: [PATCH 076/151] refactor(lane_change): check start point directly after getting start point (#8357) * check start point directly after getting start point Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../scene.hpp | 18 ++++++++ .../src/scene.cpp | 46 ++++++++----------- 2 files changed, 38 insertions(+), 26 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index a1284f355a87d..605e0499adcdb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -184,6 +184,24 @@ class NormalLaneChange : public LaneChangeBase bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const; + /** + * @brief Checks if the given pose is a valid starting point for a lane change. + * + * This function determines whether the given pose (position) of the vehicle is within + * the area of either the target neighbor lane or the target lane itself. It uses geometric + * checks to see if the start point of the lane change is covered by the polygons representing + * these lanes. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - Non-null `lanes_polygon_ptr` that contains the polygon data for lanes. + * @param pose The current pose of the vehicle + * + * @return `true` if the pose is within either the target neighbor lane or the target lane; + * `false` otherwise. + */ + bool is_valid_start_point( + const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const; + bool check_prepare_phase() const; double calcMaximumLaneChangeLength( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index eda0c4024a934..d80acf4ec18b2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -392,16 +392,9 @@ void NormalLaneChange::insertStopPoint( const auto target_objects = filterObjects(); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; - const auto is_valid_start_point = std::invoke([&]() -> bool { - auto lc_start_point = lanelet::utils::conversion::toLaneletPoint( - status_.lane_change_path.info.lane_changing_start.position); - const auto & target_neighbor_preferred_lane_poly_2d = - common_data_ptr_->lanes_polygon_ptr->target_neighbor; - return boost::geometry::covered_by( - lanelet::traits::to2D(lc_start_point), target_neighbor_preferred_lane_poly_2d); - }); + const auto & lc_start_point = status_.lane_change_path.info.lane_changing_start; - if (!is_valid_start_point) { + if (!is_valid_start_point(common_data_ptr_, lc_start_point)) { const auto stop_point = utils::insertStopPoint(stopping_distance, path); setStopPose(stop_point.point.pose); @@ -1424,6 +1417,12 @@ bool NormalLaneChange::getLaneChangePaths( continue; } + if (!is_valid_start_point(common_data_ptr_, prepare_segment.points.back().point.pose)) { + debug_print( + "Reject: lane changing start point is not within the preferred lanes or its neighbors"); + continue; + } + // lane changing start getEgoPose() is at the end of prepare segment const auto & lane_changing_start_pose = prepare_segment.points.back().point.pose; const auto target_length_from_lane_change_start_pose = utils::getArcLengthToTargetLanelet( @@ -1510,16 +1509,6 @@ bool NormalLaneChange::getLaneChangePaths( continue; } - const lanelet::BasicPoint2d lc_start_point( - prepare_segment.points.back().point.pose.position.x, - prepare_segment.points.back().point.pose.position.y); - - const auto target_lane_poly_2d = common_data_ptr_->lanes_polygon_ptr->target.value(); - - const auto is_valid_start_point = - boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) || - boost::geometry::covered_by(lc_start_point, target_lane_poly_2d); - LaneChangeInfo lane_change_info; lane_change_info.longitudinal_acceleration = LaneChangePhaseInfo{longitudinal_acc_on_prepare, longitudinal_acc_on_lane_changing}; @@ -1532,13 +1521,6 @@ bool NormalLaneChange::getLaneChangePaths( lane_change_info.lateral_acceleration = lateral_acc; lane_change_info.terminal_lane_changing_velocity = terminal_lane_changing_velocity; - if (!is_valid_start_point) { - debug_print_lat( - "Reject: lane changing points are not inside of the target preferred lanes or its " - "neighbors"); - continue; - } - const auto resample_interval = utils::lane_change::calcLaneChangeResampleInterval( lane_changing_length, initial_lane_changing_velocity); const auto target_lane_reference_path = utils::lane_change::getReferencePathFromTargetLane( @@ -2227,6 +2209,18 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan return is_vehicle_stuck; } +bool NormalLaneChange::is_valid_start_point( + const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const +{ + const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y); + + const auto & target_neighbor_poly = common_data_ptr->lanes_polygon_ptr->target_neighbor; + const auto & target_lane_poly = common_data_ptr_->lanes_polygon_ptr->target.value(); + + return boost::geometry::covered_by(lc_start_point, target_neighbor_poly) || + boost::geometry::covered_by(lc_start_point, target_lane_poly); +} + void NormalLaneChange::setStopPose(const Pose & stop_pose) { lane_change_stop_pose_ = stop_pose; From 98c7b19330cb0e711c2b5f2e21d4a40e0ef89612 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 7 Aug 2024 15:39:26 +0900 Subject: [PATCH 077/151] refactor(lane_change): refactor debug print when computing paths (#8358) Refactor debug print Signed-off-by: Zulfaqar Azmi --- .../src/scene.cpp | 29 ++++++++++--------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index d80acf4ec18b2..c83216457feba 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1226,8 +1226,6 @@ PathWithLaneId NormalLaneChange::getTargetSegment( std::min(dist_from_start, dist_from_end), s_start + std::numeric_limits::epsilon()); }); - RCLCPP_DEBUG(logger_, "in %s start: %f, end: %f", __func__, s_start, s_end); - PathWithLaneId target_segment = route_handler.getCenterLinePath(target_lanes, s_start, s_end); for (auto & point : target_segment.points) { point.point.longitudinal_velocity_mps = @@ -1391,12 +1389,6 @@ bool NormalLaneChange::getLaneChangePaths( for (const auto & prepare_duration : prepare_durations) { for (const auto & sampled_longitudinal_acc : longitudinal_acc_sampling_values) { - const auto debug_print = [&](const auto & s) { - RCLCPP_DEBUG_STREAM( - logger_, " - " << s << " : prep_time = " << prepare_duration - << ", lon_acc = " << sampled_longitudinal_acc); - }; - // get path on original lanes const auto prepare_velocity = std::clamp( current_velocity + sampled_longitudinal_acc * prepare_duration, @@ -1412,6 +1404,12 @@ bool NormalLaneChange::getLaneChangePaths( auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length); + const auto debug_print = [&](const auto & s) { + RCLCPP_DEBUG( + logger_, "%s | prep_time: %.5f | lon_acc sampled: %.5f, actual: %.5f | prep_len: %.5f", s, + prepare_duration, sampled_longitudinal_acc, longitudinal_acc_on_prepare, prepare_length); + }; + if (prepare_segment.points.empty()) { debug_print("prepare segment is empty...? Unexpected."); continue; @@ -1453,13 +1451,8 @@ bool NormalLaneChange::getLaneChangePaths( } RCLCPP_DEBUG(logger_, " - sampling num for lat_acc: %lu", sample_lat_acc.size()); + debug_print("Prepare path satisfy constraints"); for (const auto & lateral_acc : sample_lat_acc) { - const auto debug_print_lat = [&](const auto & s) { - RCLCPP_DEBUG_STREAM( - logger_, " - " << s << " : prep_time = " << prepare_duration << ", lon_acc = " - << sampled_longitudinal_acc << ", lat_acc = " << lateral_acc); - }; - const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk( shift_length, lane_change_parameters_->lane_changing_lateral_jerk, lateral_acc); const double longitudinal_acc_on_lane_changing = @@ -1475,6 +1468,14 @@ bool NormalLaneChange::getLaneChangePaths( utils::lane_change::setPrepareVelocity( prepare_segment, current_velocity, terminal_lane_changing_velocity); + const auto debug_print_lat = [&](const auto & s) { + RCLCPP_DEBUG( + logger_, + " - %s | lc_time: %.5f | lon_acc sampled: %.5f, actual: %.5f | lc_len: %.5f", s, + lane_changing_time, sampled_longitudinal_acc, longitudinal_acc_on_lane_changing, + lane_changing_length); + }; + if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) { debug_print_lat("Reject: length of lane changing path is longer than length to goal!!"); continue; From a1d4bfef566bfe2bb864cbfa39110ab0cd72a53d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 7 Aug 2024 17:03:48 +0900 Subject: [PATCH 078/151] fix(lane_change): skip path computation if len exceed dist to terminal start (#8359) Skip computation if prepare length exceed distance to terminal start Signed-off-by: Zulfaqar Azmi --- .../CMakeLists.txt | 1 + .../utils/calculation.hpp | 45 +++++++++++++++++++ .../src/scene.cpp | 14 +++++- .../src/utils/calculation.cpp | 45 +++++++++++++++++++ 4 files changed, 104 insertions(+), 1 deletion(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt index b0d9967e65ddd..509f38d52dd45 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt @@ -9,6 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/interface.cpp src/manager.cpp src/scene.cpp + src/utils/calculation.cpp src/utils/markers.cpp src/utils/utils.cpp ) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp new file mode 100644 index 0000000000000..421b54db9f67a --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -0,0 +1,45 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ + +#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" + +namespace autoware::behavior_path_planner::utils::lane_change::calculation +{ +using behavior_path_planner::lane_change::CommonDataPtr; + +/** + * @brief Calculates the distance from the ego vehicle to the terminal point. + * + * This function computes the distance from the current position of the ego vehicle + * to either the goal pose or the end of the current lane, depending on whether + * the vehicle's current lane is within the goal section. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - Non null `lanes_ptr` that points to the current lanes data. + * - Non null `self_odometry_ptr` that contains the current pose of the ego vehicle. + * - Non null `route_handler_ptr` that contains the goal pose of the route. + * + * @return The distance to the terminal point (either the goal pose or the end of the current lane) + * in meters. + */ +double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr); + +double calc_dist_from_pose_to_terminal_end( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes, + const Pose & src_pose); +} // namespace autoware::behavior_path_planner::utils::lane_change::calculation + +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index c83216457feba..c8bd1f111a2ae 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -14,6 +14,7 @@ #include "autoware/behavior_path_lane_change_module/scene.hpp" +#include "autoware/behavior_path_lane_change_module/utils/calculation.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" #include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" @@ -45,6 +46,7 @@ using utils::lane_change::calcMinimumLaneChangeLength; using utils::lane_change::create_lanes_polygon; using utils::path_safety_checker::isPolygonOverlapLanelet; using utils::traffic_light::getDistanceToNextTrafficLight; +namespace calculation = utils::lane_change::calculation; NormalLaneChange::NormalLaneChange( const std::shared_ptr & parameters, LaneChangeModuleType type, @@ -1361,7 +1363,7 @@ bool NormalLaneChange::getLaneChangePaths( route_handler.getLateralIntervalsToPreferredLane(target_lanes.back())); const auto dist_to_end_of_current_lanes = - utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); + calculation::calc_ego_dist_to_terminal_end(common_data_ptr_); const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes); @@ -1402,6 +1404,16 @@ bool NormalLaneChange::getLaneChangePaths( const auto prepare_length = utils::lane_change::calcPhaseLength( current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration); + const auto ego_dist_to_terminal_start = dist_to_end_of_current_lanes - lane_change_buffer; + if (prepare_length > ego_dist_to_terminal_start) { + RCLCPP_DEBUG( + logger_, + "Reject: Prepare length exceed distance to terminal start. prep_len: %.5f, ego dist to " + "terminal start: %.5f", + prepare_length, ego_dist_to_terminal_start); + continue; + } + auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length); const auto debug_print = [&](const auto & s) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp new file mode 100644 index 0000000000000..521c30d406e7a --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -0,0 +1,45 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +namespace autoware::behavior_path_planner::utils::lane_change::calculation +{ +double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr) +{ + const auto & lanes_ptr = common_data_ptr->lanes_ptr; + const auto & current_lanes = lanes_ptr->current; + const auto & current_pose = common_data_ptr->get_ego_pose(); + + return calc_dist_from_pose_to_terminal_end(common_data_ptr, current_lanes, current_pose); +} + +double calc_dist_from_pose_to_terminal_end( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes, + const Pose & src_pose) +{ + if (lanes.empty()) { + return 0.0; + } + + const auto & lanes_ptr = common_data_ptr->lanes_ptr; + const auto & goal_pose = common_data_ptr->route_handler_ptr->getGoalPose(); + + if (lanes_ptr->current_lane_in_goal_section) { + return utils::getSignedDistance(src_pose, goal_pose, lanes); + } + return utils::getDistanceToEndOfLane(src_pose, lanes); +} +} // namespace autoware::behavior_path_planner::utils::lane_change::calculation From 2e4164c92b397b85b960a0bbea9a0c583b46f173 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 9 Aug 2024 17:37:36 +0900 Subject: [PATCH 079/151] fix(lane_change): skip generating path if lane changing path is too long (#8362) rework. skip lane changing for insufficeient distance in target lane Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../utils/data_structs.hpp | 1 + .../utils/utils.hpp | 4 -- .../src/scene.cpp | 49 ++++++++++--------- .../src/utils/utils.cpp | 20 +------- 4 files changed, 30 insertions(+), 44 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 7962c878d7d64..155fbfdb535f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -191,6 +191,7 @@ struct Lanes { bool current_lane_in_goal_section{false}; lanelet::ConstLanelets current; + lanelet::ConstLanelets target_neighbor; lanelet::ConstLanelets target; std::vector preceding_target; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index d566aceba413b..ec93a3c999152 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -106,10 +106,6 @@ lanelet::ConstLanelets getTargetNeighborLanes( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const LaneChangeModuleType & type); -lanelet::BasicPolygon2d getTargetNeighborLanesPolygon( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, - const LaneChangeModuleType & type); - bool isPathInLanelets( const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index c8bd1f111a2ae..dc4d1022615c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -87,6 +87,9 @@ void NormalLaneChange::update_lanes(const bool is_approved) common_data_ptr_->lanes_ptr->target = target_lanes; const auto & route_handler_ptr = common_data_ptr_->route_handler_ptr; + common_data_ptr_->lanes_ptr->target_neighbor = utils::lane_change::getTargetNeighborLanes( + *route_handler_ptr, current_lanes, common_data_ptr_->lc_type); + common_data_ptr_->lanes_ptr->current_lane_in_goal_section = route_handler_ptr->isInGoalRouteSection(current_lanes.back()); common_data_ptr_->lanes_ptr->preceding_target = utils::getPrecedingLanelets( @@ -1464,6 +1467,9 @@ bool NormalLaneChange::getLaneChangePaths( RCLCPP_DEBUG(logger_, " - sampling num for lat_acc: %lu", sample_lat_acc.size()); debug_print("Prepare path satisfy constraints"); + const auto dist_lc_start_to_end_of_lanes = calculation::calc_dist_from_pose_to_terminal_end( + common_data_ptr_, common_data_ptr_->lanes_ptr->target_neighbor, lane_changing_start_pose); + for (const auto & lateral_acc : sample_lat_acc) { const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk( shift_length, lane_change_parameters_->lane_changing_lateral_jerk, lateral_acc); @@ -1474,11 +1480,6 @@ bool NormalLaneChange::getLaneChangePaths( const auto lane_changing_length = utils::lane_change::calcPhaseLength( initial_lane_changing_velocity, getCommonParam().max_vel, longitudinal_acc_on_lane_changing, lane_changing_time); - const auto terminal_lane_changing_velocity = std::min( - initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time, - getCommonParam().max_vel); - utils::lane_change::setPrepareVelocity( - prepare_segment, current_velocity, terminal_lane_changing_velocity); const auto debug_print_lat = [&](const auto & s) { RCLCPP_DEBUG( @@ -1493,26 +1494,30 @@ bool NormalLaneChange::getLaneChangePaths( continue; } - if (is_goal_in_route) { - const double s_start = - lanelet::utils::getArcCoordinates(target_lanes, lane_changing_start_pose).length; - const double s_goal = - lanelet::utils::getArcCoordinates(target_lanes, route_handler.getGoalPose()).length; - const auto num = + // if multiple lane change is necessary, does the remaining distance is sufficient + const auto remaining_dist_in_target = std::invoke([&]() { + const auto finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer; + const auto num_to_preferred_lane_from_target_lane = std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back(), direction)); - const double backward_buffer = - num == 0 ? 0.0 : lane_change_parameters_->backward_length_buffer_for_end_of_lane; - const double finish_judge_buffer = - lane_change_parameters_->lane_change_finish_judge_buffer; - if ( - s_start + lane_changing_length + finish_judge_buffer + backward_buffer + - next_lane_change_buffer > - s_goal) { - debug_print_lat("Reject: length of lane changing path is longer than length to goal!!"); - continue; - } + const auto backward_len_buffer = + lane_change_parameters_->backward_length_buffer_for_end_of_lane; + const auto backward_buffer_to_target_lane = + num_to_preferred_lane_from_target_lane == 0 ? 0.0 : backward_len_buffer; + return lane_changing_length + finish_judge_buffer + backward_buffer_to_target_lane + + next_lane_change_buffer; + }); + + if (remaining_dist_in_target > dist_lc_start_to_end_of_lanes) { + debug_print_lat("Reject: length of lane changing path is longer than length to goal!!"); + continue; } + const auto terminal_lane_changing_velocity = std::min( + initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time, + getCommonParam().max_vel); + utils::lane_change::setPrepareVelocity( + prepare_segment, current_velocity, terminal_lane_changing_velocity); + const auto target_segment = getTargetSegment( target_lanes, lane_changing_start_pose, target_lane_length, lane_changing_length, initial_lane_changing_velocity, next_lane_change_buffer); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 915864c597882..1d8ffaa4b7b18 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -290,21 +290,6 @@ lanelet::ConstLanelets getTargetNeighborLanes( return neighbor_lanes; } -lanelet::BasicPolygon2d getTargetNeighborLanesPolygon( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, - const LaneChangeModuleType & type) -{ - const auto target_neighbor_lanelets = - utils::lane_change::getTargetNeighborLanes(route_handler, current_lanes, type); - if (target_neighbor_lanelets.empty()) { - return {}; - } - const auto target_neighbor_preferred_lane_poly = lanelet::utils::getPolygonFromArcLength( - target_neighbor_lanelets, 0, std::numeric_limits::max()); - - return lanelet::utils::to2D(target_neighbor_preferred_lane_poly).basicPolygon(); -} - bool isPathInLanelets( const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) @@ -1227,9 +1212,8 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr) lanes_polygon.expanded_target = utils::lane_change::createPolygon( expanded_target_lanes, 0.0, std::numeric_limits::max()); - const auto & route_handler = *common_data_ptr->route_handler_ptr; - lanes_polygon.target_neighbor = - getTargetNeighborLanesPolygon(route_handler, lanes->current, common_data_ptr->lc_type); + lanes_polygon.target_neighbor = *utils::lane_change::createPolygon( + lanes->target_neighbor, 0.0, std::numeric_limits::max()); lanes_polygon.preceding_target.reserve(lanes->preceding_target.size()); for (const auto & preceding_lane : lanes->preceding_target) { From b8306187b35d5785b8bafcf42387ee02cf66528b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 13 Aug 2024 10:43:13 +0900 Subject: [PATCH 080/151] fix(lane_change): skip generating path if longitudinal distance difference is less than threshold (#8363) * fix when prepare length is insufficient Signed-off-by: Muhammad Zulfaqar Azmi * add reason for comparing prev_prep_diff with eps for lc_length_diff Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../config/lane_change.param.yaml | 5 +++++ .../utils/data_structs.hpp | 3 +++ .../src/manager.cpp | 7 ++++++ .../src/scene.cpp | 22 +++++++++++++++++++ 4 files changed, 37 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 7a9c466fec260..a7128a0dc546f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -26,6 +26,11 @@ min_longitudinal_acc: -1.0 max_longitudinal_acc: 1.0 + skip_process: + longitudinal_distance_diff_threshold: + prepare: 0.5 + lane_changing: 0.5 + # safety check safety_check: allow_loose_check_for_cancel: true diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 155fbfdb535f9..9ef47485ec68c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -124,6 +124,9 @@ struct Parameters double min_longitudinal_acc{-1.0}; double max_longitudinal_acc{1.0}; + double skip_process_lon_diff_th_prepare{0.5}; + double skip_process_lon_diff_th_lane_changing{1.0}; + // collision check bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; bool enable_collision_check_for_prepare_phase_in_intersection{true}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index f3f371ec02a9b..42166c4dff0e0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -354,6 +354,13 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "max_longitudinal_acc", p->max_longitudinal_acc); } + { + const std::string ns = "lane_change.skip_process.longitudinal_distance_diff_threshold."; + updateParam(parameters, ns + "prepare", p->skip_process_lon_diff_th_prepare); + updateParam( + parameters, ns + "lane_changing", p->skip_process_lon_diff_th_lane_changing); + } + { const std::string ns = "lane_change.safety_check.lane_expansion."; updateParam(parameters, ns + "left_offset", p->lane_expansion_left_offset); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index dc4d1022615c6..c13d9df08d5f5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1417,6 +1417,13 @@ bool NormalLaneChange::getLaneChangePaths( continue; } + if (!candidate_paths->empty()) { + const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length; + if (std::abs(prev_prep_diff) < lane_change_parameters_->skip_process_lon_diff_th_prepare) { + RCLCPP_DEBUG(logger_, "Skip: Change in prepare length is less than threshold."); + continue; + } + } auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length); const auto debug_print = [&](const auto & s) { @@ -1488,6 +1495,21 @@ bool NormalLaneChange::getLaneChangePaths( lane_changing_time, sampled_longitudinal_acc, longitudinal_acc_on_lane_changing, lane_changing_length); }; + if (!candidate_paths->empty()) { + const auto prev_prep_diff = candidate_paths->back().info.length.prepare - prepare_length; + const auto lc_length_diff = + candidate_paths->back().info.length.lane_changing - lane_changing_length; + + // We only check lc_length_diff if and only if the current prepare_length is equal to the + // previous prepare_length. + if ( + std::abs(prev_prep_diff) < eps && + std::abs(lc_length_diff) < + lane_change_parameters_->skip_process_lon_diff_th_lane_changing) { + RCLCPP_DEBUG(logger_, "Skip: Change in lane changing length is less than threshold."); + continue; + } + } if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) { debug_print_lat("Reject: length of lane changing path is longer than length to goal!!"); From 8314f3820be73ef78443d615f0934e1b1d63d2d4 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 13 Aug 2024 11:11:46 +0900 Subject: [PATCH 081/151] refactor(lane_change): separate leading and trailing objects (#8214) * refactor(lane_change): separate leading and trailing objects Signed-off-by: Muhammad Zulfaqar Azmi * Refactor to use common function Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../scene.hpp | 17 +- .../utils/base_class.hpp | 2 +- .../utils/data_structs.hpp | 41 ++++- .../utils/debug_structs.hpp | 5 +- .../utils/markers.hpp | 5 +- .../utils/utils.hpp | 4 + .../src/interface.cpp | 2 +- .../src/scene.cpp | 164 +++++++++--------- .../src/utils/markers.cpp | 45 +++-- .../src/utils/utils.cpp | 17 ++ 10 files changed, 182 insertions(+), 120 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index 605e0499adcdb..cc695f820ee38 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -82,7 +82,7 @@ class NormalLaneChange : public LaneChangeBase PathSafetyStatus evaluateApprovedPathWithUnsafeHysteresis( PathSafetyStatus approved_path_safety_status) override; - bool isRequiredStop(const bool is_object_coming_from_rear) override; + bool isRequiredStop(const bool is_trailing_object) override; bool isNearEndOfCurrentLanes( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, @@ -120,19 +120,16 @@ class NormalLaneChange : public LaneChangeBase const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const; - ExtendedPredictedObjects getTargetObjects( - const LaneChangeLanesFilteredObjects & predicted_objects, + lane_change::TargetObjects getTargetObjects( + const FilteredByLanesExtendedObjects & predicted_objects, const lanelet::ConstLanelets & current_lanes) const; - LaneChangeLanesFilteredObjects filterObjects() const; + FilteredByLanesExtendedObjects filterObjects() const; void filterOncomingObjects(PredictedObjects & objects) const; - void filterObjectsByLanelets( - const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path, - std::vector & current_lane_objects, - std::vector & target_lane_objects, - std::vector & other_lane_objects) const; + FilteredByLanesObjects filterObjectsByLanelets( + const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path) const; PathWithLaneId getPrepareSegment( const lanelet::ConstLanelets & current_lanes, const double backward_path_length, @@ -170,7 +167,7 @@ class NormalLaneChange : public LaneChangeBase PathSafetyStatus isLaneChangePathSafe( const LaneChangePath & lane_change_path, - const ExtendedPredictedObjects & collision_check_objects, + const lane_change::TargetObjects & collision_check_objects, const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index c1cc14d98a7c7..ccc9258324ffa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -99,7 +99,7 @@ class LaneChangeBase virtual bool isEgoOnPreparePhase() const = 0; - virtual bool isRequiredStop(const bool is_object_coming_from_rear) = 0; + virtual bool isRequiredStop(const bool is_trailing_object) = 0; virtual PathSafetyStatus isApprovedPathSafe() const = 0; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp index 9ef47485ec68c..9ddeca87c12a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp @@ -215,11 +215,33 @@ struct Info double terminal_lane_changing_velocity{0.0}; }; +template struct LanesObjects { - ExtendedPredictedObjects current_lane{}; - ExtendedPredictedObjects target_lane{}; - ExtendedPredictedObjects other_lane{}; + Object current_lane{}; + Object target_lane_leading{}; + Object target_lane_trailing{}; + Object other_lane{}; + + LanesObjects() = default; + LanesObjects( + Object current_lane, Object target_lane_leading, Object target_lane_trailing, Object other_lane) + : current_lane(std::move(current_lane)), + target_lane_leading(std::move(target_lane_leading)), + target_lane_trailing(std::move(target_lane_trailing)), + other_lane(std::move(other_lane)) + { + } +}; + +struct TargetObjects +{ + ExtendedPredictedObjects leading; + ExtendedPredictedObjects trailing; + TargetObjects(ExtendedPredictedObjects leading, ExtendedPredictedObjects trailing) + : leading(std::move(leading)), trailing(std::move(trailing)) + { + } }; enum class ModuleType { @@ -231,7 +253,13 @@ enum class ModuleType { struct PathSafetyStatus { bool is_safe{true}; - bool is_object_coming_from_rear{false}; + bool is_trailing_object{false}; + + PathSafetyStatus() = default; + PathSafetyStatus(const bool is_safe, const bool is_trailing_object) + : is_safe(is_safe), is_trailing_object(is_trailing_object) + { + } }; struct LanesPolygon @@ -280,12 +308,15 @@ using CommonDataPtr = std::shared_ptr; namespace autoware::behavior_path_planner { +using autoware_perception_msgs::msg::PredictedObject; +using utils::path_safety_checker::ExtendedPredictedObjects; using LaneChangeModuleType = lane_change::ModuleType; using LaneChangeParameters = lane_change::Parameters; using LaneChangeStates = lane_change::States; using LaneChangePhaseInfo = lane_change::PhaseInfo; using LaneChangeInfo = lane_change::Info; -using LaneChangeLanesFilteredObjects = lane_change::LanesObjects; +using FilteredByLanesObjects = lane_change::LanesObjects>; +using FilteredByLanesExtendedObjects = lane_change::LanesObjects; using LateralAccelerationMap = lane_change::LateralAccelerationMap; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp index 1890b9f308e8e..fc51a82a8a842 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp @@ -35,7 +35,7 @@ struct Debug LaneChangePaths valid_paths; CollisionCheckDebugMap collision_check_objects; CollisionCheckDebugMap collision_check_objects_after_approval; - LaneChangeLanesFilteredObjects filtered_objects; + FilteredByLanesExtendedObjects filtered_objects; geometry_msgs::msg::Polygon execution_area; geometry_msgs::msg::Pose ego_pose; lanelet::ConstLanelets current_lanes; @@ -55,7 +55,8 @@ struct Debug collision_check_objects.clear(); collision_check_objects_after_approval.clear(); filtered_objects.current_lane.clear(); - filtered_objects.target_lane.clear(); + filtered_objects.target_lane_leading.clear(); + filtered_objects.target_lane_trailing.clear(); filtered_objects.other_lane.clear(); execution_area.points.clear(); current_lanes.clear(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index 91d1f1db15cbc..d403e7e1436c7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -29,6 +29,7 @@ namespace marker_utils::lane_change_markers { +using autoware::behavior_path_planner::FilteredByLanesExtendedObjects; using autoware::behavior_path_planner::LaneChangePath; using autoware::behavior_path_planner::lane_change::Debug; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; @@ -39,9 +40,7 @@ MarkerArray createLaneChangingVirtualWallMarker( const geometry_msgs::msg::Pose & lane_changing_pose, const std::string & module_name, const rclcpp::Time & now, const std::string & ns); MarkerArray showFilteredObjects( - const ExtendedPredictedObjects & current_lane_objects, - const ExtendedPredictedObjects & target_lane_objects, - const ExtendedPredictedObjects & other_lane_objects, const std::string & ns); + const FilteredByLanesExtendedObjects & filtered_objects, const std::string & ns); MarkerArray createExecutionArea(const geometry_msgs::msg::Polygon & execution_area); MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); MarkerArray createDebugMarkerArray( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index ec93a3c999152..a270900b491c3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -312,6 +312,10 @@ bool is_before_terminal( const PredictedObject & object); double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose); + +ExtendedPredictedObjects transform_to_extended_objects( + const CommonDataPtr & common_data_ptr, const std::vector & objects, + const bool check_prepare_phase); } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 4823cb0bfec22..30ac0051e0339 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -276,7 +276,7 @@ bool LaneChangeInterface::canTransitFailureState() return false; } - if (module_type_->isRequiredStop(post_process_safety_status_.is_object_coming_from_rear)) { + if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) { log_debug_throttled("Module require stopping"); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index c13d9df08d5f5..8eae075df8b41 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -465,7 +465,8 @@ void NormalLaneChange::insertStopPoint( // [ego]> | <--- lane change margin ---> [obj]> // ---------------------------------------------------------- const bool has_blocking_target_lane_obj = std::any_of( - target_objects.target_lane.begin(), target_objects.target_lane.end(), [&](const auto & o) { + target_objects.target_lane_leading.begin(), target_objects.target_lane_leading.end(), + [&](const auto & o) { const auto v = std::abs(o.initial_twist.twist.linear.x); if (v > lane_change_parameters_->stop_velocity_threshold) { return false; @@ -973,32 +974,32 @@ PathWithLaneId NormalLaneChange::getPrepareSegment( return prepare_segment; } -ExtendedPredictedObjects NormalLaneChange::getTargetObjects( - const LaneChangeLanesFilteredObjects & filtered_objects, +lane_change::TargetObjects NormalLaneChange::getTargetObjects( + const FilteredByLanesExtendedObjects & filtered_objects, const lanelet::ConstLanelets & current_lanes) const { - ExtendedPredictedObjects target_objects = filtered_objects.target_lane; + ExtendedPredictedObjects leading_objects = filtered_objects.target_lane_leading; const auto is_stuck = isVehicleStuck(current_lanes); const auto chk_obj_in_curr_lanes = lane_change_parameters_->check_objects_on_current_lanes; if (chk_obj_in_curr_lanes || is_stuck) { - target_objects.insert( - target_objects.end(), filtered_objects.current_lane.begin(), + leading_objects.insert( + leading_objects.end(), filtered_objects.current_lane.begin(), filtered_objects.current_lane.end()); } const auto chk_obj_in_other_lanes = lane_change_parameters_->check_objects_on_other_lanes; if (chk_obj_in_other_lanes) { - target_objects.insert( - target_objects.end(), filtered_objects.other_lane.begin(), filtered_objects.other_lane.end()); + leading_objects.insert( + leading_objects.end(), filtered_objects.other_lane.begin(), + filtered_objects.other_lane.end()); } - return target_objects; + return {leading_objects, filtered_objects.target_lane_trailing}; } -LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const +FilteredByLanesExtendedObjects NormalLaneChange::filterObjects() const { const auto & route_handler = getRouteHandler(); - const auto & common_parameters = planner_data_->parameters; auto objects = *planner_data_->dynamic_object; utils::path_safety_checker::filterObjectsByClass( objects, lane_change_parameters_->object_types_to_check); @@ -1019,10 +1020,6 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const return {}; } - std::vector target_lane_objects; - std::vector current_lane_objects; - std::vector other_lane_objects; - const auto & target_lanes = get_target_lanes(); if (target_lanes.empty()) { @@ -1032,8 +1029,7 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const const auto path = route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); - filterObjectsByLanelets( - objects, path, current_lane_objects, target_lane_objects, other_lane_objects); + auto filtered_by_lanes_objects = filterObjectsByLanelets(objects, path); const auto is_within_vel_th = [](const auto & object) -> bool { constexpr double min_vel_th = 1.0; @@ -1042,14 +1038,12 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const }; utils::path_safety_checker::filterObjects( - target_lane_objects, [&](const PredictedObject & object) { - const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); - return is_within_vel_th(object) || ahead_of_ego; - }); + filtered_by_lanes_objects.target_lane_trailing, + [&](const PredictedObject & object) { return is_within_vel_th(object); }); if (lane_change_parameters_->check_objects_on_other_lanes) { utils::path_safety_checker::filterObjects( - other_lane_objects, [&](const PredictedObject & object) { + filtered_by_lanes_objects.other_lane, [&](const PredictedObject & object) { const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); return is_within_vel_th(object) && ahead_of_ego; @@ -1057,34 +1051,27 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects() const } utils::path_safety_checker::filterObjects( - current_lane_objects, [&](const PredictedObject & object) { + filtered_by_lanes_objects.current_lane, [&](const PredictedObject & object) { const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); return is_within_vel_th(object) && ahead_of_ego; }); - LaneChangeLanesFilteredObjects lane_change_target_objects; - const auto is_check_prepare_phase = check_prepare_phase(); - std::for_each(target_lane_objects.begin(), target_lane_objects.end(), [&](const auto & object) { - auto extended_predicted_object = utils::lane_change::transform( - object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); - lane_change_target_objects.target_lane.push_back(extended_predicted_object); - }); - - std::for_each(current_lane_objects.begin(), current_lane_objects.end(), [&](const auto & object) { - auto extended_predicted_object = utils::lane_change::transform( - object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); - lane_change_target_objects.current_lane.push_back(extended_predicted_object); - }); - - std::for_each(other_lane_objects.begin(), other_lane_objects.end(), [&](const auto & object) { - auto extended_predicted_object = utils::lane_change::transform( - object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); - lane_change_target_objects.other_lane.push_back(extended_predicted_object); - }); - + const auto target_lane_leading_extended_objects = + utils::lane_change::transform_to_extended_objects( + common_data_ptr_, filtered_by_lanes_objects.target_lane_leading, is_check_prepare_phase); + const auto target_lane_trailing_extended_objects = + utils::lane_change::transform_to_extended_objects( + common_data_ptr_, filtered_by_lanes_objects.target_lane_trailing, is_check_prepare_phase); + const auto current_lane_extended_objects = utils::lane_change::transform_to_extended_objects( + common_data_ptr_, filtered_by_lanes_objects.current_lane, is_check_prepare_phase); + const auto other_lane_extended_objects = utils::lane_change::transform_to_extended_objects( + common_data_ptr_, filtered_by_lanes_objects.other_lane, is_check_prepare_phase); + + FilteredByLanesExtendedObjects lane_change_target_objects( + current_lane_extended_objects, target_lane_leading_extended_objects, + target_lane_trailing_extended_objects, other_lane_extended_objects); lane_change_debug_.filtered_objects = lane_change_target_objects; - return lane_change_target_objects; } @@ -1115,12 +1102,14 @@ void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const }); } -void NormalLaneChange::filterObjectsByLanelets( - const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path, - std::vector & current_lane_objects, - std::vector & target_lane_objects, - std::vector & other_lane_objects) const +FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets( + const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path) const { + std::vector target_lane_leading_objects; + std::vector target_lane_trailing_objects; + std::vector current_lane_objects; + std::vector other_lane_objects; + const auto & current_pose = getEgoPose(); const auto & current_lanes = common_data_ptr_->lanes_ptr->current; const auto & target_lanes = common_data_ptr_->lanes_ptr->target; @@ -1152,12 +1141,11 @@ void NormalLaneChange::filterObjectsByLanelets( const auto dist_ego_to_current_lanes_center = lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); - { - const auto reserve_size = objects.objects.size(); - current_lane_objects.reserve(reserve_size); - target_lane_objects.reserve(reserve_size); - other_lane_objects.reserve(reserve_size); - } + const auto reserve_size = objects.objects.size(); + current_lane_objects.reserve(reserve_size); + target_lane_leading_objects.reserve(reserve_size); + target_lane_trailing_objects.reserve(reserve_size); + other_lane_objects.reserve(reserve_size); for (const auto & object : objects.objects) { const auto is_lateral_far = std::invoke([&]() -> bool { @@ -1176,7 +1164,13 @@ void NormalLaneChange::filterObjectsByLanelets( if ( check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far && is_before_terminal()) { - target_lane_objects.push_back(object); + const auto ahead_of_ego = + utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object); + if (ahead_of_ego) { + target_lane_leading_objects.push_back(object); + } else { + target_lane_trailing_objects.push_back(object); + } continue; } @@ -1191,7 +1185,7 @@ void NormalLaneChange::filterObjectsByLanelets( // check if the object intersects with target backward lanes if (is_overlap_target_backward) { - target_lane_objects.push_back(object); + target_lane_trailing_objects.push_back(object); continue; } @@ -1203,6 +1197,10 @@ void NormalLaneChange::filterObjectsByLanelets( other_lane_objects.push_back(object); } + + return { + current_lane_objects, target_lane_leading_objects, target_lane_trailing_objects, + other_lane_objects}; } PathWithLaneId NormalLaneChange::getTargetSegment( @@ -1629,7 +1627,7 @@ bool NormalLaneChange::getLaneChangePaths( if ( !is_stuck && !utils::lane_change::passed_parked_objects( - common_data_ptr_, *candidate_path, filtered_objects.target_lane, + common_data_ptr_, *candidate_path, filtered_objects.target_lane_leading, lane_change_buffer, lane_change_debug_.collision_check_objects)) { debug_print_lat( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " @@ -1642,7 +1640,7 @@ bool NormalLaneChange::getLaneChangePaths( return false; } - const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe( + const auto [is_safe, is_trailing_object] = isLaneChangePathSafe( *candidate_path, target_objects, rss_params, lane_change_debug_.collision_check_objects); if (is_safe) { @@ -1820,7 +1818,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const common_data_ptr_->route_handler_ptr->getLateralIntervalsToPreferredLane(current_lanes.back())); const auto has_passed_parked_objects = utils::lane_change::passed_parked_objects( - common_data_ptr_, path, filtered_objects.target_lane, min_lc_length, debug_data); + common_data_ptr_, path, filtered_objects.target_lane_leading, min_lc_length, debug_data); if (!has_passed_parked_objects) { RCLCPP_DEBUG(logger_, "Lane change has been delayed."); @@ -1908,13 +1906,13 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const return true; } -bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) +bool NormalLaneChange::isRequiredStop(const bool is_trailing_object) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto threshold = lane_change_parameters_->backward_length_buffer_for_end_of_lane; if ( isNearEndOfCurrentLanes(get_current_lanes(), get_target_lanes(), threshold) && - isAbleToStopSafely() && is_object_coming_from_rear) { + isAbleToStopSafely() && is_trailing_object) { current_lane_change_state_ = LaneChangeStates::Stop; return true; } @@ -2064,16 +2062,18 @@ bool NormalLaneChange::calcAbortPath() } PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( - const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & collision_check_objects, + const LaneChangePath & lane_change_path, + const lane_change::TargetObjects & collision_check_objects, const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - PathSafetyStatus path_safety_status; + constexpr auto is_safe = true; + constexpr auto is_object_behind_ego = true; - if (collision_check_objects.empty()) { + if (collision_check_objects.leading.empty() && collision_check_objects.trailing.empty()) { RCLCPP_DEBUG(logger_, "There is nothing to check."); - return path_safety_status; + return {is_safe, !is_object_behind_ego}; } const auto & path = lane_change_path.path; @@ -2082,11 +2082,10 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const auto current_twist = getEgoTwist(); if (path.points.empty()) { - path_safety_status.is_safe = false; - return path_safety_status; + return {!is_safe, !is_object_behind_ego}; } - const double & time_resolution = lane_change_parameters_->prediction_time_resolution; + const auto time_resolution = lane_change_parameters_->prediction_time_resolution; const auto ego_predicted_path = utils::lane_change::convertToPredictedPath( lane_change_path, current_twist, current_pose, common_parameters, *lane_change_parameters_, @@ -2099,7 +2098,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( constexpr double collision_check_yaw_diff_threshold{M_PI}; - for (const auto & obj : collision_check_objects) { + const auto check_collision = [&](const ExtendedPredictedObject & obj) { auto current_debug_data = utils::path_safety_checker::createObjectDebug(obj); const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( obj, lane_change_parameters_->use_all_predicted_path); @@ -2132,21 +2131,28 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( continue; } - is_safe = false; - path_safety_status.is_safe = false; utils::path_safety_checker::updateCollisionCheckDebugMap( - debug_data, current_debug_data, is_safe); - const auto & obj_pose = obj.initial_pose.pose; - const auto obj_polygon = autoware::universe_utils::toPolygon2d(obj_pose, obj.shape); - path_safety_status.is_object_coming_from_rear |= - !utils::path_safety_checker::isTargetObjectFront( - path, current_pose, common_parameters.vehicle_info, obj_polygon); + debug_data, current_debug_data, !is_safe); + return !is_safe; } utils::path_safety_checker::updateCollisionCheckDebugMap( debug_data, current_debug_data, is_safe); + return is_safe; + }; + + for (const auto & obj : collision_check_objects.trailing) { + if (!check_collision(obj)) { + return {!is_safe, is_object_behind_ego}; + } + } + + for (const auto & obj : collision_check_objects.leading) { + if (!check_collision(obj)) { + return {!is_safe, !is_object_behind_ego}; + } } - return path_safety_status; + return {is_safe, !is_object_behind_ego}; } // Check if the ego vehicle is in stuck by a stationary obstacle or by the terminal of current lanes diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index 9a553cf97af5c..eb64493b0c728 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -101,27 +101,36 @@ MarkerArray createLaneChangingVirtualWallMarker( } MarkerArray showFilteredObjects( - const ExtendedPredictedObjects & current_lane_objects, - const ExtendedPredictedObjects & target_lane_objects, - const ExtendedPredictedObjects & other_lane_objects, const std::string & ns) + const FilteredByLanesExtendedObjects & filtered_objects, const std::string & ns) { int32_t update_id = 0; - auto current_marker = - marker_utils::showFilteredObjects(current_lane_objects, ns, colors::yellow(), update_id); + auto current_marker = marker_utils::showFilteredObjects( + filtered_objects.current_lane, ns, colors::yellow(), update_id); update_id += static_cast(current_marker.markers.size()); - auto target_marker = - marker_utils::showFilteredObjects(target_lane_objects, ns, colors::aqua(), update_id); - update_id += static_cast(target_marker.markers.size()); - auto other_marker = - marker_utils::showFilteredObjects(other_lane_objects, ns, colors::medium_orchid(), update_id); + auto target_leading_marker = marker_utils::showFilteredObjects( + filtered_objects.target_lane_leading, ns, colors::aqua(), update_id); + update_id += static_cast(target_leading_marker.markers.size()); + auto target_trailing_marker = marker_utils::showFilteredObjects( + filtered_objects.target_lane_trailing, ns, colors::blue(), update_id); + update_id += static_cast(target_trailing_marker.markers.size()); + auto other_marker = marker_utils::showFilteredObjects( + filtered_objects.other_lane, ns, colors::medium_orchid(), update_id); MarkerArray marker_array; - marker_array.markers.insert( - marker_array.markers.end(), current_marker.markers.begin(), current_marker.markers.end()); - marker_array.markers.insert( - marker_array.markers.end(), target_marker.markers.begin(), target_marker.markers.end()); - marker_array.markers.insert( - marker_array.markers.end(), other_marker.markers.begin(), other_marker.markers.end()); + std::move( + current_marker.markers.begin(), current_marker.markers.end(), + std::back_inserter(marker_array.markers)); + std::move( + target_leading_marker.markers.begin(), target_leading_marker.markers.end(), + std::back_inserter(marker_array.markers)); + + std::move( + target_trailing_marker.markers.begin(), target_trailing_marker.markers.end(), + std::back_inserter(marker_array.markers)); + + std::move( + other_marker.markers.begin(), other_marker.markers.end(), + std::back_inserter(marker_array.markers)); return marker_array; } @@ -190,9 +199,7 @@ MarkerArray createDebugMarkerArray( "target_backward_lanes", debug_data.target_backward_lanes, colors::blue(0.2))); add(showAllValidLaneChangePath(debug_valid_paths, "lane_change_valid_paths")); - add(showFilteredObjects( - debug_filtered_objects.current_lane, debug_filtered_objects.target_lane, - debug_filtered_objects.other_lane, "object_filtered")); + add(showFilteredObjects(debug_filtered_objects, "object_filtered")); if (!debug_collision_check_object.empty()) { add(showSafetyCheckInfo(debug_collision_check_object, "collision_check_object_info")); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 1d8ffaa4b7b18..71e6b0bf6530e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -1338,6 +1338,23 @@ double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, co const auto closest_pose = lanelet::utils::getClosestCenterPose(closest_lanelet, pose.position); return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, pose)); } + +ExtendedPredictedObjects transform_to_extended_objects( + const CommonDataPtr & common_data_ptr, const std::vector & objects, + const bool check_prepare_phase) +{ + ExtendedPredictedObjects extended_objects; + extended_objects.reserve(objects.size()); + + const auto & bpp_param = *common_data_ptr->bpp_param_ptr; + const auto & lc_param = *common_data_ptr->lc_param_ptr; + std::transform( + objects.begin(), objects.end(), std::back_inserter(extended_objects), [&](const auto & object) { + return utils::lane_change::transform(object, bpp_param, lc_param, check_prepare_phase); + }); + + return extended_objects; +} } // namespace autoware::behavior_path_planner::utils::lane_change namespace autoware::behavior_path_planner::utils::lane_change::debug From 72d525448210942c3ad8a4b8ba7c1f62c621c9ae Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 19 Jul 2024 12:56:25 +0900 Subject: [PATCH 082/151] feat(static_obstacle_avoidance): enable force execution under unsafe conditions (#8094) * add force execution for static obstacle avoidance Signed-off-by: Go Sakayori * fix Signed-off-by: Go Sakayori * erase unused function in RTC interface Signed-off-by: Go Sakayori * refactor with lamda function Signed-off-by: Go Sakayori * fix rtc_interface Signed-off-by: Go Sakayori * add warn throtthle and move code block Signed-off-by: Go Sakayori * fix Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../autoware/rtc_interface/rtc_interface.hpp | 1 + .../src/rtc_interface.cpp | 23 +++++++++++ .../scene.hpp | 23 +++++++++-- .../src/scene.cpp | 39 +++++++++++++++++++ 4 files changed, 82 insertions(+), 4 deletions(-) diff --git a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp index 23f7f0b4b36c5..be9b2cfc1ccf6 100644 --- a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp +++ b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp @@ -59,6 +59,7 @@ class RTCInterface void removeExpiredCooperateStatus(); void clearCooperateStatus(); bool isActivated(const UUID & uuid) const; + bool isForceActivated(const UUID & uuid) const; bool isRegistered(const UUID & uuid) const; bool isRTCEnabled(const UUID & uuid) const; bool isTerminated(const UUID & uuid) const; diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 44678077d5dd1..7dcdc4d5984a6 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -345,6 +345,29 @@ bool RTCInterface::isActivated(const UUID & uuid) const return false; } +bool RTCInterface::isForceActivated(const UUID & uuid) const +{ + std::lock_guard lock(mutex_); + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](const auto & s) { return s.uuid == uuid; }); + + if (itr != registered_status_.statuses.end()) { + if (itr->state.type != State::WAITING_FOR_EXECUTION && itr->state.type != State::RUNNING) { + return false; + } + if (itr->command_status.type == Command::ACTIVATE && !itr->safe) { + return true; + } else { + return false; + } + } + + RCLCPP_WARN_STREAM( + getLogger(), "[isForceActivated] uuid : " << to_string(uuid) << " is not found" << std::endl); + return false; +} + bool RTCInterface::isRegistered(const UUID & uuid) const { std::lock_guard lock(mutex_); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 34d06a46d9ac8..87a4c91792649 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -118,8 +118,16 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const double start_distance = autoware::motion_utils::calcSignedArcLength( path.points, ego_idx, left_shift.start_pose.position); const double finish_distance = start_distance + left_shift.relative_longitudinal; - rtc_interface_ptr_map_.at("left")->updateCooperateStatus( - left_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now()); + + // If force activated keep safety to false + if (rtc_interface_ptr_map_.at("left")->isForceActivated(left_shift.uuid)) { + rtc_interface_ptr_map_.at("left")->updateCooperateStatus( + left_shift.uuid, false, State::RUNNING, start_distance, finish_distance, clock_->now()); + } else { + rtc_interface_ptr_map_.at("left")->updateCooperateStatus( + left_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now()); + } + if (finish_distance > -1.0e-03) { steering_factor_interface_ptr_->updateSteeringFactor( {left_shift.start_pose, left_shift.finish_pose}, {start_distance, finish_distance}, @@ -131,8 +139,15 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const double start_distance = autoware::motion_utils::calcSignedArcLength( path.points, ego_idx, right_shift.start_pose.position); const double finish_distance = start_distance + right_shift.relative_longitudinal; - rtc_interface_ptr_map_.at("right")->updateCooperateStatus( - right_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now()); + + if (rtc_interface_ptr_map_.at("right")->isForceActivated(right_shift.uuid)) { + rtc_interface_ptr_map_.at("right")->updateCooperateStatus( + right_shift.uuid, false, State::RUNNING, start_distance, finish_distance, clock_->now()); + } else { + rtc_interface_ptr_map_.at("right")->updateCooperateStatus( + right_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now()); + } + if (finish_distance > -1.0e-03) { steering_factor_interface_ptr_->updateSteeringFactor( {right_shift.start_pose, right_shift.finish_pose}, {start_distance, finish_distance}, diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 39a8d1b853e47..422c7b8ce0f26 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -579,6 +579,45 @@ void StaticObstacleAvoidanceModule::fillEgoStatus( return; } + auto candidate_sl_force_activated = [&](const std::string & direction) { + // If statement to avoid unnecessary warning occurring from isForceActivated function + if (candidate_uuid_ == uuid_map_.at(direction)) { + if (rtc_interface_ptr_map_.at(direction)->isForceActivated(candidate_uuid_)) { + return true; + } + } + return false; + }; + + auto registered_sl_force_activated = + [&](const std::string & direction, const RegisteredShiftLineArray shift_line_array) { + return std::any_of( + shift_line_array.begin(), shift_line_array.end(), [&](const auto & shift_line) { + return rtc_interface_ptr_map_.at(direction)->isForceActivated(shift_line.uuid); + }); + }; + + /** + * Check if the candidate avoidance path is force activated + */ + if (candidate_sl_force_activated("left") || candidate_sl_force_activated("right")) { + data.yield_required = false; + data.safe_shift_line = data.new_shift_line; + return; + } + + /** + * Check if any registered shift line is force activated + */ + if ( + registered_sl_force_activated("left", left_shift_array_) || + registered_sl_force_activated("right", right_shift_array_)) { + data.yield_required = false; + data.safe_shift_line = data.new_shift_line; + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe but force executed"); + return; + } + /** * If the yield maneuver is disabled, use unapproved_new_sl for avoidance path generation even if * the shift line is unsafe. From 5f8afec2313d3657bc9cca67d444765ba5c2c672 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 19 Jul 2024 18:47:47 +0900 Subject: [PATCH 083/151] fix(rtc_interface): fix build error (#8111) * fix Signed-off-by: Go Sakayori * fix format Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- planning/autoware_rtc_interface/src/rtc_interface.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 7dcdc4d5984a6..1352ec10557f9 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -364,7 +364,8 @@ bool RTCInterface::isForceActivated(const UUID & uuid) const } RCLCPP_WARN_STREAM( - getLogger(), "[isForceActivated] uuid : " << to_string(uuid) << " is not found" << std::endl); + getLogger(), + "[isForceActivated] uuid : " << uuid_to_string(uuid) << " is not found" << std::endl); return false; } From 275d6d4262c01bd3781c4c12f3d6045225fa22f0 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 22 Jul 2024 23:00:31 +0900 Subject: [PATCH 084/151] feat(lane_change): enable force execution under unsafe conditions (#8131) add force execution conditions Signed-off-by: Go Sakayori --- .../src/interface.cpp | 24 ++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index b55b41828081e..34c4cbda75e11 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -123,9 +123,18 @@ BehaviorModuleOutput LaneChangeInterface::plan() } else { const auto path = assignToCandidate(module_type_->getLaneChangePath(), module_type_->getEgoPosition()); - updateRTCStatus( - path.start_distance_to_path_change, path.finish_distance_to_path_change, true, - State::RUNNING); + const auto force_activated = std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), + [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); + if (!force_activated) { + updateRTCStatus( + path.start_distance_to_path_change, path.finish_distance_to_path_change, true, + State::RUNNING); + } else { + updateRTCStatus( + path.start_distance_to_path_change, path.finish_distance_to_path_change, false, + State::RUNNING); + } } return output; @@ -226,6 +235,15 @@ bool LaneChangeInterface::canTransitFailureState() updateDebugMarker(); log_debug_throttled(__func__); + const auto force_activated = std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), + [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); + + if (force_activated) { + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe but force executed"); + return false; + } + if (module_type_->isAbortState() && !module_type_->hasFinishedAbort()) { log_debug_throttled("Abort process has on going."); return false; From e7d45e331f8a35b8ab9582b459bbcb4ce526ea86 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 29 Jul 2024 09:36:25 +0900 Subject: [PATCH 085/151] feat(rtc_inteface): add function to check force deactivate (#8221) add function to check for deactivation Signed-off-by: Go Sakayori --- .../autoware/rtc_interface/rtc_interface.hpp | 1 + .../src/rtc_interface.cpp | 24 +++++++++++++++++++ 2 files changed, 25 insertions(+) diff --git a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp index be9b2cfc1ccf6..705395c2b1741 100644 --- a/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp +++ b/planning/autoware_rtc_interface/include/autoware/rtc_interface/rtc_interface.hpp @@ -60,6 +60,7 @@ class RTCInterface void clearCooperateStatus(); bool isActivated(const UUID & uuid) const; bool isForceActivated(const UUID & uuid) const; + bool isForceDeactivated(const UUID & UUID) const; bool isRegistered(const UUID & uuid) const; bool isRTCEnabled(const UUID & uuid) const; bool isTerminated(const UUID & uuid) const; diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 1352ec10557f9..f35134c9774c6 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -369,6 +369,30 @@ bool RTCInterface::isForceActivated(const UUID & uuid) const return false; } +bool RTCInterface::isForceDeactivated(const UUID & uuid) const +{ + std::lock_guard lock(mutex_); + const auto itr = std::find_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [uuid](const auto & s) { return s.uuid == uuid; }); + + if (itr != registered_status_.statuses.end()) { + if (itr->state.type != State::RUNNING) { + return false; + } + if (itr->command_status.type == Command::DEACTIVATE && itr->safe && !itr->auto_mode) { + return true; + } else { + return false; + } + } + + RCLCPP_WARN_STREAM( + getLogger(), + "[isForceDeactivated] uuid : " << uuid_to_string(uuid) << " is not found" << std::endl); + return false; +} + bool RTCInterface::isRegistered(const UUID & uuid) const { std::lock_guard lock(mutex_); From bbbeb38b6bbc5a54c2691a271b924f9bbad675f0 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 29 Jul 2024 14:46:33 +0900 Subject: [PATCH 086/151] feat(lane_change): force deactivation in prepare phase (#8235) transfer to cancel state when force deactivated Signed-off-by: Go Sakayori --- .../src/interface.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 34c4cbda75e11..09ac356f7088e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -274,6 +274,19 @@ bool LaneChangeInterface::canTransitFailureState() return true; } + const auto force_deactivated = std::any_of( + rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), + [&](const auto & rtc) { return rtc.second->isForceDeactivated(uuid_map_.at(rtc.first)); }); + + if (force_deactivated && module_type_->isAbleToReturnCurrentLane()) { + log_debug_throttled("Cancel lane change due to force deactivation"); + module_type_->toCancelState(); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); + return true; + } + if (post_process_safety_status_.is_safe) { log_debug_throttled("Can't transit to failure state. Ego is on prepare, and it's safe."); return false; From d6b8c9cf0e34efafa76cbc57fdbeaad1f46d9374 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 31 Jul 2024 19:45:26 +0900 Subject: [PATCH 087/151] feat(static_obstacle_avoidance): force deactivation (#8288) * add force cancel function Signed-off-by: Go Sakayori * fix format Signed-off-by: Go Sakayori * fix json schema Signed-off-by: Go Sakayori * fix spelling Signed-off-by: Go Sakayori * fix Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../static_obstacle_avoidance.param.yaml | 2 ++ .../data_structs.hpp | 4 +++ .../parameter_helper.hpp | 2 ++ .../scene.hpp | 3 ++ .../static_obstacle_avoidance.schema.json | 10 ++++++ .../src/manager.cpp | 5 +++ .../src/scene.cpp | 35 +++++++++++++++++++ 7 files changed, 61 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 0e60e3216361d..f10f871ca3cc0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -243,6 +243,8 @@ # For cancel maneuver cancel: enable: true # [-] + force: + duration_time: 2.0 # [s] # For yield maneuver yield: diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 4e14dc4886768..35b547da1f9f6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -107,6 +107,8 @@ struct AvoidanceParameters // if this param is true, it reverts avoidance path when the path is no longer needed. bool enable_cancel_maneuver{false}; + double force_deactivate_duration_time{0.0}; + // enable avoidance for all parking vehicle std::string policy_ambiguous_vehicle{"ignore"}; @@ -581,6 +583,8 @@ struct AvoidancePlanningData bool found_avoidance_path{false}; + bool force_deactivated{false}; + double to_stop_line{std::numeric_limits::max()}; double to_start_point{std::numeric_limits::lowest()}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 56ac3d7f4f1bb..cc7254380cf0b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -301,6 +301,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) { const std::string ns = "avoidance.cancel."; p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable"); + p.force_deactivate_duration_time = + getOrDeclareParameter(*node, ns + "force.duration_time"); } // yield diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 87a4c91792649..ea12c66859a36 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -477,6 +477,9 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface mutable std::vector debug_avoidance_initializer_for_shift_line_; mutable rclcpp::Time debug_avoidance_initializer_for_shift_line_time_; + + bool force_deactivated_{false}; + rclcpp::Time last_deactivation_triggered_time_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index 38a91ac39525b..2a581f90ab255 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -1263,6 +1263,16 @@ "type": "boolean", "description": "Flag to enable cancel maneuver.", "default": "true" + }, + "force": { + "type": "object", + "properties": { + "duration_time": { + "type": "number", + "description": "force deactivate duration time", + "default": 2.0 + } + } } }, "required": ["enable"], diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index 5655696ff086d..015a82aea3013 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -182,6 +182,11 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams( updateParam(parameters, ns + "consider_rear_overhang", p->consider_rear_overhang); } + { + const std::string ns = "avoidance.cancel."; + updateParam(parameters, ns + "force.duration_time", p->force_deactivate_duration_time); + } + { const std::string ns = "avoidance.stop."; updateParam(parameters, ns + "max_distance", p->stop_max_distance); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 422c7b8ce0f26..9e09a6ba0428e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -570,6 +570,24 @@ void StaticObstacleAvoidanceModule::fillEgoStatus( return; } + const auto registered_sl_force_deactivated = + [&](const std::string & direction, const RegisteredShiftLineArray shift_line_array) { + return std::any_of( + shift_line_array.begin(), shift_line_array.end(), [&](const auto & shift_line) { + return rtc_interface_ptr_map_.at(direction)->isForceDeactivated(shift_line.uuid); + }); + }; + + const auto is_force_deactivated = registered_sl_force_deactivated("left", left_shift_array_) || + registered_sl_force_deactivated("right", right_shift_array_); + if (is_force_deactivated && can_yield_maneuver) { + data.yield_required = true; + data.safe_shift_line = data.new_shift_line; + data.force_deactivated = true; + RCLCPP_INFO(getLogger(), "this module is force deactivated. wait until reactivation"); + return; + } + /** * If the avoidance path is safe, use unapproved_new_sl for avoidance path generation. */ @@ -755,6 +773,10 @@ bool StaticObstacleAvoidanceModule::isSafePath( universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & p = planner_data_->parameters; + if (force_deactivated_) { + return false; + } + if (!parameters_->enable_safety_check) { return true; // if safety check is disabled, it always return safe. } @@ -1366,6 +1388,19 @@ void StaticObstacleAvoidanceModule::updateData() } safe_ = avoid_data_.safe; + + if (!force_deactivated_) { + last_deactivation_triggered_time_ = clock_->now(); + force_deactivated_ = avoid_data_.force_deactivated; + return; + } + + if ( + (clock_->now() - last_deactivation_triggered_time_).seconds() > + parameters_->force_deactivate_duration_time) { + RCLCPP_INFO(getLogger(), "The force deactivation is released"); + force_deactivated_ = false; + } } void StaticObstacleAvoidanceModule::processOnEntry() From 419f89786a66b871e37a3ce4362e914819487357 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 9 Aug 2024 12:05:46 +0900 Subject: [PATCH 088/151] fix(ring_outlier_filter): remove unnecessary resize to prevent zero points (#8402) fix: remove unnecessary resize Signed-off-by: yoshiri --- .../src/outlier_filter/ring_outlier_filter_nodelet.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index e05f44240b53a..127c0c65b9915 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -355,7 +355,6 @@ void RingOutlierFilterComponent::setUpPointCloudFormat( // == true` formatted_points.header.frame_id = !tf_input_frame_.empty() ? tf_input_frame_ : tf_input_orig_frame_; - formatted_points.data.resize(formatted_points.point_step * input->width); formatted_points.height = 1; formatted_points.width = static_cast(formatted_points.data.size() / formatted_points.point_step); From 769e091e2408a3dbaab073f9a3284b9ee3a5ab75 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 14 Aug 2024 01:10:51 +0900 Subject: [PATCH 089/151] fix(goal_planner): fix lane departure check not working correctly due to uninitialized variable (#8449) Signed-off-by: kosuke55 --- .../README.md | 19 ++++++++++--------- .../config/goal_planner.param.yaml | 1 + .../goal_planner_parameters.hpp | 1 + .../src/goal_planner_module.cpp | 4 ++++ .../src/manager.cpp | 5 +++++ 5 files changed, 21 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md index 3e155aba0af2e..5e93c86c9be1c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md @@ -206,15 +206,16 @@ The main thread will be the one called from the planner manager flow. - The path candidates generated there are referred to by the main thread, and the one judged to be valid for the current planner data (e.g. ego and object information) is selected from among them. valid means no sudden deceleration, no collision with obstacles, etc. The selected path will be the output of this module. - If there is no path selected, or if the selected path is collision and ego is stuck, a separate thread(freespace path generation thread) will generate a path using freespace planning algorithm. If a valid free space path is found, it will be the output of the module. If the object moves and the pull over path generated along the lane is collision-free, the path is used as output again. See also the section on freespace parking for more information on the flow of generating freespace paths. -| Name | Unit | Type | Description | Default value | -| :------------------------------- | :----- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--------------------------------------- | -| pull_over_minimum_request_length | [m] | double | when the ego-vehicle approaches the goal by this distance or a safe distance to stop, pull over is activated. | 100.0 | -| pull_over_velocity | [m/s] | double | decelerate to this speed by the goal search area | 3.0 | -| pull_over_minimum_velocity | [m/s] | double | speed of pull_over after stopping once. this prevents excessive acceleration. | 1.38 | -| decide_path_distance | [m] | double | decide path if it approaches this distance relative to the parking position. after that, no path planning and goal search are performed | 10.0 | -| maximum_deceleration | [m/s2] | double | maximum deceleration. it prevents sudden deceleration when a parking path cannot be found suddenly | 1.0 | -| path_priority | [-] | string | In case `efficient_path` use a goal that can generate an efficient path which is set in `efficient_path_order`. In case `close_goal` use the closest goal to the original one. | efficient_path | -| efficient_path_order | [-] | string | efficient order of pull over planner along lanes excluding freespace pull over | ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] | +| Name | Unit | Type | Description | Default value | +| :------------------------------------ | :----- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--------------------------------------- | +| pull_over_minimum_request_length | [m] | double | when the ego-vehicle approaches the goal by this distance or a safe distance to stop, pull over is activated. | 100.0 | +| pull_over_velocity | [m/s] | double | decelerate to this speed by the goal search area | 3.0 | +| pull_over_minimum_velocity | [m/s] | double | speed of pull_over after stopping once. this prevents excessive acceleration. | 1.38 | +| decide_path_distance | [m] | double | decide path if it approaches this distance relative to the parking position. after that, no path planning and goal search are performed | 10.0 | +| maximum_deceleration | [m/s2] | double | maximum deceleration. it prevents sudden deceleration when a parking path cannot be found suddenly | 1.0 | +| path_priority | [-] | string | In case `efficient_path` use a goal that can generate an efficient path which is set in `efficient_path_order`. In case `close_goal` use the closest goal to the original one. | efficient_path | +| efficient_path_order | [-] | string | efficient order of pull over planner along lanes excluding freespace pull over | ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] | +| lane_departure_check_expansion_margin | [m] | double | margin to expand the ego vehicle footprint when doing lane departure checks | 0.0 | ### **shift parking** diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml index e6f84e7eece0c..156483df65f20 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml @@ -54,6 +54,7 @@ maximum_jerk: 1.0 path_priority: "efficient_path" # "efficient_path" or "close_goal" efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exclude freespace parking) + lane_departure_check_expansion_margin: 0.0 # shift parking shift_parking: diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp index 6a10c0fb183f6..1272ea38451ee 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp @@ -89,6 +89,7 @@ struct GoalPlannerParameters double maximum_jerk{0.0}; std::string path_priority; // "efficient_path" or "close_goal" std::vector efficient_path_order{}; + double lane_departure_check_expansion_margin{0.0}; // shift path bool enable_shift_parking{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index dc7a76031a3c1..ed2e3f30540b6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -68,6 +68,10 @@ GoalPlannerModule::GoalPlannerModule( { LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_); + lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = + parameters->lane_departure_check_expansion_margin; + lane_departure_checker.setParam(lane_departure_checker_params); occupancy_grid_map_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index b86bbbca7d98b..2d565607ec610 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -137,6 +137,8 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) p.path_priority = node->declare_parameter(ns + "path_priority"); p.efficient_path_order = node->declare_parameter>(ns + "efficient_path_order"); + p.lane_departure_check_expansion_margin = + node->declare_parameter(ns + "lane_departure_check_expansion_margin"); } // shift parking @@ -526,6 +528,9 @@ void GoalPlannerModuleManager::updateModuleParams( updateParam(parameters, ns + "deceleration_interval", p->deceleration_interval); updateParam( parameters, ns + "after_shift_straight_distance", p->after_shift_straight_distance); + updateParam( + parameters, ns + "lane_departure_check_expansion_margin", + p->lane_departure_check_expansion_margin); } // parallel parking common From 60356be1ed4bee51f8d7f3d96b976f0a29d3c770 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 14 Aug 2024 10:56:03 +0900 Subject: [PATCH 090/151] fix(lane_departure_checker): fix uninitialized variables (#8451) fix(lane_departure_checker): fix uninitialized_variables Signed-off-by: kosuke55 --- .../lane_departure_checker.hpp | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index b43a7d0d0369a..7aeedd096862d 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -59,18 +59,18 @@ typedef boost::geometry::index::rtree Date: Thu, 15 Aug 2024 10:16:09 +0900 Subject: [PATCH 091/151] perf(autoware_map_based_prediction autoware_universe_utils): improve performance of map_based_prediction (#1464) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * fix(autoware_map_based_prediction): fix argument order (#8031) fix(autoware_map_based_prediction): fix argument order in call `getFrenetPoint()` Signed-off-by: yucedagonurcan Co-authored-by: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * perf(map_based_prediction): remove unncessary withinRoadLanelet() (#8403) Signed-off-by: Mamoru Sobue * perf(map_based_prediction): create a fence LineString layer and use rtree query (#8406) use fence layer Signed-off-by: Mamoru Sobue * perf(map_based_prediction): apply lerp instead of spline (#8416) perf: apply lerp interpolation instead of spline Signed-off-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * perf(autoware_map_based_prediction): improve orientation calculation and resample converted path (#8427) * refactor: improve orientation calculation and resample converted path with linear interpolation Simplify the calculation of the orientation for each pose in the convertPathType function by directly calculating the sine and cosine of half the yaw angle. This improves efficiency and readability. Also, improve the resampling of the converted path by using linear interpolation for better performance. Signed-off-by: Taekjin LEE * Update perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * Update perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> --------- Signed-off-by: Taekjin LEE Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * perf(map_based_prediction): improve world to map transform calculation (#8413) * perf(map_based_prediction): improve world to map transform calculation 1. remove unused transforms 2. make transform loading late as possible Signed-off-by: Taekjin LEE * perf(map_based_prediction): get transform only when it is necessary Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE * feat(autoware_universe_utils): add LRU Cache (#8456) Signed-off-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> * perf(autoware_map_based_prediction): speed up map based prediction by using lru cache in convertPathType (#8461) feat(autoware_map_based_prediction): speed up map based prediction by using lru cache in convertPathType Signed-off-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> * fix(autoware_map_based_prediction): use surrounding_crosswalks instead of external_surrounding_crosswalks (#8467) Signed-off-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> --------- Signed-off-by: Mamoru Sobue Signed-off-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Signed-off-by: Taekjin LEE Signed-off-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Co-authored-by: Onur Can YücedaÄŸ Co-authored-by: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Co-authored-by: Mamoru Sobue Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> --- .../examples/example_lru_cache.cpp | 73 +++++++++ .../universe_utils/system/lru_cache.hpp | 142 ++++++++++++++++++ .../test/src/system/test_lru_cache.cpp | 78 ++++++++++ .../map_based_prediction_node.hpp | 32 +++- .../src/map_based_prediction_node.cpp | 111 +++++++++----- .../src/path_generator.cpp | 23 ++- 6 files changed, 406 insertions(+), 53 deletions(-) create mode 100644 common/autoware_universe_utils/examples/example_lru_cache.cpp create mode 100644 common/autoware_universe_utils/include/autoware/universe_utils/system/lru_cache.hpp create mode 100644 common/autoware_universe_utils/test/src/system/test_lru_cache.cpp diff --git a/common/autoware_universe_utils/examples/example_lru_cache.cpp b/common/autoware_universe_utils/examples/example_lru_cache.cpp new file mode 100644 index 0000000000000..95decf8eb336d --- /dev/null +++ b/common/autoware_universe_utils/examples/example_lru_cache.cpp @@ -0,0 +1,73 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/universe_utils/system/lru_cache.hpp" + +#include +#include +#include + +using autoware::universe_utils::LRUCache; + +// Fibonacci calculation with LRU cache +int64_t fibonacci_with_cache(int n, LRUCache * cache) +{ + if (n <= 1) return n; + + if (cache->contains(n)) { + return *cache->get(n); + } + int64_t result = fibonacci_with_cache(n - 1, cache) + fibonacci_with_cache(n - 2, cache); + cache->put(n, result); + return result; +} + +// Fibonacci calculation without cache +int64_t fibonacci_no_cache(int n) +{ + if (n <= 1) return n; + return fibonacci_no_cache(n - 1) + fibonacci_no_cache(n - 2); +} + +// Helper function to measure execution time +template +int64_t measure_time(Func func, Args &&... args) +{ + auto start = std::chrono::high_resolution_clock::now(); + func(std::forward(args)...); + auto end = std::chrono::high_resolution_clock::now(); + return std::chrono::duration_cast(end - start).count(); +} + +int main() +{ + const int max_n = 40; // Increased for more noticeable time difference + LRUCache cache(max_n); // Cache size set to MAX_N + + std::cout << "Comparing Fibonacci calculation time with and without LRU cache:\n\n"; + std::cout << "n\tWith Cache (μs)\tWithout Cache (μs)\n"; + std::cout << std::string(43, '-') << "\n"; + + for (int i = 30; i <= max_n; ++i) { // Starting from 30 for more significant differences + int64_t time_with_cache = measure_time([i, &cache]() { fibonacci_with_cache(i, &cache); }); + int64_t time_without_cache = measure_time([i]() { fibonacci_no_cache(i); }); + + std::cout << i << "\t" << time_with_cache << "\t\t" << time_without_cache << "\n"; + + // Clear the cache after each iteration to ensure fair comparison + cache.clear(); + } + + return 0; +} diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/lru_cache.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/lru_cache.hpp new file mode 100644 index 0000000000000..ecd8fc7e6c01a --- /dev/null +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/lru_cache.hpp @@ -0,0 +1,142 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE__UNIVERSE_UTILS__SYSTEM__LRU_CACHE_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__SYSTEM__LRU_CACHE_HPP_ + +#include +#include +#include +#include +#include + +namespace autoware::universe_utils +{ + +/** + * @brief A template class for LRU (Least Recently Used) Cache. + * + * This class implements a simple LRU cache using a combination of a list and a hash map. + * + * @tparam Key The type of keys. + * @tparam Value The type of values. + * @tparam Map The type of underlying map, defaulted to std::unordered_map. + */ +template class Map = std::unordered_map> +class LRUCache +{ +private: + size_t capacity_; ///< The maximum capacity of the cache. + std::list> cache_list_; ///< List to maintain the order of elements. + Map>::iterator> + cache_map_; ///< Map for fast access to elements. + +public: + /** + * @brief Construct a new LRUCache object. + * + * @param size The capacity of the cache. + */ + explicit LRUCache(size_t size) : capacity_(size) {} + + /** + * @brief Get the capacity of the cache. + * + * @return The capacity of the cache. + */ + [[nodiscard]] size_t capacity() const { return capacity_; } + + /** + * @brief Insert a key-value pair into the cache. + * + * If the key already exists, its value is updated and it is moved to the front. + * If the cache exceeds its capacity, the least recently used element is removed. + * + * @param key The key to insert. + * @param value The value to insert. + */ + void put(const Key & key, const Value & value) + { + auto it = cache_map_.find(key); + if (it != cache_map_.end()) { + cache_list_.erase(it->second); + } + cache_list_.push_front({key, value}); + cache_map_[key] = cache_list_.begin(); + + if (cache_map_.size() > capacity_) { + auto last = cache_list_.back(); + cache_map_.erase(last.first); + cache_list_.pop_back(); + } + } + + /** + * @brief Retrieve a value from the cache. + * + * If the key does not exist in the cache, std::nullopt is returned. + * If the key exists, the value is returned and the element is moved to the front. + * + * @param key The key to retrieve. + * @return The value associated with the key, or std::nullopt if the key does not exist. + */ + std::optional get(const Key & key) + { + auto it = cache_map_.find(key); + if (it == cache_map_.end()) { + return std::nullopt; + } + cache_list_.splice(cache_list_.begin(), cache_list_, it->second); + return it->second->second; + } + + /** + * @brief Clear the cache. + * + * This removes all elements from the cache. + */ + void clear() + { + cache_list_.clear(); + cache_map_.clear(); + } + + /** + * @brief Get the current size of the cache. + * + * @return The number of elements in the cache. + */ + [[nodiscard]] size_t size() const { return cache_map_.size(); } + + /** + * @brief Check if the cache is empty. + * + * @return True if the cache is empty, false otherwise. + */ + [[nodiscard]] bool empty() const { return cache_map_.empty(); } + + /** + * @brief Check if a key exists in the cache. + * + * @param key The key to check. + * @return True if the key exists, false otherwise. + */ + [[nodiscard]] bool contains(const Key & key) const + { + return cache_map_.find(key) != cache_map_.end(); + } +}; + +} // namespace autoware::universe_utils + +#endif // AUTOWARE__UNIVERSE_UTILS__SYSTEM__LRU_CACHE_HPP_ diff --git a/common/autoware_universe_utils/test/src/system/test_lru_cache.cpp b/common/autoware_universe_utils/test/src/system/test_lru_cache.cpp new file mode 100644 index 0000000000000..f30f732431fa6 --- /dev/null +++ b/common/autoware_universe_utils/test/src/system/test_lru_cache.cpp @@ -0,0 +1,78 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#include "autoware/universe_utils/system/lru_cache.hpp" + +#include + +#include +#include +#include +#include + +using autoware::universe_utils::LRUCache; + +// Fibonacci calculation with LRU cache +int64_t fibonacci_with_cache(int n, LRUCache * cache) +{ + if (n <= 1) return n; + + if (cache->contains(n)) { + return *cache->get(n); + } + int64_t result = fibonacci_with_cache(n - 1, cache) + fibonacci_with_cache(n - 2, cache); + cache->put(n, result); + return result; +} + +// Fibonacci calculation without cache +int64_t fibonacci_no_cache(int n) +{ + if (n <= 1) return n; + return fibonacci_no_cache(n - 1) + fibonacci_no_cache(n - 2); +} + +// Helper function to measure execution time +template +std::pair()(std::declval()...))> measure_time( + Func func, Args &&... args) +{ + auto start = std::chrono::high_resolution_clock::now(); + auto result = func(std::forward(args)...); + auto end = std::chrono::high_resolution_clock::now(); + return {std::chrono::duration_cast(end - start).count(), result}; +} + +// Test case to verify Fibonacci calculation results with and without cache +TEST(FibonacciLRUCacheTest, CompareResultsAndPerformance) +{ + const int max_n = 40; // Test range + LRUCache cache(max_n); // Cache with capacity set to max_n + + for (int i = 0; i <= max_n; ++i) { + // Measure time for performance comparison + auto [time_with_cache, result_with_cache] = + measure_time([i, &cache]() { return fibonacci_with_cache(i, &cache); }); + auto [time_without_cache, result_without_cache] = + measure_time([i]() { return fibonacci_no_cache(i); }); + + EXPECT_EQ(result_with_cache, result_without_cache) << "Mismatch at n = " << i; + + // Print the calculation time + std::cout << "n = " << i << ": With Cache = " << time_with_cache + << " μs, Without Cache = " << time_without_cache << " μs\n"; + + // // Clear the cache after each iteration to ensure fair comparison + cache.clear(); + } +} diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 1c677c9d0f6e4..1f13391ae442a 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -39,7 +40,9 @@ #include #include +#include #include +#include #include #include @@ -53,6 +56,27 @@ #include #include +namespace std +{ +template <> +struct hash +{ + // 0x9e3779b9 is a magic number. See + // https://stackoverflow.com/questions/4948780/magic-number-in-boosthash-combine + size_t operator()(const lanelet::routing::LaneletPaths & paths) const + { + size_t seed = 0; + for (const auto & path : paths) { + for (const auto & lanelet : path) { + seed ^= hash{}(lanelet.id()) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U); + } + // Add a separator between paths + seed ^= hash{}(0) + 0x9e3779b9 + (seed << 6U) + (seed >> 2U); + } + return seed; + } +}; +} // namespace std namespace autoware::map_based_prediction { struct LateralKinematicsToLanelet @@ -178,6 +202,9 @@ class MapBasedPredictionNode : public rclcpp::Node // Crosswalk Entry Points lanelet::ConstLanelets crosswalks_; + // Fences + lanelet::LaneletMapUPtr fence_layer_{nullptr}; + // Parameters bool enable_delay_compensation_; PredictionTimeHorizon prediction_time_horizon_; @@ -287,7 +314,10 @@ class MapBasedPredictionNode : public rclcpp::Node const float path_probability, const ManeuverProbability & maneuver_probability, const Maneuver & maneuver, std::vector & reference_paths, const double speed_limit = 0.0); - std::vector convertPathType(const lanelet::routing::LaneletPaths & paths); + + mutable universe_utils::LRUCache> + lru_cache_of_convert_path_type_{1000}; + std::vector convertPathType(const lanelet::routing::LaneletPaths & paths) const; void updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths); diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index 29cfe52855d24..649a92ac981f5 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -411,8 +411,8 @@ bool withinRoadLanelet( boost::optional isReachableCrosswalkEdgePoints( const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets, - const lanelet::ConstLanelets & external_surrounding_crosswalks, - const CrosswalkEdgePoints & edge_points, const double time_horizon, const double min_object_vel) + const lanelet::ConstLanelets & surrounding_crosswalks, const CrosswalkEdgePoints & edge_points, + const double time_horizon, const double min_object_vel) { using Point = boost::geometry::model::d2::point_xy; @@ -439,10 +439,10 @@ boost::optional isReachableCrosswalkEdgePoints( const auto is_stop_object = estimated_velocity < stop_velocity_th; const auto velocity = std::max(min_object_vel, estimated_velocity); - const auto isAcrossAnyRoad = [&surrounding_lanelets, &external_surrounding_crosswalks]( + const auto isAcrossAnyRoad = [&surrounding_lanelets, &surrounding_crosswalks]( const Point & p_src, const Point & p_dst) { - const auto withinAnyCrosswalk = [&external_surrounding_crosswalks](const Point & p) { - for (const auto & crosswalk : external_surrounding_crosswalks) { + const auto withinAnyCrosswalk = [&surrounding_crosswalks](const Point & p) { + for (const auto & crosswalk : surrounding_crosswalks) { if (boost::geometry::within(p, crosswalk.polygon2d().basicPolygon())) { return true; } @@ -662,7 +662,6 @@ ObjectClassification::_label_type changeLabelForPrediction( } case ObjectClassification::PEDESTRIAN: { - const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); const float max_velocity_for_human_mps = autoware::universe_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h const double abs_speed = std::hypot( @@ -670,7 +669,6 @@ ObjectClassification::_label_type changeLabelForPrediction( object.kinematics.twist_with_covariance.twist.linear.y); const bool high_speed_object = abs_speed > max_velocity_for_human_mps; // fast, human-like object: like segway - if (within_road_lanelet && high_speed_object) return label; // currently do nothing // return ObjectClassification::MOTORCYCLE; if (high_speed_object) return label; // currently do nothing // fast human outside road lanelet will move like unknown object @@ -924,6 +922,7 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg( *msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_); + lru_cache_of_convert_path_type_.clear(); // clear cache RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Map is loaded"); const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); @@ -931,6 +930,16 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg const auto walkways = lanelet::utils::query::walkwayLanelets(all_lanelets); crosswalks_.insert(crosswalks_.end(), crosswalks.begin(), crosswalks.end()); crosswalks_.insert(crosswalks_.end(), walkways.begin(), walkways.end()); + + lanelet::LineStrings3d fences; + for (const auto & linestring : lanelet_map_ptr_->lineStringLayer) { + if (const std::string type = linestring.attributeOr(lanelet::AttributeName::Type, "none"); + type == "fence") { + fences.push_back(lanelet::LineString3d( + std::const_pointer_cast(linestring.constData()))); + } + } + fence_layer_ = lanelet::utils::createMap(fences); } void MapBasedPredictionNode::trafficSignalsCallback( @@ -963,23 +972,6 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt return; } - auto world2map_transform = transform_listener_.getTransform( - "map", // target - in_objects->header.frame_id, // src - in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1)); - auto map2world_transform = transform_listener_.getTransform( - in_objects->header.frame_id, // target - "map", // src - in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1)); - auto debug_map2lidar_transform = transform_listener_.getTransform( - "base_link", // target - "map", // src - rclcpp::Time(), rclcpp::Duration::from_seconds(0.1)); - - if (!world2map_transform || !map2world_transform || !debug_map2lidar_transform) { - return; - } - // Remove old objects information in object history const double objects_detected_time = rclcpp::Time(in_objects->header.stamp).seconds(); removeOldObjectsHistory(objects_detected_time, object_buffer_time_length_, road_users_history); @@ -1018,12 +1010,24 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } std::unordered_set predicted_crosswalk_users_ids; + // get world to map transform + geometry_msgs::msg::TransformStamped::ConstSharedPtr world2map_transform; + + bool is_object_not_in_map_frame = in_objects->header.frame_id != "map"; + if (is_object_not_in_map_frame) { + world2map_transform = transform_listener_.getTransform( + "map", // target + in_objects->header.frame_id, // src + in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1)); + if (!world2map_transform) return; + } + for (const auto & object : in_objects->objects) { std::string object_id = autoware::universe_utils::toHexString(object.object_id); TrackedObject transformed_object = object; // transform object frame if it's based on map frame - if (in_objects->header.frame_id != "map") { + if (is_object_not_in_map_frame) { geometry_msgs::msg::PoseStamped pose_in_map; geometry_msgs::msg::PoseStamped pose_orig; pose_orig.pose = object.kinematics.pose_with_covariance.pose; @@ -1316,10 +1320,14 @@ std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared( bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path) { autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - const lanelet::ConstLineStrings3d & all_fences = - lanelet::utils::query::getAllFences(lanelet_map_ptr_); - for (const auto & fence_line : all_fences) { - if (doesPathCrossFence(predicted_path, fence_line)) { + + lanelet::BasicLineString2d predicted_path_ls; + for (const auto & p : predicted_path.path) + predicted_path_ls.emplace_back(p.position.x, p.position.y); + const auto candidates = + fence_layer_->lineStringLayer.search(lanelet::geometry::boundingBox2d(predicted_path_ls)); + for (const auto & candidate : candidates) { + if (doesPathCrossFence(predicted_path, candidate)) { return true; } } @@ -1381,7 +1389,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y}, prediction_time_horizon_.pedestrian * velocity); lanelet::ConstLanelets surrounding_lanelets; - lanelet::ConstLanelets external_surrounding_crosswalks; + lanelet::ConstLanelets surrounding_crosswalks; for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) { surrounding_lanelets.push_back(lanelet); const auto attr = lanelet.attribute(lanelet::AttributeName::Subtype); @@ -1389,10 +1397,9 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( attr.value() == lanelet::AttributeValueString::Crosswalk || attr.value() == lanelet::AttributeValueString::Walkway) { const auto & crosswalk = lanelet; + surrounding_crosswalks.push_back(crosswalk); if (withinLanelet(object, crosswalk)) { crossing_crosswalk = crosswalk; - } else { - external_surrounding_crosswalks.push_back(crosswalk); } } } @@ -1456,7 +1463,10 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( // try to find the edge points for other surrounding crosswalks and generate path to the crosswalk // edge - for (const auto & crosswalk : external_surrounding_crosswalks) { + for (const auto & crosswalk : surrounding_crosswalks) { + if (crossing_crosswalk && crossing_crosswalk.get() == crosswalk) { + continue; + } const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk); if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) { if (!calcIntentionToCrossWithTrafficSignal( @@ -1481,7 +1491,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( } const auto reachable_crosswalk = isReachableCrosswalkEdgePoints( - object, surrounding_lanelets, external_surrounding_crosswalks, edge_points, + object, surrounding_lanelets, surrounding_crosswalks, edge_points, prediction_time_horizon_.pedestrian, min_crosswalk_user_velocity_); if (!reachable_crosswalk) { @@ -2366,10 +2376,14 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( } std::vector MapBasedPredictionNode::convertPathType( - const lanelet::routing::LaneletPaths & paths) + const lanelet::routing::LaneletPaths & paths) const { autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + if (lru_cache_of_convert_path_type_.contains(paths)) { + return *lru_cache_of_convert_path_type_.get(paths); + } + std::vector converted_paths; for (const auto & path : paths) { PosePath converted_path; @@ -2392,7 +2406,13 @@ std::vector MapBasedPredictionNode::convertPathType( const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); - current_p.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw); + const double sin_yaw_half = std::sin(lane_yaw / 2.0); + const double cos_yaw_half = std::cos(lane_yaw / 2.0); + current_p.orientation.x = 0.0; + current_p.orientation.y = 0.0; + current_p.orientation.z = sin_yaw_half; + current_p.orientation.w = cos_yaw_half; + converted_path.push_back(current_p); prev_p = current_p; } @@ -2423,18 +2443,31 @@ std::vector MapBasedPredictionNode::convertPathType( const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); - current_p.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw); + const double sin_yaw_half = std::sin(lane_yaw / 2.0); + const double cos_yaw_half = std::cos(lane_yaw / 2.0); + current_p.orientation.x = 0.0; + current_p.orientation.y = 0.0; + current_p.orientation.z = sin_yaw_half; + current_p.orientation.w = cos_yaw_half; + converted_path.push_back(current_p); prev_p = current_p; } } // Resample Path - const auto resampled_converted_path = - autoware::motion_utils::resamplePoseVector(converted_path, reference_path_resolution_); + const bool use_akima_spline_for_xy = true; + const bool use_lerp_for_z = true; + // the options use_akima_spline_for_xy and use_lerp_for_z are set to true + // but the implementation of use_akima_spline_for_xy in resamplePoseVector and + // resamplePointVector is opposite to the options so the options are set to true to use linear + // interpolation for xy + const auto resampled_converted_path = autoware::motion_utils::resamplePoseVector( + converted_path, reference_path_resolution_, use_akima_spline_for_xy, use_lerp_for_z); converted_paths.push_back(resampled_converted_path); } + lru_cache_of_convert_path_type_.put(paths, converted_paths); return converted_paths; } diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index aeb1b0fedd33f..b483503215cc6 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include @@ -188,7 +188,7 @@ PredictedPath PathGenerator::generatePolynomialPath( { // Get current Frenet Point const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path, speed_limit, duration); + const auto current_point = getFrenetPoint(object, ref_path, duration, speed_limit); // Step1. Set Target Frenet Point // Note that we do not set position s, @@ -332,29 +332,26 @@ PosePath PathGenerator::interpolateReferencePath( std::reverse(resampled_s.begin(), resampled_s.end()); } - // Spline Interpolation - std::vector spline_ref_path_x = - interpolation::spline(base_path_s, base_path_x, resampled_s); - std::vector spline_ref_path_y = - interpolation::spline(base_path_s, base_path_y, resampled_s); - std::vector spline_ref_path_z = - interpolation::spline(base_path_s, base_path_z, resampled_s); + // Lerp Interpolation + std::vector lerp_ref_path_x = interpolation::lerp(base_path_s, base_path_x, resampled_s); + std::vector lerp_ref_path_y = interpolation::lerp(base_path_s, base_path_y, resampled_s); + std::vector lerp_ref_path_z = interpolation::lerp(base_path_s, base_path_z, resampled_s); interpolated_path.resize(interpolate_num); for (size_t i = 0; i < interpolate_num - 1; ++i) { geometry_msgs::msg::Pose interpolated_pose; const auto current_point = - autoware::universe_utils::createPoint(spline_ref_path_x.at(i), spline_ref_path_y.at(i), 0.0); + autoware::universe_utils::createPoint(lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), 0.0); const auto next_point = autoware::universe_utils::createPoint( - spline_ref_path_x.at(i + 1), spline_ref_path_y.at(i + 1), 0.0); + lerp_ref_path_x.at(i + 1), lerp_ref_path_y.at(i + 1), 0.0); const double yaw = autoware::universe_utils::calcAzimuthAngle(current_point, next_point); interpolated_pose.position = autoware::universe_utils::createPoint( - spline_ref_path_x.at(i), spline_ref_path_y.at(i), spline_ref_path_z.at(i)); + lerp_ref_path_x.at(i), lerp_ref_path_y.at(i), lerp_ref_path_z.at(i)); interpolated_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); interpolated_path.at(i) = interpolated_pose; } interpolated_path.back().position = autoware::universe_utils::createPoint( - spline_ref_path_x.back(), spline_ref_path_y.back(), spline_ref_path_z.back()); + lerp_ref_path_x.back(), lerp_ref_path_y.back(), lerp_ref_path_z.back()); interpolated_path.back().orientation = interpolated_path.at(interpolate_num - 2).orientation; return interpolated_path; From 398ab6ef9cc76fc461ef082e944387d4bc7d4285 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 15 Aug 2024 11:26:00 +0900 Subject: [PATCH 092/151] chore(map_based_prediction): debug options (#1466) refactor(autoware_map_based_prediction): map based pred time keeper ptr (#8462) * refactor(map_based_prediction): implement time keeper by pointer * feat(map_based_prediction): set time keeper in path generator * feat: use scoped time track only when the timekeeper ptr is not null * refactor: define publish function to measure time * chore: add debug parameters for map-based prediction * chore: remove unnecessary ScopedTimeTrack instances * feat: replace member to pointer --------- Signed-off-by: Taekjin LEE --- .../config/map_based_prediction.param.yaml | 5 + .../map_based_prediction_node.hpp | 6 +- .../map_based_prediction/path_generator.hpp | 5 + .../src/map_based_prediction_node.cpp | 181 +++++++++++------- .../src/path_generator.cpp | 41 ++++ 5 files changed, 170 insertions(+), 68 deletions(-) diff --git a/perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml b/perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml index a5b7b0ad6be01..b45cc25f82c1c 100644 --- a/perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml @@ -50,3 +50,8 @@ consider_only_routable_neighbours: false reference_path_resolution: 0.5 #[m] + + # debug parameters + publish_processing_time: false + publish_processing_time_detail: false + publish_debug_markers: false diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 1f13391ae442a..3078fe89444b8 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -252,7 +252,7 @@ class MapBasedPredictionNode : public rclcpp::Node std::unique_ptr published_time_publisher_; rclcpp::Publisher::SharedPtr detailed_processing_time_publisher_; - mutable autoware::universe_utils::TimeKeeper time_keeper_; + std::shared_ptr time_keeper_; // Member Functions void mapCallback(const LaneletMapBin::ConstSharedPtr msg); @@ -343,6 +343,10 @@ class MapBasedPredictionNode : public rclcpp::Node const TrackedObject & object, const LaneletData & current_lanelet_data, const double object_detected_time); + void publish( + const PredictedObjects & output, + const visualization_msgs::msg::MarkerArray & debug_markers) const; + // NOTE: This function is copied from the motion_velocity_smoother package. // TODO(someone): Consolidate functions and move them to a common inline std::vector calcTrajectoryCurvatureFrom3Points( diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp index bd098894f8a88..8861598ae7fb2 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -16,6 +16,7 @@ #define MAP_BASED_PREDICTION__PATH_GENERATOR_HPP_ #include +#include #include #include @@ -82,6 +83,8 @@ class PathGenerator public: PathGenerator(const double sampling_time_interval, const double min_crosswalk_user_velocity); + void setTimeKeeper(std::shared_ptr time_keeper_ptr); + PredictedPath generatePathForNonVehicleObject( const TrackedObject & object, const double duration) const; @@ -119,6 +122,8 @@ class PathGenerator bool use_vehicle_acceleration_; double acceleration_exponential_half_life_; + std::shared_ptr time_keeper_; + // Member functions PredictedPath generateStraightPath(const TrackedObject & object, const double duration) const; diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index 649a92ac981f5..e95113641104d 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -52,6 +52,7 @@ namespace autoware::map_based_prediction { +using autoware::universe_utils::ScopedTimeTrack; namespace { @@ -831,12 +832,18 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ timeout_set_for_no_intention_to_walk_ = declare_parameter>( "crosswalk_with_signal.timeout_set_for_no_intention_to_walk"); + // debug parameter + bool use_time_publisher = declare_parameter("publish_processing_time"); + bool use_time_keeper = declare_parameter("publish_processing_time_detail"); + bool use_debug_marker = declare_parameter("publish_debug_markers"); + path_generator_ = std::make_shared( prediction_sampling_time_interval_, min_crosswalk_user_velocity_); path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_); path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_); + // subscribers sub_objects_ = this->create_subscription( "~/input/objects", 1, std::bind(&MapBasedPredictionNode::objectsCallback, this, std::placeholders::_1)); @@ -844,26 +851,37 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ "/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&MapBasedPredictionNode::mapCallback, this, std::placeholders::_1)); + // publishers pub_objects_ = this->create_publisher("~/output/objects", rclcpp::QoS{1}); - pub_debug_markers_ = - this->create_publisher("maneuver", rclcpp::QoS{1}); - processing_time_publisher_ = - std::make_unique(this, "map_based_prediction"); - - published_time_publisher_ = - std::make_unique(this); - detailed_processing_time_publisher_ = - this->create_publisher( - "~/debug/processing_time_detail_ms", 1); - time_keeper_ = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_); + // debug publishers + if (use_time_publisher) { + processing_time_publisher_ = + std::make_unique(this, "map_based_prediction"); + published_time_publisher_ = + std::make_unique(this); + stop_watch_ptr_ = + std::make_unique>(); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + } + + if (use_time_keeper) { + detailed_processing_time_publisher_ = + this->create_publisher( + "~/debug/processing_time_detail_ms", 1); + auto time_keeper = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_); + time_keeper_ = std::make_shared(time_keeper); + path_generator_->setTimeKeeper(time_keeper_); + } + + if (use_debug_marker) { + pub_debug_markers_ = + this->create_publisher("maneuver", rclcpp::QoS{1}); + } + // dynamic reconfigure set_param_res_ = this->add_on_set_parameters_callback( std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1)); - - stop_watch_ptr_ = - std::make_unique>(); - stop_watch_ptr_->tic("cyclic_time"); - stop_watch_ptr_->tic("processing_time"); } rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam( @@ -916,8 +934,6 @@ PredictedObject MapBasedPredictionNode::convertToPredictedObject( void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - RCLCPP_DEBUG(get_logger(), "[Map Based Prediction]: Start loading lanelet"); lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg( @@ -945,7 +961,8 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg void MapBasedPredictionNode::trafficSignalsCallback( const TrafficLightGroupArray::ConstSharedPtr msg) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); traffic_signal_id_map_.clear(); for (const auto & signal : msg->traffic_light_groups) { @@ -955,9 +972,10 @@ void MapBasedPredictionNode::trafficSignalsCallback( void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - stop_watch_ptr_->toc("processing_time", true); + if (stop_watch_ptr_) stop_watch_ptr_->toc("processing_time", true); // take traffic_signal { @@ -1116,14 +1134,16 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } // Get Debug Marker for On Lane Vehicles - const auto max_prob_path = std::max_element( - ref_paths.begin(), ref_paths.end(), - [](const PredictedRefPath & a, const PredictedRefPath & b) { - return a.probability < b.probability; - }); - const auto debug_marker = - getDebugMarker(object, max_prob_path->maneuver, debug_markers.markers.size()); - debug_markers.markers.push_back(debug_marker); + if (pub_debug_markers_) { + const auto max_prob_path = std::max_element( + ref_paths.begin(), ref_paths.end(), + [](const PredictedRefPath & a, const PredictedRefPath & b) { + return a.probability < b.probability; + }); + const auto debug_marker = + getDebugMarker(object, max_prob_path->maneuver, debug_markers.markers.size()); + debug_markers.markers.push_back(debug_marker); + } // Fix object angle if its orientation unreliable (e.g. far object by radar sensor) // This prevent bending predicted path @@ -1229,21 +1249,36 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } // Publish Results + publish(output, debug_markers); + + // Publish Processing Time + if (stop_watch_ptr_) { + const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true); + const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + processing_time_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + processing_time_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + } +} + +void MapBasedPredictionNode::publish( + const PredictedObjects & output, const visualization_msgs::msg::MarkerArray & debug_markers) const +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + pub_objects_->publish(output); - published_time_publisher_->publish_if_subscribed(pub_objects_, output.header.stamp); - pub_debug_markers_->publish(debug_markers); - const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - processing_time_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - processing_time_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); + if (published_time_publisher_) + published_time_publisher_->publish_if_subscribed(pub_objects_, output.header.stamp); + if (pub_debug_markers_) pub_debug_markers_->publish(debug_markers); } void MapBasedPredictionNode::updateCrosswalkUserHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const std::string & object_id) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); CrosswalkUserData crosswalk_user_data; crosswalk_user_data.header = header; @@ -1260,7 +1295,8 @@ void MapBasedPredictionNode::updateCrosswalkUserHistory( std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared( const std::string & object_id, std::unordered_map & current_users) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); const auto known_match_opt = [&]() -> std::optional { if (!known_matches_.count(object_id)) { @@ -1319,7 +1355,8 @@ std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared( bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); lanelet::BasicLineString2d predicted_path_ls; for (const auto & p : predicted_path.path) @@ -1337,7 +1374,8 @@ bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predict bool MapBasedPredictionNode::doesPathCrossFence( const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // check whether the predicted path cross with fence for (size_t i = 0; i < predicted_path.path.size() - 1; ++i) { @@ -1356,6 +1394,9 @@ bool MapBasedPredictionNode::isIntersecting( const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2, const lanelet::ConstPoint3d & point3, const lanelet::ConstPoint3d & point4) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + const auto p1 = autoware::universe_utils::createPoint(point1.x, point1.y, 0.0); const auto p2 = autoware::universe_utils::createPoint(point2.x, point2.y, 0.0); const auto p3 = autoware::universe_utils::createPoint(point3.x(), point3.y(), 0.0); @@ -1367,7 +1408,8 @@ bool MapBasedPredictionNode::isIntersecting( PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( const TrackedObject & object) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); auto predicted_object = convertToPredictedObject(object); { @@ -1523,7 +1565,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( void MapBasedPredictionNode::updateObjectData(TrackedObject & object) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); if ( object.kinematics.orientation_availability == @@ -1575,8 +1618,6 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) void MapBasedPredictionNode::removeStaleTrafficLightInfo( const TrackedObjects::ConstSharedPtr in_objects) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - for (auto it = stopped_times_against_green_.begin(); it != stopped_times_against_green_.end();) { const bool isDisappeared = std::none_of( in_objects->objects.begin(), in_objects->objects.end(), @@ -1593,7 +1634,8 @@ void MapBasedPredictionNode::removeStaleTrafficLightInfo( LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & object) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // obstacle point lanelet::BasicPoint2d search_point( @@ -1685,7 +1727,8 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob bool MapBasedPredictionNode::checkCloseLaneletCondition( const std::pair & lanelet, const TrackedObject & object) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // Step1. If we only have one point in the centerline, we will ignore the lanelet if (lanelet.second.centerline().size() <= 1) { @@ -1733,7 +1776,8 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( float MapBasedPredictionNode::calculateLocalLikelihood( const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); const auto & obj_point = object.kinematics.pose_with_covariance.pose.position; @@ -1770,7 +1814,8 @@ void MapBasedPredictionNode::updateRoadUsersHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const LaneletsData & current_lanelets_data) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); std::string object_id = autoware::universe_utils::toHexString(object.object_id); const auto current_lanelets = getLanelets(current_lanelets_data); @@ -1813,7 +1858,8 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time, const double time_horizon) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, @@ -1976,7 +2022,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuver( const TrackedObject & object, const LaneletData & current_lanelet_data, const double object_detected_time) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // calculate maneuver const auto current_maneuver = [&]() { @@ -2028,7 +2075,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByTimeToLaneChange( const TrackedObject & object, const LaneletData & current_lanelet_data, const double /*object_detected_time*/) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // Step1. Check if we have the object in the buffer const std::string object_id = autoware::universe_utils::toHexString(object.object_id); @@ -2101,7 +2149,8 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance( const TrackedObject & object, const LaneletData & current_lanelet_data, const double /*object_detected_time*/) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); // Step1. Check if we have the object in the buffer const std::string object_id = autoware::universe_utils::toHexString(object.object_id); @@ -2246,8 +2295,6 @@ geometry_msgs::msg::Pose MapBasedPredictionNode::compensateTimeDelay( double MapBasedPredictionNode::calcRightLateralOffset( const lanelet::ConstLineString2d & boundary_line, const geometry_msgs::msg::Pose & search_pose) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - std::vector boundary_path(boundary_line.size()); for (size_t i = 0; i < boundary_path.size(); ++i) { const double x = boundary_line[i].x(); @@ -2267,7 +2314,8 @@ double MapBasedPredictionNode::calcLeftLateralOffset( void MapBasedPredictionNode::updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { @@ -2293,7 +2341,8 @@ void MapBasedPredictionNode::addReferencePaths( const Maneuver & maneuver, std::vector & reference_paths, const double speed_limit) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); if (!candidate_paths.empty()) { updateFuturePossibleLanelets(object, candidate_paths); @@ -2314,7 +2363,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( const lanelet::routing::LaneletPaths & right_paths, const lanelet::routing::LaneletPaths & center_paths) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); float left_lane_change_probability = 0.0; float right_lane_change_probability = 0.0; @@ -2378,7 +2428,8 @@ ManeuverProbability MapBasedPredictionNode::calculateManeuverProbability( std::vector MapBasedPredictionNode::convertPathType( const lanelet::routing::LaneletPaths & paths) const { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); if (lru_cache_of_convert_path_type_.contains(paths)) { return *lru_cache_of_convert_path_type_.get(paths); @@ -2475,8 +2526,6 @@ bool MapBasedPredictionNode::isDuplicated( const std::pair & target_lanelet, const LaneletsData & lanelets_data) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - const double CLOSE_LANELET_THRESHOLD = 0.1; for (const auto & lanelet_data : lanelets_data) { const auto target_lanelet_end_p = target_lanelet.second.centerline2d().back(); @@ -2494,8 +2543,6 @@ bool MapBasedPredictionNode::isDuplicated( bool MapBasedPredictionNode::isDuplicated( const PredictedPath & predicted_path, const std::vector & predicted_paths) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - const double CLOSE_PATH_THRESHOLD = 0.1; for (const auto & prev_predicted_path : predicted_paths) { const auto prev_path_end = prev_predicted_path.path.back().position; @@ -2512,8 +2559,6 @@ bool MapBasedPredictionNode::isDuplicated( std::optional MapBasedPredictionNode::getTrafficSignalId( const lanelet::ConstLanelet & way_lanelet) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); - const auto traffic_light_reg_elems = way_lanelet.regulatoryElementsAs(); if (traffic_light_reg_elems.empty()) { @@ -2530,7 +2575,8 @@ std::optional MapBasedPredictionNode::getTrafficSignalId( std::optional MapBasedPredictionNode::getTrafficSignalElement( const lanelet::Id & id) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); if (traffic_signal_id_map_.count(id) != 0) { const auto & signal_elements = traffic_signal_id_map_.at(id).elements; @@ -2548,7 +2594,8 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal( const TrackedObject & object, const lanelet::ConstLanelet & crosswalk, const lanelet::Id & signal_id) { - autoware::universe_utils::ScopedTimeTrack st(__func__, time_keeper_); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); const auto signal_color = [&] { const auto elem_opt = getTrafficSignalElement(signal_id); diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index b483503215cc6..6c61876176b68 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -22,6 +22,8 @@ namespace autoware::map_based_prediction { +using autoware::universe_utils::ScopedTimeTrack; + PathGenerator::PathGenerator( const double sampling_time_interval, const double min_crosswalk_user_velocity) : sampling_time_interval_(sampling_time_interval), @@ -29,15 +31,27 @@ PathGenerator::PathGenerator( { } +void PathGenerator::setTimeKeeper( + std::shared_ptr time_keeper_ptr) +{ + time_keeper_ = std::move(time_keeper_ptr); +} + PredictedPath PathGenerator::generatePathForNonVehicleObject( const TrackedObject & object, const double duration) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + return generateStraightPath(object, duration); } PredictedPath PathGenerator::generatePathToTargetPoint( const TrackedObject & object, const Eigen::Vector2d & point) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + PredictedPath predicted_path{}; const double ep = 0.001; @@ -77,6 +91,9 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, const double duration) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + PredictedPath predicted_path{}; const double ep = 0.001; @@ -135,6 +152,9 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( PredictedPath PathGenerator::generatePathForLowSpeedVehicle( const TrackedObject & object, const double duration) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + PredictedPath path; path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); const double ep = 0.001; @@ -148,6 +168,9 @@ PredictedPath PathGenerator::generatePathForLowSpeedVehicle( PredictedPath PathGenerator::generatePathForOffLaneVehicle( const TrackedObject & object, const double duration) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + return generateStraightPath(object, duration); } @@ -155,6 +178,9 @@ PredictedPath PathGenerator::generatePathForOnLaneVehicle( const TrackedObject & object, const PosePath & ref_paths, const double duration, const double lateral_duration, const double speed_limit) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (ref_paths.size() < 2) { return generateStraightPath(object, duration); } @@ -186,6 +212,9 @@ PredictedPath PathGenerator::generatePolynomialPath( const TrackedObject & object, const PosePath & ref_path, const double duration, const double lateral_duration, const double speed_limit) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // Get current Frenet Point const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path); const auto current_point = getFrenetPoint(object, ref_path, duration, speed_limit); @@ -219,6 +248,9 @@ FrenetPath PathGenerator::generateFrenetPath( const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, const double duration, const double lateral_duration) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + FrenetPath path; // Compute Lateral and Longitudinal Coefficients to generate the trajectory @@ -303,6 +335,9 @@ Eigen::Vector2d PathGenerator::calcLonCoefficients( PosePath PathGenerator::interpolateReferencePath( const PosePath & base_path, const FrenetPath & frenet_predicted_path) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + PosePath interpolated_path; const size_t interpolate_num = frenet_predicted_path.size(); if (interpolate_num < 2) { @@ -361,6 +396,9 @@ PredictedPath PathGenerator::convertToPredictedPath( const TrackedObject & object, const FrenetPath & frenet_predicted_path, const PosePath & ref_path) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + PredictedPath predicted_path; predicted_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); predicted_path.path.resize(ref_path.size()); @@ -392,6 +430,9 @@ FrenetPoint PathGenerator::getFrenetPoint( const TrackedObject & object, const PosePath & ref_path, const double duration, const double speed_limit) const { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + FrenetPoint frenet_point; const auto obj_point = object.kinematics.pose_with_covariance.pose.position; From 83b3e4c4153d76dc3be6c3a0f74c90458157938b Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 15 Aug 2024 14:21:54 +0900 Subject: [PATCH 093/151] perf(autoware_map_based_prediction): enhance speed by removing unnecessary calculation (#1469) perf(autoware_map_based_prediction): enhance speed by removing unnecessary calculation (#8471) * fix(autoware_map_based_prediction): use surrounding_crosswalks instead of external_surrounding_crosswalks * perf(autoware_map_based_prediction): enhance speed by removing unnecessary calculation --------- Signed-off-by: Y.Hisaki Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> --- .../src/map_based_prediction_node.cpp | 41 +++++++------------ 1 file changed, 14 insertions(+), 27 deletions(-) diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index e95113641104d..8c595c75eb481 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -359,28 +359,6 @@ CrosswalkEdgePoints getCrosswalkEdgePoints(const lanelet::ConstLanelet & crosswa back_center_point, r_p_back, l_p_back}; } -bool withinLanelet( - const TrackedObject & object, const lanelet::ConstLanelet & lanelet, - const bool use_yaw_information = false, const float yaw_threshold = 0.6) -{ - using Point = boost::geometry::model::d2::point_xy; - - const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; - const Point p_object{obj_pos.x, obj_pos.y}; - - auto polygon = lanelet.polygon2d().basicPolygon(); - boost::geometry::correct(polygon); - bool with_in_polygon = boost::geometry::within(p_object, polygon); - - if (!use_yaw_information) return with_in_polygon; - - // use yaw angle to compare - const double abs_yaw_diff = calcAbsYawDiffBetweenLaneletAndObject(object, lanelet); - if (abs_yaw_diff < yaw_threshold) return with_in_polygon; - - return false; -} - bool withinRoadLanelet( const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr, const bool use_yaw_information = false) @@ -392,9 +370,12 @@ bool withinRoadLanelet( const auto surrounding_lanelets = lanelet::geometry::findNearest(lanelet_map_ptr->laneletLayer, search_point, search_radius); - for (const auto & lanelet : surrounding_lanelets) { - if (lanelet.second.hasAttribute(lanelet::AttributeName::Subtype)) { - lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype); + for (const auto & lanelet_with_dist : surrounding_lanelets) { + const auto & dist = lanelet_with_dist.first; + const auto & lanelet = lanelet_with_dist.second; + + if (lanelet.hasAttribute(lanelet::AttributeName::Subtype)) { + lanelet::Attribute attr = lanelet.attribute(lanelet::AttributeName::Subtype); if ( attr.value() == lanelet::AttributeValueString::Crosswalk || attr.value() == lanelet::AttributeValueString::Walkway) { @@ -402,7 +383,13 @@ bool withinRoadLanelet( } } - if (withinLanelet(object, lanelet.second, use_yaw_information)) { + constexpr float yaw_threshold = 0.6; + bool within_lanelet = std::abs(dist) < 1e-5; + if (use_yaw_information) { + within_lanelet = + within_lanelet && calcAbsYawDiffBetweenLaneletAndObject(object, lanelet) < yaw_threshold; + } + if (within_lanelet) { return true; } } @@ -1440,7 +1427,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( attr.value() == lanelet::AttributeValueString::Walkway) { const auto & crosswalk = lanelet; surrounding_crosswalks.push_back(crosswalk); - if (withinLanelet(object, crosswalk)) { + if (std::abs(dist) < 1e-5) { crossing_crosswalk = crosswalk; } } From 55e6408fefcc39d7363e0b96fe129c87bc681b1d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 15 Aug 2024 11:33:55 +0900 Subject: [PATCH 094/151] fix(lane_change): fix invalid doesn't have stop point (#8470) fix invalid doesn't have stop point Signed-off-by: Zulfaqar Azmi --- .../autoware_behavior_path_lane_change_module/src/scene.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 8eae075df8b41..062b74e4525fc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -301,6 +301,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (!status_.is_valid_path) { RCLCPP_DEBUG(logger_, "No valid path found. Returning previous module's path as output."); + insertStopPoint(get_current_lanes(), prev_module_output_.path); return prev_module_output_; } From a05034fa0967b3a3f93198ce89c81c357caea454 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 15 Aug 2024 16:20:12 +0900 Subject: [PATCH 095/151] fix(lane_change): do not cancel when approaching terminal start (#8381) * do not cancel if ego vehicle approaching terminal start Signed-off-by: Muhammad Zulfaqar Azmi * Insert stop point if object is coming from rear Signed-off-by: Muhammad Zulfaqar Azmi * minor edit to fix conflict Signed-off-by: Muhammad Zulfaqar Azmi * rename function Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../scene.hpp | 2 ++ .../utils/base_class.hpp | 2 ++ .../utils/calculation.hpp | 18 +++++++++++++ .../src/interface.cpp | 9 +++++++ .../src/scene.cpp | 25 +++++++++++++++++++ .../src/utils/calculation.cpp | 12 +++++++++ 6 files changed, 68 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index cc695f820ee38..3a11b0ed903dc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -92,6 +92,8 @@ class NormalLaneChange : public LaneChangeBase bool isAbleToReturnCurrentLane() const override; + bool is_near_terminal() const final; + bool isEgoOnPreparePhase() const override; bool isAbleToStopSafely() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index ccc9258324ffa..65f57fa583817 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -93,6 +93,8 @@ class LaneChangeBase virtual bool isAbleToReturnCurrentLane() const = 0; + virtual bool is_near_terminal() const = 0; + virtual LaneChangePath getLaneChangePath() const = 0; virtual BehaviorModuleOutput getTerminalLaneChangePath() const = 0; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index 421b54db9f67a..3dc5e7ee62a57 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -19,6 +19,7 @@ namespace autoware::behavior_path_planner::utils::lane_change::calculation { using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::LCParamPtr; /** * @brief Calculates the distance from the ego vehicle to the terminal point. @@ -40,6 +41,23 @@ double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr); double calc_dist_from_pose_to_terminal_end( const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes, const Pose & src_pose); + +/** + * @brief Calculates the minimum stopping distance to terminal start. + * + * This function computes the minimum stopping distance to terminal start based on the + * minimum lane changing velocity and the minimum longitudinal acceleration. It then + * compares this calculated distance with a pre-defined backward length buffer parameter + * and returns the larger of the two values to ensure safe lane changing. + * + * @param lc_param_ptr Shared pointer to an LCParam structure, which should include: + * - `minimum_lane_changing_velocity`: The minimum velocity required for lane changing. + * - `min_longitudinal_acc`: The minimum longitudinal acceleration used for deceleration. + * - `backward_length_buffer_for_end_of_lane`: A predefined backward buffer length parameter. + * + * @return The required backward buffer distance in meters. + */ +double calc_stopping_distance(const LCParamPtr & lc_param_ptr); } // namespace autoware::behavior_path_planner::utils::lane_change::calculation #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 30ac0051e0339..9354b117cb160 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -247,6 +247,15 @@ bool LaneChangeInterface::canTransitFailureState() return true; } + if (module_type_->is_near_terminal()) { + log_debug_throttled("Unsafe, but ego is approaching terminal. Continue lane change"); + + if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) { + log_debug_throttled("Module require stopping"); + } + return false; + } + if (module_type_->isCancelEnabled() && module_type_->isEgoOnPreparePhase()) { if (module_type_->isStoppedAtRedTrafficLight()) { log_debug_throttled("Stopping at traffic light while in prepare phase. Cancel lane change"); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 062b74e4525fc..a47faf8d3a215 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -769,6 +769,31 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const return true; } +bool NormalLaneChange::is_near_terminal() const +{ + const auto & current_lanes = common_data_ptr_->lanes_ptr->current; + + if (current_lanes.empty()) { + return true; + } + + const auto & current_lanes_terminal = current_lanes.back(); + const auto & lc_param_ptr = common_data_ptr_->lc_param_ptr; + const auto direction = common_data_ptr_->direction; + const auto & route_handler_ptr = common_data_ptr_->route_handler_ptr; + const auto min_lane_changing_distance = calcMinimumLaneChangeLength( + route_handler_ptr, current_lanes_terminal, *lc_param_ptr, direction); + + const auto backward_buffer = calculation::calc_stopping_distance(lc_param_ptr); + + const auto min_lc_dist_with_buffer = + backward_buffer + min_lane_changing_distance + lc_param_ptr->lane_change_finish_judge_buffer; + const auto dist_from_ego_to_terminal_end = + calculation::calc_ego_dist_to_terminal_end(common_data_ptr_); + + return dist_from_ego_to_terminal_end < min_lc_dist_with_buffer; +} + bool NormalLaneChange::isEgoOnPreparePhase() const { const auto & start_position = status_.lane_change_path.info.shift_line.start.position; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index 521c30d406e7a..ac205ceedb34b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -1,3 +1,4 @@ + // Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); @@ -42,4 +43,15 @@ double calc_dist_from_pose_to_terminal_end( } return utils::getDistanceToEndOfLane(src_pose, lanes); } + +double calc_stopping_distance(const LCParamPtr & lc_param_ptr) +{ + // v^2 = u^2 + 2ad + const auto min_lc_vel = lc_param_ptr->minimum_lane_changing_velocity; + const auto min_lon_acc = lc_param_ptr->min_longitudinal_acc; + const auto min_back_dist = std::abs((min_lc_vel * min_lc_vel) / (2 * min_lon_acc)); + + const auto param_back_dist = lc_param_ptr->backward_length_buffer_for_end_of_lane; + return std::max(min_back_dist, param_back_dist); +} } // namespace autoware::behavior_path_planner::utils::lane_change::calculation From c98677d68d10d8d84bd5a2b13d29049edac00a48 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 15 Aug 2024 16:49:37 +0900 Subject: [PATCH 096/151] fix(lane_change): moving object is filtered in the extended target lanes (#8218) * object 3rd Signed-off-by: Zulfaqar Azmi * named param Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/scene.cpp | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index a47faf8d3a215..0f96475429265 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1188,7 +1188,7 @@ FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets( }; if ( - check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far && + check_optional_polygon(object, lanes_polygon.target) && is_lateral_far && is_before_terminal()) { const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object); @@ -1200,6 +1200,20 @@ FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets( continue; } + if ( + check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far && + is_before_terminal()) { + const auto ahead_of_ego = + utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object); + constexpr double stopped_obj_vel_th = 1.0; + if (object.kinematics.initial_twist_with_covariance.twist.linear.x < stopped_obj_vel_th) { + if (ahead_of_ego) { + target_lane_leading_objects.push_back(object); + continue; + } + } + } + const auto is_overlap_target_backward = std::invoke([&]() -> bool { const auto check_backward_polygon = [&object](const auto & target_backward_polygon) { return isPolygonOverlapLanelet(object, target_backward_polygon); From d25170fd95d75ce84e44e1d8d5d5f1a721d4f769 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 16 Aug 2024 09:29:36 +0900 Subject: [PATCH 097/151] perf(autoware_map_based_prediction): removed duplicate findNearest calculations (#8490) (#1470) Signed-off-by: Y.Hisaki Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> --- .../src/map_based_prediction_node.cpp | 36 ++++++++++--------- 1 file changed, 20 insertions(+), 16 deletions(-) diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index 8c595c75eb481..409e5bc4bc7d7 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -32,6 +32,7 @@ #include #include +#include #include #include #include @@ -360,20 +361,11 @@ CrosswalkEdgePoints getCrosswalkEdgePoints(const lanelet::ConstLanelet & crosswa } bool withinRoadLanelet( - const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr, + const TrackedObject & object, + const std::vector> & surrounding_lanelets_with_dist, const bool use_yaw_information = false) { - const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; - lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y); - // nearest lanelet - constexpr double search_radius = 10.0; // [m] - const auto surrounding_lanelets = - lanelet::geometry::findNearest(lanelet_map_ptr->laneletLayer, search_point, search_radius); - - for (const auto & lanelet_with_dist : surrounding_lanelets) { - const auto & dist = lanelet_with_dist.first; - const auto & lanelet = lanelet_with_dist.second; - + for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) { if (lanelet.hasAttribute(lanelet::AttributeName::Subtype)) { lanelet::Attribute attr = lanelet.attribute(lanelet::AttributeName::Subtype); if ( @@ -397,6 +389,20 @@ bool withinRoadLanelet( return false; } +bool withinRoadLanelet( + const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr, + const bool use_yaw_information = false) +{ + const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; + lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y); + // nearest lanelet + constexpr double search_radius = 10.0; // [m] + const auto surrounding_lanelets_with_dist = + lanelet::geometry::findWithin2d(lanelet_map_ptr->laneletLayer, search_point, search_radius); + + return withinRoadLanelet(object, surrounding_lanelets_with_dist, use_yaw_information); +} + boost::optional isReachableCrosswalkEdgePoints( const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets, const lanelet::ConstLanelets & surrounding_crosswalks, const CrosswalkEdgePoints & edge_points, @@ -1412,9 +1418,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear; const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto velocity = std::max(min_crosswalk_user_velocity_, estimated_velocity); - // TODO(Mamoru Sobue): 3rd argument of findNearest is the number of lanelets, not radius, so past - // implementation has been wrong. - const auto surrounding_lanelets_with_dist = lanelet::geometry::findNearest( + const auto surrounding_lanelets_with_dist = lanelet::geometry::findWithin2d( lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y}, prediction_time_horizon_.pedestrian * velocity); lanelet::ConstLanelets surrounding_lanelets; @@ -1459,7 +1463,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( // If the object is not crossing the crosswalk, in the road lanelets, try to find the closest // crosswalk and generate path to the crosswalk edge - } else if (withinRoadLanelet(object, lanelet_map_ptr_)) { + } else if (withinRoadLanelet(object, surrounding_lanelets_with_dist)) { lanelet::ConstLanelet closest_crosswalk{}; const auto & obj_pose = object.kinematics.pose_with_covariance.pose; const auto found_closest_crosswalk = From 9969fe9d3ab14587c83e1cf6d33b20052732a507 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Fri, 16 Aug 2024 12:18:09 +0900 Subject: [PATCH 098/151] fix(turn_signal, lane_change, goal_planner): add optional to tackle lane change turn signal and pull over turn signal (#1468) fix(turn_signal, lane_change, goal_planner): add optional to tackle lane change turn signal and pull over turn signal (#8463) * add optional to tackle LC turn signal and pull over turn signal * CPP file should not re-define default value; typo in copying from internal repos --------- Signed-off-by: YuxuanLiuTier4Desktop <619684051@qq.com> --- .../src/goal_planner_module.cpp | 4 +++- .../src/scene.cpp | 4 +++- .../behavior_path_planner_common/data_manager.hpp | 5 +++-- .../turn_signal_decider.hpp | 3 ++- .../src/turn_signal_decider.cpp | 14 +++++++++----- 5 files changed, 20 insertions(+), 10 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index dc7a76031a3c1..d0132ad85dfad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1880,6 +1880,8 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() constexpr bool is_driving_forward = true; constexpr bool is_pull_out = false; + constexpr bool is_lane_change = false; + constexpr bool is_pull_over = true; const bool override_ego_stopped_check = std::invoke([&]() { if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::SHIFT) { return false; @@ -1895,7 +1897,7 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo( path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length, is_driving_forward, - egos_lane_is_shifted, override_ego_stopped_check, is_pull_out); + egos_lane_is_shifted, override_ego_stopped_check, is_pull_out, is_lane_change, is_pull_over); ignore_signal_ = update_ignore_signal(closest_lanelet.id(), is_ignore); return new_signal; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 0f96475429265..42b22f9b1631c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -604,10 +604,12 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const // The getBehaviorTurnSignalInfo method expects the shifted line to be generated off of the ego's // current lane, lane change is different, so we set this flag to false. constexpr bool egos_lane_is_shifted = false; + constexpr bool is_pull_out = false; + constexpr bool is_lane_change = true; const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo( shift_path, shift_line, current_lanes, current_shift_length, is_driving_forward, - egos_lane_is_shifted); + egos_lane_is_shifted, is_pull_out, is_lane_change); return new_signal; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp index 0ec7841f77cfe..8412abaadb378 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp @@ -174,7 +174,8 @@ struct PlannerData const PathWithLaneId & path, const size_t shift_start_idx, const size_t shift_end_idx, const lanelet::ConstLanelets & current_lanelets, const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted, - const bool override_ego_stopped_check = false, const bool is_pull_out = false) const + const bool override_ego_stopped_check = false, const bool is_pull_out = false, + const bool is_lane_change = false, const bool is_pull_over = false) const { if (shift_start_idx + 1 > path.points.size()) { RCLCPP_WARN(rclcpp::get_logger(__func__), "index inconsistency."); @@ -211,7 +212,7 @@ struct PlannerData return turn_signal_decider.getBehaviorTurnSignalInfo( shifted_path, shift_line, current_lanelets, route_handler, parameters, self_odometry, current_shift_length, is_driving_forward, egos_lane_is_shifted, override_ego_stopped_check, - is_pull_out); + is_pull_out, is_lane_change, is_pull_over); } std::pair getBehaviorTurnSignalInfo( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp index 94ed8af3c82b4..c8f567a119811 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp @@ -134,7 +134,8 @@ class TurnSignalDecider const BehaviorPathPlannerParameters & parameters, const Odometry::ConstSharedPtr self_odometry, const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted, const bool override_ego_stopped_check = false, - const bool is_pull_out = false) const; + const bool is_pull_out = false, const bool is_lane_change = false, + const bool is_pull_over = false) const; private: std::optional getIntersectionTurnSignalInfo( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp index 73f81ce59844c..8960819dd8c60 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp @@ -652,7 +652,8 @@ std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( const std::shared_ptr route_handler, const BehaviorPathPlannerParameters & parameters, const Odometry::ConstSharedPtr self_odometry, const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted, - const bool override_ego_stopped_check, const bool is_pull_out) const + const bool override_ego_stopped_check, const bool is_pull_out, const bool is_lane_change, + const bool is_pull_over) const { using autoware::universe_utils::getPose; @@ -770,15 +771,18 @@ std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( right_same_direction_lane.has_value() || !right_opposite_lanes.empty(); if ( - !is_pull_out && !existShiftSideLane( - start_shift_length, end_shift_length, !has_left_lane, !has_right_lane, - p.turn_signal_shift_length_threshold)) { + (!is_pull_out && !is_lane_change && !is_pull_over) && + !existShiftSideLane( + start_shift_length, end_shift_length, !has_left_lane, !has_right_lane, + p.turn_signal_shift_length_threshold)) { return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true); } // Check if the ego will cross lane bounds. // Note that pull out requires blinkers, even if the ego does not cross lane bounds - if (!is_pull_out && !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) { + if ( + (!is_pull_out && !is_pull_over) && + !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) { return std::make_pair(TurnSignalInfo(p_path_start, p_path_end), true); } From f55c26bc17f15f578581776171caeb670ccac404 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 16 Aug 2024 13:41:43 +0900 Subject: [PATCH 099/151] fix(start/goal_planner): align geometric parall parking start pose with center line (#8326) (#1443) Signed-off-by: kosuke55 --- .../geometric_parallel_parking.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index 113b87f4c0032..104d0a345be3a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -17,10 +17,12 @@ #include "autoware/behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" +#include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include +#include #include #include @@ -333,8 +335,20 @@ std::optional GeometricParallelParking::calcStartPose( } const double dx_sign = is_forward ? -1 : 1; const double dx = 2 * std::sqrt(squared_distance_to_arc_connect) * dx_sign; - const Pose start_pose = - calcOffsetPose(goal_pose, dx + start_pose_offset, -arc_coordinates.distance, 0); + + // Assuming parallel poses, calculate the approximate start pose on the centerline from the goal + // pose + const Pose approximate_start_pose = calcOffsetPose(goal_pose, dx, -arc_coordinates.distance, 0); + lanelet::ConstLanelet closest_road_lane{}; + + // Calculate start pose on the centerline, then offset it. + lanelet::utils::query::getClosestLanelet(road_lanes, approximate_start_pose, &closest_road_lane); + const Pose start_pose_no_offset = + lanelet::utils::getClosestCenterPose(closest_road_lane, approximate_start_pose.position); + const auto road_lane_path = planner_data_->route_handler->getCenterLinePath( + road_lanes, 0.0, std::numeric_limits::max()); + const auto start_pose = autoware::motion_utils::calcLongitudinalOffsetPose( + road_lane_path.points, start_pose_no_offset.position, start_pose_offset); return start_pose; } From 6d0db533ce12470012b3753d3980ed7f58bf88c9 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 16 Aug 2024 15:45:32 +0900 Subject: [PATCH 100/151] perf(out_of_lane): use rtree to get stop lines and trajectory lanelets (#1461) perf(out_of_lane): use rtree to get stop lines and trajectory lanelets (#8439) Signed-off-by: Maxime CLEMENT --- .../src/filter_predicted_objects.cpp | 63 ++++++++++--------- .../src/filter_predicted_objects.hpp | 15 +++-- .../src/lanelets_selection.cpp | 13 ++-- .../src/out_of_lane_module.cpp | 52 ++++++++++++++- .../src/types.hpp | 26 ++++++-- .../test/test_filter_predicted_objects.cpp | 2 +- 6 files changed, 121 insertions(+), 50 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index 1231bf49759d5..a53129f372e3d 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -15,20 +15,23 @@ #include "filter_predicted_objects.hpp" #include +#include #include #include +#include #include #include #include +#include namespace autoware::motion_velocity_planner::out_of_lane { void cut_predicted_path_beyond_line( autoware_perception_msgs::msg::PredictedPath & predicted_path, - const lanelet::BasicLineString2d & stop_line, const double object_front_overhang) + const universe_utils::LineString2d & stop_line, const double object_front_overhang) { if (predicted_path.path.empty() || stop_line.size() < 2) return; @@ -58,43 +61,43 @@ void cut_predicted_path_beyond_line( } } -std::optional find_next_stop_line( - const autoware_perception_msgs::msg::PredictedPath & path, - const std::shared_ptr planner_data) +std::optional find_next_stop_line( + const autoware_perception_msgs::msg::PredictedPath & path, const EgoData & ego_data) { - lanelet::ConstLanelets lanelets; - lanelet::BasicLineString2d query_line; - for (const auto & p : path.path) query_line.emplace_back(p.position.x, p.position.y); - const auto query_results = lanelet::geometry::findWithin2d( - planner_data->route_handler->getLaneletMapPtr()->laneletLayer, query_line); - for (const auto & r : query_results) lanelets.push_back(r.second); - for (const auto & ll : lanelets) { - for (const auto & element : ll.regulatoryElementsAs()) { - const auto traffic_signal_stamped = planner_data->get_traffic_signal(element->id()); - if ( - traffic_signal_stamped.has_value() && element->stopLine().has_value() && - traffic_light_utils::isTrafficSignalStop(ll, traffic_signal_stamped.value().signal)) { - lanelet::BasicLineString2d stop_line; - for (const auto & p : *(element->stopLine())) stop_line.emplace_back(p.x(), p.y()); - return stop_line; + universe_utils::LineString2d query_path; + for (const auto & p : path.path) query_path.emplace_back(p.position.x, p.position.y); + std::vector query_results; + ego_data.stop_lines_rtree.query( + boost::geometry::index::intersects(query_path), std::back_inserter(query_results)); + auto earliest_intersecting_index = query_path.size(); + std::optional earliest_stop_line; + universe_utils::Segment2d path_segment; + for (const auto & [_, stop_line] : query_results) { + for (auto index = 0UL; index + 1 < query_path.size(); ++index) { + path_segment.first = query_path[index]; + path_segment.second = query_path[index + 1]; + if (boost::geometry::intersects(path_segment, stop_line.stop_line)) { + bool within_stop_line_lanelet = + std::any_of(stop_line.lanelets.begin(), stop_line.lanelets.end(), [&](const auto & ll) { + return boost::geometry::within(path_segment.first, ll.polygon2d().basicPolygon()); + }); + if (within_stop_line_lanelet) { + earliest_intersecting_index = std::min(index, earliest_intersecting_index); + earliest_stop_line = stop_line.stop_line; + } } } } - return std::nullopt; + return earliest_stop_line; } void cut_predicted_path_beyond_red_lights( - autoware_perception_msgs::msg::PredictedPath & predicted_path, - const std::shared_ptr planner_data, const double object_front_overhang) + autoware_perception_msgs::msg::PredictedPath & predicted_path, const EgoData & ego_data, + const double object_front_overhang) { - const auto stop_line = find_next_stop_line(predicted_path, planner_data); + const auto stop_line = find_next_stop_line(predicted_path, ego_data); if (stop_line) { - // we use a longer stop line to also cut predicted paths that slightly go around the stop line - auto longer_stop_line = *stop_line; - const auto diff = stop_line->back() - stop_line->front(); - longer_stop_line.front() -= diff * 0.5; - longer_stop_line.back() += diff * 0.5; - cut_predicted_path_beyond_line(predicted_path, longer_stop_line, object_front_overhang); + cut_predicted_path_beyond_line(predicted_path, *stop_line, object_front_overhang); } } @@ -141,7 +144,7 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( if (params.objects_cut_predicted_paths_beyond_red_lights) for (auto & predicted_path : predicted_paths) cut_predicted_path_beyond_red_lights( - predicted_path, planner_data, filtered_object.shape.dimensions.x); + predicted_path, ego_data, filtered_object.shape.dimensions.x); predicted_paths.erase( std::remove_if( predicted_paths.begin(), predicted_paths.end(), diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp index 49f18bfe372db..baf07e4b06ea5 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -30,22 +30,21 @@ namespace autoware::motion_velocity_planner::out_of_lane /// @param [in] object_front_overhang extra distance to cut ahead of the stop line void cut_predicted_path_beyond_line( autoware_perception_msgs::msg::PredictedPath & predicted_path, - const lanelet::BasicLineString2d & stop_line, const double object_front_overhang); + const universe_utils::LineString2d & stop_line, const double object_front_overhang); /// @brief find the next red light stop line along the given path /// @param [in] path predicted path to check for a stop line -/// @param [in] planner_data planner data with stop line information +/// @param [in] ego_data ego data with the stop lines information /// @return the first red light stop line found along the path (if any) -std::optional find_next_stop_line( - const autoware_perception_msgs::msg::PredictedPath & path, - const std::shared_ptr planner_data); +std::optional find_next_stop_line( + const autoware_perception_msgs::msg::PredictedPath & path, const EgoData & ego_data); /// @brief cut predicted path beyond stop lines of red lights /// @param [inout] predicted_path predicted path to cut -/// @param [in] planner_data planner data to get the map and traffic light information +/// @param [in] ego_data ego data with the stop lines information void cut_predicted_path_beyond_red_lights( - autoware_perception_msgs::msg::PredictedPath & predicted_path, - const std::shared_ptr planner_data, const double object_front_overhang); + autoware_perception_msgs::msg::PredictedPath & predicted_path, const EgoData & ego_data, + const double object_front_overhang); /// @brief filter predicted objects and their predicted paths /// @param [in] planner_data planner data diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp index bfa38e544227f..bca849f806f63 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -16,6 +16,9 @@ #include +#include + +#include #include #include @@ -71,10 +74,12 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( lanelet::BasicLineString2d trajectory_ls; for (const auto & p : ego_data.trajectory_points) trajectory_ls.emplace_back(p.pose.position.x, p.pose.position.y); - for (const auto & dist_lanelet : - lanelet::geometry::findWithin2d(lanelet_map_ptr->laneletLayer, trajectory_ls)) { - if (!contains_lanelet(trajectory_lanelets, dist_lanelet.second.id())) - trajectory_lanelets.push_back(dist_lanelet.second); + const auto candidates = + lanelet_map_ptr->laneletLayer.search(lanelet::geometry::boundingBox2d(trajectory_ls)); + for (const auto & ll : candidates) { + if (!boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { + trajectory_lanelets.push_back(ll); + } } const auto missing_lanelets = get_missing_lane_change_lanelets(trajectory_lanelets, route_handler); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index 0afedcd7f9c9a..a6b34a1566e19 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -25,13 +25,19 @@ #include #include +#include +#include #include #include #include +#include +#include #include -#include +#include +#include +#include #include #include @@ -155,6 +161,42 @@ void OutOfLaneModule::update_parameters(const std::vector & p updateParam(parameters, ns_ + ".ego.extra_right_offset", pp.extra_right_offset); } +void prepare_stop_lines_rtree( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, const double search_distance) +{ + std::vector rtree_nodes; + const auto bbox = lanelet::BoundingBox2d( + lanelet::BasicPoint2d{ + ego_data.pose.position.x - search_distance, ego_data.pose.position.y - search_distance}, + lanelet::BasicPoint2d{ + ego_data.pose.position.x + search_distance, ego_data.pose.position.y + search_distance}); + out_of_lane::StopLineNode stop_line_node; + for (const auto & ll : + planner_data.route_handler->getLaneletMapPtr()->laneletLayer.search(bbox)) { + for (const auto & element : ll.regulatoryElementsAs()) { + const auto traffic_signal_stamped = planner_data.get_traffic_signal(element->id()); + if ( + traffic_signal_stamped.has_value() && element->stopLine().has_value() && + traffic_light_utils::isTrafficSignalStop(ll, traffic_signal_stamped.value().signal)) { + stop_line_node.second.stop_line.clear(); + for (const auto & p : element->stopLine()->basicLineString()) { + stop_line_node.second.stop_line.emplace_back(p.x(), p.y()); + } + // use a longer stop line to also cut predicted paths that slightly go around the stop line + const auto diff = + stop_line_node.second.stop_line.back() - stop_line_node.second.stop_line.front(); + stop_line_node.second.stop_line.front() -= diff * 0.5; + stop_line_node.second.stop_line.back() += diff * 0.5; + stop_line_node.second.lanelets = planner_data.route_handler->getPreviousLanelets(ll); + stop_line_node.first = + boost::geometry::return_envelope(stop_line_node.second.stop_line); + rtree_nodes.push_back(stop_line_node); + } + } + } + ego_data.stop_lines_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; +} + VelocityPlanningResult OutOfLaneModule::plan( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) @@ -169,6 +211,10 @@ VelocityPlanningResult OutOfLaneModule::plan( autoware::motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); ego_data.velocity = planner_data->current_odometry.twist.twist.linear.x; ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel(); + stopwatch.tic("preprocessing"); + prepare_stop_lines_rtree(ego_data, *planner_data, 100.0); + const auto preprocessing_us = stopwatch.toc("preprocessing"); + stopwatch.tic("calculate_trajectory_footprints"); const auto current_ego_footprint = out_of_lane::calculate_current_ego_footprint(ego_data, params_, true); @@ -289,6 +335,7 @@ VelocityPlanningResult OutOfLaneModule::plan( RCLCPP_DEBUG( logger_, "Total time = %2.2fus\n" + "\tpreprocessing = %2.0fus\n" "\tcalculate_lanelets = %2.0fus\n" "\tcalculate_trajectory_footprints = %2.0fus\n" "\tcalculate_overlapping_ranges = %2.0fus\n" @@ -296,7 +343,7 @@ VelocityPlanningResult OutOfLaneModule::plan( "\tcalculate_decisions = %2.0fus\n" "\tcalc_slowdown_points = %2.0fus\n" "\tinsert_slowdown_points = %2.0fus\n", - total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_us, + preprocessing_us, total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_us, calculate_overlapping_ranges_us, filter_predicted_objects_us, calculate_decisions_us, calc_slowdown_points_us, insert_slowdown_points_us); debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array(debug_data_)); @@ -304,6 +351,7 @@ VelocityPlanningResult OutOfLaneModule::plan( out_of_lane::debug::create_virtual_walls(debug_data_, params_)); virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); std::map processing_times; + processing_times["preprocessing"] = preprocessing_us / 1000; processing_times["calculate_lanelets"] = calculate_lanelets_us / 1000; processing_times["calculate_trajectory_footprints"] = calculate_trajectory_footprints_us / 1000; processing_times["calculate_overlapping_ranges"] = calculate_overlapping_ranges_us / 1000; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 9c68a0bf23a92..96c54064e296c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -16,12 +16,17 @@ #define TYPES_HPP_ #include +#include #include #include #include #include +#include +#include + +#include #include #include @@ -172,6 +177,16 @@ struct OtherLane } }; +namespace bgi = boost::geometry::index; +struct StopLine +{ + universe_utils::LineString2d stop_line; + lanelet::ConstLanelets lanelets; +}; +using StopLineNode = std::pair; +using StopLinesRtree = bgi::rtree>; +using OutAreaRtree = bgi::rtree, bgi::rstar<16>>; + /// @brief data related to the ego vehicle struct EgoData { @@ -180,16 +195,17 @@ struct EgoData double velocity{}; // [m/s] double max_decel{}; // [m/s²] geometry_msgs::msg::Pose pose{}; + StopLinesRtree stop_lines_rtree; }; /// @brief data needed to make decisions struct DecisionInputs { - OverlapRanges ranges{}; - EgoData ego_data{}; - autoware_perception_msgs::msg::PredictedObjects objects{}; - std::shared_ptr route_handler{}; - lanelet::ConstLanelets lanelets{}; + OverlapRanges ranges; + EgoData ego_data; + autoware_perception_msgs::msg::PredictedObjects objects; + std::shared_ptr route_handler; + lanelet::ConstLanelets lanelets; }; /// @brief debug data diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp index 6d1ba8084b821..2287a7cbf308a 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp @@ -25,7 +25,7 @@ TEST(TestCollisionDistance, CutPredictedPathBeyondLine) { using autoware::motion_velocity_planner::out_of_lane::cut_predicted_path_beyond_line; autoware_perception_msgs::msg::PredictedPath predicted_path; - lanelet::BasicLineString2d stop_line; + autoware::universe_utils::LineString2d stop_line; double object_front_overhang = 0.0; const auto eps = 1e-9; From dc446be6bc94c06a92d07645ca5ce54dc19917eb Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Sat, 17 Aug 2024 00:00:33 +0900 Subject: [PATCH 101/151] fix(tensorrt_yolox): missing param file arg (#1462) * fix(tensorrt_yolox): missing param file arg Signed-off-by: badai-nguyen * fix: yolox_tiny Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml | 2 ++ perception/tensorrt_yolox/launch/yolox_tiny.launch.xml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml index dd15eda2913ce..fa303e573bc62 100644 --- a/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml +++ b/perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml @@ -9,9 +9,11 @@ + + diff --git a/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml b/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml index 9e5d1c371b13b..46d431fb2e3b7 100644 --- a/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml +++ b/perception/tensorrt_yolox/launch/yolox_tiny.launch.xml @@ -8,9 +8,11 @@ + + From 7da383d327911f0441be1f98785b0f727e86b34c Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Wed, 10 Jul 2024 13:42:44 +0900 Subject: [PATCH 102/151] feat(lidar_transfusion): intensity as uint8 and tests (#7745) * feat(lidar_transfusion): intensity as uint8 and tests Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix * fix(lidar_transfusion): headers include Signed-off-by: Amadeusz Szymko * feat(lidar_transfusion): use autoware_point_types for validation & refactor Signed-off-by: Amadeusz Szymko * style(lidar_transfusion): remove deprecated function Signed-off-by: Amadeusz Szymko * test(lidar_transfusion): point_step validation is not required Signed-off-by: Amadeusz Szymko * docs(lidar_transfusion): update assumptions / known limits Signed-off-by: Amadeusz Szymko * refactor(lidar_transfusion): redundant points structure Signed-off-by: Amadeusz Szymko * docs(lidar_transfusion): update assumptions / known limits Signed-off-by: Amadeusz Szymko * test(lidar_transfusion): temporary disable CUDA tests Signed-off-by: Amadeusz Szymko --------- Signed-off-by: Amadeusz Szymko Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa --- perception/lidar_transfusion/CMakeLists.txt | 52 +++ perception/lidar_transfusion/README.md | 18 ++ .../preprocess/pointcloud_densification.hpp | 2 +- .../preprocess/preprocess_kernel.hpp | 6 +- .../preprocess/voxel_generator.hpp | 8 +- .../include/lidar_transfusion/ros_utils.hpp | 68 ++++ .../include/lidar_transfusion/utils.hpp | 46 --- .../preprocess/pointcloud_densification.cpp | 9 +- .../lib/preprocess/preprocess_kernel.cu | 61 ++-- .../lib/preprocess/voxel_generator.cpp | 23 +- perception/lidar_transfusion/package.xml | 1 + .../test/test_detection_class_remapper.cpp | 92 ++++++ .../lidar_transfusion/test/test_nms.cpp | 121 +++++++ .../test/test_postprocess_kernel.cpp | 299 ++++++++++++++++++ .../test/test_postprocess_kernel.hpp | 48 +++ .../test/test_preprocess_kernel.cpp | 265 ++++++++++++++++ .../test/test_preprocess_kernel.hpp | 50 +++ .../lidar_transfusion/test/test_ros_utils.cpp | 104 ++++++ .../test/test_voxel_generator.cpp | 284 +++++++++++++++++ .../test/test_voxel_generator.hpp | 65 ++++ 20 files changed, 1517 insertions(+), 105 deletions(-) create mode 100644 perception/lidar_transfusion/test/test_detection_class_remapper.cpp create mode 100644 perception/lidar_transfusion/test/test_nms.cpp create mode 100644 perception/lidar_transfusion/test/test_postprocess_kernel.cpp create mode 100644 perception/lidar_transfusion/test/test_postprocess_kernel.hpp create mode 100644 perception/lidar_transfusion/test/test_preprocess_kernel.cpp create mode 100644 perception/lidar_transfusion/test/test_preprocess_kernel.hpp create mode 100644 perception/lidar_transfusion/test/test_ros_utils.cpp create mode 100644 perception/lidar_transfusion/test/test_voxel_generator.cpp create mode 100644 perception/lidar_transfusion/test/test_voxel_generator.hpp diff --git a/perception/lidar_transfusion/CMakeLists.txt b/perception/lidar_transfusion/CMakeLists.txt index c0e2d85f27e62..677a835e5b04e 100644 --- a/perception/lidar_transfusion/CMakeLists.txt +++ b/perception/lidar_transfusion/CMakeLists.txt @@ -137,6 +137,58 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_detection_class_remapper + test/test_detection_class_remapper.cpp + ) + ament_auto_add_gtest(test_ros_utils + test/test_ros_utils.cpp + ) + ament_auto_add_gtest(test_nms + test/test_nms.cpp + ) + + # Temporary disabled, tracked by: + # https://github.com/autowarefoundation/autoware.universe/issues/7724 + # ament_auto_add_gtest(test_voxel_generator + # test/test_voxel_generator.cpp + # ) + + # # preprocess kernel test + # add_executable(test_preprocess_kernel + # test/test_preprocess_kernel.cpp + # ) + # target_include_directories(test_preprocess_kernel PUBLIC + # ${test_preprocess_kernel_SOURCE_DIR} + # ) + # target_link_libraries(test_preprocess_kernel + # transfusion_cuda_lib + # gtest + # gtest_main + # ) + # ament_add_test(test_preprocess_kernel + # GENERATE_RESULT_FOR_RETURN_CODE_ZERO + # COMMAND "$" + # ) + + # # postprocess kernel test + # add_executable(test_postprocess_kernel + # test/test_postprocess_kernel.cpp + # ) + # target_include_directories(test_postprocess_kernel PUBLIC + # ${test_postprocess_kernel_SOURCE_DIR} + # ) + # target_link_libraries(test_postprocess_kernel + # transfusion_cuda_lib + # gtest + # gtest_main + # ) + # ament_add_test(test_postprocess_kernel + # GENERATE_RESULT_FOR_RETURN_CODE_ZERO + # COMMAND "$" + # ) + endif() ament_auto_package( diff --git a/perception/lidar_transfusion/README.md b/perception/lidar_transfusion/README.md index 7974714720c32..e30403141e8ad 100644 --- a/perception/lidar_transfusion/README.md +++ b/perception/lidar_transfusion/README.md @@ -59,6 +59,24 @@ ros2 launch lidar_transfusion lidar_transfusion.launch.xml log_level:=debug ## Assumptions / Known limits +This library operates on raw cloud data (bytes). It is assumed that the input pointcloud message has following format: + +```python +[ + sensor_msgs.msg.PointField(name='x', offset=0, datatype=7, count=1), + sensor_msgs.msg.PointField(name='y', offset=4, datatype=7, count=1), + sensor_msgs.msg.PointField(name='z', offset=8, datatype=7, count=1), + sensor_msgs.msg.PointField(name='intensity', offset=12, datatype=2, count=1) +] +``` + +This input may consist of other fields as well - shown format is required minimum. +For debug purposes, you can validate your pointcloud topic using simple command: + +```bash +ros2 topic echo --field fields +``` + ## Trained Models You can download the onnx format of trained models by clicking on the links below. diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp index 25095f4dc9c0b..6ac0a6544389f 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp @@ -51,7 +51,7 @@ class DensificationParam struct PointCloudWithTransform { - cuda::unique_ptr points_d{nullptr}; + cuda::unique_ptr data_d{nullptr}; std_msgs::msg::Header header; size_t num_points{0}; Eigen::Affine3f affine_past2world; diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp index c571990d84b51..592f09c2d288a 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp @@ -56,12 +56,8 @@ class PreprocessCuda unsigned int * mask, float * voxels, unsigned int * pillar_num, float * voxel_features, unsigned int * voxel_num, unsigned int * voxel_idxs); - // cudaError_t generateVoxelsInput_launch( - // uint8_t * cloud_data, CloudInfo & cloud_info, unsigned int points_agg, unsigned int - // points_size, float time_lag, float * affine_transform, float * points); - cudaError_t generateSweepPoints_launch( - const float * input_points, size_t points_size, int input_point_step, float time_lag, + const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, const float * transform, float * output_points); private: diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp index 3e3660e238473..f0d253ee28755 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp @@ -18,8 +18,8 @@ #include "lidar_transfusion/cuda_utils.hpp" #include "lidar_transfusion/preprocess/pointcloud_densification.hpp" #include "lidar_transfusion/preprocess/preprocess_kernel.hpp" +#include "lidar_transfusion/ros_utils.hpp" #include "lidar_transfusion/transfusion_config.hpp" -#include "lidar_transfusion/utils.hpp" #ifdef ROS_DISTRO_GALACTIC #include @@ -27,6 +27,8 @@ #include #endif +#include + #include #include @@ -36,8 +38,8 @@ namespace lidar_transfusion { -constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix -constexpr size_t MAX_CLOUD_STEP_SIZE = 35; // PointXYZIRCADT +constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix +constexpr size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware_point_types::PointXYZIRCAEDT); class VoxelGenerator { diff --git a/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp index f013a02404a29..cbfc4e87b1610 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp @@ -17,16 +17,84 @@ #include "lidar_transfusion/utils.hpp" +#include + #include #include #include #include +#include +#include #include #include +#define CHECK_OFFSET(offset, structure, field) \ + static_assert( \ + offsetof(structure, field) == offset, \ + "Offset of " #field " in " #structure " does not match expected offset.") +#define CHECK_TYPE(type, structure, field) \ + static_assert( \ + std::is_same::value, \ + "Type of " #field " in " #structure " does not match expected type.") +#define CHECK_FIELD(offset, type, structure, field) \ + CHECK_OFFSET(offset, structure, field); \ + CHECK_TYPE(type, structure, field) + namespace lidar_transfusion { +using sensor_msgs::msg::PointField; + +CHECK_FIELD(0, float, autoware_point_types::PointXYZIRCAEDT, x); +CHECK_FIELD(4, float, autoware_point_types::PointXYZIRCAEDT, y); +CHECK_FIELD(8, float, autoware_point_types::PointXYZIRCAEDT, z); +CHECK_FIELD(12, uint8_t, autoware_point_types::PointXYZIRCAEDT, intensity); + +struct CloudInfo +{ + uint32_t x_offset{0}; + uint32_t y_offset{sizeof(float)}; + uint32_t z_offset{sizeof(float) * 2}; + uint32_t intensity_offset{sizeof(float) * 3}; + uint8_t x_datatype{PointField::FLOAT32}; + uint8_t y_datatype{PointField::FLOAT32}; + uint8_t z_datatype{PointField::FLOAT32}; + uint8_t intensity_datatype{PointField::UINT8}; + uint8_t x_count{1}; + uint8_t y_count{1}; + uint8_t z_count{1}; + uint8_t intensity_count{1}; + uint32_t point_step{sizeof(autoware_point_types::PointXYZIRCAEDT)}; + bool is_bigendian{false}; + + bool operator!=(const CloudInfo & rhs) const + { + return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset || + intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype || + y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype || + intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count || + y_count != rhs.y_count || z_count != rhs.z_count || + intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian; + } + + friend std::ostream & operator<<(std::ostream & os, const CloudInfo & info) + { + os << "x_offset: " << static_cast(info.x_offset) << std::endl; + os << "y_offset: " << static_cast(info.y_offset) << std::endl; + os << "z_offset: " << static_cast(info.z_offset) << std::endl; + os << "intensity_offset: " << static_cast(info.intensity_offset) << std::endl; + os << "x_datatype: " << static_cast(info.x_datatype) << std::endl; + os << "y_datatype: " << static_cast(info.y_datatype) << std::endl; + os << "z_datatype: " << static_cast(info.z_datatype) << std::endl; + os << "intensity_datatype: " << static_cast(info.intensity_datatype) << std::endl; + os << "x_count: " << static_cast(info.x_count) << std::endl; + os << "y_count: " << static_cast(info.y_count) << std::endl; + os << "z_count: " << static_cast(info.z_count) << std::endl; + os << "intensity_count: " << static_cast(info.intensity_count) << std::endl; + os << "is_bigendian: " << static_cast(info.is_bigendian) << std::endl; + return os; + } +}; void box3DToDetectedObject( const Box3D & box3d, const std::vector & class_names, diff --git a/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp index e73fe7f055953..cc40e55851738 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp @@ -36,52 +36,6 @@ struct Box3D float yaw; }; -struct CloudInfo -{ - uint32_t x_offset; - uint32_t y_offset; - uint32_t z_offset; - uint32_t intensity_offset; - uint8_t x_datatype; - uint8_t y_datatype; - uint8_t z_datatype; - uint8_t intensity_datatype; - uint8_t x_count; - uint8_t y_count; - uint8_t z_count; - uint8_t intensity_count; - uint32_t point_step; - bool is_bigendian; - - CloudInfo() - : x_offset(0), - y_offset(4), - z_offset(8), - intensity_offset(12), - x_datatype(7), - y_datatype(7), - z_datatype(7), - intensity_datatype(7), - x_count(1), - y_count(1), - z_count(1), - intensity_count(1), - point_step(16), - is_bigendian(false) - { - } - - bool operator!=(const CloudInfo & rhs) const - { - return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset || - intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype || - y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype || - intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count || - y_count != rhs.y_count || z_count != rhs.z_count || - intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian; - } -}; - enum NetworkIO { voxels = 0, num_points, coors, cls_score, dir_pred, bbox_pred, ENUM_SIZE }; // cspell: ignore divup diff --git a/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp b/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp index 774b3a05d71c1..c13423f2d24d8 100644 --- a/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp +++ b/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp @@ -93,16 +93,15 @@ void PointCloudDensification::enqueue( affine_world2current_ = affine_world2current; current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds(); - assert(sizeof(uint8_t) * msg.width * msg.height * msg.point_step % sizeof(float) == 1); - auto points_d = cuda::make_unique( - sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(float)); + auto data_d = cuda::make_unique( + sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(uint8_t)); CHECK_CUDA_ERROR(cudaMemcpyAsync( - points_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step, + data_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step, cudaMemcpyHostToDevice, stream_)); PointCloudWithTransform pointcloud = { - std::move(points_d), msg.header, msg.width * msg.height, affine_world2current.inverse()}; + std::move(data_d), msg.header, msg.width * msg.height, affine_world2current.inverse()}; pointcloud_cache_.push_front(std::move(pointcloud)); } diff --git a/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu b/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu index b8f9ae998fd4f..48bb4eb9332a8 100644 --- a/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu @@ -31,6 +31,8 @@ #include "lidar_transfusion/cuda_utils.hpp" #include "lidar_transfusion/preprocess/preprocess_kernel.hpp" +#include + namespace lidar_transfusion { @@ -99,9 +101,12 @@ __global__ void generateVoxels_random_kernel( cudaError_t PreprocessCuda::generateVoxels_random_launch( float * points, unsigned int points_size, unsigned int * mask, float * voxels) { - int threadNum = config_.threads_for_voxel_; - dim3 blocks((points_size + threadNum - 1) / threadNum); - dim3 threads(threadNum); + if (points_size == 0) { + return cudaGetLastError(); + } + dim3 blocks(divup(points_size, config_.threads_for_voxel_)); + dim3 threads(config_.threads_for_voxel_); + generateVoxels_random_kernel<<>>( points, points_size, config_.min_x_range_, config_.max_x_range_, config_.min_y_range_, config_.max_y_range_, config_.min_z_range_, config_.max_z_range_, config_.voxel_x_size_, @@ -165,40 +170,48 @@ cudaError_t PreprocessCuda::generateBaseFeatures_launch( } __global__ void generateSweepPoints_kernel( - const float * input_points, size_t points_size, int input_point_step, float time_lag, + const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, const float * transform_array, int num_features, float * output_points) { int point_idx = blockIdx.x * blockDim.x + threadIdx.x; if (point_idx >= points_size) return; - const float input_x = input_points[point_idx * input_point_step + 0]; - const float input_y = input_points[point_idx * input_point_step + 1]; - const float input_z = input_points[point_idx * input_point_step + 2]; - const float intensity = input_points[point_idx * input_point_step + 3]; - - output_points[point_idx * num_features] = transform_array[0] * input_x + - transform_array[4] * input_y + - transform_array[8] * input_z + transform_array[12]; - output_points[point_idx * num_features + 1] = transform_array[1] * input_x + - transform_array[5] * input_y + - transform_array[9] * input_z + transform_array[13]; - output_points[point_idx * num_features + 2] = transform_array[2] * input_x + - transform_array[6] * input_y + - transform_array[10] * input_z + transform_array[14]; - output_points[point_idx * num_features + 3] = intensity; + union { + uint32_t raw{0}; + float value; + } input_x, input_y, input_z; + +#pragma unroll + for (int i = 0; i < 4; i++) { // 4 bytes for float32 + input_x.raw |= input_data[point_idx * input_point_step + i] << i * 8; + input_y.raw |= input_data[point_idx * input_point_step + i + 4] << i * 8; + input_z.raw |= input_data[point_idx * input_point_step + i + 8] << i * 8; + } + + float input_intensity = static_cast(input_data[point_idx * input_point_step + 12]); + + output_points[point_idx * num_features] = + transform_array[0] * input_x.value + transform_array[4] * input_y.value + + transform_array[8] * input_z.value + transform_array[12]; + output_points[point_idx * num_features + 1] = + transform_array[1] * input_x.value + transform_array[5] * input_y.value + + transform_array[9] * input_z.value + transform_array[13]; + output_points[point_idx * num_features + 2] = + transform_array[2] * input_x.value + transform_array[6] * input_y.value + + transform_array[10] * input_z.value + transform_array[14]; + output_points[point_idx * num_features + 3] = input_intensity; output_points[point_idx * num_features + 4] = time_lag; } cudaError_t PreprocessCuda::generateSweepPoints_launch( - const float * input_points, size_t points_size, int input_point_step, float time_lag, + const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, const float * transform_array, float * output_points) { - int threadNum = config_.threads_for_voxel_; - dim3 blocks((points_size + threadNum - 1) / threadNum); - dim3 threads(threadNum); + dim3 blocks(divup(points_size, config_.threads_for_voxel_)); + dim3 threads(config_.threads_for_voxel_); generateSweepPoints_kernel<<>>( - input_points, points_size, input_point_step, time_lag, transform_array, + input_data, points_size, input_point_step, time_lag, transform_array, config_.num_point_feature_size_, output_points); cudaError_t err = cudaGetLastError(); diff --git a/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp b/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp index 7072e8491af66..cb8bac984aef3 100644 --- a/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp +++ b/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp @@ -23,25 +23,6 @@ namespace lidar_transfusion { -std::ostream & operator<<(std::ostream & os, const CloudInfo & info) -{ - os << "x_offset: " << static_cast(info.x_offset) << std::endl; - os << "y_offset: " << static_cast(info.y_offset) << std::endl; - os << "z_offset: " << static_cast(info.z_offset) << std::endl; - os << "intensity_offset: " << static_cast(info.intensity_offset) << std::endl; - os << "x_datatype: " << static_cast(info.x_datatype) << std::endl; - os << "y_datatype: " << static_cast(info.y_datatype) << std::endl; - os << "z_datatype: " << static_cast(info.z_datatype) << std::endl; - os << "intensity_datatype: " << static_cast(info.intensity_datatype) << std::endl; - os << "x_count: " << static_cast(info.x_count) << std::endl; - os << "y_count: " << static_cast(info.y_count) << std::endl; - os << "z_count: " << static_cast(info.z_count) << std::endl; - os << "intensity_count: " << static_cast(info.intensity_count) << std::endl; - os << "point_step: " << static_cast(info.point_step) << std::endl; - os << "is_bigendian: " << static_cast(info.is_bigendian) << std::endl; - return os; -} - VoxelGenerator::VoxelGenerator( const DensificationParam & densification_param, const TransfusionConfig & config, cudaStream_t & stream) @@ -106,8 +87,8 @@ std::size_t VoxelGenerator::generateSweepPoints( CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); pre_ptr_->generateSweepPoints_launch( - pc_cache_iter->points_d.get(), sweep_num_points, cloud_info_.point_step / sizeof(float), - time_lag, affine_past2current_d_.get(), points_d.get() + shift); + pc_cache_iter->data_d.get(), sweep_num_points, cloud_info_.point_step, time_lag, + affine_past2current_d_.get(), points_d.get() + shift); point_counter += sweep_num_points; } diff --git a/perception/lidar_transfusion/package.xml b/perception/lidar_transfusion/package.xml index ffbe091b998e5..3b495025b1c34 100644 --- a/perception/lidar_transfusion/package.xml +++ b/perception/lidar_transfusion/package.xml @@ -13,6 +13,7 @@ autoware_cmake autoware_perception_msgs + autoware_point_types autoware_universe_utils launch_ros object_recognition_utils diff --git a/perception/lidar_transfusion/test/test_detection_class_remapper.cpp b/perception/lidar_transfusion/test/test_detection_class_remapper.cpp new file mode 100644 index 0000000000000..6e7f896e44d2c --- /dev/null +++ b/perception/lidar_transfusion/test/test_detection_class_remapper.cpp @@ -0,0 +1,92 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +TEST(DetectionClassRemapperTest, MapClasses) +{ + lidar_transfusion::DetectionClassRemapper remapper; + + // Set up the parameters for the remapper + // Labels: CAR, TRUCK, TRAILER + std::vector allow_remapping_by_area_matrix = { + 0, 0, 0, // CAR cannot be remapped + 0, 0, 1, // TRUCK can be remapped to TRAILER + 0, 1, 0 // TRAILER can be remapped to TRUCK + }; + std::vector min_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0}; + std::vector max_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 999.0, 0.0, 10.0, 0.0}; + + remapper.setParameters(allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); + + // Create a DetectedObjects message with some objects + autoware_perception_msgs::msg::DetectedObjects msg; + + // CAR with area 4.0, which is out of the range for remapping + autoware_perception_msgs::msg::DetectedObject obj1; + autoware_perception_msgs::msg::ObjectClassification obj1_classification; + obj1.shape.dimensions.x = 2.0; + obj1.shape.dimensions.y = 2.0; + obj1_classification.label = 0; + obj1_classification.probability = 1.0; + obj1.classification = {obj1_classification}; + msg.objects.push_back(obj1); + + // TRUCK with area 16.0, which is in the range for remapping to TRAILER + autoware_perception_msgs::msg::DetectedObject obj2; + autoware_perception_msgs::msg::ObjectClassification obj2_classification; + obj2.shape.dimensions.x = 8.0; + obj2.shape.dimensions.y = 2.0; + obj2_classification.label = 1; + obj2_classification.probability = 1.0; + obj2.classification = {obj2_classification}; + msg.objects.push_back(obj2); + + // TRAILER with area 9.0, which is in the range for remapping to TRUCK + autoware_perception_msgs::msg::DetectedObject obj3; + autoware_perception_msgs::msg::ObjectClassification obj3_classification; + obj3.shape.dimensions.x = 3.0; + obj3.shape.dimensions.y = 3.0; + obj3_classification.label = 2; + obj3_classification.probability = 1.0; + obj3.classification = {obj3_classification}; + msg.objects.push_back(obj3); + + // TRAILER with area 12.0, which is out of the range for remapping + autoware_perception_msgs::msg::DetectedObject obj4; + autoware_perception_msgs::msg::ObjectClassification obj4_classification; + obj4.shape.dimensions.x = 4.0; + obj4.shape.dimensions.y = 3.0; + obj4_classification.label = 2; + obj4_classification.probability = 1.0; + obj4.classification = {obj4_classification}; + msg.objects.push_back(obj4); + + // Call the mapClasses function + remapper.mapClasses(msg); + + // Check the remapped labels + EXPECT_EQ(msg.objects[0].classification[0].label, 0); + EXPECT_EQ(msg.objects[1].classification[0].label, 2); + EXPECT_EQ(msg.objects[2].classification[0].label, 1); + EXPECT_EQ(msg.objects[3].classification[0].label, 2); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_transfusion/test/test_nms.cpp b/perception/lidar_transfusion/test/test_nms.cpp new file mode 100644 index 0000000000000..b6f0ec8c31684 --- /dev/null +++ b/perception/lidar_transfusion/test/test_nms.cpp @@ -0,0 +1,121 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "lidar_transfusion/postprocess/non_maximum_suppression.hpp" + +#include + +TEST(NonMaximumSuppressionTest, Apply) +{ + lidar_transfusion::NonMaximumSuppression nms; + lidar_transfusion::NMSParams params; + params.search_distance_2d_ = 1.0; + params.iou_threshold_ = 0.2; + params.nms_type_ = lidar_transfusion::NMS_TYPE::IoU_BEV; + params.target_class_names_ = {"CAR"}; + nms.setParameters(params); + + std::vector input_objects(4); + + // Object 1 + autoware_perception_msgs::msg::ObjectClassification obj1_classification; + obj1_classification.label = 0; // Assuming "car" has label 0 + obj1_classification.probability = 1.0; + input_objects[0].classification = {obj1_classification}; // Assuming "car" has label 0 + input_objects[0].kinematics.pose_with_covariance.pose.position.x = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.position.y = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[0].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[0].shape.dimensions.x = 4.0; + input_objects[0].shape.dimensions.y = 2.0; + + // Object 2 (overlaps with Object 1) + autoware_perception_msgs::msg::ObjectClassification obj2_classification; + obj2_classification.label = 0; // Assuming "car" has label 0 + obj2_classification.probability = 1.0; + input_objects[1].classification = {obj2_classification}; // Assuming "car" has label 0 + input_objects[1].kinematics.pose_with_covariance.pose.position.x = 0.5; + input_objects[1].kinematics.pose_with_covariance.pose.position.y = 0.5; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[1].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[1].shape.dimensions.x = 4.0; + input_objects[1].shape.dimensions.y = 2.0; + + // Object 3 + autoware_perception_msgs::msg::ObjectClassification obj3_classification; + obj3_classification.label = 0; // Assuming "car" has label 0 + obj3_classification.probability = 1.0; + input_objects[2].classification = {obj3_classification}; // Assuming "car" has label 0 + input_objects[2].kinematics.pose_with_covariance.pose.position.x = 5.0; + input_objects[2].kinematics.pose_with_covariance.pose.position.y = 5.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[2].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[2].shape.dimensions.x = 4.0; + input_objects[2].shape.dimensions.y = 2.0; + + // Object 4 (different class) + autoware_perception_msgs::msg::ObjectClassification obj4_classification; + obj4_classification.label = 1; // Assuming "pedestrian" has label 1 + obj4_classification.probability = 1.0; + input_objects[3].classification = {obj4_classification}; // Assuming "pedestrian" has label 1 + input_objects[3].kinematics.pose_with_covariance.pose.position.x = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.position.y = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[3].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[3].shape.dimensions.x = 0.5; + input_objects[3].shape.dimensions.y = 0.5; + + std::vector output_objects = nms.apply(input_objects); + + // Assert the expected number of output objects + EXPECT_EQ(output_objects.size(), 3); + + // Assert that input_objects[2] is included in the output_objects + bool is_input_object_2_included = false; + for (const auto & output_object : output_objects) { + if (output_object == input_objects[2]) { + is_input_object_2_included = true; + break; + } + } + EXPECT_TRUE(is_input_object_2_included); + + // Assert that input_objects[3] is included in the output_objects + bool is_input_object_3_included = false; + for (const auto & output_object : output_objects) { + if (output_object == input_objects[3]) { + is_input_object_3_included = true; + break; + } + } + EXPECT_TRUE(is_input_object_3_included); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_transfusion/test/test_postprocess_kernel.cpp b/perception/lidar_transfusion/test/test_postprocess_kernel.cpp new file mode 100644 index 0000000000000..1e01db5a8b3d7 --- /dev/null +++ b/perception/lidar_transfusion/test/test_postprocess_kernel.cpp @@ -0,0 +1,299 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "test_postprocess_kernel.hpp" + +#include + +#include +#include + +namespace lidar_transfusion +{ + +void PostprocessKernelTest::SetUp() +{ + cudaStreamCreate(&stream_); + + auto voxels_num = std::vector{1, 3, 5}; + auto point_cloud_range = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; + auto voxel_size = std::vector{0.3, 0.3, 8.0}; + auto score_threshold = 0.2f; + auto circle_nms_dist_threshold = 0.5f; + auto yaw_norm_thresholds = std::vector{0.5, 0.5, 0.5}; + config_ptr_ = std::make_unique( + voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, + score_threshold); + post_ptr_ = std::make_unique(*config_ptr_, stream_); + + cls_size_ = config_ptr_->num_proposals_ * config_ptr_->num_classes_; + box_size_ = config_ptr_->num_proposals_ * config_ptr_->num_box_values_; + dir_cls_size_ = config_ptr_->num_proposals_ * 2; // x, y + + cls_output_d_ = cuda::make_unique(cls_size_); + box_output_d_ = cuda::make_unique(box_size_); + dir_cls_output_d_ = cuda::make_unique(dir_cls_size_); + + cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); + cuda::clear_async(box_output_d_.get(), box_size_, stream_); + cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); +} + +void PostprocessKernelTest::TearDown() +{ +} + +TEST_F(PostprocessKernelTest, EmptyTensorTest) +{ + std::vector det_boxes3d; + + CHECK_CUDA_ERROR(post_ptr_->generateDetectedBoxes3D_launch( + cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_)); + + EXPECT_EQ(0, det_boxes3d.size()); +} + +TEST_F(PostprocessKernelTest, SingleDetectionTest) +{ + cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); + cuda::clear_async(box_output_d_.get(), box_size_, stream_); + cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + std::vector det_boxes3d; + unsigned int det_idx = 42; + unsigned int cls_idx = 2; + + constexpr float detection_score = 1.f; + constexpr float detection_x = 50.f; + constexpr float detection_y = -38.4f; + constexpr float detection_z = 1.0; + const float detection_raw_x = (detection_x - config_ptr_->min_x_range_) / + (config_ptr_->num_point_values_ * config_ptr_->voxel_x_size_); + const float detection_raw_y = (detection_y - config_ptr_->min_y_range_) / + (config_ptr_->num_point_values_ * config_ptr_->voxel_y_size_); + const float detection_raw_z = detection_z; + + constexpr float detection_w = 3.2f; + constexpr float detection_l = 9.3f; + constexpr float detection_h = 1.7f; + constexpr float detection_log_w = std::log(detection_w); + constexpr float detection_log_l = std::log(detection_l); + constexpr float detection_log_h = std::log(detection_h); + + constexpr float detection_yaw = M_PI_4; + constexpr float detection_yaw_sin = std::sin(detection_yaw); + constexpr float detection_yaw_cos = std::cos(detection_yaw); + + // Set the values in the cuda tensor + cudaMemcpy( + &cls_output_d_[cls_idx * config_ptr_->num_proposals_ + det_idx], &detection_score, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &dir_cls_output_d_[det_idx], &detection_yaw_sin, 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &dir_cls_output_d_[det_idx + config_ptr_->num_proposals_], &detection_yaw_cos, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy(&box_output_d_[det_idx], &detection_raw_x, 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + config_ptr_->num_proposals_], &detection_raw_y, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 2 * config_ptr_->num_proposals_], &detection_raw_z, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 3 * config_ptr_->num_proposals_], &detection_log_w, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 4 * config_ptr_->num_proposals_], &detection_log_l, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 5 * config_ptr_->num_proposals_], &detection_log_h, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + auto code1 = cudaGetLastError(); + ASSERT_EQ(cudaSuccess, code1); + + // Extract the boxes + auto code2 = post_ptr_->generateDetectedBoxes3D_launch( + cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + ASSERT_EQ(cudaSuccess, code2); + ASSERT_EQ(1, det_boxes3d.size()); + + const auto det_box3d = det_boxes3d[0]; + EXPECT_EQ(cls_idx, det_box3d.label); + EXPECT_EQ(detection_score, det_box3d.score); + EXPECT_EQ(detection_x, det_box3d.x); + EXPECT_EQ(detection_y, det_box3d.y); + EXPECT_EQ(detection_z, det_box3d.z); + EXPECT_NEAR(detection_w, det_box3d.width, 1e-6); + EXPECT_NEAR(detection_l, det_box3d.length, 1e-6); + EXPECT_NEAR(detection_h, det_box3d.height, 1e-6); + EXPECT_EQ(detection_yaw, det_box3d.yaw); +} + +TEST_F(PostprocessKernelTest, InvalidYawTest) +{ + cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); + cuda::clear_async(box_output_d_.get(), box_size_, stream_); + cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + std::vector det_boxes3d; + unsigned int det_idx = 42; + unsigned int cls_idx = 2; + + constexpr float detection_score = 1.f; + constexpr float detection_x = 50.f; + constexpr float detection_y = -38.4f; + constexpr float detection_z = 1.0; + const float detection_raw_x = (detection_x - config_ptr_->min_x_range_) / + (config_ptr_->num_point_values_ * config_ptr_->voxel_x_size_); + const float detection_raw_y = (detection_y - config_ptr_->min_y_range_) / + (config_ptr_->num_point_values_ * config_ptr_->voxel_y_size_); + const float detection_raw_z = detection_z; + + constexpr float detection_w = 3.2f; + constexpr float detection_l = 9.3f; + constexpr float detection_h = 1.7f; + constexpr float detection_log_w = std::log(detection_w); + constexpr float detection_log_l = std::log(detection_l); + constexpr float detection_log_h = std::log(detection_h); + + constexpr float detection_yaw_sin = 0.f; + constexpr float detection_yaw_cos = 0.2f; + + // Set the values in the cuda tensor + cudaMemcpy( + &cls_output_d_[cls_idx * config_ptr_->num_proposals_ + det_idx], &detection_score, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &dir_cls_output_d_[det_idx], &detection_yaw_sin, 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &dir_cls_output_d_[det_idx + config_ptr_->num_proposals_], &detection_yaw_cos, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy(&box_output_d_[det_idx], &detection_raw_x, 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + config_ptr_->num_proposals_], &detection_raw_y, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 2 * config_ptr_->num_proposals_], &detection_raw_z, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 3 * config_ptr_->num_proposals_], &detection_log_w, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 4 * config_ptr_->num_proposals_], &detection_log_l, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + 5 * config_ptr_->num_proposals_], &detection_log_h, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + auto code1 = cudaGetLastError(); + ASSERT_EQ(cudaSuccess, code1); + + // Extract the boxes + auto code2 = post_ptr_->generateDetectedBoxes3D_launch( + cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + ASSERT_EQ(cudaSuccess, code2); + EXPECT_EQ(0, det_boxes3d.size()); +} + +TEST_F(PostprocessKernelTest, CircleNMSTest) +{ + cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); + cuda::clear_async(box_output_d_.get(), box_size_, stream_); + cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + std::vector det_boxes3d; + unsigned int det_idx = 42; + unsigned int det_num = 2; + unsigned int cls_idx = 2; + + constexpr float detection_score = 1.f; + constexpr float detection_x = 50.f; + constexpr float detection_y = -38.4f; + constexpr float detection_z = 1.0; + const float detection_raw_x = (detection_x - config_ptr_->min_x_range_) / + (config_ptr_->num_point_values_ * config_ptr_->voxel_x_size_); + const float detection_raw_y = (detection_y - config_ptr_->min_y_range_) / + (config_ptr_->num_point_values_ * config_ptr_->voxel_y_size_); + const float detection_raw_z = detection_z; + + constexpr float detection_w = 3.2f; + constexpr float detection_l = 9.3f; + constexpr float detection_h = 1.7f; + constexpr float detection_log_w = std::log(detection_w); + constexpr float detection_log_l = std::log(detection_l); + constexpr float detection_log_h = std::log(detection_h); + + constexpr float detection_yaw = M_PI_4; + constexpr float detection_yaw_sin = std::sin(detection_yaw); + constexpr float detection_yaw_cos = std::cos(detection_yaw); + + // Set the values in the cuda tensor for 2 detections + for (std::size_t i = 0; i < det_num; ++i) { + cudaMemcpy( + &cls_output_d_[cls_idx * config_ptr_->num_proposals_ + det_idx + i], &detection_score, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &dir_cls_output_d_[det_idx + i], &detection_yaw_sin, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &dir_cls_output_d_[det_idx + i + config_ptr_->num_proposals_], &detection_yaw_cos, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + i], &detection_raw_x, 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + i + config_ptr_->num_proposals_], &detection_raw_y, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + i + 2 * config_ptr_->num_proposals_], &detection_raw_z, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + i + 3 * config_ptr_->num_proposals_], &detection_log_w, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + i + 4 * config_ptr_->num_proposals_], &detection_log_l, + 1 * sizeof(float), cudaMemcpyHostToDevice); + cudaMemcpy( + &box_output_d_[det_idx + i + 5 * config_ptr_->num_proposals_], &detection_log_h, + 1 * sizeof(float), cudaMemcpyHostToDevice); + } + + auto code1 = cudaGetLastError(); + ASSERT_EQ(cudaSuccess, code1); + + // Extract the boxes + auto code2 = post_ptr_->generateDetectedBoxes3D_launch( + cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + ASSERT_EQ(cudaSuccess, code2); + EXPECT_EQ(1, det_boxes3d.size()); +} + +} // namespace lidar_transfusion + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_transfusion/test/test_postprocess_kernel.hpp b/perception/lidar_transfusion/test/test_postprocess_kernel.hpp new file mode 100644 index 0000000000000..60fa7882ecc11 --- /dev/null +++ b/perception/lidar_transfusion/test/test_postprocess_kernel.hpp @@ -0,0 +1,48 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_POSTPROCESS_KERNEL_HPP_ +#define TEST_POSTPROCESS_KERNEL_HPP_ + +#include +#include + +#include + +#include + +namespace lidar_transfusion +{ + +class PostprocessKernelTest : public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; + + std::unique_ptr post_ptr_{nullptr}; + std::unique_ptr config_ptr_{}; + cudaStream_t stream_{}; + + unsigned int cls_size_{0}; + unsigned int box_size_{0}; + unsigned int dir_cls_size_{0}; + cuda::unique_ptr cls_output_d_{nullptr}; + cuda::unique_ptr box_output_d_{nullptr}; + cuda::unique_ptr dir_cls_output_d_{nullptr}; +}; + +} // namespace lidar_transfusion + +#endif // TEST_POSTPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/test/test_preprocess_kernel.cpp b/perception/lidar_transfusion/test/test_preprocess_kernel.cpp new file mode 100644 index 0000000000000..c1c2a824f0f53 --- /dev/null +++ b/perception/lidar_transfusion/test/test_preprocess_kernel.cpp @@ -0,0 +1,265 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "test_preprocess_kernel.hpp" + +#include "lidar_transfusion/cuda_utils.hpp" + +#include + +#include +#include +#include + +#include +#include + +namespace lidar_transfusion +{ + +void PreprocessKernelTest::SetUp() +{ + cudaStreamCreate(&stream_); + + auto voxels_num = std::vector{1, 3, 5}; + auto point_cloud_range = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; + auto voxel_size = std::vector{0.3, 0.3, 8.0}; + auto score_threshold = 0.2f; + auto circle_nms_dist_threshold = 0.5f; + auto yaw_norm_thresholds = std::vector{0.5, 0.5, 0.5}; + config_ptr_ = std::make_unique( + voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, + score_threshold); + pre_ptr_ = std::make_unique(*config_ptr_, stream_); + + voxel_features_size_ = config_ptr_->max_voxels_ * config_ptr_->max_num_points_per_pillar_ * + config_ptr_->num_point_feature_size_; + voxel_num_size_ = config_ptr_->max_voxels_; + voxel_idxs_size_ = config_ptr_->max_voxels_ * config_ptr_->num_point_values_; + + params_input_d_ = cuda::make_unique(); + voxel_features_d_ = cuda::make_unique(voxel_features_size_); + voxel_num_d_ = cuda::make_unique(voxel_num_size_); + voxel_idxs_d_ = cuda::make_unique(voxel_idxs_size_); + points_d_ = + cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + + cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); + cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); + cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); + cuda::clear_async(params_input_d_.get(), 1, stream_); + cuda::clear_async( + points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); +} + +void PreprocessKernelTest::TearDown() +{ +} + +TEST_F(PreprocessKernelTest, EmptyVoxelTest) +{ + std::vector points{}; + std::size_t count = 0; + + pre_ptr_->generateVoxels( + points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), + voxel_idxs_d_.get()); + unsigned int params_input; + auto code1 = cudaStreamSynchronize(stream_); + + auto code2 = cudaMemcpyAsync( + ¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + auto code3 = cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + + ASSERT_EQ(cudaSuccess, code1); + ASSERT_EQ(cudaSuccess, code2); + ASSERT_EQ(cudaSuccess, code3); + + EXPECT_EQ(0, params_input); +} + +TEST_F(PreprocessKernelTest, BasicTest) +{ + cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); + cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); + cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); + cuda::clear_async(params_input_d_.get(), 1, stream_); + cuda::clear_async( + points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); + cudaStreamSynchronize(stream_); + + std::vector point1{25.f, -61.1f, 1.8f, 42.0, 0.1f}; + std::vector point2{-31.6f, 1.1f, 2.8f, 77.0, 0.1f}; + std::vector point3{42.6f, 15.1f, -0.1f, 3.0, 0.1f}; + + std::vector points; + points.reserve(point1.size() + point2.size() + point3.size()); + points.insert(points.end(), point1.begin(), point1.end()); + points.insert(points.end(), point2.begin(), point2.end()); + points.insert(points.end(), point3.begin(), point3.end()); + std::size_t count = 3; + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + // Compute the total amount of voxels filled + pre_ptr_->generateVoxels( + points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), + voxel_idxs_d_.get()); + + unsigned int params_input; + CHECK_CUDA_ERROR( + cudaMemcpy(¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + ASSERT_EQ(count, params_input); + + // Check if voxels were filled + unsigned int voxel_num; + + for (std::size_t i = 0; i < count; ++i) { + CHECK_CUDA_ERROR( + cudaMemcpy(&voxel_num, voxel_num_d_.get() + i, sizeof(unsigned int), cudaMemcpyDeviceToHost)); + EXPECT_EQ(1, voxel_num); + } + + // Check grid indices + thrust::host_vector voxel_idxs(config_ptr_->num_point_values_ * count, 0); + unsigned int voxel_idx_gt; + unsigned int voxel_idy_gt; + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_idxs.data(), voxel_idxs_d_.get(), + config_ptr_->num_point_values_ * count * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + for (std::size_t i = 0; i < count; ++i) { + voxel_idx_gt = std::floor( + (points[config_ptr_->num_point_feature_size_ * i + 0] - config_ptr_->min_x_range_) / + config_ptr_->voxel_x_size_); + voxel_idy_gt = std::floor( + (points[config_ptr_->num_point_feature_size_ * i + 1] - config_ptr_->min_y_range_) / + config_ptr_->voxel_y_size_); + + EXPECT_EQ( + voxel_idx_gt, + voxel_idxs[config_ptr_->num_point_values_ * i + 3]); // {0, 0, voxel_idy, VOXEL_IDX} + EXPECT_EQ( + voxel_idy_gt, + voxel_idxs[config_ptr_->num_point_values_ * i + 2]); // {0, 0, VOXEL_IDY, voxel_idx} + } + + // Check voxel features + thrust::host_vector voxel_features( + count * config_ptr_->max_num_points_per_pillar_ * config_ptr_->num_point_feature_size_, 0.f); + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_features.data(), voxel_features_d_.get(), + count * config_ptr_->max_num_points_per_pillar_ * config_ptr_->num_point_feature_size_ * + sizeof(float), + cudaMemcpyDeviceToHost)); + + for (std::size_t i = 0; i < count; ++i) { + for (std::size_t j = 0; j < config_ptr_->num_point_feature_size_; ++j) { + EXPECT_EQ( + points[config_ptr_->num_point_feature_size_ * i + j], + voxel_features + [i * config_ptr_->max_num_points_per_pillar_ * config_ptr_->num_point_feature_size_ + j]); + } + } +} + +TEST_F(PreprocessKernelTest, OutOfRangeTest) +{ + cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); + cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); + cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); + cuda::clear_async(params_input_d_.get(), 1, stream_); + cuda::clear_async( + points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); + cudaStreamSynchronize(stream_); + + std::vector points{25.f, config_ptr_->max_y_range_ + 0.1f, 2.1f, 55.f, 0.1f}; + std::size_t count = 0; + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + pre_ptr_->generateVoxels( + points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), + voxel_idxs_d_.get()); + + unsigned int params_input; + CHECK_CUDA_ERROR( + cudaMemcpy(¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + EXPECT_EQ(count, params_input); +} + +TEST_F(PreprocessKernelTest, VoxelOverflowTest) +{ + cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); + cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); + cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); + cuda::clear_async(params_input_d_.get(), 1, stream_); + cuda::clear_async( + points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); + cudaStreamSynchronize(stream_); + + std::vector point{config_ptr_->min_x_range_, -61.1f, 1.8f, 42.f, 0.1f}; + std::size_t count = config_ptr_->max_voxels_ + 1; + std::vector points{}; + points.reserve(count * config_ptr_->num_point_feature_size_); + + for (std::size_t i = 0; i < count; ++i) { + points.insert(points.end(), point.begin(), point.end()); + point[0] += config_ptr_->voxel_x_size_; + } + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + pre_ptr_->generateVoxels( + points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), + voxel_idxs_d_.get()); + + ASSERT_EQ(cudaSuccess, cudaGetLastError()); + + unsigned int params_input; + CHECK_CUDA_ERROR( + cudaMemcpy(¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + EXPECT_EQ(config_ptr_->max_voxels_, params_input); +} + +} // namespace lidar_transfusion + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_transfusion/test/test_preprocess_kernel.hpp b/perception/lidar_transfusion/test/test_preprocess_kernel.hpp new file mode 100644 index 0000000000000..024fae5eae4b1 --- /dev/null +++ b/perception/lidar_transfusion/test/test_preprocess_kernel.hpp @@ -0,0 +1,50 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_PREPROCESS_KERNEL_HPP_ +#define TEST_PREPROCESS_KERNEL_HPP_ + +#include +#include + +#include + +#include + +namespace lidar_transfusion +{ + +class PreprocessKernelTest : public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; + + std::unique_ptr pre_ptr_{nullptr}; + std::unique_ptr config_ptr_{}; + cudaStream_t stream_{}; + + unsigned int voxel_features_size_{0}; + unsigned int voxel_num_size_{0}; + unsigned int voxel_idxs_size_{0}; + cuda::unique_ptr points_d_{nullptr}; + cuda::unique_ptr params_input_d_{nullptr}; + cuda::unique_ptr voxel_features_d_{nullptr}; + cuda::unique_ptr voxel_num_d_{nullptr}; + cuda::unique_ptr voxel_idxs_d_{nullptr}; +}; + +} // namespace lidar_transfusion + +#endif // TEST_PREPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/test/test_ros_utils.cpp b/perception/lidar_transfusion/test/test_ros_utils.cpp new file mode 100644 index 0000000000000..15541e6353b42 --- /dev/null +++ b/perception/lidar_transfusion/test/test_ros_utils.cpp @@ -0,0 +1,104 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "lidar_transfusion/ros_utils.hpp" + +#include + +TEST(TestSuite, box3DToDetectedObject) +{ + std::vector class_names = {"CAR", "TRUCK", "BUS", "TRAILER", + "BICYCLE", "MOTORCYCLE", "PEDESTRIAN"}; + + // Test case 1: Test with valid label + { + lidar_transfusion::Box3D box3d; + box3d.label = 0; // CAR + box3d.score = 0.8f; + box3d.x = 1.0; + box3d.y = 2.0; + box3d.z = 3.0; + box3d.width = 2.0; + box3d.height = 1.5; + box3d.length = 4.0; + box3d.yaw = 0.5; + + autoware_perception_msgs::msg::DetectedObject obj; + lidar_transfusion::box3DToDetectedObject(box3d, class_names, obj); + + EXPECT_FLOAT_EQ(obj.existence_probability, 0.8f); + EXPECT_EQ( + obj.classification[0].label, autoware_perception_msgs::msg::ObjectClassification::CAR); + EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.x, 1.0); + EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.y, 2.0); + EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.z, 3.0); + EXPECT_FLOAT_EQ(obj.shape.dimensions.x, 4.0); + EXPECT_FLOAT_EQ(obj.shape.dimensions.y, 2.0); + EXPECT_FLOAT_EQ(obj.shape.dimensions.z, 1.5); + EXPECT_FALSE(obj.kinematics.has_position_covariance); + EXPECT_FALSE(obj.kinematics.has_twist); + EXPECT_FALSE(obj.kinematics.has_twist_covariance); + } + + // Test case 2: Test with invalid label + { + lidar_transfusion::Box3D box3d; + box3d.score = 0.5f; + box3d.label = 10; // Invalid + + autoware_perception_msgs::msg::DetectedObject obj; + lidar_transfusion::box3DToDetectedObject(box3d, class_names, obj); + + EXPECT_FLOAT_EQ(obj.existence_probability, 0.5f); + EXPECT_EQ( + obj.classification[0].label, autoware_perception_msgs::msg::ObjectClassification::UNKNOWN); + EXPECT_FALSE(obj.kinematics.has_position_covariance); + EXPECT_FALSE(obj.kinematics.has_twist); + EXPECT_FALSE(obj.kinematics.has_twist_covariance); + } +} + +TEST(TestSuite, getSemanticType) +{ + EXPECT_EQ( + lidar_transfusion::getSemanticType("CAR"), + autoware_perception_msgs::msg::ObjectClassification::CAR); + EXPECT_EQ( + lidar_transfusion::getSemanticType("TRUCK"), + autoware_perception_msgs::msg::ObjectClassification::TRUCK); + EXPECT_EQ( + lidar_transfusion::getSemanticType("BUS"), + autoware_perception_msgs::msg::ObjectClassification::BUS); + EXPECT_EQ( + lidar_transfusion::getSemanticType("TRAILER"), + autoware_perception_msgs::msg::ObjectClassification::TRAILER); + EXPECT_EQ( + lidar_transfusion::getSemanticType("MOTORCYCLE"), + autoware_perception_msgs::msg::ObjectClassification::MOTORCYCLE); + EXPECT_EQ( + lidar_transfusion::getSemanticType("BICYCLE"), + autoware_perception_msgs::msg::ObjectClassification::BICYCLE); + EXPECT_EQ( + lidar_transfusion::getSemanticType("PEDESTRIAN"), + autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN); + EXPECT_EQ( + lidar_transfusion::getSemanticType("UNKNOWN"), + autoware_perception_msgs::msg::ObjectClassification::UNKNOWN); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_transfusion/test/test_voxel_generator.cpp b/perception/lidar_transfusion/test/test_voxel_generator.cpp new file mode 100644 index 0000000000000..2673a341b3721 --- /dev/null +++ b/perception/lidar_transfusion/test/test_voxel_generator.cpp @@ -0,0 +1,284 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "test_voxel_generator.hpp" + +#include "gtest/gtest.h" +#include "lidar_transfusion/transfusion_config.hpp" +#include "lidar_transfusion/utils.hpp" + +#include + +#include "sensor_msgs/point_cloud2_iterator.hpp" + +namespace lidar_transfusion +{ + +void VoxelGeneratorTest::SetUp() +{ + // Setup things that should occur before every test instance should go here + node_ = std::make_shared("voxel_generator_test_node"); + + world_frame_ = "map"; + lidar_frame_ = "lidar"; + delta_pointcloud_x_ = 1.0; + points_per_pointcloud_ = 300; + + voxels_num_ = std::vector{5000, 30000, 60000}; + point_cloud_range_ = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; + voxel_size_ = std::vector{0.3, 0.3, 8.0}; + score_threshold_ = 0.2f; + circle_nms_dist_threshold_ = 0.5f; + yaw_norm_thresholds_ = std::vector{0.5, 0.5, 0.5}; + config_ptr_ = std::make_unique( + voxels_num_, point_cloud_range_, voxel_size_, circle_nms_dist_threshold_, yaw_norm_thresholds_, + score_threshold_); + + cloud1_ = std::make_unique(); + cloud2_ = std::make_unique(); + + // Set up the fields + point_cloud_msg_wrapper::PointCloud2Modifier< + autoware_point_types::PointXYZIRCAEDT, autoware_point_types::PointXYZIRCAEDTGenerator> + modifier{*cloud1_, lidar_frame_}; + + // Resize the cloud to hold points_per_pointcloud_ points + modifier.resize(points_per_pointcloud_); + + // Create an iterator for desired fields + sensor_msgs::PointCloud2Iterator iter_x(*cloud1_, "x"); + sensor_msgs::PointCloud2Iterator iter_y(*cloud1_, "y"); + sensor_msgs::PointCloud2Iterator iter_z(*cloud1_, "z"); + sensor_msgs::PointCloud2Iterator iter_i(*cloud1_, "intensity"); + + // Populate the point cloud + for (size_t i = 0; i < modifier.size(); ++i, ++iter_x, ++iter_y, ++iter_z) { + *iter_x = static_cast(i); + *iter_y = static_cast(i); + *iter_z = static_cast(i); + } + for (size_t i = 0; i < modifier.size(); ++i, ++iter_i) { + *iter_i = static_cast(i % 256); + } + + *cloud2_ = *cloud1_; + + // Set the stamps for the point clouds. They usually come every 100ms + cloud1_->header.stamp.sec = 1; + cloud1_->header.stamp.nanosec = 100'000'000; + cloud2_->header.stamp.sec = 1; + cloud2_->header.stamp.nanosec = 200'000'000; + + tf2_buffer_ = std::make_unique(node_->get_clock()); + tf2_buffer_->setUsingDedicatedThread(true); + + // The vehicle moves 1m/s in the x direction + const double world_origin_x = 6'371'000.0; + const double world_origin_y = 1'371'000.0; + + transform1_.header.stamp = cloud1_->header.stamp; + transform1_.header.frame_id = world_frame_; + transform1_.child_frame_id = lidar_frame_; + transform1_.transform.translation.x = world_origin_x; + transform1_.transform.translation.y = world_origin_y; + transform1_.transform.translation.z = 1.8; + transform1_.transform.rotation.x = 0.0; + transform1_.transform.rotation.y = 0.0; + transform1_.transform.rotation.z = 0.0; + transform1_.transform.rotation.w = 1.0; + + transform2_ = transform1_; + transform2_.header.stamp = cloud2_->header.stamp; + transform2_.transform.translation.x = world_origin_x + delta_pointcloud_x_; + + cudaStreamCreate(&stream_); +} + +void VoxelGeneratorTest::TearDown() +{ +} + +TEST_F(VoxelGeneratorTest, CloudInfo) +{ + CloudInfo cloud_info{}; + EXPECT_EQ(cloud1_->is_bigendian, cloud_info.is_bigendian); + EXPECT_EQ(cloud1_->fields[0].name, "x"); + EXPECT_EQ(cloud1_->fields[0].datatype, cloud_info.x_datatype); + EXPECT_EQ(cloud1_->fields[0].count, cloud_info.x_count); + EXPECT_EQ(cloud1_->fields[0].offset, cloud_info.x_offset); + EXPECT_EQ(cloud1_->fields[1].name, "y"); + EXPECT_EQ(cloud1_->fields[1].datatype, cloud_info.y_datatype); + EXPECT_EQ(cloud1_->fields[1].count, cloud_info.y_count); + EXPECT_EQ(cloud1_->fields[1].offset, cloud_info.y_offset); + EXPECT_EQ(cloud1_->fields[2].name, "z"); + EXPECT_EQ(cloud1_->fields[2].datatype, cloud_info.z_datatype); + EXPECT_EQ(cloud1_->fields[2].count, cloud_info.z_count); + EXPECT_EQ(cloud1_->fields[2].offset, cloud_info.z_offset); + EXPECT_EQ(cloud1_->fields[3].name, "intensity"); + EXPECT_EQ(cloud1_->fields[3].datatype, cloud_info.intensity_datatype); + EXPECT_EQ(cloud1_->fields[3].count, cloud_info.intensity_count); + EXPECT_EQ(cloud1_->fields[3].offset, cloud_info.intensity_offset); + EXPECT_EQ(cloud1_->width, points_per_pointcloud_); + EXPECT_EQ(cloud1_->height, 1); +} + +TEST_F(VoxelGeneratorTest, SingleFrame) +{ + const unsigned int num_past_frames = 0; // only current frame + DensificationParam param(world_frame_, num_past_frames); + VoxelGenerator voxel_generator(param, *config_ptr_, stream_); + std::vector points; + points.resize(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + std::fill(points.begin(), points.end(), std::nan("")); + + auto points_d = + cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + cudaMemcpy( + points_d.get(), points.data(), + points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(*cloud1_, points_d); + + cudaMemcpy( + points.data(), points_d.get(), + points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost); + + EXPECT_TRUE(status1); + EXPECT_EQ(generated_points_num, points_per_pointcloud_); + + // Check valid points + for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { + // There are no tf conversions + EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 0]); + EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 1]); + EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 2]); + EXPECT_EQ(static_cast(i % 256), points[i * config_ptr_->num_point_feature_size_ + 3]); + EXPECT_EQ(static_cast(0), points[i * config_ptr_->num_point_feature_size_ + 4]); + } + + // Check invalid points + for (std::size_t i = points_per_pointcloud_ * config_ptr_->num_point_feature_size_; + i < points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * 2; ++i) { + EXPECT_TRUE(std::isnan(points[i])); + } +} + +TEST_F(VoxelGeneratorTest, TwoFramesNoTf) +{ + const unsigned int num_past_frames = 1; + DensificationParam param(world_frame_, num_past_frames); + VoxelGenerator voxel_generator(param, *config_ptr_, stream_); + std::vector points; + points.resize(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + std::fill(points.begin(), points.end(), std::nan("")); + + auto points_d = + cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + cudaMemcpy( + points_d.get(), points.data(), + points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); + bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(*cloud1_, points_d); + + cudaMemcpy( + points.data(), points_d.get(), + points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost); + + EXPECT_FALSE(status1); + EXPECT_FALSE(status2); + EXPECT_EQ(0, generated_points_num); +} + +TEST_F(VoxelGeneratorTest, TwoFrames) +{ + const unsigned int num_past_frames = 1; + DensificationParam param(world_frame_, num_past_frames); + VoxelGenerator voxel_generator(param, *config_ptr_, stream_); + std::vector points; + points.resize(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + std::fill(points.begin(), points.end(), std::nan("")); + + auto points_d = + cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); + cudaMemcpy( + points_d.get(), points.data(), + 2 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + + tf2_buffer_->setTransform(transform1_, "authority1"); + tf2_buffer_->setTransform(transform2_, "authority1"); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); + bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(*cloud1_, points_d); + + cudaMemcpy( + points.data(), points_d.get(), + 2 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost); + + EXPECT_TRUE(status1); + EXPECT_TRUE(status2); + EXPECT_EQ(2 * points_per_pointcloud_, generated_points_num); + + // Check valid points for the latest pointcloud + for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { + // There are no tf conversions + EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 0]); + EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 1]); + EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 2]); + EXPECT_EQ(static_cast(i % 256), points[i * config_ptr_->num_point_feature_size_ + 3]); + EXPECT_EQ(static_cast(0), points[i * config_ptr_->num_point_feature_size_ + 4]); + } + + // Check valid points for the oldest pointcloud + for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { + // There are tf conversions, so results are not numerically the same + EXPECT_NEAR( + static_cast(i) - delta_pointcloud_x_, + points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 0], 1e-6); + EXPECT_NEAR( + static_cast(i), + points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 1], 1e-6); + EXPECT_NEAR( + static_cast(i), + points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 2], 1e-6); + EXPECT_NEAR( + static_cast(i % 256), + points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 3], 1e-6); + EXPECT_NEAR( + 0.1, points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 4], 1e-6); + } + + // Check invalid points + for (std::size_t i = 2 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_; + i < 3 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_; ++i) { + EXPECT_TRUE(std::isnan(points[i])); + } +} +} // namespace lidar_transfusion + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_transfusion/test/test_voxel_generator.hpp b/perception/lidar_transfusion/test/test_voxel_generator.hpp new file mode 100644 index 0000000000000..eccbe6412d183 --- /dev/null +++ b/perception/lidar_transfusion/test/test_voxel_generator.hpp @@ -0,0 +1,65 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_VOXEL_GENERATOR_HPP_ +#define TEST_VOXEL_GENERATOR_HPP_ + +#include +#include + +#include + +#include + +#include +#include +#include + +namespace lidar_transfusion +{ + +class VoxelGeneratorTest : public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; + + // These need to be public so that they can be accessed in the test cases + rclcpp::Node::SharedPtr node_{}; + + std::unique_ptr cloud1_{}, cloud2_{}; + geometry_msgs::msg::TransformStamped transform1_{}, transform2_{}; + + std::unique_ptr densification_param_ptr_{}; + std::unique_ptr config_ptr_{}; + + std::unique_ptr tf2_buffer_{}; + + std::string world_frame_{}; + std::string lidar_frame_{}; + double delta_pointcloud_x_{}; + std::size_t points_per_pointcloud_{}; + + std::vector voxels_num_{}; + std::vector point_cloud_range_{}; + std::vector voxel_size_{}; + float circle_nms_dist_threshold_{}; + std::vector yaw_norm_thresholds_{}; + float score_threshold_{}; + + cudaStream_t stream_{}; +}; +} // namespace lidar_transfusion + +#endif // TEST_VOXEL_GENERATOR_HPP_ From 1f01a7c96140e67eab84b5c7fb9af01279a57ed0 Mon Sep 17 00:00:00 2001 From: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Date: Wed, 10 Jul 2024 15:41:17 +0900 Subject: [PATCH 103/151] feat(lidar_transfusion): update TransFusion-L model (#7890) * add num_proposals Signed-off-by: scepter914 * fix config Signed-off-by: scepter914 * update README Signed-off-by: scepter914 --------- Signed-off-by: scepter914 --- perception/lidar_transfusion/README.md | 4 ++-- .../lidar_transfusion/config/transfusion.param.yaml | 7 ++++--- .../lidar_transfusion/transfusion_config.hpp | 13 ++++++++++--- .../schema/transfusion.schema.json | 6 ++++++ .../src/lidar_transfusion_node.cpp | 5 +++-- 5 files changed, 25 insertions(+), 10 deletions(-) diff --git a/perception/lidar_transfusion/README.md b/perception/lidar_transfusion/README.md index e30403141e8ad..6745cc1f7d219 100644 --- a/perception/lidar_transfusion/README.md +++ b/perception/lidar_transfusion/README.md @@ -81,9 +81,9 @@ ros2 topic echo --field fields You can download the onnx format of trained models by clicking on the links below. -- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/v1/transfusion.onnx) +- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/t4xx1_90m/v2/transfusion.onnx) -The model was trained in TIER IV's internal database (~11k lidar frames) for 20 epochs. +The model was trained in TIER IV's internal database (~11k lidar frames) for 50 epochs. ### Changelog diff --git a/perception/lidar_transfusion/config/transfusion.param.yaml b/perception/lidar_transfusion/config/transfusion.param.yaml index feabe359caf1f..2c6680fe50af1 100644 --- a/perception/lidar_transfusion/config/transfusion.param.yaml +++ b/perception/lidar_transfusion/config/transfusion.param.yaml @@ -4,8 +4,9 @@ class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] trt_precision: fp16 voxels_num: [5000, 30000, 60000] # [min, opt, max] - point_cloud_range: [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0] # [x_min, y_min, z_min, x_max, y_max, z_max] - voxel_size: [0.3, 0.3, 8.0] # [x, y, z] + point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max] + voxel_size: [0.24, 0.24, 10.0] # [x, y, z] + num_proposals: 500 onnx_path: "$(var model_path)/transfusion.onnx" engine_path: "$(var model_path)/transfusion.engine" # pre-process params @@ -17,4 +18,4 @@ iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names - score_threshold: 0.2 + score_threshold: 0.1 diff --git a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp index 31976de56a9da..0ad3ab2231f50 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp @@ -26,8 +26,9 @@ class TransfusionConfig public: TransfusionConfig( const std::vector & voxels_num, const std::vector & point_cloud_range, - const std::vector & voxel_size, const float circle_nms_dist_threshold, - const std::vector & yaw_norm_thresholds, const float score_threshold) + const std::vector & voxel_size, const int num_proposals, + const float circle_nms_dist_threshold, const std::vector & yaw_norm_thresholds, + const float score_threshold) { if (voxels_num.size() == 3) { max_voxels_ = voxels_num[2]; @@ -61,6 +62,9 @@ class TransfusionConfig voxel_y_size_ = static_cast(voxel_size[1]); voxel_z_size_ = static_cast(voxel_size[2]); } + if (num_proposals > 0) { + num_proposals_ = num_proposals; + } if (score_threshold > 0.0) { score_threshold_ = score_threshold; } @@ -76,6 +80,9 @@ class TransfusionConfig grid_x_size_ = static_cast((max_x_range_ - min_x_range_) / voxel_x_size_); grid_y_size_ = static_cast((max_y_range_ - min_y_range_) / voxel_y_size_); grid_z_size_ = static_cast((max_z_range_ - min_z_range_) / voxel_z_size_); + + feature_x_size_ = grid_x_size_ / out_size_factor_; + feature_y_size_ = grid_y_size_ / out_size_factor_; } ///// INPUT PARAMETERS ///// @@ -107,7 +114,7 @@ class TransfusionConfig const std::size_t out_size_factor_{4}; const std::size_t max_num_points_per_pillar_{points_per_voxel_}; const std::size_t num_point_values_{4}; - const std::size_t num_proposals_{200}; + std::size_t num_proposals_{200}; // the number of feature maps for pillar scatter const std::size_t num_feature_scatter_{pillar_feature_size_}; // the score threshold for classification diff --git a/perception/lidar_transfusion/schema/transfusion.schema.json b/perception/lidar_transfusion/schema/transfusion.schema.json index 41d8d887236a8..7debc0edda6fb 100644 --- a/perception/lidar_transfusion/schema/transfusion.schema.json +++ b/perception/lidar_transfusion/schema/transfusion.schema.json @@ -61,6 +61,12 @@ "default": "$(var model_path)/transfusion.engine", "pattern": "\\.engine$" }, + "num_proposals": { + "type": "integer", + "description": "Number of proposals at TransHead.", + "default": 500, + "minimum": 1 + }, "down_sample_factor": { "type": "integer", "description": "A scale factor of downsampling points", diff --git a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp index e3ea6b3780de8..7f5833e60d6d0 100644 --- a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp @@ -31,6 +31,7 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) const auto point_cloud_range = this->declare_parameter>("point_cloud_range", descriptor); const auto voxel_size = this->declare_parameter>("voxel_size", descriptor); + const int num_proposals = (this->declare_parameter("num_proposals", descriptor)); const std::string onnx_path = this->declare_parameter("onnx_path", descriptor); const std::string engine_path = this->declare_parameter("engine_path", descriptor); @@ -73,8 +74,8 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); TransfusionConfig config( - voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, - score_threshold); + voxels_num, point_cloud_range, voxel_size, num_proposals, circle_nms_dist_threshold, + yaw_norm_thresholds, score_threshold); const auto allow_remapping_by_area_matrix = this->declare_parameter>("allow_remapping_by_area_matrix", descriptor); From e3f5099f8a6897a81772502627056a657700321e Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Tue, 20 Aug 2024 21:20:56 +0900 Subject: [PATCH 104/151] revert: "feat(lidar_transfusion): update TransFusion-L model" (#1478) Revert "feat(lidar_transfusion): update TransFusion-L model" --- perception/lidar_transfusion/CMakeLists.txt | 52 --- perception/lidar_transfusion/README.md | 22 +- .../config/transfusion.param.yaml | 7 +- .../preprocess/pointcloud_densification.hpp | 2 +- .../preprocess/preprocess_kernel.hpp | 6 +- .../preprocess/voxel_generator.hpp | 8 +- .../include/lidar_transfusion/ros_utils.hpp | 68 ---- .../lidar_transfusion/transfusion_config.hpp | 13 +- .../include/lidar_transfusion/utils.hpp | 46 +++ .../preprocess/pointcloud_densification.cpp | 9 +- .../lib/preprocess/preprocess_kernel.cu | 61 ++-- .../lib/preprocess/voxel_generator.cpp | 23 +- perception/lidar_transfusion/package.xml | 1 - .../schema/transfusion.schema.json | 6 - .../src/lidar_transfusion_node.cpp | 5 +- .../test/test_detection_class_remapper.cpp | 92 ------ .../lidar_transfusion/test/test_nms.cpp | 121 ------- .../test/test_postprocess_kernel.cpp | 299 ------------------ .../test/test_postprocess_kernel.hpp | 48 --- .../test/test_preprocess_kernel.cpp | 265 ---------------- .../test/test_preprocess_kernel.hpp | 50 --- .../lidar_transfusion/test/test_ros_utils.cpp | 104 ------ .../test/test_voxel_generator.cpp | 284 ----------------- .../test/test_voxel_generator.hpp | 65 ---- 24 files changed, 115 insertions(+), 1542 deletions(-) delete mode 100644 perception/lidar_transfusion/test/test_detection_class_remapper.cpp delete mode 100644 perception/lidar_transfusion/test/test_nms.cpp delete mode 100644 perception/lidar_transfusion/test/test_postprocess_kernel.cpp delete mode 100644 perception/lidar_transfusion/test/test_postprocess_kernel.hpp delete mode 100644 perception/lidar_transfusion/test/test_preprocess_kernel.cpp delete mode 100644 perception/lidar_transfusion/test/test_preprocess_kernel.hpp delete mode 100644 perception/lidar_transfusion/test/test_ros_utils.cpp delete mode 100644 perception/lidar_transfusion/test/test_voxel_generator.cpp delete mode 100644 perception/lidar_transfusion/test/test_voxel_generator.hpp diff --git a/perception/lidar_transfusion/CMakeLists.txt b/perception/lidar_transfusion/CMakeLists.txt index 677a835e5b04e..c0e2d85f27e62 100644 --- a/perception/lidar_transfusion/CMakeLists.txt +++ b/perception/lidar_transfusion/CMakeLists.txt @@ -137,58 +137,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() - - find_package(ament_cmake_gtest REQUIRED) - ament_auto_add_gtest(test_detection_class_remapper - test/test_detection_class_remapper.cpp - ) - ament_auto_add_gtest(test_ros_utils - test/test_ros_utils.cpp - ) - ament_auto_add_gtest(test_nms - test/test_nms.cpp - ) - - # Temporary disabled, tracked by: - # https://github.com/autowarefoundation/autoware.universe/issues/7724 - # ament_auto_add_gtest(test_voxel_generator - # test/test_voxel_generator.cpp - # ) - - # # preprocess kernel test - # add_executable(test_preprocess_kernel - # test/test_preprocess_kernel.cpp - # ) - # target_include_directories(test_preprocess_kernel PUBLIC - # ${test_preprocess_kernel_SOURCE_DIR} - # ) - # target_link_libraries(test_preprocess_kernel - # transfusion_cuda_lib - # gtest - # gtest_main - # ) - # ament_add_test(test_preprocess_kernel - # GENERATE_RESULT_FOR_RETURN_CODE_ZERO - # COMMAND "$" - # ) - - # # postprocess kernel test - # add_executable(test_postprocess_kernel - # test/test_postprocess_kernel.cpp - # ) - # target_include_directories(test_postprocess_kernel PUBLIC - # ${test_postprocess_kernel_SOURCE_DIR} - # ) - # target_link_libraries(test_postprocess_kernel - # transfusion_cuda_lib - # gtest - # gtest_main - # ) - # ament_add_test(test_postprocess_kernel - # GENERATE_RESULT_FOR_RETURN_CODE_ZERO - # COMMAND "$" - # ) - endif() ament_auto_package( diff --git a/perception/lidar_transfusion/README.md b/perception/lidar_transfusion/README.md index 6745cc1f7d219..7974714720c32 100644 --- a/perception/lidar_transfusion/README.md +++ b/perception/lidar_transfusion/README.md @@ -59,31 +59,13 @@ ros2 launch lidar_transfusion lidar_transfusion.launch.xml log_level:=debug ## Assumptions / Known limits -This library operates on raw cloud data (bytes). It is assumed that the input pointcloud message has following format: - -```python -[ - sensor_msgs.msg.PointField(name='x', offset=0, datatype=7, count=1), - sensor_msgs.msg.PointField(name='y', offset=4, datatype=7, count=1), - sensor_msgs.msg.PointField(name='z', offset=8, datatype=7, count=1), - sensor_msgs.msg.PointField(name='intensity', offset=12, datatype=2, count=1) -] -``` - -This input may consist of other fields as well - shown format is required minimum. -For debug purposes, you can validate your pointcloud topic using simple command: - -```bash -ros2 topic echo --field fields -``` - ## Trained Models You can download the onnx format of trained models by clicking on the links below. -- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/t4xx1_90m/v2/transfusion.onnx) +- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/v1/transfusion.onnx) -The model was trained in TIER IV's internal database (~11k lidar frames) for 50 epochs. +The model was trained in TIER IV's internal database (~11k lidar frames) for 20 epochs. ### Changelog diff --git a/perception/lidar_transfusion/config/transfusion.param.yaml b/perception/lidar_transfusion/config/transfusion.param.yaml index 2c6680fe50af1..feabe359caf1f 100644 --- a/perception/lidar_transfusion/config/transfusion.param.yaml +++ b/perception/lidar_transfusion/config/transfusion.param.yaml @@ -4,9 +4,8 @@ class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] trt_precision: fp16 voxels_num: [5000, 30000, 60000] # [min, opt, max] - point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max] - voxel_size: [0.24, 0.24, 10.0] # [x, y, z] - num_proposals: 500 + point_cloud_range: [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0] # [x_min, y_min, z_min, x_max, y_max, z_max] + voxel_size: [0.3, 0.3, 8.0] # [x, y, z] onnx_path: "$(var model_path)/transfusion.onnx" engine_path: "$(var model_path)/transfusion.engine" # pre-process params @@ -18,4 +17,4 @@ iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names - score_threshold: 0.1 + score_threshold: 0.2 diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp index 6ac0a6544389f..25095f4dc9c0b 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp @@ -51,7 +51,7 @@ class DensificationParam struct PointCloudWithTransform { - cuda::unique_ptr data_d{nullptr}; + cuda::unique_ptr points_d{nullptr}; std_msgs::msg::Header header; size_t num_points{0}; Eigen::Affine3f affine_past2world; diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp index 592f09c2d288a..c571990d84b51 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp @@ -56,8 +56,12 @@ class PreprocessCuda unsigned int * mask, float * voxels, unsigned int * pillar_num, float * voxel_features, unsigned int * voxel_num, unsigned int * voxel_idxs); + // cudaError_t generateVoxelsInput_launch( + // uint8_t * cloud_data, CloudInfo & cloud_info, unsigned int points_agg, unsigned int + // points_size, float time_lag, float * affine_transform, float * points); + cudaError_t generateSweepPoints_launch( - const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, + const float * input_points, size_t points_size, int input_point_step, float time_lag, const float * transform, float * output_points); private: diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp index f0d253ee28755..3e3660e238473 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp @@ -18,8 +18,8 @@ #include "lidar_transfusion/cuda_utils.hpp" #include "lidar_transfusion/preprocess/pointcloud_densification.hpp" #include "lidar_transfusion/preprocess/preprocess_kernel.hpp" -#include "lidar_transfusion/ros_utils.hpp" #include "lidar_transfusion/transfusion_config.hpp" +#include "lidar_transfusion/utils.hpp" #ifdef ROS_DISTRO_GALACTIC #include @@ -27,8 +27,6 @@ #include #endif -#include - #include #include @@ -38,8 +36,8 @@ namespace lidar_transfusion { -constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix -constexpr size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware_point_types::PointXYZIRCAEDT); +constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix +constexpr size_t MAX_CLOUD_STEP_SIZE = 35; // PointXYZIRCADT class VoxelGenerator { diff --git a/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp index cbfc4e87b1610..f013a02404a29 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp @@ -17,84 +17,16 @@ #include "lidar_transfusion/utils.hpp" -#include - #include #include #include #include -#include -#include #include #include -#define CHECK_OFFSET(offset, structure, field) \ - static_assert( \ - offsetof(structure, field) == offset, \ - "Offset of " #field " in " #structure " does not match expected offset.") -#define CHECK_TYPE(type, structure, field) \ - static_assert( \ - std::is_same::value, \ - "Type of " #field " in " #structure " does not match expected type.") -#define CHECK_FIELD(offset, type, structure, field) \ - CHECK_OFFSET(offset, structure, field); \ - CHECK_TYPE(type, structure, field) - namespace lidar_transfusion { -using sensor_msgs::msg::PointField; - -CHECK_FIELD(0, float, autoware_point_types::PointXYZIRCAEDT, x); -CHECK_FIELD(4, float, autoware_point_types::PointXYZIRCAEDT, y); -CHECK_FIELD(8, float, autoware_point_types::PointXYZIRCAEDT, z); -CHECK_FIELD(12, uint8_t, autoware_point_types::PointXYZIRCAEDT, intensity); - -struct CloudInfo -{ - uint32_t x_offset{0}; - uint32_t y_offset{sizeof(float)}; - uint32_t z_offset{sizeof(float) * 2}; - uint32_t intensity_offset{sizeof(float) * 3}; - uint8_t x_datatype{PointField::FLOAT32}; - uint8_t y_datatype{PointField::FLOAT32}; - uint8_t z_datatype{PointField::FLOAT32}; - uint8_t intensity_datatype{PointField::UINT8}; - uint8_t x_count{1}; - uint8_t y_count{1}; - uint8_t z_count{1}; - uint8_t intensity_count{1}; - uint32_t point_step{sizeof(autoware_point_types::PointXYZIRCAEDT)}; - bool is_bigendian{false}; - - bool operator!=(const CloudInfo & rhs) const - { - return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset || - intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype || - y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype || - intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count || - y_count != rhs.y_count || z_count != rhs.z_count || - intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian; - } - - friend std::ostream & operator<<(std::ostream & os, const CloudInfo & info) - { - os << "x_offset: " << static_cast(info.x_offset) << std::endl; - os << "y_offset: " << static_cast(info.y_offset) << std::endl; - os << "z_offset: " << static_cast(info.z_offset) << std::endl; - os << "intensity_offset: " << static_cast(info.intensity_offset) << std::endl; - os << "x_datatype: " << static_cast(info.x_datatype) << std::endl; - os << "y_datatype: " << static_cast(info.y_datatype) << std::endl; - os << "z_datatype: " << static_cast(info.z_datatype) << std::endl; - os << "intensity_datatype: " << static_cast(info.intensity_datatype) << std::endl; - os << "x_count: " << static_cast(info.x_count) << std::endl; - os << "y_count: " << static_cast(info.y_count) << std::endl; - os << "z_count: " << static_cast(info.z_count) << std::endl; - os << "intensity_count: " << static_cast(info.intensity_count) << std::endl; - os << "is_bigendian: " << static_cast(info.is_bigendian) << std::endl; - return os; - } -}; void box3DToDetectedObject( const Box3D & box3d, const std::vector & class_names, diff --git a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp index 0ad3ab2231f50..31976de56a9da 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp @@ -26,9 +26,8 @@ class TransfusionConfig public: TransfusionConfig( const std::vector & voxels_num, const std::vector & point_cloud_range, - const std::vector & voxel_size, const int num_proposals, - const float circle_nms_dist_threshold, const std::vector & yaw_norm_thresholds, - const float score_threshold) + const std::vector & voxel_size, const float circle_nms_dist_threshold, + const std::vector & yaw_norm_thresholds, const float score_threshold) { if (voxels_num.size() == 3) { max_voxels_ = voxels_num[2]; @@ -62,9 +61,6 @@ class TransfusionConfig voxel_y_size_ = static_cast(voxel_size[1]); voxel_z_size_ = static_cast(voxel_size[2]); } - if (num_proposals > 0) { - num_proposals_ = num_proposals; - } if (score_threshold > 0.0) { score_threshold_ = score_threshold; } @@ -80,9 +76,6 @@ class TransfusionConfig grid_x_size_ = static_cast((max_x_range_ - min_x_range_) / voxel_x_size_); grid_y_size_ = static_cast((max_y_range_ - min_y_range_) / voxel_y_size_); grid_z_size_ = static_cast((max_z_range_ - min_z_range_) / voxel_z_size_); - - feature_x_size_ = grid_x_size_ / out_size_factor_; - feature_y_size_ = grid_y_size_ / out_size_factor_; } ///// INPUT PARAMETERS ///// @@ -114,7 +107,7 @@ class TransfusionConfig const std::size_t out_size_factor_{4}; const std::size_t max_num_points_per_pillar_{points_per_voxel_}; const std::size_t num_point_values_{4}; - std::size_t num_proposals_{200}; + const std::size_t num_proposals_{200}; // the number of feature maps for pillar scatter const std::size_t num_feature_scatter_{pillar_feature_size_}; // the score threshold for classification diff --git a/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp index cc40e55851738..e73fe7f055953 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp @@ -36,6 +36,52 @@ struct Box3D float yaw; }; +struct CloudInfo +{ + uint32_t x_offset; + uint32_t y_offset; + uint32_t z_offset; + uint32_t intensity_offset; + uint8_t x_datatype; + uint8_t y_datatype; + uint8_t z_datatype; + uint8_t intensity_datatype; + uint8_t x_count; + uint8_t y_count; + uint8_t z_count; + uint8_t intensity_count; + uint32_t point_step; + bool is_bigendian; + + CloudInfo() + : x_offset(0), + y_offset(4), + z_offset(8), + intensity_offset(12), + x_datatype(7), + y_datatype(7), + z_datatype(7), + intensity_datatype(7), + x_count(1), + y_count(1), + z_count(1), + intensity_count(1), + point_step(16), + is_bigendian(false) + { + } + + bool operator!=(const CloudInfo & rhs) const + { + return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset || + intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype || + y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype || + intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count || + y_count != rhs.y_count || z_count != rhs.z_count || + intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian; + } +}; + enum NetworkIO { voxels = 0, num_points, coors, cls_score, dir_pred, bbox_pred, ENUM_SIZE }; // cspell: ignore divup diff --git a/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp b/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp index c13423f2d24d8..774b3a05d71c1 100644 --- a/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp +++ b/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp @@ -93,15 +93,16 @@ void PointCloudDensification::enqueue( affine_world2current_ = affine_world2current; current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds(); - auto data_d = cuda::make_unique( - sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(uint8_t)); + assert(sizeof(uint8_t) * msg.width * msg.height * msg.point_step % sizeof(float) == 1); + auto points_d = cuda::make_unique( + sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(float)); CHECK_CUDA_ERROR(cudaMemcpyAsync( - data_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step, + points_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step, cudaMemcpyHostToDevice, stream_)); PointCloudWithTransform pointcloud = { - std::move(data_d), msg.header, msg.width * msg.height, affine_world2current.inverse()}; + std::move(points_d), msg.header, msg.width * msg.height, affine_world2current.inverse()}; pointcloud_cache_.push_front(std::move(pointcloud)); } diff --git a/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu b/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu index 48bb4eb9332a8..b8f9ae998fd4f 100644 --- a/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu @@ -31,8 +31,6 @@ #include "lidar_transfusion/cuda_utils.hpp" #include "lidar_transfusion/preprocess/preprocess_kernel.hpp" -#include - namespace lidar_transfusion { @@ -101,12 +99,9 @@ __global__ void generateVoxels_random_kernel( cudaError_t PreprocessCuda::generateVoxels_random_launch( float * points, unsigned int points_size, unsigned int * mask, float * voxels) { - if (points_size == 0) { - return cudaGetLastError(); - } - dim3 blocks(divup(points_size, config_.threads_for_voxel_)); - dim3 threads(config_.threads_for_voxel_); - + int threadNum = config_.threads_for_voxel_; + dim3 blocks((points_size + threadNum - 1) / threadNum); + dim3 threads(threadNum); generateVoxels_random_kernel<<>>( points, points_size, config_.min_x_range_, config_.max_x_range_, config_.min_y_range_, config_.max_y_range_, config_.min_z_range_, config_.max_z_range_, config_.voxel_x_size_, @@ -170,48 +165,40 @@ cudaError_t PreprocessCuda::generateBaseFeatures_launch( } __global__ void generateSweepPoints_kernel( - const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, + const float * input_points, size_t points_size, int input_point_step, float time_lag, const float * transform_array, int num_features, float * output_points) { int point_idx = blockIdx.x * blockDim.x + threadIdx.x; if (point_idx >= points_size) return; - union { - uint32_t raw{0}; - float value; - } input_x, input_y, input_z; - -#pragma unroll - for (int i = 0; i < 4; i++) { // 4 bytes for float32 - input_x.raw |= input_data[point_idx * input_point_step + i] << i * 8; - input_y.raw |= input_data[point_idx * input_point_step + i + 4] << i * 8; - input_z.raw |= input_data[point_idx * input_point_step + i + 8] << i * 8; - } - - float input_intensity = static_cast(input_data[point_idx * input_point_step + 12]); - - output_points[point_idx * num_features] = - transform_array[0] * input_x.value + transform_array[4] * input_y.value + - transform_array[8] * input_z.value + transform_array[12]; - output_points[point_idx * num_features + 1] = - transform_array[1] * input_x.value + transform_array[5] * input_y.value + - transform_array[9] * input_z.value + transform_array[13]; - output_points[point_idx * num_features + 2] = - transform_array[2] * input_x.value + transform_array[6] * input_y.value + - transform_array[10] * input_z.value + transform_array[14]; - output_points[point_idx * num_features + 3] = input_intensity; + const float input_x = input_points[point_idx * input_point_step + 0]; + const float input_y = input_points[point_idx * input_point_step + 1]; + const float input_z = input_points[point_idx * input_point_step + 2]; + const float intensity = input_points[point_idx * input_point_step + 3]; + + output_points[point_idx * num_features] = transform_array[0] * input_x + + transform_array[4] * input_y + + transform_array[8] * input_z + transform_array[12]; + output_points[point_idx * num_features + 1] = transform_array[1] * input_x + + transform_array[5] * input_y + + transform_array[9] * input_z + transform_array[13]; + output_points[point_idx * num_features + 2] = transform_array[2] * input_x + + transform_array[6] * input_y + + transform_array[10] * input_z + transform_array[14]; + output_points[point_idx * num_features + 3] = intensity; output_points[point_idx * num_features + 4] = time_lag; } cudaError_t PreprocessCuda::generateSweepPoints_launch( - const uint8_t * input_data, size_t points_size, int input_point_step, float time_lag, + const float * input_points, size_t points_size, int input_point_step, float time_lag, const float * transform_array, float * output_points) { - dim3 blocks(divup(points_size, config_.threads_for_voxel_)); - dim3 threads(config_.threads_for_voxel_); + int threadNum = config_.threads_for_voxel_; + dim3 blocks((points_size + threadNum - 1) / threadNum); + dim3 threads(threadNum); generateSweepPoints_kernel<<>>( - input_data, points_size, input_point_step, time_lag, transform_array, + input_points, points_size, input_point_step, time_lag, transform_array, config_.num_point_feature_size_, output_points); cudaError_t err = cudaGetLastError(); diff --git a/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp b/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp index cb8bac984aef3..7072e8491af66 100644 --- a/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp +++ b/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp @@ -23,6 +23,25 @@ namespace lidar_transfusion { +std::ostream & operator<<(std::ostream & os, const CloudInfo & info) +{ + os << "x_offset: " << static_cast(info.x_offset) << std::endl; + os << "y_offset: " << static_cast(info.y_offset) << std::endl; + os << "z_offset: " << static_cast(info.z_offset) << std::endl; + os << "intensity_offset: " << static_cast(info.intensity_offset) << std::endl; + os << "x_datatype: " << static_cast(info.x_datatype) << std::endl; + os << "y_datatype: " << static_cast(info.y_datatype) << std::endl; + os << "z_datatype: " << static_cast(info.z_datatype) << std::endl; + os << "intensity_datatype: " << static_cast(info.intensity_datatype) << std::endl; + os << "x_count: " << static_cast(info.x_count) << std::endl; + os << "y_count: " << static_cast(info.y_count) << std::endl; + os << "z_count: " << static_cast(info.z_count) << std::endl; + os << "intensity_count: " << static_cast(info.intensity_count) << std::endl; + os << "point_step: " << static_cast(info.point_step) << std::endl; + os << "is_bigendian: " << static_cast(info.is_bigendian) << std::endl; + return os; +} + VoxelGenerator::VoxelGenerator( const DensificationParam & densification_param, const TransfusionConfig & config, cudaStream_t & stream) @@ -87,8 +106,8 @@ std::size_t VoxelGenerator::generateSweepPoints( CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); pre_ptr_->generateSweepPoints_launch( - pc_cache_iter->data_d.get(), sweep_num_points, cloud_info_.point_step, time_lag, - affine_past2current_d_.get(), points_d.get() + shift); + pc_cache_iter->points_d.get(), sweep_num_points, cloud_info_.point_step / sizeof(float), + time_lag, affine_past2current_d_.get(), points_d.get() + shift); point_counter += sweep_num_points; } diff --git a/perception/lidar_transfusion/package.xml b/perception/lidar_transfusion/package.xml index 3b495025b1c34..ffbe091b998e5 100644 --- a/perception/lidar_transfusion/package.xml +++ b/perception/lidar_transfusion/package.xml @@ -13,7 +13,6 @@ autoware_cmake autoware_perception_msgs - autoware_point_types autoware_universe_utils launch_ros object_recognition_utils diff --git a/perception/lidar_transfusion/schema/transfusion.schema.json b/perception/lidar_transfusion/schema/transfusion.schema.json index 7debc0edda6fb..41d8d887236a8 100644 --- a/perception/lidar_transfusion/schema/transfusion.schema.json +++ b/perception/lidar_transfusion/schema/transfusion.schema.json @@ -61,12 +61,6 @@ "default": "$(var model_path)/transfusion.engine", "pattern": "\\.engine$" }, - "num_proposals": { - "type": "integer", - "description": "Number of proposals at TransHead.", - "default": 500, - "minimum": 1 - }, "down_sample_factor": { "type": "integer", "description": "A scale factor of downsampling points", diff --git a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp index 7f5833e60d6d0..e3ea6b3780de8 100644 --- a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp @@ -31,7 +31,6 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) const auto point_cloud_range = this->declare_parameter>("point_cloud_range", descriptor); const auto voxel_size = this->declare_parameter>("voxel_size", descriptor); - const int num_proposals = (this->declare_parameter("num_proposals", descriptor)); const std::string onnx_path = this->declare_parameter("onnx_path", descriptor); const std::string engine_path = this->declare_parameter("engine_path", descriptor); @@ -74,8 +73,8 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); TransfusionConfig config( - voxels_num, point_cloud_range, voxel_size, num_proposals, circle_nms_dist_threshold, - yaw_norm_thresholds, score_threshold); + voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, + score_threshold); const auto allow_remapping_by_area_matrix = this->declare_parameter>("allow_remapping_by_area_matrix", descriptor); diff --git a/perception/lidar_transfusion/test/test_detection_class_remapper.cpp b/perception/lidar_transfusion/test/test_detection_class_remapper.cpp deleted file mode 100644 index 6e7f896e44d2c..0000000000000 --- a/perception/lidar_transfusion/test/test_detection_class_remapper.cpp +++ /dev/null @@ -1,92 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include - -TEST(DetectionClassRemapperTest, MapClasses) -{ - lidar_transfusion::DetectionClassRemapper remapper; - - // Set up the parameters for the remapper - // Labels: CAR, TRUCK, TRAILER - std::vector allow_remapping_by_area_matrix = { - 0, 0, 0, // CAR cannot be remapped - 0, 0, 1, // TRUCK can be remapped to TRAILER - 0, 1, 0 // TRAILER can be remapped to TRUCK - }; - std::vector min_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0}; - std::vector max_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 999.0, 0.0, 10.0, 0.0}; - - remapper.setParameters(allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); - - // Create a DetectedObjects message with some objects - autoware_perception_msgs::msg::DetectedObjects msg; - - // CAR with area 4.0, which is out of the range for remapping - autoware_perception_msgs::msg::DetectedObject obj1; - autoware_perception_msgs::msg::ObjectClassification obj1_classification; - obj1.shape.dimensions.x = 2.0; - obj1.shape.dimensions.y = 2.0; - obj1_classification.label = 0; - obj1_classification.probability = 1.0; - obj1.classification = {obj1_classification}; - msg.objects.push_back(obj1); - - // TRUCK with area 16.0, which is in the range for remapping to TRAILER - autoware_perception_msgs::msg::DetectedObject obj2; - autoware_perception_msgs::msg::ObjectClassification obj2_classification; - obj2.shape.dimensions.x = 8.0; - obj2.shape.dimensions.y = 2.0; - obj2_classification.label = 1; - obj2_classification.probability = 1.0; - obj2.classification = {obj2_classification}; - msg.objects.push_back(obj2); - - // TRAILER with area 9.0, which is in the range for remapping to TRUCK - autoware_perception_msgs::msg::DetectedObject obj3; - autoware_perception_msgs::msg::ObjectClassification obj3_classification; - obj3.shape.dimensions.x = 3.0; - obj3.shape.dimensions.y = 3.0; - obj3_classification.label = 2; - obj3_classification.probability = 1.0; - obj3.classification = {obj3_classification}; - msg.objects.push_back(obj3); - - // TRAILER with area 12.0, which is out of the range for remapping - autoware_perception_msgs::msg::DetectedObject obj4; - autoware_perception_msgs::msg::ObjectClassification obj4_classification; - obj4.shape.dimensions.x = 4.0; - obj4.shape.dimensions.y = 3.0; - obj4_classification.label = 2; - obj4_classification.probability = 1.0; - obj4.classification = {obj4_classification}; - msg.objects.push_back(obj4); - - // Call the mapClasses function - remapper.mapClasses(msg); - - // Check the remapped labels - EXPECT_EQ(msg.objects[0].classification[0].label, 0); - EXPECT_EQ(msg.objects[1].classification[0].label, 2); - EXPECT_EQ(msg.objects[2].classification[0].label, 1); - EXPECT_EQ(msg.objects[3].classification[0].label, 2); -} - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/perception/lidar_transfusion/test/test_nms.cpp b/perception/lidar_transfusion/test/test_nms.cpp deleted file mode 100644 index b6f0ec8c31684..0000000000000 --- a/perception/lidar_transfusion/test/test_nms.cpp +++ /dev/null @@ -1,121 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "lidar_transfusion/postprocess/non_maximum_suppression.hpp" - -#include - -TEST(NonMaximumSuppressionTest, Apply) -{ - lidar_transfusion::NonMaximumSuppression nms; - lidar_transfusion::NMSParams params; - params.search_distance_2d_ = 1.0; - params.iou_threshold_ = 0.2; - params.nms_type_ = lidar_transfusion::NMS_TYPE::IoU_BEV; - params.target_class_names_ = {"CAR"}; - nms.setParameters(params); - - std::vector input_objects(4); - - // Object 1 - autoware_perception_msgs::msg::ObjectClassification obj1_classification; - obj1_classification.label = 0; // Assuming "car" has label 0 - obj1_classification.probability = 1.0; - input_objects[0].classification = {obj1_classification}; // Assuming "car" has label 0 - input_objects[0].kinematics.pose_with_covariance.pose.position.x = 0.0; - input_objects[0].kinematics.pose_with_covariance.pose.position.y = 0.0; - input_objects[0].kinematics.pose_with_covariance.pose.orientation.x = 0.0; - input_objects[0].kinematics.pose_with_covariance.pose.orientation.y = 0.0; - input_objects[0].kinematics.pose_with_covariance.pose.orientation.z = 0.0; - input_objects[0].kinematics.pose_with_covariance.pose.orientation.w = 1.0; - input_objects[0].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; - input_objects[0].shape.dimensions.x = 4.0; - input_objects[0].shape.dimensions.y = 2.0; - - // Object 2 (overlaps with Object 1) - autoware_perception_msgs::msg::ObjectClassification obj2_classification; - obj2_classification.label = 0; // Assuming "car" has label 0 - obj2_classification.probability = 1.0; - input_objects[1].classification = {obj2_classification}; // Assuming "car" has label 0 - input_objects[1].kinematics.pose_with_covariance.pose.position.x = 0.5; - input_objects[1].kinematics.pose_with_covariance.pose.position.y = 0.5; - input_objects[1].kinematics.pose_with_covariance.pose.orientation.x = 0.0; - input_objects[1].kinematics.pose_with_covariance.pose.orientation.y = 0.0; - input_objects[1].kinematics.pose_with_covariance.pose.orientation.z = 0.0; - input_objects[1].kinematics.pose_with_covariance.pose.orientation.w = 1.0; - input_objects[1].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; - input_objects[1].shape.dimensions.x = 4.0; - input_objects[1].shape.dimensions.y = 2.0; - - // Object 3 - autoware_perception_msgs::msg::ObjectClassification obj3_classification; - obj3_classification.label = 0; // Assuming "car" has label 0 - obj3_classification.probability = 1.0; - input_objects[2].classification = {obj3_classification}; // Assuming "car" has label 0 - input_objects[2].kinematics.pose_with_covariance.pose.position.x = 5.0; - input_objects[2].kinematics.pose_with_covariance.pose.position.y = 5.0; - input_objects[2].kinematics.pose_with_covariance.pose.orientation.x = 0.0; - input_objects[2].kinematics.pose_with_covariance.pose.orientation.y = 0.0; - input_objects[2].kinematics.pose_with_covariance.pose.orientation.z = 0.0; - input_objects[2].kinematics.pose_with_covariance.pose.orientation.w = 1.0; - input_objects[2].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; - input_objects[2].shape.dimensions.x = 4.0; - input_objects[2].shape.dimensions.y = 2.0; - - // Object 4 (different class) - autoware_perception_msgs::msg::ObjectClassification obj4_classification; - obj4_classification.label = 1; // Assuming "pedestrian" has label 1 - obj4_classification.probability = 1.0; - input_objects[3].classification = {obj4_classification}; // Assuming "pedestrian" has label 1 - input_objects[3].kinematics.pose_with_covariance.pose.position.x = 0.0; - input_objects[3].kinematics.pose_with_covariance.pose.position.y = 0.0; - input_objects[3].kinematics.pose_with_covariance.pose.orientation.x = 0.0; - input_objects[3].kinematics.pose_with_covariance.pose.orientation.y = 0.0; - input_objects[3].kinematics.pose_with_covariance.pose.orientation.z = 0.0; - input_objects[3].kinematics.pose_with_covariance.pose.orientation.w = 1.0; - input_objects[3].shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; - input_objects[3].shape.dimensions.x = 0.5; - input_objects[3].shape.dimensions.y = 0.5; - - std::vector output_objects = nms.apply(input_objects); - - // Assert the expected number of output objects - EXPECT_EQ(output_objects.size(), 3); - - // Assert that input_objects[2] is included in the output_objects - bool is_input_object_2_included = false; - for (const auto & output_object : output_objects) { - if (output_object == input_objects[2]) { - is_input_object_2_included = true; - break; - } - } - EXPECT_TRUE(is_input_object_2_included); - - // Assert that input_objects[3] is included in the output_objects - bool is_input_object_3_included = false; - for (const auto & output_object : output_objects) { - if (output_object == input_objects[3]) { - is_input_object_3_included = true; - break; - } - } - EXPECT_TRUE(is_input_object_3_included); -} - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/perception/lidar_transfusion/test/test_postprocess_kernel.cpp b/perception/lidar_transfusion/test/test_postprocess_kernel.cpp deleted file mode 100644 index 1e01db5a8b3d7..0000000000000 --- a/perception/lidar_transfusion/test/test_postprocess_kernel.cpp +++ /dev/null @@ -1,299 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "test_postprocess_kernel.hpp" - -#include - -#include -#include - -namespace lidar_transfusion -{ - -void PostprocessKernelTest::SetUp() -{ - cudaStreamCreate(&stream_); - - auto voxels_num = std::vector{1, 3, 5}; - auto point_cloud_range = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; - auto voxel_size = std::vector{0.3, 0.3, 8.0}; - auto score_threshold = 0.2f; - auto circle_nms_dist_threshold = 0.5f; - auto yaw_norm_thresholds = std::vector{0.5, 0.5, 0.5}; - config_ptr_ = std::make_unique( - voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, - score_threshold); - post_ptr_ = std::make_unique(*config_ptr_, stream_); - - cls_size_ = config_ptr_->num_proposals_ * config_ptr_->num_classes_; - box_size_ = config_ptr_->num_proposals_ * config_ptr_->num_box_values_; - dir_cls_size_ = config_ptr_->num_proposals_ * 2; // x, y - - cls_output_d_ = cuda::make_unique(cls_size_); - box_output_d_ = cuda::make_unique(box_size_); - dir_cls_output_d_ = cuda::make_unique(dir_cls_size_); - - cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); - cuda::clear_async(box_output_d_.get(), box_size_, stream_); - cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); -} - -void PostprocessKernelTest::TearDown() -{ -} - -TEST_F(PostprocessKernelTest, EmptyTensorTest) -{ - std::vector det_boxes3d; - - CHECK_CUDA_ERROR(post_ptr_->generateDetectedBoxes3D_launch( - cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_)); - - EXPECT_EQ(0, det_boxes3d.size()); -} - -TEST_F(PostprocessKernelTest, SingleDetectionTest) -{ - cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); - cuda::clear_async(box_output_d_.get(), box_size_, stream_); - cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - std::vector det_boxes3d; - unsigned int det_idx = 42; - unsigned int cls_idx = 2; - - constexpr float detection_score = 1.f; - constexpr float detection_x = 50.f; - constexpr float detection_y = -38.4f; - constexpr float detection_z = 1.0; - const float detection_raw_x = (detection_x - config_ptr_->min_x_range_) / - (config_ptr_->num_point_values_ * config_ptr_->voxel_x_size_); - const float detection_raw_y = (detection_y - config_ptr_->min_y_range_) / - (config_ptr_->num_point_values_ * config_ptr_->voxel_y_size_); - const float detection_raw_z = detection_z; - - constexpr float detection_w = 3.2f; - constexpr float detection_l = 9.3f; - constexpr float detection_h = 1.7f; - constexpr float detection_log_w = std::log(detection_w); - constexpr float detection_log_l = std::log(detection_l); - constexpr float detection_log_h = std::log(detection_h); - - constexpr float detection_yaw = M_PI_4; - constexpr float detection_yaw_sin = std::sin(detection_yaw); - constexpr float detection_yaw_cos = std::cos(detection_yaw); - - // Set the values in the cuda tensor - cudaMemcpy( - &cls_output_d_[cls_idx * config_ptr_->num_proposals_ + det_idx], &detection_score, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &dir_cls_output_d_[det_idx], &detection_yaw_sin, 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &dir_cls_output_d_[det_idx + config_ptr_->num_proposals_], &detection_yaw_cos, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy(&box_output_d_[det_idx], &detection_raw_x, 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + config_ptr_->num_proposals_], &detection_raw_y, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 2 * config_ptr_->num_proposals_], &detection_raw_z, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 3 * config_ptr_->num_proposals_], &detection_log_w, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 4 * config_ptr_->num_proposals_], &detection_log_l, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 5 * config_ptr_->num_proposals_], &detection_log_h, 1 * sizeof(float), - cudaMemcpyHostToDevice); - - auto code1 = cudaGetLastError(); - ASSERT_EQ(cudaSuccess, code1); - - // Extract the boxes - auto code2 = post_ptr_->generateDetectedBoxes3D_launch( - cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - ASSERT_EQ(cudaSuccess, code2); - ASSERT_EQ(1, det_boxes3d.size()); - - const auto det_box3d = det_boxes3d[0]; - EXPECT_EQ(cls_idx, det_box3d.label); - EXPECT_EQ(detection_score, det_box3d.score); - EXPECT_EQ(detection_x, det_box3d.x); - EXPECT_EQ(detection_y, det_box3d.y); - EXPECT_EQ(detection_z, det_box3d.z); - EXPECT_NEAR(detection_w, det_box3d.width, 1e-6); - EXPECT_NEAR(detection_l, det_box3d.length, 1e-6); - EXPECT_NEAR(detection_h, det_box3d.height, 1e-6); - EXPECT_EQ(detection_yaw, det_box3d.yaw); -} - -TEST_F(PostprocessKernelTest, InvalidYawTest) -{ - cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); - cuda::clear_async(box_output_d_.get(), box_size_, stream_); - cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - std::vector det_boxes3d; - unsigned int det_idx = 42; - unsigned int cls_idx = 2; - - constexpr float detection_score = 1.f; - constexpr float detection_x = 50.f; - constexpr float detection_y = -38.4f; - constexpr float detection_z = 1.0; - const float detection_raw_x = (detection_x - config_ptr_->min_x_range_) / - (config_ptr_->num_point_values_ * config_ptr_->voxel_x_size_); - const float detection_raw_y = (detection_y - config_ptr_->min_y_range_) / - (config_ptr_->num_point_values_ * config_ptr_->voxel_y_size_); - const float detection_raw_z = detection_z; - - constexpr float detection_w = 3.2f; - constexpr float detection_l = 9.3f; - constexpr float detection_h = 1.7f; - constexpr float detection_log_w = std::log(detection_w); - constexpr float detection_log_l = std::log(detection_l); - constexpr float detection_log_h = std::log(detection_h); - - constexpr float detection_yaw_sin = 0.f; - constexpr float detection_yaw_cos = 0.2f; - - // Set the values in the cuda tensor - cudaMemcpy( - &cls_output_d_[cls_idx * config_ptr_->num_proposals_ + det_idx], &detection_score, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &dir_cls_output_d_[det_idx], &detection_yaw_sin, 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &dir_cls_output_d_[det_idx + config_ptr_->num_proposals_], &detection_yaw_cos, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy(&box_output_d_[det_idx], &detection_raw_x, 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + config_ptr_->num_proposals_], &detection_raw_y, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 2 * config_ptr_->num_proposals_], &detection_raw_z, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 3 * config_ptr_->num_proposals_], &detection_log_w, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 4 * config_ptr_->num_proposals_], &detection_log_l, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + 5 * config_ptr_->num_proposals_], &detection_log_h, 1 * sizeof(float), - cudaMemcpyHostToDevice); - - auto code1 = cudaGetLastError(); - ASSERT_EQ(cudaSuccess, code1); - - // Extract the boxes - auto code2 = post_ptr_->generateDetectedBoxes3D_launch( - cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - ASSERT_EQ(cudaSuccess, code2); - EXPECT_EQ(0, det_boxes3d.size()); -} - -TEST_F(PostprocessKernelTest, CircleNMSTest) -{ - cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); - cuda::clear_async(box_output_d_.get(), box_size_, stream_); - cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - std::vector det_boxes3d; - unsigned int det_idx = 42; - unsigned int det_num = 2; - unsigned int cls_idx = 2; - - constexpr float detection_score = 1.f; - constexpr float detection_x = 50.f; - constexpr float detection_y = -38.4f; - constexpr float detection_z = 1.0; - const float detection_raw_x = (detection_x - config_ptr_->min_x_range_) / - (config_ptr_->num_point_values_ * config_ptr_->voxel_x_size_); - const float detection_raw_y = (detection_y - config_ptr_->min_y_range_) / - (config_ptr_->num_point_values_ * config_ptr_->voxel_y_size_); - const float detection_raw_z = detection_z; - - constexpr float detection_w = 3.2f; - constexpr float detection_l = 9.3f; - constexpr float detection_h = 1.7f; - constexpr float detection_log_w = std::log(detection_w); - constexpr float detection_log_l = std::log(detection_l); - constexpr float detection_log_h = std::log(detection_h); - - constexpr float detection_yaw = M_PI_4; - constexpr float detection_yaw_sin = std::sin(detection_yaw); - constexpr float detection_yaw_cos = std::cos(detection_yaw); - - // Set the values in the cuda tensor for 2 detections - for (std::size_t i = 0; i < det_num; ++i) { - cudaMemcpy( - &cls_output_d_[cls_idx * config_ptr_->num_proposals_ + det_idx + i], &detection_score, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &dir_cls_output_d_[det_idx + i], &detection_yaw_sin, 1 * sizeof(float), - cudaMemcpyHostToDevice); - cudaMemcpy( - &dir_cls_output_d_[det_idx + i + config_ptr_->num_proposals_], &detection_yaw_cos, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + i], &detection_raw_x, 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + i + config_ptr_->num_proposals_], &detection_raw_y, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + i + 2 * config_ptr_->num_proposals_], &detection_raw_z, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + i + 3 * config_ptr_->num_proposals_], &detection_log_w, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + i + 4 * config_ptr_->num_proposals_], &detection_log_l, - 1 * sizeof(float), cudaMemcpyHostToDevice); - cudaMemcpy( - &box_output_d_[det_idx + i + 5 * config_ptr_->num_proposals_], &detection_log_h, - 1 * sizeof(float), cudaMemcpyHostToDevice); - } - - auto code1 = cudaGetLastError(); - ASSERT_EQ(cudaSuccess, code1); - - // Extract the boxes - auto code2 = post_ptr_->generateDetectedBoxes3D_launch( - cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - ASSERT_EQ(cudaSuccess, code2); - EXPECT_EQ(1, det_boxes3d.size()); -} - -} // namespace lidar_transfusion - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/perception/lidar_transfusion/test/test_postprocess_kernel.hpp b/perception/lidar_transfusion/test/test_postprocess_kernel.hpp deleted file mode 100644 index 60fa7882ecc11..0000000000000 --- a/perception/lidar_transfusion/test/test_postprocess_kernel.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef TEST_POSTPROCESS_KERNEL_HPP_ -#define TEST_POSTPROCESS_KERNEL_HPP_ - -#include -#include - -#include - -#include - -namespace lidar_transfusion -{ - -class PostprocessKernelTest : public testing::Test -{ -public: - void SetUp() override; - void TearDown() override; - - std::unique_ptr post_ptr_{nullptr}; - std::unique_ptr config_ptr_{}; - cudaStream_t stream_{}; - - unsigned int cls_size_{0}; - unsigned int box_size_{0}; - unsigned int dir_cls_size_{0}; - cuda::unique_ptr cls_output_d_{nullptr}; - cuda::unique_ptr box_output_d_{nullptr}; - cuda::unique_ptr dir_cls_output_d_{nullptr}; -}; - -} // namespace lidar_transfusion - -#endif // TEST_POSTPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/test/test_preprocess_kernel.cpp b/perception/lidar_transfusion/test/test_preprocess_kernel.cpp deleted file mode 100644 index c1c2a824f0f53..0000000000000 --- a/perception/lidar_transfusion/test/test_preprocess_kernel.cpp +++ /dev/null @@ -1,265 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "test_preprocess_kernel.hpp" - -#include "lidar_transfusion/cuda_utils.hpp" - -#include - -#include -#include -#include - -#include -#include - -namespace lidar_transfusion -{ - -void PreprocessKernelTest::SetUp() -{ - cudaStreamCreate(&stream_); - - auto voxels_num = std::vector{1, 3, 5}; - auto point_cloud_range = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; - auto voxel_size = std::vector{0.3, 0.3, 8.0}; - auto score_threshold = 0.2f; - auto circle_nms_dist_threshold = 0.5f; - auto yaw_norm_thresholds = std::vector{0.5, 0.5, 0.5}; - config_ptr_ = std::make_unique( - voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, - score_threshold); - pre_ptr_ = std::make_unique(*config_ptr_, stream_); - - voxel_features_size_ = config_ptr_->max_voxels_ * config_ptr_->max_num_points_per_pillar_ * - config_ptr_->num_point_feature_size_; - voxel_num_size_ = config_ptr_->max_voxels_; - voxel_idxs_size_ = config_ptr_->max_voxels_ * config_ptr_->num_point_values_; - - params_input_d_ = cuda::make_unique(); - voxel_features_d_ = cuda::make_unique(voxel_features_size_); - voxel_num_d_ = cuda::make_unique(voxel_num_size_); - voxel_idxs_d_ = cuda::make_unique(voxel_idxs_size_); - points_d_ = - cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - - cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); - cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); - cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); - cuda::clear_async(params_input_d_.get(), 1, stream_); - cuda::clear_async( - points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); -} - -void PreprocessKernelTest::TearDown() -{ -} - -TEST_F(PreprocessKernelTest, EmptyVoxelTest) -{ - std::vector points{}; - std::size_t count = 0; - - pre_ptr_->generateVoxels( - points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), - voxel_idxs_d_.get()); - unsigned int params_input; - auto code1 = cudaStreamSynchronize(stream_); - - auto code2 = cudaMemcpyAsync( - ¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost, stream_); - CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); - - auto code3 = cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice); - - ASSERT_EQ(cudaSuccess, code1); - ASSERT_EQ(cudaSuccess, code2); - ASSERT_EQ(cudaSuccess, code3); - - EXPECT_EQ(0, params_input); -} - -TEST_F(PreprocessKernelTest, BasicTest) -{ - cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); - cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); - cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); - cuda::clear_async(params_input_d_.get(), 1, stream_); - cuda::clear_async( - points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); - cudaStreamSynchronize(stream_); - - std::vector point1{25.f, -61.1f, 1.8f, 42.0, 0.1f}; - std::vector point2{-31.6f, 1.1f, 2.8f, 77.0, 0.1f}; - std::vector point3{42.6f, 15.1f, -0.1f, 3.0, 0.1f}; - - std::vector points; - points.reserve(point1.size() + point2.size() + point3.size()); - points.insert(points.end(), point1.begin(), point1.end()); - points.insert(points.end(), point2.begin(), point2.end()); - points.insert(points.end(), point3.begin(), point3.end()); - std::size_t count = 3; - - CHECK_CUDA_ERROR(cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice)); - - // Compute the total amount of voxels filled - pre_ptr_->generateVoxels( - points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), - voxel_idxs_d_.get()); - - unsigned int params_input; - CHECK_CUDA_ERROR( - cudaMemcpy(¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); - CHECK_CUDA_ERROR(cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice)); - - ASSERT_EQ(count, params_input); - - // Check if voxels were filled - unsigned int voxel_num; - - for (std::size_t i = 0; i < count; ++i) { - CHECK_CUDA_ERROR( - cudaMemcpy(&voxel_num, voxel_num_d_.get() + i, sizeof(unsigned int), cudaMemcpyDeviceToHost)); - EXPECT_EQ(1, voxel_num); - } - - // Check grid indices - thrust::host_vector voxel_idxs(config_ptr_->num_point_values_ * count, 0); - unsigned int voxel_idx_gt; - unsigned int voxel_idy_gt; - CHECK_CUDA_ERROR(cudaMemcpy( - voxel_idxs.data(), voxel_idxs_d_.get(), - config_ptr_->num_point_values_ * count * sizeof(unsigned int), cudaMemcpyDeviceToHost)); - - for (std::size_t i = 0; i < count; ++i) { - voxel_idx_gt = std::floor( - (points[config_ptr_->num_point_feature_size_ * i + 0] - config_ptr_->min_x_range_) / - config_ptr_->voxel_x_size_); - voxel_idy_gt = std::floor( - (points[config_ptr_->num_point_feature_size_ * i + 1] - config_ptr_->min_y_range_) / - config_ptr_->voxel_y_size_); - - EXPECT_EQ( - voxel_idx_gt, - voxel_idxs[config_ptr_->num_point_values_ * i + 3]); // {0, 0, voxel_idy, VOXEL_IDX} - EXPECT_EQ( - voxel_idy_gt, - voxel_idxs[config_ptr_->num_point_values_ * i + 2]); // {0, 0, VOXEL_IDY, voxel_idx} - } - - // Check voxel features - thrust::host_vector voxel_features( - count * config_ptr_->max_num_points_per_pillar_ * config_ptr_->num_point_feature_size_, 0.f); - CHECK_CUDA_ERROR(cudaMemcpy( - voxel_features.data(), voxel_features_d_.get(), - count * config_ptr_->max_num_points_per_pillar_ * config_ptr_->num_point_feature_size_ * - sizeof(float), - cudaMemcpyDeviceToHost)); - - for (std::size_t i = 0; i < count; ++i) { - for (std::size_t j = 0; j < config_ptr_->num_point_feature_size_; ++j) { - EXPECT_EQ( - points[config_ptr_->num_point_feature_size_ * i + j], - voxel_features - [i * config_ptr_->max_num_points_per_pillar_ * config_ptr_->num_point_feature_size_ + j]); - } - } -} - -TEST_F(PreprocessKernelTest, OutOfRangeTest) -{ - cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); - cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); - cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); - cuda::clear_async(params_input_d_.get(), 1, stream_); - cuda::clear_async( - points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); - cudaStreamSynchronize(stream_); - - std::vector points{25.f, config_ptr_->max_y_range_ + 0.1f, 2.1f, 55.f, 0.1f}; - std::size_t count = 0; - - CHECK_CUDA_ERROR(cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice)); - - pre_ptr_->generateVoxels( - points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), - voxel_idxs_d_.get()); - - unsigned int params_input; - CHECK_CUDA_ERROR( - cudaMemcpy(¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); - CHECK_CUDA_ERROR(cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice)); - - EXPECT_EQ(count, params_input); -} - -TEST_F(PreprocessKernelTest, VoxelOverflowTest) -{ - cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); - cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); - cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); - cuda::clear_async(params_input_d_.get(), 1, stream_); - cuda::clear_async( - points_d_.get(), config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_, stream_); - cudaStreamSynchronize(stream_); - - std::vector point{config_ptr_->min_x_range_, -61.1f, 1.8f, 42.f, 0.1f}; - std::size_t count = config_ptr_->max_voxels_ + 1; - std::vector points{}; - points.reserve(count * config_ptr_->num_point_feature_size_); - - for (std::size_t i = 0; i < count; ++i) { - points.insert(points.end(), point.begin(), point.end()); - point[0] += config_ptr_->voxel_x_size_; - } - - CHECK_CUDA_ERROR(cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice)); - - pre_ptr_->generateVoxels( - points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), - voxel_idxs_d_.get()); - - ASSERT_EQ(cudaSuccess, cudaGetLastError()); - - unsigned int params_input; - CHECK_CUDA_ERROR( - cudaMemcpy(¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); - CHECK_CUDA_ERROR(cudaMemcpy( - points_d_.get(), points.data(), count * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice)); - - EXPECT_EQ(config_ptr_->max_voxels_, params_input); -} - -} // namespace lidar_transfusion - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/perception/lidar_transfusion/test/test_preprocess_kernel.hpp b/perception/lidar_transfusion/test/test_preprocess_kernel.hpp deleted file mode 100644 index 024fae5eae4b1..0000000000000 --- a/perception/lidar_transfusion/test/test_preprocess_kernel.hpp +++ /dev/null @@ -1,50 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef TEST_PREPROCESS_KERNEL_HPP_ -#define TEST_PREPROCESS_KERNEL_HPP_ - -#include -#include - -#include - -#include - -namespace lidar_transfusion -{ - -class PreprocessKernelTest : public testing::Test -{ -public: - void SetUp() override; - void TearDown() override; - - std::unique_ptr pre_ptr_{nullptr}; - std::unique_ptr config_ptr_{}; - cudaStream_t stream_{}; - - unsigned int voxel_features_size_{0}; - unsigned int voxel_num_size_{0}; - unsigned int voxel_idxs_size_{0}; - cuda::unique_ptr points_d_{nullptr}; - cuda::unique_ptr params_input_d_{nullptr}; - cuda::unique_ptr voxel_features_d_{nullptr}; - cuda::unique_ptr voxel_num_d_{nullptr}; - cuda::unique_ptr voxel_idxs_d_{nullptr}; -}; - -} // namespace lidar_transfusion - -#endif // TEST_PREPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/test/test_ros_utils.cpp b/perception/lidar_transfusion/test/test_ros_utils.cpp deleted file mode 100644 index 15541e6353b42..0000000000000 --- a/perception/lidar_transfusion/test/test_ros_utils.cpp +++ /dev/null @@ -1,104 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "lidar_transfusion/ros_utils.hpp" - -#include - -TEST(TestSuite, box3DToDetectedObject) -{ - std::vector class_names = {"CAR", "TRUCK", "BUS", "TRAILER", - "BICYCLE", "MOTORCYCLE", "PEDESTRIAN"}; - - // Test case 1: Test with valid label - { - lidar_transfusion::Box3D box3d; - box3d.label = 0; // CAR - box3d.score = 0.8f; - box3d.x = 1.0; - box3d.y = 2.0; - box3d.z = 3.0; - box3d.width = 2.0; - box3d.height = 1.5; - box3d.length = 4.0; - box3d.yaw = 0.5; - - autoware_perception_msgs::msg::DetectedObject obj; - lidar_transfusion::box3DToDetectedObject(box3d, class_names, obj); - - EXPECT_FLOAT_EQ(obj.existence_probability, 0.8f); - EXPECT_EQ( - obj.classification[0].label, autoware_perception_msgs::msg::ObjectClassification::CAR); - EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.x, 1.0); - EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.y, 2.0); - EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.z, 3.0); - EXPECT_FLOAT_EQ(obj.shape.dimensions.x, 4.0); - EXPECT_FLOAT_EQ(obj.shape.dimensions.y, 2.0); - EXPECT_FLOAT_EQ(obj.shape.dimensions.z, 1.5); - EXPECT_FALSE(obj.kinematics.has_position_covariance); - EXPECT_FALSE(obj.kinematics.has_twist); - EXPECT_FALSE(obj.kinematics.has_twist_covariance); - } - - // Test case 2: Test with invalid label - { - lidar_transfusion::Box3D box3d; - box3d.score = 0.5f; - box3d.label = 10; // Invalid - - autoware_perception_msgs::msg::DetectedObject obj; - lidar_transfusion::box3DToDetectedObject(box3d, class_names, obj); - - EXPECT_FLOAT_EQ(obj.existence_probability, 0.5f); - EXPECT_EQ( - obj.classification[0].label, autoware_perception_msgs::msg::ObjectClassification::UNKNOWN); - EXPECT_FALSE(obj.kinematics.has_position_covariance); - EXPECT_FALSE(obj.kinematics.has_twist); - EXPECT_FALSE(obj.kinematics.has_twist_covariance); - } -} - -TEST(TestSuite, getSemanticType) -{ - EXPECT_EQ( - lidar_transfusion::getSemanticType("CAR"), - autoware_perception_msgs::msg::ObjectClassification::CAR); - EXPECT_EQ( - lidar_transfusion::getSemanticType("TRUCK"), - autoware_perception_msgs::msg::ObjectClassification::TRUCK); - EXPECT_EQ( - lidar_transfusion::getSemanticType("BUS"), - autoware_perception_msgs::msg::ObjectClassification::BUS); - EXPECT_EQ( - lidar_transfusion::getSemanticType("TRAILER"), - autoware_perception_msgs::msg::ObjectClassification::TRAILER); - EXPECT_EQ( - lidar_transfusion::getSemanticType("MOTORCYCLE"), - autoware_perception_msgs::msg::ObjectClassification::MOTORCYCLE); - EXPECT_EQ( - lidar_transfusion::getSemanticType("BICYCLE"), - autoware_perception_msgs::msg::ObjectClassification::BICYCLE); - EXPECT_EQ( - lidar_transfusion::getSemanticType("PEDESTRIAN"), - autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN); - EXPECT_EQ( - lidar_transfusion::getSemanticType("UNKNOWN"), - autoware_perception_msgs::msg::ObjectClassification::UNKNOWN); -} - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/perception/lidar_transfusion/test/test_voxel_generator.cpp b/perception/lidar_transfusion/test/test_voxel_generator.cpp deleted file mode 100644 index 2673a341b3721..0000000000000 --- a/perception/lidar_transfusion/test/test_voxel_generator.cpp +++ /dev/null @@ -1,284 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "test_voxel_generator.hpp" - -#include "gtest/gtest.h" -#include "lidar_transfusion/transfusion_config.hpp" -#include "lidar_transfusion/utils.hpp" - -#include - -#include "sensor_msgs/point_cloud2_iterator.hpp" - -namespace lidar_transfusion -{ - -void VoxelGeneratorTest::SetUp() -{ - // Setup things that should occur before every test instance should go here - node_ = std::make_shared("voxel_generator_test_node"); - - world_frame_ = "map"; - lidar_frame_ = "lidar"; - delta_pointcloud_x_ = 1.0; - points_per_pointcloud_ = 300; - - voxels_num_ = std::vector{5000, 30000, 60000}; - point_cloud_range_ = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; - voxel_size_ = std::vector{0.3, 0.3, 8.0}; - score_threshold_ = 0.2f; - circle_nms_dist_threshold_ = 0.5f; - yaw_norm_thresholds_ = std::vector{0.5, 0.5, 0.5}; - config_ptr_ = std::make_unique( - voxels_num_, point_cloud_range_, voxel_size_, circle_nms_dist_threshold_, yaw_norm_thresholds_, - score_threshold_); - - cloud1_ = std::make_unique(); - cloud2_ = std::make_unique(); - - // Set up the fields - point_cloud_msg_wrapper::PointCloud2Modifier< - autoware_point_types::PointXYZIRCAEDT, autoware_point_types::PointXYZIRCAEDTGenerator> - modifier{*cloud1_, lidar_frame_}; - - // Resize the cloud to hold points_per_pointcloud_ points - modifier.resize(points_per_pointcloud_); - - // Create an iterator for desired fields - sensor_msgs::PointCloud2Iterator iter_x(*cloud1_, "x"); - sensor_msgs::PointCloud2Iterator iter_y(*cloud1_, "y"); - sensor_msgs::PointCloud2Iterator iter_z(*cloud1_, "z"); - sensor_msgs::PointCloud2Iterator iter_i(*cloud1_, "intensity"); - - // Populate the point cloud - for (size_t i = 0; i < modifier.size(); ++i, ++iter_x, ++iter_y, ++iter_z) { - *iter_x = static_cast(i); - *iter_y = static_cast(i); - *iter_z = static_cast(i); - } - for (size_t i = 0; i < modifier.size(); ++i, ++iter_i) { - *iter_i = static_cast(i % 256); - } - - *cloud2_ = *cloud1_; - - // Set the stamps for the point clouds. They usually come every 100ms - cloud1_->header.stamp.sec = 1; - cloud1_->header.stamp.nanosec = 100'000'000; - cloud2_->header.stamp.sec = 1; - cloud2_->header.stamp.nanosec = 200'000'000; - - tf2_buffer_ = std::make_unique(node_->get_clock()); - tf2_buffer_->setUsingDedicatedThread(true); - - // The vehicle moves 1m/s in the x direction - const double world_origin_x = 6'371'000.0; - const double world_origin_y = 1'371'000.0; - - transform1_.header.stamp = cloud1_->header.stamp; - transform1_.header.frame_id = world_frame_; - transform1_.child_frame_id = lidar_frame_; - transform1_.transform.translation.x = world_origin_x; - transform1_.transform.translation.y = world_origin_y; - transform1_.transform.translation.z = 1.8; - transform1_.transform.rotation.x = 0.0; - transform1_.transform.rotation.y = 0.0; - transform1_.transform.rotation.z = 0.0; - transform1_.transform.rotation.w = 1.0; - - transform2_ = transform1_; - transform2_.header.stamp = cloud2_->header.stamp; - transform2_.transform.translation.x = world_origin_x + delta_pointcloud_x_; - - cudaStreamCreate(&stream_); -} - -void VoxelGeneratorTest::TearDown() -{ -} - -TEST_F(VoxelGeneratorTest, CloudInfo) -{ - CloudInfo cloud_info{}; - EXPECT_EQ(cloud1_->is_bigendian, cloud_info.is_bigendian); - EXPECT_EQ(cloud1_->fields[0].name, "x"); - EXPECT_EQ(cloud1_->fields[0].datatype, cloud_info.x_datatype); - EXPECT_EQ(cloud1_->fields[0].count, cloud_info.x_count); - EXPECT_EQ(cloud1_->fields[0].offset, cloud_info.x_offset); - EXPECT_EQ(cloud1_->fields[1].name, "y"); - EXPECT_EQ(cloud1_->fields[1].datatype, cloud_info.y_datatype); - EXPECT_EQ(cloud1_->fields[1].count, cloud_info.y_count); - EXPECT_EQ(cloud1_->fields[1].offset, cloud_info.y_offset); - EXPECT_EQ(cloud1_->fields[2].name, "z"); - EXPECT_EQ(cloud1_->fields[2].datatype, cloud_info.z_datatype); - EXPECT_EQ(cloud1_->fields[2].count, cloud_info.z_count); - EXPECT_EQ(cloud1_->fields[2].offset, cloud_info.z_offset); - EXPECT_EQ(cloud1_->fields[3].name, "intensity"); - EXPECT_EQ(cloud1_->fields[3].datatype, cloud_info.intensity_datatype); - EXPECT_EQ(cloud1_->fields[3].count, cloud_info.intensity_count); - EXPECT_EQ(cloud1_->fields[3].offset, cloud_info.intensity_offset); - EXPECT_EQ(cloud1_->width, points_per_pointcloud_); - EXPECT_EQ(cloud1_->height, 1); -} - -TEST_F(VoxelGeneratorTest, SingleFrame) -{ - const unsigned int num_past_frames = 0; // only current frame - DensificationParam param(world_frame_, num_past_frames); - VoxelGenerator voxel_generator(param, *config_ptr_, stream_); - std::vector points; - points.resize(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - std::fill(points.begin(), points.end(), std::nan("")); - - auto points_d = - cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - cudaMemcpy( - points_d.get(), points.data(), - points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice); - - bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); - std::size_t generated_points_num = voxel_generator.generateSweepPoints(*cloud1_, points_d); - - cudaMemcpy( - points.data(), points_d.get(), - points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyDeviceToHost); - - EXPECT_TRUE(status1); - EXPECT_EQ(generated_points_num, points_per_pointcloud_); - - // Check valid points - for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { - // There are no tf conversions - EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 0]); - EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 1]); - EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 2]); - EXPECT_EQ(static_cast(i % 256), points[i * config_ptr_->num_point_feature_size_ + 3]); - EXPECT_EQ(static_cast(0), points[i * config_ptr_->num_point_feature_size_ + 4]); - } - - // Check invalid points - for (std::size_t i = points_per_pointcloud_ * config_ptr_->num_point_feature_size_; - i < points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * 2; ++i) { - EXPECT_TRUE(std::isnan(points[i])); - } -} - -TEST_F(VoxelGeneratorTest, TwoFramesNoTf) -{ - const unsigned int num_past_frames = 1; - DensificationParam param(world_frame_, num_past_frames); - VoxelGenerator voxel_generator(param, *config_ptr_, stream_); - std::vector points; - points.resize(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - std::fill(points.begin(), points.end(), std::nan("")); - - auto points_d = - cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - cudaMemcpy( - points_d.get(), points.data(), - points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice); - - bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); - bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); - std::size_t generated_points_num = voxel_generator.generateSweepPoints(*cloud1_, points_d); - - cudaMemcpy( - points.data(), points_d.get(), - points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyDeviceToHost); - - EXPECT_FALSE(status1); - EXPECT_FALSE(status2); - EXPECT_EQ(0, generated_points_num); -} - -TEST_F(VoxelGeneratorTest, TwoFrames) -{ - const unsigned int num_past_frames = 1; - DensificationParam param(world_frame_, num_past_frames); - VoxelGenerator voxel_generator(param, *config_ptr_, stream_); - std::vector points; - points.resize(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - std::fill(points.begin(), points.end(), std::nan("")); - - auto points_d = - cuda::make_unique(config_ptr_->cloud_capacity_ * config_ptr_->num_point_feature_size_); - cudaMemcpy( - points_d.get(), points.data(), - 2 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice); - - tf2_buffer_->setTransform(transform1_, "authority1"); - tf2_buffer_->setTransform(transform2_, "authority1"); - - bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); - bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); - std::size_t generated_points_num = voxel_generator.generateSweepPoints(*cloud1_, points_d); - - cudaMemcpy( - points.data(), points_d.get(), - 2 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_ * sizeof(float), - cudaMemcpyDeviceToHost); - - EXPECT_TRUE(status1); - EXPECT_TRUE(status2); - EXPECT_EQ(2 * points_per_pointcloud_, generated_points_num); - - // Check valid points for the latest pointcloud - for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { - // There are no tf conversions - EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 0]); - EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 1]); - EXPECT_EQ(static_cast(i), points[i * config_ptr_->num_point_feature_size_ + 2]); - EXPECT_EQ(static_cast(i % 256), points[i * config_ptr_->num_point_feature_size_ + 3]); - EXPECT_EQ(static_cast(0), points[i * config_ptr_->num_point_feature_size_ + 4]); - } - - // Check valid points for the oldest pointcloud - for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { - // There are tf conversions, so results are not numerically the same - EXPECT_NEAR( - static_cast(i) - delta_pointcloud_x_, - points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 0], 1e-6); - EXPECT_NEAR( - static_cast(i), - points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 1], 1e-6); - EXPECT_NEAR( - static_cast(i), - points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 2], 1e-6); - EXPECT_NEAR( - static_cast(i % 256), - points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 3], 1e-6); - EXPECT_NEAR( - 0.1, points[(points_per_pointcloud_ + i) * config_ptr_->num_point_feature_size_ + 4], 1e-6); - } - - // Check invalid points - for (std::size_t i = 2 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_; - i < 3 * points_per_pointcloud_ * config_ptr_->num_point_feature_size_; ++i) { - EXPECT_TRUE(std::isnan(points[i])); - } -} -} // namespace lidar_transfusion - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - rclcpp::init(argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/perception/lidar_transfusion/test/test_voxel_generator.hpp b/perception/lidar_transfusion/test/test_voxel_generator.hpp deleted file mode 100644 index eccbe6412d183..0000000000000 --- a/perception/lidar_transfusion/test/test_voxel_generator.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef TEST_VOXEL_GENERATOR_HPP_ -#define TEST_VOXEL_GENERATOR_HPP_ - -#include -#include - -#include - -#include - -#include -#include -#include - -namespace lidar_transfusion -{ - -class VoxelGeneratorTest : public testing::Test -{ -public: - void SetUp() override; - void TearDown() override; - - // These need to be public so that they can be accessed in the test cases - rclcpp::Node::SharedPtr node_{}; - - std::unique_ptr cloud1_{}, cloud2_{}; - geometry_msgs::msg::TransformStamped transform1_{}, transform2_{}; - - std::unique_ptr densification_param_ptr_{}; - std::unique_ptr config_ptr_{}; - - std::unique_ptr tf2_buffer_{}; - - std::string world_frame_{}; - std::string lidar_frame_{}; - double delta_pointcloud_x_{}; - std::size_t points_per_pointcloud_{}; - - std::vector voxels_num_{}; - std::vector point_cloud_range_{}; - std::vector voxel_size_{}; - float circle_nms_dist_threshold_{}; - std::vector yaw_norm_thresholds_{}; - float score_threshold_{}; - - cudaStream_t stream_{}; -}; -} // namespace lidar_transfusion - -#endif // TEST_VOXEL_GENERATOR_HPP_ From d73a09a26317ebbe86f0a40662f90e6e850623ac Mon Sep 17 00:00:00 2001 From: SHtokuda <165623782+shtokuda@users.noreply.github.com> Date: Fri, 9 Aug 2024 19:38:06 +0900 Subject: [PATCH 105/151] feat(autoware_vehicle_cmd_gate): check the timestamp of input topics to avoid using old topics (#8084) * add prev_commands_ and check cmd's time stamp Signed-off-by: shtokuda * add timestamp when is_engaged is false Signed-off-by: shtokuda * style(pre-commit): autofix * add initialization for hazard_light timestamp in Commands Signed-off-by: shtokuda * style(pre-commit): autofix * update README.md Signed-off-by: shtokuda * style(pre-commit): autofix * fix typo Signed-off-by: shtokuda * fix(autoware_vehicle_cmd_gate): rename the function that checks the continuity of topics Signed-off-by: shtokuda Co-authored-by: Takamasa Horibe * style(pre-commit): autofix * feat(autoware_vehicle_cmd_gate): check continuity using shared_ptr Signed-off-by: shtokuda * feat(autoware_vehicle_cmd_gate): add INFO message for topics that are not receiving Signed-off-by: shtokuda * fix template function to pass build-and-test-differential Signed-off-by: shtokuda * fix(autoware_vehicle_cmd_gate): add #include according to pre-commit.ci Signed-off-by: shtokuda * fix(vehicle_cmd_gate) add underscores to member variable names for consistency Signed-off-by: shtokuda * style(pre-commit): autofix --------- Signed-off-by: shtokuda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> --- control/autoware_vehicle_cmd_gate/README.md | 7 +++ .../src/vehicle_cmd_gate.cpp | 59 +++++++++++++++++-- .../src/vehicle_cmd_gate.hpp | 10 ++++ 3 files changed, 72 insertions(+), 4 deletions(-) diff --git a/control/autoware_vehicle_cmd_gate/README.md b/control/autoware_vehicle_cmd_gate/README.md index e46db3c06cfeb..336c1acbe9bae 100644 --- a/control/autoware_vehicle_cmd_gate/README.md +++ b/control/autoware_vehicle_cmd_gate/README.md @@ -84,6 +84,13 @@ This functionality for starting/stopping was embedded in the source code but was ## Assumptions / Known limits +### External Emergency Heartbeat + The parameter `check_external_emergency_heartbeat` (true by default) enables an emergency stop request from external modules. This feature requires a `~/input/external_emergency_stop_heartbeat` topic for health monitoring of the external module, and the vehicle_cmd_gate module will not start without the topic. The `check_external_emergency_heartbeat` parameter must be false when the "external emergency stop" function is not used. + +### Commands on Mode changes + +Output commands' topics: `turn_indicators_cmd`, `hazard_light` and `gear_cmd` are selected based on `gate_mode`. +However, to ensure the continuity of commands, these commands will not change until the topics of new input commands arrive, even if a mode change occurs. diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index dd6e2f0f54aea..a02ab010e8cea 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -53,6 +53,10 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) using std::placeholders::_2; using std::placeholders::_3; + prev_turn_indicator_ = nullptr; + prev_hazard_light_ = nullptr; + prev_gear_ = nullptr; + rclcpp::QoS durable_qos{1}; durable_qos.transient_local(); @@ -352,6 +356,21 @@ void VehicleCmdGate::onEmergencyCtrlCmd(Control::ConstSharedPtr msg) } } +// check the continuity of topics +template +T VehicleCmdGate::getContinuousTopic( + const std::shared_ptr & prev_topic, const T & current_topic, const std::string & topic_name) +{ + if ((rclcpp::Time(current_topic.stamp) - rclcpp::Time(prev_topic->stamp)).seconds() > 0.0) { + return current_topic; + } else { + RCLCPP_INFO( + get_logger(), + "The operation mode is changed, but the %s is not received yet:", topic_name.c_str()); + return *prev_topic; + } +} + void VehicleCmdGate::onTimer() { // Subscriber for auto @@ -447,6 +466,8 @@ void VehicleCmdGate::onTimer() if (!is_engaged_) { turn_indicator.command = TurnIndicatorsCommand::NO_COMMAND; hazard_light.command = HazardLightsCommand::NO_COMMAND; + turn_indicator.stamp = this->now(); + hazard_light.stamp = this->now(); } } else if (current_gate_mode_.data == GateMode::EXTERNAL) { turn_indicator = remote_commands_.turn_indicator; @@ -457,10 +478,40 @@ void VehicleCmdGate::onTimer() } } - // Publish topics - turn_indicator_cmd_pub_->publish(turn_indicator); - hazard_light_cmd_pub_->publish(hazard_light); - gear_cmd_pub_->publish(gear); + // Publish Turn Indicators, Hazard Lights and Gear Command + if (prev_turn_indicator_ != nullptr) { + *prev_turn_indicator_ = + getContinuousTopic(prev_turn_indicator_, turn_indicator, "TurnIndicatorsCommand"); + turn_indicator_cmd_pub_->publish(*prev_turn_indicator_); + } else { + if (msg_auto_command_turn_indicator || msg_remote_command_turn_indicator) { + prev_turn_indicator_ = std::make_shared(turn_indicator); + } + turn_indicator_cmd_pub_->publish(turn_indicator); + } + + if (prev_hazard_light_ != nullptr) { + *prev_hazard_light_ = + getContinuousTopic(prev_hazard_light_, hazard_light, "HazardLightsCommand"); + hazard_light_cmd_pub_->publish(*prev_hazard_light_); + } else { + if ( + msg_auto_command_hazard_light || msg_remote_command_hazard_light || + msg_emergency_command_hazard_light) { + prev_hazard_light_ = std::make_shared(hazard_light); + } + hazard_light_cmd_pub_->publish(hazard_light); + } + + if (prev_gear_ != nullptr) { + *prev_gear_ = getContinuousTopic(prev_gear_, gear, "GearCommand"); + gear_cmd_pub_->publish(*prev_gear_); + } else { + if (msg_auto_command_gear || msg_remote_command_gear || msg_emergency_command_gear) { + prev_gear_ = std::make_shared(gear); + } + gear_cmd_pub_->publish(gear); + } } void VehicleCmdGate::publishControlCommands(const Commands & commands) diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 42e28d633d16b..3f74be72be9dc 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -50,6 +50,7 @@ #include #include +#include #include namespace autoware::vehicle_cmd_gate @@ -183,6 +184,11 @@ class VehicleCmdGate : public rclcpp::Node this, "input/emergency/gear_cmd"}; void onEmergencyCtrlCmd(Control::ConstSharedPtr msg); + // Previous Turn Indicators, Hazard Lights and Gear + TurnIndicatorsCommand::SharedPtr prev_turn_indicator_; + HazardLightsCommand::SharedPtr prev_hazard_light_; + GearCommand::SharedPtr prev_gear_; + // Parameter bool use_emergency_handling_; bool check_external_emergency_heartbeat_; @@ -232,6 +238,10 @@ class VehicleCmdGate : public rclcpp::Node void checkExternalEmergencyStop(diagnostic_updater::DiagnosticStatusWrapper & stat); + template + T getContinuousTopic( + const std::shared_ptr & prev_topic, const T & current_topic, const std::string & topic_name); + // Algorithm Control prev_control_cmd_; Control createStopControlCmd() const; From 60b733af0d11f4a9e883e5ec43964b02dfb738bb Mon Sep 17 00:00:00 2001 From: SHtokuda <165623782+shtokuda@users.noreply.github.com> Date: Fri, 16 Aug 2024 09:56:02 +0900 Subject: [PATCH 106/151] feat(autoware_vehicle_cmd_gate): accept same topic unless mode change occurs (#8479) * add prev_commands_ and check cmd's time stamp Signed-off-by: shtokuda * add timestamp when is_engaged is false Signed-off-by: shtokuda * style(pre-commit): autofix * add initialization for hazard_light timestamp in Commands Signed-off-by: shtokuda * style(pre-commit): autofix * update README.md Signed-off-by: shtokuda * style(pre-commit): autofix * fix typo Signed-off-by: shtokuda * fix(autoware_vehicle_cmd_gate): rename the function that checks the continuity of topics Signed-off-by: shtokuda Co-authored-by: Takamasa Horibe * style(pre-commit): autofix * feat(autoware_vehicle_cmd_gate): check continuity using shared_ptr Signed-off-by: shtokuda * feat(autoware_vehicle_cmd_gate): add INFO message for topics that are not receiving Signed-off-by: shtokuda * fix template function to pass build-and-test-differential Signed-off-by: shtokuda * fix(autoware_vehicle_cmd_gate): add #include according to pre-commit.ci Signed-off-by: shtokuda * fix(vehicle_cmd_gate) add underscores to member variable names for consistency Signed-off-by: shtokuda * style(pre-commit): autofix * feat(vehicle_cmd_gate): accept same topic unless mode change occurs Signed-off-by: shtokuda * feat(vehicle_cmd_gate): add default topic_name to getContinuousTopic function Signed-off-by: shtokuda --------- Signed-off-by: shtokuda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> --- .../autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 10 ++++++---- .../autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 3 ++- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index a02ab010e8cea..b26a2630ed994 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -361,12 +361,14 @@ template T VehicleCmdGate::getContinuousTopic( const std::shared_ptr & prev_topic, const T & current_topic, const std::string & topic_name) { - if ((rclcpp::Time(current_topic.stamp) - rclcpp::Time(prev_topic->stamp)).seconds() > 0.0) { + if ((rclcpp::Time(current_topic.stamp) - rclcpp::Time(prev_topic->stamp)).seconds() >= 0.0) { return current_topic; } else { - RCLCPP_INFO( - get_logger(), - "The operation mode is changed, but the %s is not received yet:", topic_name.c_str()); + if (topic_name != "") { + RCLCPP_INFO( + get_logger(), + "The operation mode is changed, but the %s is not received yet:", topic_name.c_str()); + } return *prev_topic; } } diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 3f74be72be9dc..279bc6036bd34 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -240,7 +240,8 @@ class VehicleCmdGate : public rclcpp::Node template T getContinuousTopic( - const std::shared_ptr & prev_topic, const T & current_topic, const std::string & topic_name); + const std::shared_ptr & prev_topic, const T & current_topic, + const std::string & topic_name = ""); // Algorithm Control prev_control_cmd_; From a4b44596e81ec6135c008e2fd21b4ac6afcbfd63 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 20 Aug 2024 20:04:02 +0900 Subject: [PATCH 107/151] feat(intersection): fix topological sort for complicated intersection (#8520) * for enclave occlusion detection lanelet Signed-off-by: Mamoru Sobue * some refactorings and modify doxygen Signed-off-by: Y.Hisaki * fix ci Signed-off-by: Mamoru Sobue --------- Signed-off-by: Mamoru Sobue Signed-off-by: Y.Hisaki Co-authored-by: Y.Hisaki --- .../CMakeLists.txt | 10 + .../package.xml | 2 + .../src/scene_intersection.hpp | 3 +- .../src/scene_intersection_prepare_data.cpp | 100 +- .../src/util.cpp | 156 +- .../src/util.hpp | 28 +- .../test/test_util.cpp | 111 + .../test_map/intersection/lanelet2_map.osm | 19869 ++++++++++++++++ 8 files changed, 20179 insertions(+), 100 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt index f3b31001978e9..167c7182e8f05 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt @@ -28,6 +28,16 @@ target_link_libraries(${PROJECT_NAME} ament_auto_package(INSTALL_TO_SHARE config) +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + ${TEST_SOURCES} + ) + target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) +endif() + install(PROGRAMS scripts/ttc.py DESTINATION lib/${PROJECT_NAME} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index e240722e66a5b..bad8e1b1ecf26 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -24,6 +24,7 @@ autoware_planning_msgs autoware_route_handler autoware_rtc_interface + autoware_test_utils autoware_universe_utils autoware_vehicle_info_utils fmt @@ -39,6 +40,7 @@ tier4_planning_msgs visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index ea2e1a7ae16d7..e3879cc6acdef 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -590,7 +590,8 @@ class IntersectionModule : public SceneModuleInterface * @brief generate discretized detection lane linestring. */ std::vector generateDetectionLaneDivisions( - lanelet::ConstLanelets detection_lanelets, + const lanelet::ConstLanelets & occlusion_detection_lanelets, + const lanelet::ConstLanelets & conflicting_detection_lanelets, const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) const; /** @} */ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index 1390104d98175..5c6c0bc8d38ab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -266,8 +266,8 @@ Result IntersectionModule::prepare if (!occlusion_attention_divisions_) { occlusion_attention_divisions_ = generateDetectionLaneDivisions( - intersection_lanelets.occlusion_attention(), routing_graph_ptr, - planner_data_->occupancy_grid->info.resolution); + intersection_lanelets.occlusion_attention(), intersection_lanelets.attention_non_preceding(), + routing_graph_ptr, planner_data_->occupancy_grid->info.resolution); } if (has_traffic_light_) { @@ -577,6 +577,73 @@ std::optional IntersectionModule::generateIntersectionSto return intersection_stoplines; } +static std::vector> getPrecedingLaneletsUptoIntersectionRecursive( + const lanelet::routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet, + const double length, const lanelet::ConstLanelets & exclude_lanelets) +{ + std::vector> preceding_lanelet_sequences; + + const auto prev_lanelets = graph->previous(lanelet); + const double lanelet_length = lanelet::utils::getLaneletLength3d(lanelet); + + // end condition of the recursive function + if (prev_lanelets.empty() || lanelet_length >= length) { + preceding_lanelet_sequences.push_back({lanelet}); + return preceding_lanelet_sequences; + } + + for (const auto & prev_lanelet : prev_lanelets) { + if (lanelet::utils::contains(exclude_lanelets, prev_lanelet)) { + // if prev_lanelet is included in exclude_lanelets, + // remove prev_lanelet from preceding_lanelet_sequences + continue; + } + if (const std::string turn_direction = prev_lanelet.attributeOr("turn_direction", "else"); + turn_direction == "left" || turn_direction == "right") { + continue; + } + + // get lanelet sequence after prev_lanelet + auto tmp_lanelet_sequences = getPrecedingLaneletsUptoIntersectionRecursive( + graph, prev_lanelet, length - lanelet_length, exclude_lanelets); + for (auto & tmp_lanelet_sequence : tmp_lanelet_sequences) { + tmp_lanelet_sequence.push_back(lanelet); + preceding_lanelet_sequences.push_back(tmp_lanelet_sequence); + } + } + + if (preceding_lanelet_sequences.empty()) { + preceding_lanelet_sequences.push_back({lanelet}); + } + return preceding_lanelet_sequences; +} + +static std::vector getPrecedingLaneletsUptoIntersection( + const lanelet::routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet, + const double length, const lanelet::ConstLanelets & exclude_lanelets) +{ + std::vector lanelet_sequences_vec; + const auto prev_lanelets = graph->previous(lanelet); + for (const auto & prev_lanelet : prev_lanelets) { + if (lanelet::utils::contains(exclude_lanelets, prev_lanelet)) { + // if prev_lanelet is included in exclude_lanelets, + // remove prev_lanelet from preceding_lanelet_sequences + continue; + } + if (const std::string turn_direction = prev_lanelet.attributeOr("turn_direction", "else"); + turn_direction == "left" || turn_direction == "right") { + continue; + } + // convert deque into vector + const auto lanelet_sequences_deq = + getPrecedingLaneletsUptoIntersectionRecursive(graph, prev_lanelet, length, exclude_lanelets); + for (const auto & lanelet_sequence : lanelet_sequences_deq) { + lanelet_sequences_vec.emplace_back(lanelet_sequence.begin(), lanelet_sequence.end()); + } + } + return lanelet_sequences_vec; +} + IntersectionLanelets IntersectionModule::generateObjectiveLanelets( lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, const lanelet::ConstLanelet assigned_lanelet) const @@ -706,8 +773,8 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets( if (inserted.second) occlusion_detection_and_preceding_lanelets.push_back(ll); // get preceding lanelets without ego_lanelets // to prevent the detection area from including the ego lanes and its' preceding lanes. - const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences( - routing_graph_ptr, ll, length, ego_lanelets); + const auto lanelet_sequences = + getPrecedingLaneletsUptoIntersection(routing_graph_ptr, ll, length, ego_lanelets); for (const auto & ls : lanelet_sequences) { for (const auto & l : ls) { const auto & inserted = detection_ids.insert(l.id()); @@ -716,17 +783,10 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets( } } } - lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets_wo_turn_direction; - for (const auto & ll : occlusion_detection_and_preceding_lanelets) { - const std::string turn_direction = ll.attributeOr("turn_direction", "else"); - if (turn_direction == "left" || turn_direction == "right") { - continue; - } - occlusion_detection_and_preceding_lanelets_wo_turn_direction.push_back(ll); - } auto [attention_lanelets, original_attention_lanelet_sequences] = - util::mergeLaneletsByTopologicalSort(detection_and_preceding_lanelets, routing_graph_ptr); + util::mergeLaneletsByTopologicalSort( + detection_and_preceding_lanelets, detection_lanelets, routing_graph_ptr); IntersectionLanelets result; result.attention_ = std::move(attention_lanelets); @@ -764,8 +824,7 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets( // NOTE: occlusion_attention is not inverted here // TODO(Mamoru Sobue): apply mergeLaneletsByTopologicalSort for occlusion lanelets as well and // then trim part of them based on curvature threshold - result.occlusion_attention_ = - std::move(occlusion_detection_and_preceding_lanelets_wo_turn_direction); + result.occlusion_attention_ = std::move(occlusion_detection_and_preceding_lanelets); // NOTE: to properly update(), each element in conflicting_/conflicting_area_, // attention_non_preceding_/attention_non_preceding_area_ need to be matched @@ -851,7 +910,8 @@ std::optional IntersectionModule::generatePathLanelets( } std::vector IntersectionModule::generateDetectionLaneDivisions( - lanelet::ConstLanelets detection_lanelets_all, + const lanelet::ConstLanelets & occlusion_detection_lanelets, + const lanelet::ConstLanelets & conflicting_detection_lanelets, const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) const { const double curvature_threshold = @@ -861,9 +921,9 @@ std::vector IntersectionModule::generateDetectionLan using lanelet::utils::getCenterlineWithOffset; - // (0) remove left/right lanelet + // (0) remove curved lanelet::ConstLanelets detection_lanelets; - for (const auto & detection_lanelet : detection_lanelets_all) { + for (const auto & detection_lanelet : occlusion_detection_lanelets) { // TODO(Mamoru Sobue): instead of ignoring, only trim straight part of lanelet const auto fine_centerline = lanelet::utils::generateFineCenterline(detection_lanelet, curvature_calculation_ds); @@ -875,8 +935,8 @@ std::vector IntersectionModule::generateDetectionLan } // (1) tsort detection_lanelets - const auto [merged_detection_lanelets, originals] = - util::mergeLaneletsByTopologicalSort(detection_lanelets, routing_graph_ptr); + const auto [merged_detection_lanelets, originals] = util::mergeLaneletsByTopologicalSort( + detection_lanelets, conflicting_detection_lanelets, routing_graph_ptr); // (2) merge each branch to one lanelet // NOTE: somehow bg::area() for merged lanelet does not work, so calculate it here diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp index 893ec646dba73..66a3264a85b58 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -32,12 +32,10 @@ #include #include -#include -#include -#include #include #include #include +#include #include namespace autoware::behavior_velocity_planner::util @@ -214,98 +212,106 @@ std::optional getFirstPointInsidePolygon( } return std::nullopt; } +std::vector> retrievePathsBackward( + const std::vector> & adjacency, size_t start_node) +{ + std::vector> paths; + std::vector current_path; + std::unordered_set visited; + + std::function retrieve_paths_backward_impl = [&](size_t src_ind) { + current_path.push_back(src_ind); + visited.insert(src_ind); + + bool is_terminal = true; + const auto & nexts = adjacency[src_ind]; + + for (size_t next = 0; next < nexts.size(); ++next) { + if (nexts[next]) { + is_terminal = false; + if (visited.find(next) == visited.end()) { + retrieve_paths_backward_impl(next); + } else { + // Loop detected + paths.push_back(current_path); + } + } + } + + if (is_terminal) { + paths.push_back(current_path); + } + + current_path.pop_back(); + visited.erase(src_ind); + }; + + retrieve_paths_backward_impl(start_node); + return paths; +} std::pair> mergeLaneletsByTopologicalSort( - const lanelet::ConstLanelets & lanelets, + const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & terminal_lanelets, const lanelet::routing::RoutingGraphPtr routing_graph_ptr) { - const int n_node = lanelets.size(); - std::vector> adjacency(n_node); - for (int dst = 0; dst < n_node; ++dst) { - adjacency[dst].resize(n_node); - for (int src = 0; src < n_node; ++src) { - adjacency[dst][src] = false; - } - } - std::set lanelet_ids; - std::unordered_map id2ind; - std::unordered_map ind2id; - std::unordered_map id2lanelet; - int ind = 0; + std::set lanelet_Ids; + std::unordered_map Id2ind; + std::unordered_map ind2Id; + std::unordered_map Id2lanelet; for (const auto & lanelet : lanelets) { - lanelet_ids.insert(lanelet.id()); - const auto id = lanelet.id(); - id2ind[id] = ind; - ind2id[ind] = id; - id2lanelet[id] = lanelet; - ind++; + size_t ind = ind2Id.size(); + const auto Id = lanelet.id(); + lanelet_Ids.insert(Id); + Id2ind[Id] = ind; + ind2Id[ind] = Id; + Id2lanelet[Id] = lanelet; } - // NOTE: this function aims to traverse the detection lanelet backward from ego side to farthest - // side, so if lane B follows lane A on the routing_graph, adj[B][A] = true + std::set terminal_inds; + for (const auto & terminal_lanelet : terminal_lanelets) { + terminal_inds.insert(Id2ind[terminal_lanelet.id()]); + } + + // create adjacency matrix + const auto n_node = lanelets.size(); + std::vector> adjacency(n_node, std::vector(n_node, false)); + + // NOTE: this function aims to traverse the detection lanelet in the lane direction, so if lane B + // follows lane A on the routing_graph, adj[A][B] = true for (const auto & lanelet : lanelets) { const auto & followings = routing_graph_ptr->following(lanelet); - const int dst = lanelet.id(); + const auto src = lanelet.id(); for (const auto & following : followings) { - if (const int src = following.id(); lanelet_ids.find(src) != lanelet_ids.end()) { - adjacency[(id2ind[src])][(id2ind[dst])] = true; + if (const auto dst = following.id(); lanelet_Ids.find(dst) != lanelet_Ids.end()) { + adjacency[(Id2ind[dst])][(Id2ind[src])] = true; } } } - // terminal node - std::map> branches; - auto has_no_previous = [&](const int node) { - for (int dst = 0; dst < n_node; dst++) { - if (adjacency[dst][node]) { - return false; - } - } - return true; - }; - for (int src = 0; src < n_node; src++) { - if (!has_no_previous(src)) { - continue; - } - // So `src` has no previous lanelets - branches[(ind2id[src])] = std::vector{}; - auto & branch = branches[(ind2id[src])]; - lanelet::Id node_iter = ind2id[src]; - std::set visited_ids; - while (true) { - const auto & destinations = adjacency[(id2ind[node_iter])]; - // NOTE: assuming detection lanelets have only one "previous"(on the routing_graph) lanelet - const auto next = std::find(destinations.begin(), destinations.end(), true); - if (next == destinations.end()) { - branch.push_back(node_iter); - break; - } - if (visited_ids.find(node_iter) != visited_ids.end()) { - // loop detected - break; - } - branch.push_back(node_iter); - visited_ids.insert(node_iter); - node_iter = ind2id[std::distance(destinations.begin(), next)]; - } + + std::unordered_map>> branches; + for (const auto & terminal_ind : terminal_inds) { + branches[terminal_ind] = retrievePathsBackward(adjacency, terminal_ind); } - for (decltype(branches)::iterator it = branches.begin(); it != branches.end(); it++) { - auto & branch = it->second; - std::reverse(branch.begin(), branch.end()); + + for (auto & [terminal_ind, paths] : branches) { + for (auto & path : paths) { + std::reverse(path.begin(), path.end()); + } } lanelet::ConstLanelets merged; std::vector originals; - for (const auto & [id, sub_ids] : branches) { - if (sub_ids.size() == 0) { + for (const auto & [ind, sub_branches] : branches) { + if (sub_branches.empty()) { continue; } - lanelet::ConstLanelets merge; - originals.push_back(lanelet::ConstLanelets({})); - auto & original = originals.back(); - for (const auto sub_id : sub_ids) { - merge.push_back(id2lanelet[sub_id]); - original.push_back(id2lanelet[sub_id]); + for (const auto & sub_inds : sub_branches) { + lanelet::ConstLanelets to_merge; + for (const auto & sub_ind : sub_inds) { + to_merge.push_back(Id2lanelet[ind2Id[sub_ind]]); + } + originals.push_back(to_merge); + merged.push_back(lanelet::utils::combineLaneletsShape(to_merge)); } - merged.push_back(lanelet::utils::combineLaneletsShape(merge)); } return {merged, originals}; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp index f89d6b0ea67ae..6e15298535291 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -110,15 +110,35 @@ geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( * @brief this function sorts the set of lanelets topologically using topological sort and merges * the lanelets from each root to each end. each branch is merged and returned with the original * lanelets - * @param[in] lanelets the set of lanelets - * @param[in] routing_graph_ptr the routing graph - * @return the pair of merged lanelets and their corresponding original lanelets + * + * @param lanelets The set of input lanelets to be processed + * @param terminal_lanelets The set of lanelets considered as terminal + * @param routing_graph_ptr Pointer to the routing graph used for determining lanelet + * connections + * + * @return A pair containing: + * - First: A vector of merged lanelets, where each element represents a merged lanelet from + * a branch + * - Second: A vector of vectors, where each inner vector contains the original lanelets + * that were merged to form the corresponding merged lanelet */ std::pair> mergeLaneletsByTopologicalSort( - const lanelet::ConstLanelets & lanelets, + const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & terminal_lanelets, const lanelet::routing::RoutingGraphPtr routing_graph_ptr); +/** + * @brief Retrieves all paths from the given source to terminal nodes on the tree + * + * @param adjacency A 2D vector representing the adjacency matrix of the graph + * @param src_ind The index of the current source node being processed + * + * @return A vector of vectors, where each inner vector represents a path from the source node to a + * terminal node. + */ +std::vector> retrievePathsBackward( + const std::vector> & adjacency, size_t start_node); + /** * @brief find the index of the first point where vehicle footprint intersects with the given * polygon diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp new file mode 100644 index 0000000000000..8e27cd223ef80 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp @@ -0,0 +1,111 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// TODO(Mamoru Sobue): create project include dir later +#include "../src/util.hpp" + +#include +#include + +#include + +TEST(TestUtil, retrievePathsBackward) +{ + /* + 0 ----> 1 ----> 2 ----> 4 ----> 6 + ^ \ ^\ + | \ | \ + | 3 ----> 5 | \ + | | <---7 + <------------------| + */ + const std::vector> adjacency = { + {false, true /*1*/, false, false, false, false, false, false}, // 0 + {false, false, true /*2*/, true /*3*/, false, false, false, false}, // 1 + {false, false, false, false, true /*4*/, false, false, false}, // 2 + {false, false, false, false, false, true /*5*/, false, false}, // 3 + {false, false, false, false, false, false, true /*6*/, true /*7*/}, // 4 + {true /* 0*/, false, false, false, false, false, false, false}, // 5 + {false, false, false, false, false, false, false, false}, // 6 + {false, false, false, false, true /*4*/, false, false, false}, // 7 + }; + { + const size_t src_ind = 6; + auto paths = + autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind); + EXPECT_EQ(paths.size(), 1); + EXPECT_EQ(paths.at(0).size(), 1); + EXPECT_EQ(paths.at(0).at(0), 6); + } + { + const size_t src_ind = 4; + auto paths = + autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind); + EXPECT_EQ(paths.size(), 2); + // 4 --> 6 + EXPECT_EQ(paths.at(0).size(), 2); + EXPECT_EQ(paths.at(0).at(0), 4); + EXPECT_EQ(paths.at(0).at(1), 6); + // 4 --> 7 + EXPECT_EQ(paths.at(1).size(), 2); + EXPECT_EQ(paths.at(1).at(0), 4); + EXPECT_EQ(paths.at(1).at(1), 7); + } + { + const size_t src_ind = 0; + auto paths = + autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind); + EXPECT_EQ(paths.size(), 3); + // 0 --> 1 --> 2 --> 4 --> 6 + EXPECT_EQ(paths.at(0).size(), 5); + EXPECT_EQ(paths.at(0).at(0), 0); + EXPECT_EQ(paths.at(0).at(1), 1); + EXPECT_EQ(paths.at(0).at(2), 2); + EXPECT_EQ(paths.at(0).at(3), 4); + EXPECT_EQ(paths.at(0).at(4), 6); + // 0 --> 1 --> 2 --> 4 --> 7 + EXPECT_EQ(paths.at(1).at(0), 0); + EXPECT_EQ(paths.at(1).at(1), 1); + EXPECT_EQ(paths.at(1).at(2), 2); + EXPECT_EQ(paths.at(1).at(3), 4); + EXPECT_EQ(paths.at(1).at(4), 7); + // 0 --> 1 --> 3 --> 5 + EXPECT_EQ(paths.at(2).at(0), 0); + EXPECT_EQ(paths.at(2).at(1), 1); + EXPECT_EQ(paths.at(2).at(2), 3); + EXPECT_EQ(paths.at(2).at(3), 5); + } +} + +/* + TOOD(Mamoru Sobue): instantiating intersection_module and PlannerData is a messy +class TestWithMap : public ::testing::Test +{ +protected: + void SetUp() override + { + const std::string intersection_map_file = autoware_test_utils::get_absolute_path_to_lanelet_map( + "autoware_behavior_velocity_planner_common", "intersection/lanelet2_map.osm"); + const auto map_bin_msg = autoware_test_utils::make_map_bin_msg(intersection_map_file, 0.5); + route_handler_ = std::make_shared(map_bin_msg); + } + +private: + std::shared_ptr route_handler_; +}; + +TEST_F(TestWithMap, mergeLaneletsByTopologicalSort) +{ +} +*/ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm new file mode 100644 index 0000000000000..f6ed497461c2e --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test_map/intersection/lanelet2_map.osm @@ -0,0 +1,19869 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From dc032a1df71659557c4bd92bd350b52f2de63e90 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 21 Aug 2024 20:05:57 +0900 Subject: [PATCH 108/151] fix(intersection): additional fix for 8520 (#8561) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection_prepare_data.cpp | 9 +- .../src/util.cpp | 97 ++++++++++--------- .../src/util.hpp | 28 ++---- .../test/test_util.cpp | 12 +-- 4 files changed, 75 insertions(+), 71 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index 5c6c0bc8d38ab..a3059affc0c2a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -934,6 +934,14 @@ std::vector IntersectionModule::generateDetectionLan detection_lanelets.push_back(detection_lanelet); } + std::vector detection_divisions; + if (detection_lanelets.empty()) { + // NOTE(soblin): due to the above filtering detection_lanelets may be empty or do not contain + // conflicting_detection_lanelets + // OK to return empty detction_divsions + return detection_divisions; + } + // (1) tsort detection_lanelets const auto [merged_detection_lanelets, originals] = util::mergeLaneletsByTopologicalSort( detection_lanelets, conflicting_detection_lanelets, routing_graph_ptr); @@ -952,7 +960,6 @@ std::vector IntersectionModule::generateDetectionLan } // (3) discretize each merged lanelet - std::vector detection_divisions; for (const auto & [merged_lanelet, area] : merged_lanelet_with_area) { const double length = bg::length(merged_lanelet.centerline()); const double width = area / length; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp index 66a3264a85b58..ab482e7ec62e3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -32,10 +32,13 @@ #include #include +#include +#include +#include +#include #include #include #include -#include #include namespace autoware::behavior_velocity_planner::util @@ -212,42 +215,35 @@ std::optional getFirstPointInsidePolygon( } return std::nullopt; } -std::vector> retrievePathsBackward( - const std::vector> & adjacency, size_t start_node) + +void retrievePathsBackward( + const std::vector> & adjacency, const size_t src_ind, + const std::vector & visited_inds, std::vector> & paths) { - std::vector> paths; - std::vector current_path; - std::unordered_set visited; - - std::function retrieve_paths_backward_impl = [&](size_t src_ind) { - current_path.push_back(src_ind); - visited.insert(src_ind); - - bool is_terminal = true; - const auto & nexts = adjacency[src_ind]; - - for (size_t next = 0; next < nexts.size(); ++next) { - if (nexts[next]) { - is_terminal = false; - if (visited.find(next) == visited.end()) { - retrieve_paths_backward_impl(next); - } else { - // Loop detected - paths.push_back(current_path); - } - } + const auto & nexts = adjacency.at(src_ind); + const bool is_terminal = (std::find(nexts.begin(), nexts.end(), true) == nexts.end()); + if (is_terminal) { + std::vector path(visited_inds.begin(), visited_inds.end()); + path.push_back(src_ind); + paths.emplace_back(std::move(path)); + return; + } + for (size_t next = 0; next < nexts.size(); next++) { + if (!nexts.at(next)) { + continue; } - - if (is_terminal) { - paths.push_back(current_path); + if (std::find(visited_inds.begin(), visited_inds.end(), next) != visited_inds.end()) { + // loop detected + std::vector path(visited_inds.begin(), visited_inds.end()); + path.push_back(src_ind); + paths.emplace_back(std::move(path)); + continue; } - - current_path.pop_back(); - visited.erase(src_ind); - }; - - retrieve_paths_backward_impl(start_node); - return paths; + auto new_visited_inds = visited_inds; + new_visited_inds.push_back(src_ind); + retrievePathsBackward(adjacency, next, new_visited_inds, paths); + } + return; } std::pair> @@ -269,13 +265,20 @@ mergeLaneletsByTopologicalSort( } std::set terminal_inds; for (const auto & terminal_lanelet : terminal_lanelets) { - terminal_inds.insert(Id2ind[terminal_lanelet.id()]); + if (Id2ind.count(terminal_lanelet.id()) > 0) { + terminal_inds.insert(Id2ind[terminal_lanelet.id()]); + } } // create adjacency matrix const auto n_node = lanelets.size(); - std::vector> adjacency(n_node, std::vector(n_node, false)); - + std::vector> adjacency(n_node); + for (size_t dst = 0; dst < n_node; ++dst) { + adjacency[dst].resize(n_node); + for (size_t src = 0; src < n_node; ++src) { + adjacency[dst][src] = false; + } + } // NOTE: this function aims to traverse the detection lanelet in the lane direction, so if lane B // follows lane A on the routing_graph, adj[A][B] = true for (const auto & lanelet : lanelets) { @@ -290,10 +293,14 @@ mergeLaneletsByTopologicalSort( std::unordered_map>> branches; for (const auto & terminal_ind : terminal_inds) { - branches[terminal_ind] = retrievePathsBackward(adjacency, terminal_ind); + std::vector> paths; + std::vector visited; + retrievePathsBackward(adjacency, terminal_ind, visited, paths); + branches[terminal_ind] = std::move(paths); } - for (auto & [terminal_ind, paths] : branches) { + for (auto it = branches.begin(); it != branches.end(); it++) { + auto & paths = it->second; for (auto & path : paths) { std::reverse(path.begin(), path.end()); } @@ -301,16 +308,18 @@ mergeLaneletsByTopologicalSort( lanelet::ConstLanelets merged; std::vector originals; for (const auto & [ind, sub_branches] : branches) { - if (sub_branches.empty()) { + if (sub_branches.size() == 0) { continue; } for (const auto & sub_inds : sub_branches) { - lanelet::ConstLanelets to_merge; + lanelet::ConstLanelets to_be_merged; + originals.push_back(lanelet::ConstLanelets({})); + auto & original = originals.back(); for (const auto & sub_ind : sub_inds) { - to_merge.push_back(Id2lanelet[ind2Id[sub_ind]]); + to_be_merged.push_back(Id2lanelet[ind2Id[sub_ind]]); + original.push_back(Id2lanelet[ind2Id[sub_ind]]); } - originals.push_back(to_merge); - merged.push_back(lanelet::utils::combineLaneletsShape(to_merge)); + merged.push_back(lanelet::utils::combineLaneletsShape(to_be_merged)); } } return {merged, originals}; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp index 6e15298535291..9c32a9e6e3658 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -110,17 +110,9 @@ geometry_msgs::msg::Pose getObjectPoseWithVelocityDirection( * @brief this function sorts the set of lanelets topologically using topological sort and merges * the lanelets from each root to each end. each branch is merged and returned with the original * lanelets - * - * @param lanelets The set of input lanelets to be processed - * @param terminal_lanelets The set of lanelets considered as terminal - * @param routing_graph_ptr Pointer to the routing graph used for determining lanelet - * connections - * - * @return A pair containing: - * - First: A vector of merged lanelets, where each element represents a merged lanelet from - * a branch - * - Second: A vector of vectors, where each inner vector contains the original lanelets - * that were merged to form the corresponding merged lanelet + * @param[in] lanelets the set of lanelets + * @param[in] routing_graph_ptr the routing graph + * @return the pair of merged lanelets and their corresponding original lanelets */ std::pair> mergeLaneletsByTopologicalSort( @@ -128,16 +120,12 @@ mergeLaneletsByTopologicalSort( const lanelet::routing::RoutingGraphPtr routing_graph_ptr); /** - * @brief Retrieves all paths from the given source to terminal nodes on the tree - * - * @param adjacency A 2D vector representing the adjacency matrix of the graph - * @param src_ind The index of the current source node being processed - * - * @return A vector of vectors, where each inner vector represents a path from the source node to a - * terminal node. + * @brief this functions retrieves all the paths from the given source to terminal nodes on the tree + @param[in] visited_inds visited node indices excluding src_ind so far */ -std::vector> retrievePathsBackward( - const std::vector> & adjacency, size_t start_node); +void retrievePathsBackward( + const std::vector> & adjacency, const size_t src_ind, + const std::vector & visited_inds, std::vector> & paths); /** * @brief find the index of the first point where vehicle footprint intersects with the given diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp index 8e27cd223ef80..d9ef145eb5ce9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp @@ -42,16 +42,16 @@ TEST(TestUtil, retrievePathsBackward) }; { const size_t src_ind = 6; - auto paths = - autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind); + std::vector> paths; + autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind, {}, paths); EXPECT_EQ(paths.size(), 1); EXPECT_EQ(paths.at(0).size(), 1); EXPECT_EQ(paths.at(0).at(0), 6); } { const size_t src_ind = 4; - auto paths = - autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind); + std::vector> paths; + autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind, {}, paths); EXPECT_EQ(paths.size(), 2); // 4 --> 6 EXPECT_EQ(paths.at(0).size(), 2); @@ -64,8 +64,8 @@ TEST(TestUtil, retrievePathsBackward) } { const size_t src_ind = 0; - auto paths = - autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind); + std::vector> paths; + autoware::behavior_velocity_planner::util::retrievePathsBackward(adjacency, src_ind, {}, paths); EXPECT_EQ(paths.size(), 3); // 0 --> 1 --> 2 --> 4 --> 6 EXPECT_EQ(paths.at(0).size(), 5); From 403537696e357c5ec0a3bceb06ab400ed8d5ebce Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 26 Aug 2024 14:36:34 +0900 Subject: [PATCH 109/151] fix(goal_planner): remove time keeper in non main thread (#8610) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 7792b427c5fa1..3078414c63213 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1243,8 +1243,6 @@ bool GoalPlannerModule::hasDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1277,8 +1275,6 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; From 83aa6bfa5a9f8397504b834e39a29b925dcb9204 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 21 Aug 2024 14:36:49 +0900 Subject: [PATCH 110/151] fix(static_obstacle_avoidance): target object sorting (#8545) * fix compensateLostTargetObjects function Signed-off-by: Go Sakayori * remove empty case Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../src/utils.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index f7bda56150b49..79ba00cdf4d94 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1674,8 +1674,8 @@ void compensateLostTargetObjects( const std::shared_ptr & parameters) { const auto include = [](const auto & objects, const auto & search_id) { - return std::all_of(objects.begin(), objects.end(), [&search_id](const auto & o) { - return o.object.object_id != search_id; + return std::any_of(objects.begin(), objects.end(), [&search_id](const auto & o) { + return o.object.object_id == search_id; }); }; From 4de049b48c506638089db40ecbd8d91222a67151 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 21 Aug 2024 18:01:15 +0900 Subject: [PATCH 111/151] feat(static_obstacle_avoidance): update envelope polygon creation method (#8551) * update envelope polygon by considering pose covariance Signed-off-by: Go Sakayori * change parameter Signed-off-by: Go Sakayori * modify schema json Signed-off-by: Go Sakayori * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../static_obstacle_avoidance.param.yaml | 8 +++ .../data_structs.hpp | 5 ++ .../parameter_helper.hpp | 2 + .../type_alias.hpp | 1 + .../utils.hpp | 2 + .../static_obstacle_avoidance.schema.json | 64 ++++++++++++++++--- .../src/manager.cpp | 2 + .../src/utils.cpp | 31 +++++++++ 8 files changed, 107 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 0e60e3216361d..8c9dff8ece448 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -28,6 +28,7 @@ hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER + th_error_eclipse_long_radius : 0.6 # [m] truck: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -38,6 +39,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 bus: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -48,6 +50,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 trailer: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -58,6 +61,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 unknown: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -68,6 +72,7 @@ hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 + th_error_eclipse_long_radius : 0.6 bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -78,6 +83,7 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 @@ -88,6 +94,7 @@ hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -98,6 +105,7 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 4e14dc4886768..b530da909c59d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -90,6 +90,8 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; double longitudinal_margin{0.0}; + + double th_error_eclipse_long_radius{0.0}; }; struct AvoidanceParameters @@ -420,6 +422,9 @@ struct ObjectData // avoidance target // to stop line distance double to_stop_line{std::numeric_limits::infinity()}; + // long radius of the covariance error ellipse + double error_eclipse_max{std::numeric_limits::infinity()}; + // if lateral margin is NOT enough, the ego must avoid the object. bool avoid_required{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 56ac3d7f4f1bb..b56c48d15df24 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -69,6 +69,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); + param.th_error_eclipse_long_radius = + getOrDeclareParameter(*node, ns + "th_error_eclipse_long_radius"); return param; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp index cfbd3f89308ac..d9055bc8a1c34 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp @@ -41,6 +41,7 @@ using tier4_planning_msgs::msg::PathWithLaneId; // ROS 2 general msgs using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; +using geometry_msgs::msg::PoseWithCovariance; using geometry_msgs::msg::TransformStamped; using geometry_msgs::msg::Vector3; using std_msgs::msg::ColorRGBA; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 909d28ed4bab6..66e8ee550fb2a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -174,6 +174,8 @@ double calcDistanceToAvoidStartLine( const std::shared_ptr & planner_data, const std::shared_ptr & parameters); +double calcErrorEclipseLongRadius(const PoseWithCovariance & pose); + } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance #endif // AUTOWARE__BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index 38a91ac39525b..eb80c705cfdc2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -96,6 +96,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -104,7 +109,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -158,6 +164,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -166,7 +177,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -220,6 +232,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -228,7 +245,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -282,6 +300,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -290,7 +313,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -344,6 +368,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -352,7 +381,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -406,6 +436,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -414,7 +449,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -468,6 +504,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -476,7 +517,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -530,6 +572,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -538,7 +585,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index 5655696ff086d..ddc425fd1520b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -60,6 +60,8 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams( parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle", config.lateral_hard_margin_for_parked_vehicle); updateParam(parameters, ns + "longitudinal_margin", config.longitudinal_margin); + updateParam( + parameters, ns + "th_error_eclipse_long_radius", config.th_error_eclipse_long_radius); }; { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 79ba00cdf4d94..3729188ff9294 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -21,6 +21,7 @@ #include "autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp" +#include #include #include @@ -1500,11 +1501,27 @@ void fillObjectEnvelopePolygon( if (same_id_obj == registered_objects.end()) { object_data.envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + object_data.error_eclipse_max = + calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); return; } const auto one_shot_envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + const double error_eclipse_long_radius = + calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); + + if (error_eclipse_long_radius > object_parameter.th_error_eclipse_long_radius) { + if (error_eclipse_long_radius < object_data.error_eclipse_max) { + object_data.error_eclipse_max = error_eclipse_long_radius; + object_data.envelope_poly = one_shot_envelope_poly; + return; + } + object_data.envelope_poly = same_id_obj->envelope_poly; + return; + } + + object_data.error_eclipse_max = error_eclipse_long_radius; // If the one_shot_envelope_poly is within the registered envelope, use the registered one if (boost::geometry::within(one_shot_envelope_poly, same_id_obj->envelope_poly)) { @@ -2512,4 +2529,18 @@ double calcDistanceToReturnDeadLine( return distance_to_return_dead_line; } + +double calcErrorEclipseLongRadius(const PoseWithCovariance & pose) +{ + Eigen::Matrix2d xy_covariance; + const auto cov = pose.covariance; + xy_covariance(0, 0) = cov[0 * 6 + 0]; + xy_covariance(0, 1) = cov[0 * 6 + 1]; + xy_covariance(1, 0) = cov[1 * 6 + 0]; + xy_covariance(1, 1) = cov[1 * 6 + 1]; + + Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); + + return std::sqrt(eigensolver.eigenvalues()(1)); +} } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance From 2106efd5575f6ae10bfba768f2dc101e652c30ba Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 29 Aug 2024 10:18:25 +0900 Subject: [PATCH 112/151] fix(reaction_analyzer): fix include hierarchy of tf2_eigen (#8663) Fixed include hierarchy of tf2_eigen Signed-off-by: Shintaro Sakoda --- tools/reaction_analyzer/include/subscriber.hpp | 2 +- tools/reaction_analyzer/include/topic_publisher.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/reaction_analyzer/include/subscriber.hpp b/tools/reaction_analyzer/include/subscriber.hpp index ff251251373e2..d2a8363e15bf3 100644 --- a/tools/reaction_analyzer/include/subscriber.hpp +++ b/tools/reaction_analyzer/include/subscriber.hpp @@ -16,7 +16,7 @@ #define SUBSCRIBER_HPP_ #include #include -#include +#include #include #include diff --git a/tools/reaction_analyzer/include/topic_publisher.hpp b/tools/reaction_analyzer/include/topic_publisher.hpp index 0c01561fec508..4517b1f793e6c 100644 --- a/tools/reaction_analyzer/include/topic_publisher.hpp +++ b/tools/reaction_analyzer/include/topic_publisher.hpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include From f30e55f438507f6e5af2d0087e3ef8995b6583c6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 30 Aug 2024 00:28:59 +0900 Subject: [PATCH 113/151] fix(static_obstacle_avoidance): change avoidance condition (#8433) (#1460) Signed-off-by: satoshi-ota --- .../src/utils.cpp | 40 +++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index f7bda56150b49..4e2a6fc7d2633 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -754,6 +754,46 @@ bool isObviousAvoidanceTarget( } } + if (object.behavior == ObjectData::Behavior::MERGING) { + object.info = ObjectInfo::MERGING_TO_EGO_LANE; + if ( + isOnRight(object) && !object.is_on_ego_lane && + object.overhang_points.front().first < parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "merging vehicle. but overhang distance is less than threshold."); + return true; + } + if ( + !isOnRight(object) && !object.is_on_ego_lane && + object.overhang_points.front().first > -1.0 * parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "merging vehicle. but overhang distance is less than threshold."); + return true; + } + } + + if (object.behavior == ObjectData::Behavior::DEVIATING) { + object.info = ObjectInfo::DEVIATING_FROM_EGO_LANE; + if ( + isOnRight(object) && !object.is_on_ego_lane && + object.overhang_points.front().first < parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "deviating vehicle. but overhang distance is less than threshold."); + return true; + } + if ( + !isOnRight(object) && !object.is_on_ego_lane && + object.overhang_points.front().first > -1.0 * parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "deviating vehicle. but overhang distance is less than threshold."); + return true; + } + } + if (!object.is_parked) { object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; } From cf3d631bcc37b0e4fb6fbb9d10a3183cd67fbc59 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 30 Aug 2024 19:26:34 +0900 Subject: [PATCH 114/151] feat(autoware_accel_brake_map_calibrator): conditional actuation data processing based on source (#1497) feat(autoware_accel_brake_map_calibrator): conditional actuation data processing based on source (#8593) * fix: Conditional Actuation Data Processing Based on Source * style(pre-commit): autofix * delete extra comentout, indent * add take validation * style(pre-commit): autofix --------- Signed-off-by: N-Eiki Co-authored-by: eiki <53928021+N-Eiki@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/accel_brake_map_calibrator_node.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp index 6a88d5c61a2d8..a99fcd6b16401 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp +++ b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp @@ -266,15 +266,16 @@ bool AccelBrakeMapCalibrator::get_current_pitch_from_tf(double * pitch) bool AccelBrakeMapCalibrator::take_data() { // take data from subscribers - // take actuation data - ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData(); - ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData(); - if (actuation_status_ptr) { + if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::STATUS) { + ActuationStatusStamped::ConstSharedPtr actuation_status_ptr = actuation_status_sub_.takeData(); + if (!actuation_status_ptr) return false; take_actuation_status(actuation_status_ptr); - } else if (actuation_cmd_ptr) { + } + // take actuation data + if (accel_brake_value_source_ == ACCEL_BRAKE_SOURCE::COMMAND) { + ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr = actuation_cmd_sub_.takeData(); + if (!actuation_cmd_ptr) return false; take_actuation_command(actuation_cmd_ptr); - } else { - return false; } // take velocity data From c9e78d68c8373d66f7358ef4edc23ad1e4f44b32 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 30 Aug 2024 19:26:50 +0900 Subject: [PATCH 115/151] feat(mrm_handler): input gear command (#8080) (#1498) * feat(mrm_handler): input gear command * style(pre-commit): autofix * fix minor --------- Signed-off-by: veqcc Co-authored-by: Ryuta Kambe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/mrm_handler/mrm_handler_core.hpp | 3 +- .../mrm_handler/launch/mrm_handler.launch.xml | 2 ++ .../src/mrm_handler/mrm_handler_core.cpp | 31 +++++++------------ 3 files changed, 16 insertions(+), 20 deletions(-) diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp index 7d7deb8c4a504..f73d0df4153ce 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -86,6 +86,8 @@ class MrmHandler : public rclcpp::Node autoware::universe_utils::InterProcessPollingSubscriber< autoware_adapi_v1_msgs::msg::OperationModeState> sub_operation_mode_state_{this, "~/input/api/operation_mode/state"}; + autoware::universe_utils::InterProcessPollingSubscriber + sub_gear_cmd_{this, "~/input/gear"}; tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr operation_mode_availability_; @@ -146,7 +148,6 @@ class MrmHandler : public rclcpp::Node void handleFailedRequest(); autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior(); bool isStopped(); - bool isDrivingBackwards(); bool isEmergency() const; bool isControlModeAutonomous(); bool isOperationModeAutonomous(); diff --git a/system/mrm_handler/launch/mrm_handler.launch.xml b/system/mrm_handler/launch/mrm_handler.launch.xml index 7e761157956df..c99b22e10ad77 100644 --- a/system/mrm_handler/launch/mrm_handler.launch.xml +++ b/system/mrm_handler/launch/mrm_handler.launch.xml @@ -7,6 +7,7 @@ + @@ -26,6 +27,7 @@ + diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 47cbb0ae7d016..bac932a7d7e1e 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -130,19 +130,20 @@ void MrmHandler::publishGearCmd() { using autoware_vehicle_msgs::msg::GearCommand; GearCommand msg; - msg.stamp = this->now(); - const auto command = [&]() { - // If stopped and use_parking is not true, send the last gear command - if (isStopped()) - return (param_.use_parking_after_stopped) ? GearCommand::PARK : last_gear_command_; - return (isDrivingBackwards()) ? GearCommand::REVERSE : GearCommand::DRIVE; - }(); - - msg.command = command; - last_gear_command_ = msg.command; + + if (isEmergency()) { + // gear command is created within mrm_handler + msg.command = + (param_.use_parking_after_stopped && isStopped()) ? GearCommand::PARK : last_gear_command_; + } else { + // use the same gear as the input gear + auto gear = sub_gear_cmd_.takeData(); + msg.command = (gear == nullptr) ? last_gear_command_ : gear->command; + last_gear_command_ = msg.command; + } + pub_gear_cmd_->publish(msg); - return; } void MrmHandler::publishMrmState() @@ -524,14 +525,6 @@ bool MrmHandler::isStopped() return (std::abs(odom->twist.twist.linear.x) < th_stopped_velocity); } -bool MrmHandler::isDrivingBackwards() -{ - auto odom = sub_odom_.takeData(); - if (odom == nullptr) return false; - constexpr auto th_moving_backwards = -0.001; - return odom->twist.twist.linear.x < th_moving_backwards; -} - bool MrmHandler::isEmergency() const { return !operation_mode_availability_->autonomous || is_emergency_holding_ || From 5d7305bc5e398ffb222ec946d8c5b251b0184967 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 21 Aug 2024 14:36:49 +0900 Subject: [PATCH 116/151] fix(static_obstacle_avoidance): target object sorting (#8545) * fix compensateLostTargetObjects function Signed-off-by: Go Sakayori * remove empty case Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../src/utils.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index f7bda56150b49..79ba00cdf4d94 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1674,8 +1674,8 @@ void compensateLostTargetObjects( const std::shared_ptr & parameters) { const auto include = [](const auto & objects, const auto & search_id) { - return std::all_of(objects.begin(), objects.end(), [&search_id](const auto & o) { - return o.object.object_id != search_id; + return std::any_of(objects.begin(), objects.end(), [&search_id](const auto & o) { + return o.object.object_id == search_id; }); }; From 071034352c372d250f9ae0b4a136c460d757473d Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 21 Aug 2024 18:01:15 +0900 Subject: [PATCH 117/151] feat(static_obstacle_avoidance): update envelope polygon creation method (#8551) * update envelope polygon by considering pose covariance Signed-off-by: Go Sakayori * change parameter Signed-off-by: Go Sakayori * modify schema json Signed-off-by: Go Sakayori * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../static_obstacle_avoidance.param.yaml | 8 +++ .../data_structs.hpp | 5 ++ .../parameter_helper.hpp | 2 + .../type_alias.hpp | 1 + .../utils.hpp | 2 + .../static_obstacle_avoidance.schema.json | 64 ++++++++++++++++--- .../src/manager.cpp | 2 + .../src/utils.cpp | 31 +++++++++ 8 files changed, 107 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index 0e60e3216361d..8c9dff8ece448 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -28,6 +28,7 @@ hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER + th_error_eclipse_long_radius : 0.6 # [m] truck: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -38,6 +39,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 bus: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -48,6 +50,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 trailer: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -58,6 +61,7 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 unknown: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -68,6 +72,7 @@ hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 + th_error_eclipse_long_radius : 0.6 bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -78,6 +83,7 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 @@ -88,6 +94,7 @@ hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -98,6 +105,7 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 + th_error_eclipse_long_radius : 0.6 lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 4e14dc4886768..b530da909c59d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -90,6 +90,8 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; double longitudinal_margin{0.0}; + + double th_error_eclipse_long_radius{0.0}; }; struct AvoidanceParameters @@ -420,6 +422,9 @@ struct ObjectData // avoidance target // to stop line distance double to_stop_line{std::numeric_limits::infinity()}; + // long radius of the covariance error ellipse + double error_eclipse_max{std::numeric_limits::infinity()}; + // if lateral margin is NOT enough, the ego must avoid the object. bool avoid_required{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 56ac3d7f4f1bb..b56c48d15df24 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -69,6 +69,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); + param.th_error_eclipse_long_radius = + getOrDeclareParameter(*node, ns + "th_error_eclipse_long_radius"); return param; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp index cfbd3f89308ac..d9055bc8a1c34 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp @@ -41,6 +41,7 @@ using tier4_planning_msgs::msg::PathWithLaneId; // ROS 2 general msgs using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; +using geometry_msgs::msg::PoseWithCovariance; using geometry_msgs::msg::TransformStamped; using geometry_msgs::msg::Vector3; using std_msgs::msg::ColorRGBA; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 909d28ed4bab6..66e8ee550fb2a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -174,6 +174,8 @@ double calcDistanceToAvoidStartLine( const std::shared_ptr & planner_data, const std::shared_ptr & parameters); +double calcErrorEclipseLongRadius(const PoseWithCovariance & pose); + } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance #endif // AUTOWARE__BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index 38a91ac39525b..eb80c705cfdc2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -96,6 +96,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -104,7 +109,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -158,6 +164,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -166,7 +177,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -220,6 +232,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -228,7 +245,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -282,6 +300,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -290,7 +313,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -344,6 +368,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -352,7 +381,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -406,6 +436,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -414,7 +449,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -468,6 +504,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -476,7 +517,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, @@ -530,6 +572,11 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 + }, + "th_error_eclipse_long_radius": { + "type": "number", + "description": "This value will be applied to judge whether the eclipse error is to large", + "default": 0.6 } }, "required": [ @@ -538,7 +585,8 @@ "longitudinal_margin", "lateral_margin", "envelope_buffer_margin", - "max_expand_ratio" + "max_expand_ratio", + "th_error_eclipse_long_radius" ], "additionalProperties": false }, diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index 5655696ff086d..ddc425fd1520b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -60,6 +60,8 @@ void StaticObstacleAvoidanceModuleManager::updateModuleParams( parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle", config.lateral_hard_margin_for_parked_vehicle); updateParam(parameters, ns + "longitudinal_margin", config.longitudinal_margin); + updateParam( + parameters, ns + "th_error_eclipse_long_radius", config.th_error_eclipse_long_radius); }; { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 79ba00cdf4d94..3729188ff9294 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -21,6 +21,7 @@ #include "autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp" +#include #include #include @@ -1500,11 +1501,27 @@ void fillObjectEnvelopePolygon( if (same_id_obj == registered_objects.end()) { object_data.envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + object_data.error_eclipse_max = + calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); return; } const auto one_shot_envelope_poly = createEnvelopePolygon(object_data, closest_pose, envelope_buffer_margin); + const double error_eclipse_long_radius = + calcErrorEclipseLongRadius(object_data.object.kinematics.initial_pose_with_covariance); + + if (error_eclipse_long_radius > object_parameter.th_error_eclipse_long_radius) { + if (error_eclipse_long_radius < object_data.error_eclipse_max) { + object_data.error_eclipse_max = error_eclipse_long_radius; + object_data.envelope_poly = one_shot_envelope_poly; + return; + } + object_data.envelope_poly = same_id_obj->envelope_poly; + return; + } + + object_data.error_eclipse_max = error_eclipse_long_radius; // If the one_shot_envelope_poly is within the registered envelope, use the registered one if (boost::geometry::within(one_shot_envelope_poly, same_id_obj->envelope_poly)) { @@ -2512,4 +2529,18 @@ double calcDistanceToReturnDeadLine( return distance_to_return_dead_line; } + +double calcErrorEclipseLongRadius(const PoseWithCovariance & pose) +{ + Eigen::Matrix2d xy_covariance; + const auto cov = pose.covariance; + xy_covariance(0, 0) = cov[0 * 6 + 0]; + xy_covariance(0, 1) = cov[0 * 6 + 1]; + xy_covariance(1, 0) = cov[1 * 6 + 0]; + xy_covariance(1, 1) = cov[1 * 6 + 1]; + + Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); + + return std::sqrt(eigensolver.eigenvalues()(1)); +} } // namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance From 9b7759f171dedeef1d9b50d996fc2c7914bb6de0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 11:21:54 +0900 Subject: [PATCH 118/151] fix(static_obstacle_avoidance): use wrong parameter (#8720) Signed-off-by: satoshi-ota --- .../behavior_path_static_obstacle_avoidance_module/helper.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index bfeb942c82be3..0f3536eeb4e7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -305,7 +305,7 @@ class AvoidanceHelper { const auto & p = parameters_; return prepare_distance > - std::max(getEgoSpeed() * p->min_prepare_distance, p->min_prepare_distance); + std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance); } bool isComfortable(const AvoidLineArray & shift_lines) const From a82c0efbc98f54b62badb126fc4dddffee94d973 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 2 Sep 2024 19:08:20 +0900 Subject: [PATCH 119/151] fix(bpp): use common steering factor interface for same scene modules (#8675) Signed-off-by: satoshi-ota --- .../src/interface.cpp | 4 +++- .../src/interface.hpp | 3 ++- .../src/manager.cpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../src/manager.cpp | 4 ++-- .../goal_planner_module.hpp | 3 ++- .../behavior_path_goal_planner_module/manager.hpp | 2 +- .../src/goal_planner_module.cpp | 5 +++-- .../behavior_path_lane_change_module/interface.hpp | 1 + .../src/interface.cpp | 4 ++-- .../src/manager.cpp | 2 +- .../interface/scene_module_interface.hpp | 8 ++++---- .../interface/scene_module_manager_interface.hpp | 8 ++++++++ .../behavior_path_sampling_planner_module/manager.hpp | 2 +- .../sampling_planner_module.hpp | 3 ++- .../src/sampling_planner_module.cpp | 5 +++-- .../autoware/behavior_path_side_shift_module/manager.hpp | 2 +- .../autoware/behavior_path_side_shift_module/scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../behavior_path_start_planner_module/manager.hpp | 2 +- .../start_planner_module.hpp | 3 ++- .../src/start_planner_module.cpp | 5 +++-- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- 27 files changed, 60 insertions(+), 36 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 4c9f139365a06..fffb86767b0a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -31,13 +31,15 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, + steering_factor_interface_ptr, std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp index c7fbba34b1adb..4d200411904b0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp @@ -40,7 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 8096d2944ee2b..ddcfda50d18c4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -192,7 +192,7 @@ AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp index 9c85a463067de..a7f470002b01b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp @@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 8f19613b50e6d..48c6084a4f424 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -343,7 +343,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index f195b91a54f21..debd13acd31dd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -331,8 +331,9 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, target_objects_manager_{TargetObjectsManager( parameters_->successive_num_to_entry_dynamic_avoidance_condition, diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index c04914ed1c72b..3c730e6d36376 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -26,7 +26,7 @@ ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } @@ -35,7 +35,7 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 749ed57f95cc9..4c23292f63e61 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -307,7 +307,8 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); ~GoalPlannerModule() { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp index 32d816d9a37e8..1ab7b6cb265a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp @@ -38,7 +38,7 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 7792b427c5fa1..54a1c0830fb06 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -57,8 +57,9 @@ GoalPlannerModule::GoalPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index bd309dd35a260..fd9375c7e9f75 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -52,6 +52,7 @@ class LaneChangeInterface : public SceneModuleInterface const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type); LaneChangeInterface(const LaneChangeInterface &) = delete; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 9354b117cb160..1bbc2d25fc0bc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -38,14 +38,14 @@ LaneChangeInterface::LaneChangeInterface( const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, prev_approved_path_{std::make_unique()} { module_type_->setTimeKeeper(getTimeKeeper()); - steering_factor_interface_ptr_ = std::make_unique(&node, name); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 42166c4dff0e0..c197d0d63aa37 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -299,7 +299,7 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index c4a05d171654d..d9ad89283d304 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -90,15 +90,15 @@ class SceneModuleInterface const std::string & name, rclcpp::Node & node, std::unordered_map> rtc_interface_ptr_map, std::unordered_map> - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, rtc_interface_ptr_map_(std::move(rtc_interface_ptr_map)), objects_of_interest_marker_interface_ptr_map_( std::move(objects_of_interest_marker_interface_ptr_map)), - steering_factor_interface_ptr_( - std::make_unique(&node, utils::convertToSnakeCase(name))), + steering_factor_interface_ptr_{steering_factor_interface_ptr}, time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -640,7 +640,7 @@ class SceneModuleInterface std::unordered_map> objects_of_interest_marker_interface_ptr_map_; - std::unique_ptr steering_factor_interface_ptr_; + std::shared_ptr steering_factor_interface_ptr_; mutable std::optional stop_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 82a364a9c37c7..ceecb7b02408a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -315,6 +315,12 @@ class SceneModuleManagerInterface "~/processing_time/" + name_, 20); } + // init steering factor + { + steering_factor_interface_ptr_ = + std::make_shared(node, utils::convertToSnakeCase(name_)); + } + // misc { node_ = node; @@ -339,6 +345,8 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; + std::shared_ptr steering_factor_interface_ptr_; + std::vector observers_; std::unique_ptr idle_module_ptr_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp index 28c310ae20ec2..778afd1698ff2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp @@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams( diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index 2b6f52998cb23..8dc04947923e1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -86,7 +86,8 @@ class SamplingPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 526a761e6957a..b820e8d03322f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -33,8 +33,9 @@ SamplingPlannerModule::SamplingPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()} { internal_params_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp index b495e6619a1c7..d1c9c8e2535ec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp @@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp index 543b17aca9352..74953b7927b5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp @@ -45,7 +45,8 @@ class SideShiftModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index bcb972bf5dc8b..cd4298c56929a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -40,8 +40,9 @@ SideShiftModule::SideShiftModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp index 5d3d224673124..a26c48ad065c9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp @@ -38,7 +38,7 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index bb70ae2638056..e0bb5d95f565a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -88,7 +88,8 @@ class StartPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); ~StartPlannerModule() override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index e318fbedf3200..dd9129216fbba 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -59,8 +59,9 @@ StartPlannerModule::StartPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp index 895390f91cc16..fa54ec52203f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp @@ -41,7 +41,7 @@ class StaticObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 34d06a46d9ac8..dc6e41fbc5f7e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -46,7 +46,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 39a8d1b853e47..3c76e288fdd55 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -76,8 +76,9 @@ StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT helper_{std::make_shared(parameters)}, parameters_{parameters}, generator_{parameters} From 6d9633e2292cec4415db8a3c6617f36c588218d6 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 15:24:47 +0900 Subject: [PATCH 120/151] fix(static_obstacle_avoidance): use wrong parameter (#8720) (#1502) Signed-off-by: satoshi-ota --- .../behavior_path_static_obstacle_avoidance_module/helper.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index bfeb942c82be3..0f3536eeb4e7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -305,7 +305,7 @@ class AvoidanceHelper { const auto & p = parameters_; return prepare_distance > - std::max(getEgoSpeed() * p->min_prepare_distance, p->min_prepare_distance); + std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance); } bool isComfortable(const AvoidLineArray & shift_lines) const From 847cb0edb08a53a0cd913490981b921b1ea37de9 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 22 Aug 2024 13:23:52 +0900 Subject: [PATCH 121/151] fix(lane_change): modify lane change requested condition (#8510) * modify lane change requested condition Signed-off-by: Muhammad Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> * style(pre-commit): autofix * fix docstring Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: kotaro-hihara --- .../utils/calculation.hpp | 38 ++++++++++++++++++ .../src/scene.cpp | 12 +++++- .../src/utils/calculation.cpp | 40 +++++++++++++++++++ 3 files changed, 89 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index 3dc5e7ee62a57..ae0a094e038a4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -58,6 +58,44 @@ double calc_dist_from_pose_to_terminal_end( * @return The required backward buffer distance in meters. */ double calc_stopping_distance(const LCParamPtr & lc_param_ptr); + +/** + * @brief Calculates the maximum preparation longitudinal distance for lane change. + * + * This function computes the maximum distance that the ego vehicle can travel during + * the preparation phase of a lane change. The distance is calculated as the product + * of the maximum lane change preparation duration and the maximum velocity of the ego vehicle. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - `lc_param_ptr->lane_change_prepare_duration`: The duration allowed for lane change + * preparation. + * - `bpp_param_ptr->max_vel`: The maximum velocity of the ego vehicle. + * + * @return The maximum preparation longitudinal distance in meters. + */ +double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr); + +/** + * @brief Calculates the distance from the ego vehicle to the start of the target lanes. + * + * This function computes the shortest distance from the current position of the ego vehicle + * to the start of the target lanes by measuring the arc length to the front points of + * the left and right boundaries of the target lane. If the target lanes are empty or other + * required data is unavailable, the function returns numeric_limits::max() preventing lane + * change being executed. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - `route_handler_ptr`: Pointer to the route handler that manages the route. + * - Other necessary parameters for ego vehicle positioning. + * @param current_lanes The set of lanelets representing the current lanes of the ego vehicle. + * @param target_lanes The set of lanelets representing the target lanes for lane changing. + * + * @return The distance from the ego vehicle to the start of the target lanes in meters, + * or numeric_limits::max() if the target lanes are empty or data is unavailable. + */ +double calc_ego_dist_to_lanes_start( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes); } // namespace autoware::behavior_path_planner::utils::lane_change::calculation #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 42b22f9b1631c..28efae2549d1e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -153,6 +153,8 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) bool NormalLaneChange::isLaneChangeRequired() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto current_lanes = utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); @@ -162,7 +164,15 @@ bool NormalLaneChange::isLaneChangeRequired() const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); - return !target_lanes.empty(); + if (target_lanes.empty()) { + return false; + } + + const auto ego_dist_to_target_start = + calculation::calc_ego_dist_to_lanes_start(common_data_ptr_, current_lanes, target_lanes); + const auto maximum_prepare_length = calculation::calc_maximum_prepare_length(common_data_ptr_); + + return ego_dist_to_target_start <= maximum_prepare_length; } bool NormalLaneChange::isStoppedAtRedTrafficLight() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index ac205ceedb34b..2dc65a8b78045 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -54,4 +54,44 @@ double calc_stopping_distance(const LCParamPtr & lc_param_ptr) const auto param_back_dist = lc_param_ptr->backward_length_buffer_for_end_of_lane; return std::max(min_back_dist, param_back_dist); } + +double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr) +{ + const auto max_prepare_duration = common_data_ptr->lc_param_ptr->lane_change_prepare_duration; + const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel; + + return max_prepare_duration * ego_max_speed; +} + +double calc_ego_dist_to_lanes_start( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes) +{ + const auto & route_handler_ptr = common_data_ptr->route_handler_ptr; + + if (!route_handler_ptr || target_lanes.empty() || current_lanes.empty()) { + return std::numeric_limits::max(); + } + + const auto & target_bound = + common_data_ptr->direction == autoware::route_handler::Direction::RIGHT + ? target_lanes.front().leftBound() + : target_lanes.front().rightBound(); + + if (target_bound.empty()) { + return std::numeric_limits::max(); + } + + const auto path = + route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + + if (path.points.empty()) { + return std::numeric_limits::max(); + } + + const auto target_front_pt = lanelet::utils::conversion::toGeomMsgPt(target_bound.front()); + const auto ego_position = common_data_ptr->get_ego_pose().position; + + return motion_utils::calcSignedArcLength(path.points, ego_position, target_front_pt); +} } // namespace autoware::behavior_path_planner::utils::lane_change::calculation From d2142b93a883493dcf8f35e311fb049619406983 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 3 Sep 2024 18:14:04 +0900 Subject: [PATCH 122/151] fix(bpp): use common steering factor interface for same scene modules (#8675) (#1505) Signed-off-by: satoshi-ota --- .../src/interface.cpp | 4 +++- .../src/interface.hpp | 3 ++- .../src/manager.cpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../src/manager.cpp | 4 ++-- .../goal_planner_module.hpp | 3 ++- .../behavior_path_goal_planner_module/manager.hpp | 2 +- .../src/goal_planner_module.cpp | 5 +++-- .../behavior_path_lane_change_module/interface.hpp | 1 + .../src/interface.cpp | 4 ++-- .../src/manager.cpp | 2 +- .../interface/scene_module_interface.hpp | 8 ++++---- .../interface/scene_module_manager_interface.hpp | 8 ++++++++ .../behavior_path_sampling_planner_module/manager.hpp | 2 +- .../sampling_planner_module.hpp | 3 ++- .../src/sampling_planner_module.cpp | 5 +++-- .../autoware/behavior_path_side_shift_module/manager.hpp | 2 +- .../autoware/behavior_path_side_shift_module/scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- .../behavior_path_start_planner_module/manager.hpp | 2 +- .../start_planner_module.hpp | 3 ++- .../src/start_planner_module.cpp | 5 +++-- .../manager.hpp | 2 +- .../scene.hpp | 3 ++- .../src/scene.cpp | 5 +++-- 27 files changed, 60 insertions(+), 36 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 4c9f139365a06..fffb86767b0a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -31,13 +31,15 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, + steering_factor_interface_ptr, std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp index c7fbba34b1adb..4d200411904b0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp @@ -40,7 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 8096d2944ee2b..ddcfda50d18c4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -192,7 +192,7 @@ AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp index 9c85a463067de..a7f470002b01b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp @@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 8f19613b50e6d..48c6084a4f424 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -343,7 +343,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index f195b91a54f21..debd13acd31dd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -331,8 +331,9 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, target_objects_manager_{TargetObjectsManager( parameters_->successive_num_to_entry_dynamic_avoidance_condition, diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index c04914ed1c72b..3c730e6d36376 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -26,7 +26,7 @@ ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } @@ -35,7 +35,7 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 749ed57f95cc9..4c23292f63e61 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -307,7 +307,8 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); ~GoalPlannerModule() { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp index 32d816d9a37e8..1ab7b6cb265a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp @@ -38,7 +38,7 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 7792b427c5fa1..54a1c0830fb06 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -57,8 +57,9 @@ GoalPlannerModule::GoalPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index bd309dd35a260..fd9375c7e9f75 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -52,6 +52,7 @@ class LaneChangeInterface : public SceneModuleInterface const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type); LaneChangeInterface(const LaneChangeInterface &) = delete; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 9354b117cb160..1bbc2d25fc0bc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -38,14 +38,14 @@ LaneChangeInterface::LaneChangeInterface( const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, prev_approved_path_{std::make_unique()} { module_type_->setTimeKeeper(getTimeKeeper()); - steering_factor_interface_ptr_ = std::make_unique(&node, name); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 42166c4dff0e0..c197d0d63aa37 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -299,7 +299,7 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index c4a05d171654d..d9ad89283d304 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -90,15 +90,15 @@ class SceneModuleInterface const std::string & name, rclcpp::Node & node, std::unordered_map> rtc_interface_ptr_map, std::unordered_map> - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, rtc_interface_ptr_map_(std::move(rtc_interface_ptr_map)), objects_of_interest_marker_interface_ptr_map_( std::move(objects_of_interest_marker_interface_ptr_map)), - steering_factor_interface_ptr_( - std::make_unique(&node, utils::convertToSnakeCase(name))), + steering_factor_interface_ptr_{steering_factor_interface_ptr}, time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -640,7 +640,7 @@ class SceneModuleInterface std::unordered_map> objects_of_interest_marker_interface_ptr_map_; - std::unique_ptr steering_factor_interface_ptr_; + std::shared_ptr steering_factor_interface_ptr_; mutable std::optional stop_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 82a364a9c37c7..ceecb7b02408a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -315,6 +315,12 @@ class SceneModuleManagerInterface "~/processing_time/" + name_, 20); } + // init steering factor + { + steering_factor_interface_ptr_ = + std::make_shared(node, utils::convertToSnakeCase(name_)); + } + // misc { node_ = node; @@ -339,6 +345,8 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; + std::shared_ptr steering_factor_interface_ptr_; + std::vector observers_; std::unique_ptr idle_module_ptr_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp index 28c310ae20ec2..778afd1698ff2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp @@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams( diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index 2b6f52998cb23..8dc04947923e1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -86,7 +86,8 @@ class SamplingPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 526a761e6957a..b820e8d03322f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -33,8 +33,9 @@ SamplingPlannerModule::SamplingPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()} { internal_params_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp index b495e6619a1c7..d1c9c8e2535ec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp @@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp index 543b17aca9352..74953b7927b5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp @@ -45,7 +45,8 @@ class SideShiftModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index bcb972bf5dc8b..cd4298c56929a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -40,8 +40,9 @@ SideShiftModule::SideShiftModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp index 5d3d224673124..a26c48ad065c9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp @@ -38,7 +38,7 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index bb70ae2638056..e0bb5d95f565a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -88,7 +88,8 @@ class StartPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); ~StartPlannerModule() override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index e318fbedf3200..dd9129216fbba 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -59,8 +59,9 @@ StartPlannerModule::StartPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp index 895390f91cc16..fa54ec52203f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp @@ -41,7 +41,7 @@ class StaticObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 34d06a46d9ac8..dc6e41fbc5f7e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -46,7 +46,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 39a8d1b853e47..3c76e288fdd55 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -76,8 +76,9 @@ StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + std::shared_ptr & steering_factor_interface_ptr) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT helper_{std::make_shared(parameters)}, parameters_{parameters}, generator_{parameters} From a891b8ec77e8d4388ffe21c4c79362c19ad2ed37 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 4 Sep 2024 10:57:19 +0900 Subject: [PATCH 123/151] fix(lane_change): modify lane change requested condition (#8510) (#1504) * modify lane change requested condition * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp * style(pre-commit): autofix * fix docstring --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../utils/calculation.hpp | 38 ++++++++++++++++++ .../src/scene.cpp | 12 +++++- .../src/utils/calculation.cpp | 40 +++++++++++++++++++ 3 files changed, 89 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index 3dc5e7ee62a57..ae0a094e038a4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -58,6 +58,44 @@ double calc_dist_from_pose_to_terminal_end( * @return The required backward buffer distance in meters. */ double calc_stopping_distance(const LCParamPtr & lc_param_ptr); + +/** + * @brief Calculates the maximum preparation longitudinal distance for lane change. + * + * This function computes the maximum distance that the ego vehicle can travel during + * the preparation phase of a lane change. The distance is calculated as the product + * of the maximum lane change preparation duration and the maximum velocity of the ego vehicle. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - `lc_param_ptr->lane_change_prepare_duration`: The duration allowed for lane change + * preparation. + * - `bpp_param_ptr->max_vel`: The maximum velocity of the ego vehicle. + * + * @return The maximum preparation longitudinal distance in meters. + */ +double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr); + +/** + * @brief Calculates the distance from the ego vehicle to the start of the target lanes. + * + * This function computes the shortest distance from the current position of the ego vehicle + * to the start of the target lanes by measuring the arc length to the front points of + * the left and right boundaries of the target lane. If the target lanes are empty or other + * required data is unavailable, the function returns numeric_limits::max() preventing lane + * change being executed. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which should include: + * - `route_handler_ptr`: Pointer to the route handler that manages the route. + * - Other necessary parameters for ego vehicle positioning. + * @param current_lanes The set of lanelets representing the current lanes of the ego vehicle. + * @param target_lanes The set of lanelets representing the target lanes for lane changing. + * + * @return The distance from the ego vehicle to the start of the target lanes in meters, + * or numeric_limits::max() if the target lanes are empty or data is unavailable. + */ +double calc_ego_dist_to_lanes_start( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes); } // namespace autoware::behavior_path_planner::utils::lane_change::calculation #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 42b22f9b1631c..28efae2549d1e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -153,6 +153,8 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) bool NormalLaneChange::isLaneChangeRequired() { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + const auto current_lanes = utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); @@ -162,7 +164,15 @@ bool NormalLaneChange::isLaneChangeRequired() const auto target_lanes = getLaneChangeLanes(current_lanes, direction_); - return !target_lanes.empty(); + if (target_lanes.empty()) { + return false; + } + + const auto ego_dist_to_target_start = + calculation::calc_ego_dist_to_lanes_start(common_data_ptr_, current_lanes, target_lanes); + const auto maximum_prepare_length = calculation::calc_maximum_prepare_length(common_data_ptr_); + + return ego_dist_to_target_start <= maximum_prepare_length; } bool NormalLaneChange::isStoppedAtRedTrafficLight() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index ac205ceedb34b..2dc65a8b78045 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -54,4 +54,44 @@ double calc_stopping_distance(const LCParamPtr & lc_param_ptr) const auto param_back_dist = lc_param_ptr->backward_length_buffer_for_end_of_lane; return std::max(min_back_dist, param_back_dist); } + +double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr) +{ + const auto max_prepare_duration = common_data_ptr->lc_param_ptr->lane_change_prepare_duration; + const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel; + + return max_prepare_duration * ego_max_speed; +} + +double calc_ego_dist_to_lanes_start( + const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes) +{ + const auto & route_handler_ptr = common_data_ptr->route_handler_ptr; + + if (!route_handler_ptr || target_lanes.empty() || current_lanes.empty()) { + return std::numeric_limits::max(); + } + + const auto & target_bound = + common_data_ptr->direction == autoware::route_handler::Direction::RIGHT + ? target_lanes.front().leftBound() + : target_lanes.front().rightBound(); + + if (target_bound.empty()) { + return std::numeric_limits::max(); + } + + const auto path = + route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + + if (path.points.empty()) { + return std::numeric_limits::max(); + } + + const auto target_front_pt = lanelet::utils::conversion::toGeomMsgPt(target_bound.front()); + const auto ego_position = common_data_ptr->get_ego_pose().position; + + return motion_utils::calcSignedArcLength(path.points, ego_position, target_front_pt); +} } // namespace autoware::behavior_path_planner::utils::lane_change::calculation From 0322aab15bc8175fba72c0490ef13e0b7c1360cf Mon Sep 17 00:00:00 2001 From: Tiankui Xian <1041084556@qq.com> Date: Wed, 21 Aug 2024 14:23:09 +0900 Subject: [PATCH 124/151] feat(motion_velocity_planner,planning_evaluator): add stop, slow_down diags (#8503) Signed-off-by: xtk8532704 <1041084556@qq.com> Co-authored-by: Kosuke Takeuchi --- .../src/node.cpp | 12 ++++- .../src/node.hpp | 3 ++ .../src/planner_manager.cpp | 51 ++++++++++++++++++- .../src/planner_manager.hpp | 11 ++++ 4 files changed, 73 insertions(+), 4 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 76b64c0a4d5e2..e458b81a53ca8 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -83,8 +83,9 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & velocity_factor_publisher_ = this->create_publisher( "~/output/velocity_factors", 1); - processing_time_publisher_ = this->create_publisher( - "~/debug/total_time/processing_time_ms", 1); + processing_time_publisher_ = + this->create_publisher("~/debug/processing_time_ms", 1); + diagnostics_pub_ = this->create_publisher("/diagnostics", 10); // Parameters smooth_velocity_before_planning_ = declare_parameter("smooth_velocity_before_planning"); @@ -293,6 +294,13 @@ void MotionVelocityPlannerNode::on_trajectory( processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); + + std::shared_ptr diagnostics = + planner_manager_.get_diagnostics(get_clock()->now()); + if (!diagnostics->status.empty()) { + diagnostics_pub_->publish(*diagnostics); + } + planner_manager_.clear_diagnostics(); } void MotionVelocityPlannerNode::insert_stop( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 8debb9cbedf00..b143018bb0e1e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -43,6 +43,8 @@ #include #include +using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + namespace autoware::motion_velocity_planner { using autoware_map_msgs::msg::LaneletMapBin; @@ -100,6 +102,7 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this}; rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; + rclcpp::Publisher::SharedPtr diagnostics_pub_; // parameters rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr set_param_callback_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp index 66063fcbaebca..04641e0cea6bb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp @@ -71,13 +71,60 @@ void MotionVelocityPlannerManager::update_module_parameters( for (auto & plugin : loaded_plugins_) plugin->update_parameters(parameters); } +std::shared_ptr MotionVelocityPlannerManager::make_diagnostic( + const std::string & module_name, const std::string & reason, const bool is_decided) +{ + auto status = std::make_shared(); + status->level = status->OK; + status->name = module_name + '.' + reason; + diagnostic_msgs::msg::KeyValue key_value; + { + // Decision + key_value.key = "decision"; + if (is_decided) + key_value.value = reason; + else + key_value.value = "none"; + status->values.push_back(key_value); + } + // Add other information to the status if necessary in the future. + return status; +} + +std::shared_ptr MotionVelocityPlannerManager::get_diagnostics( + const rclcpp::Time & current_time) const +{ + auto diagnostics = std::make_shared(); + + for (const auto & ds_ptr : diagnostics_) { + if ( + !ds_ptr->values.empty() && ds_ptr->values[0].key == "decision" && + ds_ptr->values[0].value != "none") { + diagnostics->status.push_back(*ds_ptr); + } + } + diagnostics->header.stamp = current_time; + diagnostics->header.frame_id = "map"; + return diagnostics; +} + std::vector MotionVelocityPlannerManager::plan_velocities( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) { std::vector results; - for (auto & plugin : loaded_plugins_) - results.push_back(plugin->plan(ego_trajectory_points, planner_data)); + for (auto & plugin : loaded_plugins_) { + VelocityPlanningResult res = plugin->plan(ego_trajectory_points, planner_data); + results.push_back(res); + + const auto stop_reason_diag = + make_diagnostic(plugin->get_module_name(), "stop", res.stop_points.size() > 0); + diagnostics_.push_back(stop_reason_diag); + + const auto slow_down_reason_diag = + make_diagnostic(plugin->get_module_name(), "slow_down", res.slowdown_intervals.size() > 0); + diagnostics_.push_back(slow_down_reason_diag); + } return results; } } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp index 20165d359f669..ac2e421d30cb6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -35,6 +36,9 @@ #include #include +using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; +using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + namespace autoware::motion_velocity_planner { class MotionVelocityPlannerManager @@ -48,7 +52,14 @@ class MotionVelocityPlannerManager const std::vector & ego_trajectory_points, const std::shared_ptr planner_data); + // Diagnostic + std::shared_ptr make_diagnostic( + const std::string & module_name, const std::string & reason, const bool is_decided = true); + std::shared_ptr get_diagnostics(const rclcpp::Time & current_time) const; + void clear_diagnostics() { diagnostics_.clear(); } + private: + std::vector> diagnostics_; pluginlib::ClassLoader plugin_loader_; std::vector> loaded_plugins_; }; From 9538feae5fb2325045cb40a7ec46ab18196da616 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 26 Aug 2024 11:20:01 +0900 Subject: [PATCH 125/151] feat(out_of_lane): redesign to improve accuracy and performance (#8453) Signed-off-by: Maxime CLEMENT --- .../motion_utils/trajectory/trajectory.hpp | 9 + .../src/trajectory/trajectory.cpp | 23 ++ .../README.md | 37 +- .../config/out_of_lane.param.yaml | 25 +- .../src/calculate_slowdown_points.cpp | 131 ++++-- .../src/calculate_slowdown_points.hpp | 45 +- .../src/debug.cpp | 280 ++++++------- .../src/debug.hpp | 8 +- .../src/decisions.cpp | 389 ------------------ .../src/decisions.hpp | 116 ------ .../src/filter_predicted_objects.cpp | 46 +-- .../src/filter_predicted_objects.hpp | 4 +- .../src/footprint.cpp | 23 +- .../src/footprint.hpp | 12 +- .../src/lanelets_selection.cpp | 118 ++++-- .../src/lanelets_selection.hpp | 39 +- .../src/out_of_lane_collisions.cpp | 166 ++++++++ .../src/out_of_lane_collisions.hpp | 55 +++ .../src/out_of_lane_module.cpp | 317 +++++++------- .../src/out_of_lane_module.hpp | 18 +- .../src/overlapping_range.cpp | 127 ------ .../src/overlapping_range.hpp | 63 --- .../src/types.hpp | 216 +++------- .../CMakeLists.txt | 17 +- .../collision_checker.hpp | 69 ++++ .../planner_data.hpp | 29 +- .../src/collision_checker.cpp | 70 ++++ .../test/test_collision_checker.cpp | 176 ++++++++ .../src/node.cpp | 35 +- 29 files changed, 1238 insertions(+), 1425 deletions(-) delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp index 126e66772920a..0ce42fbe1080f 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp @@ -2504,6 +2504,15 @@ extern template bool isTargetPointFront & trajectory, + const geometry_msgs::msg::Point & current_ego_point, const float min_velocity = 1.0f); + } // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__TRAJECTORY_HPP_ diff --git a/common/autoware_motion_utils/src/trajectory/trajectory.cpp b/common/autoware_motion_utils/src/trajectory/trajectory.cpp index ce26952c3d634..080d8ca8c7437 100644 --- a/common/autoware_motion_utils/src/trajectory/trajectory.cpp +++ b/common/autoware_motion_utils/src/trajectory/trajectory.cpp @@ -599,4 +599,27 @@ template bool isTargetPointFront & trajectory, + const geometry_msgs::msg::Point & current_ego_point, const float min_velocity) +{ + const auto nearest_segment_idx = findNearestSegmentIndex(trajectory, current_ego_point); + if (nearest_segment_idx + 1 == trajectory.size()) { + return; + } + for (auto & p : trajectory) { + p.time_from_start = rclcpp::Duration::from_seconds(0); + } + // TODO(Maxime): some points can have very low velocities which introduce huge time errors + // Temporary solution: use a minimum velocity + for (auto idx = nearest_segment_idx + 1; idx < trajectory.size(); ++idx) { + const auto & from = trajectory[idx - 1]; + const auto velocity = std::max(min_velocity, from.longitudinal_velocity_mps); + if (velocity != 0.0) { + auto & to = trajectory[idx]; + const auto t = universe_utils::calcDistance2d(from, to) / velocity; + to.time_from_start = rclcpp::Duration::from_seconds(t) + from.time_from_start; + } + } +} } // namespace autoware::motion_utils diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md index 99396eb0edf22..54b7cebb7c8ff 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md @@ -129,33 +129,24 @@ Moreover, parameter `action.distance_buffer` adds an extra distance between the | -------------------- | ------ | ---------------------------------------------------------------- | | `time_threshold` | double | [s] consider objects that will reach an overlap within this time | -| Parameter /intervals | Type | Description | -| --------------------- | ------ | ------------------------------------------------------- | -| `ego_time_buffer` | double | [s] extend the ego time interval by this buffer | -| `objects_time_buffer` | double | [s] extend the time intervals of objects by this buffer | - | Parameter /ttc | Type | Description | | -------------- | ------ | ------------------------------------------------------------------------------------------------------ | | `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | -| Parameter /objects | Type | Description | -| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | -| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | -| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | - -| Parameter /overlap | Type | Description | -| ------------------ | ------ | ---------------------------------------------------------------------------------------------------- | -| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | -| `extra_length` | double | [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) | - -| Parameter /action | Type | Description | -| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------- | -| `skip_if_over_max_decel` | bool | [-] if true, do not take an action that would cause more deceleration than the maximum allowed | -| `distance_buffer` | double | [m] buffer distance to try to keep between the ego footprint and lane | -| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | -| `slowdown.velocity` | double | [m] slow down velocity | -| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | +| Parameter /objects | Type | Description | +| ------------------------------- | ------ | --------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | + +| Parameter /overlap | Type | Description | +| ------------------ | ------ | --------------------------------------------------------------------- | +| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | + +| Parameter /action | Type | Description | +| ----------------------------- | ------ | --------------------------------------------------------------------- | +| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | +| `slowdown.velocity` | double | [m] slow down velocity | +| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | | Parameter /ego | Type | Description | | -------------------- | ------ | ---------------------------------------------------- | diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index a0cf69ee71027..67db597d80752 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -1,32 +1,23 @@ /**: ros__parameters: out_of_lane: # module to stop or slowdown before overlapping another lane with other objects - mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc" + mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane + ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored + max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time - intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego - ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer - objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer ttc: threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap objects: minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored - use_predicted_paths: true # if true, use the predicted paths to estimate future positions. - # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. - distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights ignore_behind_ego: true # if true, objects behind the ego vehicle are ignored - overlap: - minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered - extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) - action: # action to insert in the trajectory if an object causes a conflict at an overlap - skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed precision: 0.1 # [m] precision when inserting a stop pose in the trajectory longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle @@ -38,8 +29,8 @@ distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap ego: - min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego - extra_front_offset: 0.0 # [m] extra front distance - extra_rear_offset: 0.0 # [m] extra rear distance - extra_right_offset: 0.0 # [m] extra right distance - extra_left_offset: 0.0 # [m] extra left distance + # extra footprint offsets to calculate out of lane collisions + extra_front_offset: 0.0 # [m] extra footprint front distance + extra_rear_offset: 0.0 # [m] extra footprint rear distance + extra_right_offset: 0.0 # [m] extra footprint right distance + extra_left_offset: 0.0 # [m] extra footprint left distance diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp index 8b03fa66eab55..b7cd55ce2e642 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -15,74 +15,117 @@ #include "calculate_slowdown_points.hpp" #include "footprint.hpp" +#include "types.hpp" #include #include +#include -#include +#include +#include +#include +#include + +#include #include +#include +#include +#include + namespace autoware::motion_velocity_planner::out_of_lane { -bool can_decelerate( - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel) +std::optional calculate_last_avoiding_pose( + const std::vector & trajectory, + const universe_utils::Polygon2d & footprint, const lanelet::BasicPolygons2d & polygons_to_avoid, + const double min_arc_length, const double max_arc_length, const double precision) { - // TODO(Maxime): use the library function - const auto dist_ahead_of_ego = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, ego_data.pose.position, point.pose.position); - const auto acc_to_target_vel = - (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); - return acc_to_target_vel < std::abs(ego_data.max_decel); + geometry_msgs::msg::Pose interpolated_pose{}; + bool is_avoiding_pose = false; + + auto from = min_arc_length; + auto to = max_arc_length; + while (to - from > precision) { + auto l = from + 0.5 * (to - from); + interpolated_pose = motion_utils::calcInterpolatedPose(trajectory, l); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); + is_avoiding_pose = + std::all_of(polygons_to_avoid.begin(), polygons_to_avoid.end(), [&](const auto & polygon) { + return boost::geometry::disjoint(interpolated_footprint, polygon); + }); + if (is_avoiding_pose) { + from = l; + } else { + to = l; + } + } + if (is_avoiding_pose) { + return interpolated_pose; + } + return std::nullopt; } -std::optional calculate_last_in_lane_pose( - const EgoData & ego_data, const Slowdown & decision, - const autoware::universe_utils::Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params) +std::optional calculate_pose_ahead_of_collision( + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, + const universe_utils::Polygon2d & footprint, const double precision) { - const auto from_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, 0, ego_data.first_trajectory_idx); - const auto to_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, 0, decision.target_trajectory_idx); - TrajectoryPoint interpolated_point; - for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { - // TODO(Maxime): binary search - interpolated_point.pose = - autoware::motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); - const auto respect_decel_limit = - !params.skip_if_over_max_decel || prev_slowdown_point || - can_decelerate(ego_data, interpolated_point, decision.velocity); - const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.pose); - const auto is_overlap_lane = boost::geometry::overlaps( - interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); - const auto is_overlap_extra_lane = - prev_slowdown_point && - boost::geometry::overlaps( - interpolated_footprint, - prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); - if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) - return interpolated_point; + const auto first_avoid_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0UL, point_to_avoid.trajectory_index); + for (auto l = first_avoid_arc_length - precision; l >= ego_data.min_stop_arc_length; + l -= precision) { + const auto interpolated_pose = + motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); + if (boost::geometry::intersects(interpolated_footprint, point_to_avoid.outside_ring)) { + return interpolated_pose; + } } return std::nullopt; } -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional & prev_slowdown_point, PlannerParam params) +std::optional calculate_slowdown_point( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params) { + const auto point_to_avoid_it = std::find_if( + out_of_lane_data.outside_points.cbegin(), out_of_lane_data.outside_points.cend(), + [&](const auto & p) { return p.to_avoid; }); + if (point_to_avoid_it == out_of_lane_data.outside_points.cend()) { + return std::nullopt; + } + const auto raw_footprint = make_base_footprint(params, true); // ignore extra footprint offsets + const auto base_footprint = make_base_footprint(params); params.extra_front_offset += params.lon_dist_buffer; params.extra_right_offset += params.lat_dist_buffer; params.extra_left_offset += params.lat_dist_buffer; - const auto base_footprint = make_base_footprint(params); + const auto expanded_footprint = make_base_footprint(params); // with added distance buffers + lanelet::BasicPolygons2d polygons_to_avoid; + for (const auto & ll : point_to_avoid_it->overlapped_lanelets) { + polygons_to_avoid.push_back(ll.polygon2d().basicPolygon()); + } + // points are ordered by trajectory index so the first one has the smallest index and arc length + const auto first_outside_idx = out_of_lane_data.outside_points.front().trajectory_index; + const auto first_outside_arc_length = + motion_utils::calcSignedArcLength(ego_data.trajectory_points, 0UL, first_outside_idx); + std::optional slowdown_point; // search for the first slowdown decision for which a stop point can be inserted - for (const auto & decision : decisions) { - const auto last_in_lane_pose = - calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); - if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; + // we first try to use the expanded footprint (distance buffers + extra footprint offsets) + for (const auto & footprint : {expanded_footprint, base_footprint, raw_footprint}) { + slowdown_point = calculate_last_avoiding_pose( + ego_data.trajectory_points, footprint, polygons_to_avoid, ego_data.min_stop_arc_length, + first_outside_arc_length, params.precision); + if (slowdown_point) { + break; + } } - return std::nullopt; + // fallback to simply stopping ahead of the collision to avoid (regardless of being out of lane or + // not) + if (!slowdown_point) { + slowdown_point = calculate_pose_ahead_of_collision( + ego_data, *point_to_avoid_it, expanded_footprint, params.precision); + } + return slowdown_point; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index 145f21c94c0d0..394334d434558 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -19,40 +19,39 @@ #include +#include + #include -#include namespace autoware::motion_velocity_planner::out_of_lane { - -/// @brief estimate whether ego can decelerate without breaking the deceleration limit -/// @details assume ego wants to reach the target point at the target velocity -/// @param [in] ego_data ego data -/// @param [in] point target point -/// @param [in] target_vel target_velocity -bool can_decelerate( - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel); - -/// @brief calculate the last pose along the trajectory where ego does not overlap the lane to avoid +/// @brief calculate the last pose along the trajectory where ego does not go out of lane /// @param [in] ego_data ego data -/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed) /// @param [in] footprint the ego footprint -/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits -/// @param [in] params parameters +/// @param [in] min_arc_length minimum arc length for the search +/// @param [in] max_arc_length maximum arc length for the search +/// @param [in] precision [m] search precision /// @return the last pose that is not out of lane (if found) -std::optional calculate_last_in_lane_pose( - const EgoData & ego_data, const Slowdown & decision, - const autoware::universe_utils::Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params); +std::optional calculate_last_in_lane_pose( + const EgoData & ego_data, const autoware::universe_utils::Polygon2d & footprint, + const double min_arc_length, const double max_arc_length, const double precision); + +/// @brief calculate the slowdown pose just ahead of a point to avoid +/// @param ego_data ego data (trajectory, velocity, etc) +/// @param point_to_avoid the point to avoid +/// @param footprint the ego footprint +/// @param params parameters +/// @return optional slowdown point to insert in the trajectory +std::optional calculate_pose_ahead_of_collision( + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, + const universe_utils::Polygon2d & footprint, const double precision); /// @brief calculate the slowdown point to insert in the trajectory /// @param ego_data ego data (trajectory, velocity, etc) -/// @param decisions decision (before which point to stop, what lane to avoid entering, etc) -/// @param prev_slowdown_point previously calculated slowdown point +/// @param out_of_lane_data data about out of lane areas /// @param params parameters /// @return optional slowdown point to insert in the trajectory -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional & prev_slowdown_point, PlannerParam params); +std::optional calculate_slowdown_point( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp index d9a85e266f790..cb29f9b3b42ea 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp @@ -16,12 +16,22 @@ #include "types.hpp" +#include +#include +#include #include +#include +#include #include +#include + +#include +#include +#include + #include -#include namespace autoware::motion_velocity_planner::out_of_lane::debug { @@ -36,209 +46,167 @@ visualization_msgs::msg::Marker get_base_marker() base_marker.id = 0; base_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; base_marker.action = visualization_msgs::msg::Marker::ADD; - base_marker.pose.position = autoware::universe_utils::createMarkerPosition(0.0, 0.0, 0); - base_marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); - base_marker.scale = autoware::universe_utils::createMarkerScale(0.1, 0.1, 0.1); - base_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + base_marker.pose.position = universe_utils::createMarkerPosition(0.0, 0.0, 0); + base_marker.pose.orientation = universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + base_marker.scale = universe_utils::createMarkerScale(0.1, 0.1, 0.1); + base_marker.color = universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); return base_marker; } -void add_footprint_markers( +void add_polygons_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb) + const lanelet::BasicPolygons2d & polygons, const double z, const std::string & ns) { auto debug_marker = get_base_marker(); - debug_marker.ns = "footprints"; - for (const auto & f : footprints) { - debug_marker.points.clear(); - for (const auto & p : f) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - debug_marker.points.clear(); + debug_marker.ns = ns; + debug_marker.type = visualization_msgs::msg::Marker::LINE_LIST; + for (const auto & f : polygons) { + boost::geometry::for_each_segment(f, [&](const auto & s) { + const auto & [p1, p2] = s; + debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), z + 0.5)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), z + 0.5)); + }); } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); + debug_marker_array.markers.push_back(debug_marker); } void add_current_overlap_marker( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb) + const lanelet::BasicPolygon2d & current_footprint, const double z) { auto debug_marker = get_base_marker(); debug_marker.ns = "current_overlap"; debug_marker.points.clear(); for (const auto & p : current_footprint) - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z)); if (!debug_marker.points.empty()) debug_marker.points.push_back(debug_marker.points.front()); - if (current_overlapped_lanelets.empty()) - debug_marker.color = autoware::universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); - else - debug_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + debug_marker.color = universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; - for (const auto & ll : current_overlapped_lanelets) { - debug_marker.points.clear(); - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.5)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -void add_lanelet_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color, const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = ns; - debug_marker.color = color; - for (const auto & ll : lanelets) { - debug_marker.points.clear(); - - // add a small z offset to draw above the lanelet map - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.1)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); } -void add_range_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, - const std::vector & trajectory_points, - const size_t first_ego_idx, const double z, const size_t prev_nb) +void add_ttc_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const EgoData & ego_data, + const OutOfLaneData & out_of_lane_data, const size_t prev_nb) { auto debug_marker = get_base_marker(); - debug_marker.ns = "ranges"; - debug_marker.color = autoware::universe_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); - for (const auto & range : ranges) { - debug_marker.points.clear(); - debug_marker.points.push_back( - trajectory_points[first_ego_idx + range.entering_trajectory_idx].pose.position); - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - for (const auto & overlap : range.debug.overlaps) { - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); + debug_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + debug_marker.scale.z = 0.5; + debug_marker.ns = "ttcs"; + for (const auto & p : out_of_lane_data.outside_points) { + if (p.to_avoid) { + debug_marker.color.r = 1.0; + debug_marker.color.g = 0.0; + } else { + debug_marker.color.r = 0.0; + debug_marker.color.g = 1.0; + } + if (p.ttc) { + debug_marker.pose = ego_data.trajectory_points[p.trajectory_index].pose; + debug_marker.text = std::to_string(*p.ttc); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; } - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.exiting_point.x(), range.exiting_point.y(), z)); - debug_marker.points.push_back( - trajectory_points[first_ego_idx + range.exiting_trajectory_idx].pose.position); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker.action = visualization_msgs::msg::Marker::DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { debug_marker_array.markers.push_back(debug_marker); + } } - -void add_decision_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, +size_t add_stop_line_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const StopLinesRtree & rtree, const double z, const size_t prev_nb) { auto debug_marker = get_base_marker(); - debug_marker.action = debug_marker.ADD; - debug_marker.id = 0; - debug_marker.ns = "decisions"; - debug_marker.color = autoware::universe_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); - debug_marker.points.clear(); - for (const auto & range : ranges) { - debug_marker.type = debug_marker.LINE_STRIP; - if (range.debug.decision) { - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - debug_marker.points.push_back( - range.debug.object->kinematics.initial_pose_with_covariance.pose.position); + debug_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + debug_marker.ns = "stop_lines"; + const auto & add_lanelets_markers = [&](const auto & lanelets) { + for (const auto & ll : lanelets) { + debug_marker.points.clear(); + for (const auto & p : ll.polygon2d().basicPolygon()) { + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); + } + debug_marker.points.push_back(debug_marker.points.front()); + debug_marker_array.markers.push_back(debug_marker); + ++debug_marker.id; } - debug_marker_array.markers.push_back(debug_marker); + }; + for (const auto & [_, stop_line] : rtree) { debug_marker.points.clear(); - debug_marker.id++; - - debug_marker.type = debug_marker.TEXT_VIEW_FACING; - debug_marker.pose.position.x = range.entering_point.x(); - debug_marker.pose.position.y = range.entering_point.y(); - debug_marker.pose.position.z = z; - std::stringstream ss; - ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time - << "\n"; - if (range.debug.object) { - debug_marker.pose.position.x += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x; - debug_marker.pose.position.y += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y; - debug_marker.pose.position.x /= 2; - debug_marker.pose.position.y /= 2; - ss << "Obj: " << range.debug.times.object.enter_time << " - " - << range.debug.times.object.exit_time << "\n"; + debug_marker.color.r = 1.0; + for (const auto & p : stop_line.stop_line) { + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); } - debug_marker.scale.z = 1.0; - debug_marker.text = ss.str(); debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; + ++debug_marker.id; + debug_marker.color.r = 0.0; + add_lanelets_markers(stop_line.lanelets); } - debug_marker.action = debug_marker.DELETE; + const auto max_id = debug_marker.id; + debug_marker.action = visualization_msgs::msg::Marker::DELETE; for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { debug_marker_array.markers.push_back(debug_marker); } + return max_id; } } // namespace -visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data) + +visualization_msgs::msg::MarkerArray create_debug_marker_array( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedObjects & objects, DebugData & debug_data) { - constexpr auto z = 0.0; + const auto z = ego_data.pose.position.z; visualization_msgs::msg::MarkerArray debug_marker_array; - debug::add_footprint_markers( - debug_marker_array, debug_data.footprints, z, debug_data.prev_footprints); - debug::add_current_overlap_marker( - debug_marker_array, debug_data.current_footprint, debug_data.current_overlapped_lanelets, z, - debug_data.prev_current_overlapped_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.trajectory_lanelets, "trajectory_lanelets", - autoware::universe_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), - debug_data.prev_trajectory_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.ignored_lanelets, "ignored_lanelets", - autoware::universe_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), - debug_data.prev_ignored_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.other_lanelets, "other_lanelets", - autoware::universe_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), - debug_data.prev_other_lanelets); - debug::add_range_markers( - debug_marker_array, debug_data.ranges, debug_data.trajectory_points, - debug_data.first_trajectory_idx, z, debug_data.prev_ranges); - debug::add_decision_markers(debug_marker_array, debug_data.ranges, z, debug_data.prev_ranges); + // add_polygons_markers(debug_marker_array, ego_data.trajectory_footprints, z, "footprints"); + + lanelet::BasicPolygons2d drivable_lane_polygons; + for (const auto & poly : ego_data.drivable_lane_polygons) { + drivable_lane_polygons.push_back(poly.outer); + } + add_polygons_markers(debug_marker_array, drivable_lane_polygons, z, "ego_lane"); + + lanelet::BasicPolygons2d out_of_lane_areas; + for (const auto & p : out_of_lane_data.outside_points) { + out_of_lane_areas.push_back(p.outside_ring); + } + add_polygons_markers(debug_marker_array, out_of_lane_areas, z, "out_of_lane_areas"); + + lanelet::BasicPolygons2d object_polygons; + for (const auto & o : objects.objects) { + for (const auto & path : o.kinematics.predicted_paths) { + for (const auto & pose : path.path) { + // limit the draw distance to improve performance + if (universe_utils::calcDistance2d(pose, ego_data.pose) < 50.0) { + const auto poly = universe_utils::toPolygon2d(pose, o.shape).outer(); + lanelet::BasicPolygon2d ll_poly(poly.begin(), poly.end()); + object_polygons.push_back(ll_poly); + } + } + } + } + add_polygons_markers(debug_marker_array, object_polygons, z, "objects"); + + add_current_overlap_marker(debug_marker_array, ego_data.current_footprint, z); + + add_ttc_markers(debug_marker_array, ego_data, out_of_lane_data, debug_data.prev_ttcs); + debug_data.prev_ttcs = out_of_lane_data.outside_points.size(); + + debug_data.prev_stop_line = add_stop_line_markers( + debug_marker_array, ego_data.stop_lines_rtree, z, debug_data.prev_stop_line); + return debug_marker_array; } -autoware::motion_utils::VirtualWalls create_virtual_walls( - const DebugData & debug_data, const PlannerParam & params) +motion_utils::VirtualWalls create_virtual_walls( + const geometry_msgs::msg::Pose & pose, const bool stop, const PlannerParam & params) { - autoware::motion_utils::VirtualWalls virtual_walls; - autoware::motion_utils::VirtualWall wall; + motion_utils::VirtualWalls virtual_walls; + motion_utils::VirtualWall wall; wall.text = "out_of_lane"; wall.longitudinal_offset = params.front_offset; - wall.style = autoware::motion_utils::VirtualWallType::slowdown; - for (const auto & slowdown : debug_data.slowdowns) { - wall.pose = slowdown.point.pose; - virtual_walls.push_back(wall); - } + wall.style = stop ? motion_utils::VirtualWallType::stop : motion_utils::VirtualWallType::slowdown; + wall.pose = pose; + virtual_walls.push_back(wall); return virtual_walls; } } // namespace autoware::motion_velocity_planner::out_of_lane::debug diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp index ea225442443c8..dc1f942655612 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp @@ -23,9 +23,11 @@ namespace autoware::motion_velocity_planner::out_of_lane::debug { -visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data); -autoware::motion_utils::VirtualWalls create_virtual_walls( - const DebugData & debug_data, const PlannerParam & params); +visualization_msgs::msg::MarkerArray create_debug_marker_array( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedObjects & objects, DebugData & debug_data); +motion_utils::VirtualWalls create_virtual_walls( + const geometry_msgs::msg::Pose & pose, const bool stop, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane::debug #endif // DEBUG_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp deleted file mode 100644 index fc487a2626b88..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp +++ /dev/null @@ -1,389 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "decisions.hpp" - -#include -#include -#include -#include - -#include - -#include -#include -#include - -#include -#include -#include -#include -namespace autoware::motion_velocity_planner::out_of_lane -{ -double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx) -{ - return autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, ego_data.pose.position, ego_data.first_trajectory_idx + target_idx); -} - -double time_along_trajectory( - const EgoData & ego_data, const size_t target_idx, const double min_velocity) -{ - const auto dist = distance_along_trajectory(ego_data, target_idx); - const auto v = std::max( - std::max(ego_data.velocity, min_velocity), - ego_data.trajectory_points[ego_data.first_trajectory_idx + target_idx] - .longitudinal_velocity_mps * - 0.5); - return dist / v; -} - -bool object_is_incoming( - const lanelet::BasicPoint2d & object_position, - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lane) -{ - const auto lanelets = route_handler->getPrecedingLaneletSequence(lane, 50.0); - if (boost::geometry::within(object_position, lane.polygon2d().basicPolygon())) return true; - for (const auto & lls : lanelets) - for (const auto & ll : lls) - if (boost::geometry::within(object_position, ll.polygon2d().basicPolygon())) return true; - return false; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger) -{ - // skip the dynamic object if it is not in a lane preceding the overlapped lane - // lane changes are intentionally not considered - const auto object_point = lanelet::BasicPoint2d( - object.kinematics.initial_pose_with_covariance.pose.position.x, - object.kinematics.initial_pose_with_covariance.pose.position.y); - if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; - - const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer; - const auto max_lon_deviation = object.shape.dimensions.x / 2.0; - auto worst_enter_time = std::optional(); - auto worst_exit_time = std::optional(); - - for (const auto & predicted_path : object.kinematics.predicted_paths) { - const auto unique_path_points = - autoware::motion_utils::removeOverlapPoints(predicted_path.path); - if (unique_path_points.size() < 2) continue; - const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds(); - const auto enter_point = - geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); - const auto enter_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, enter_segment_idx, enter_point); - const auto enter_lat_dist = std::abs(autoware::motion_utils::calcLateralOffset( - unique_path_points, enter_point, enter_segment_idx)); - const auto enter_segment_length = autoware::universe_utils::calcDistance2d( - unique_path_points[enter_segment_idx], unique_path_points[enter_segment_idx + 1]); - const auto enter_offset_ratio = enter_offset / enter_segment_length; - const auto enter_time = - static_cast(enter_segment_idx) * time_step + enter_offset_ratio * time_step; - - const auto exit_point = - geometry_msgs::msg::Point().set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); - const auto exit_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, exit_segment_idx, exit_point); - const auto exit_lat_dist = std::abs( - autoware::motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); - const auto exit_segment_length = autoware::universe_utils::calcDistance2d( - unique_path_points[exit_segment_idx], unique_path_points[exit_segment_idx + 1]); - const auto exit_offset_ratio = exit_offset / static_cast(exit_segment_length); - const auto exit_time = - static_cast(exit_segment_idx) * time_step + exit_offset_ratio * time_step; - - RCLCPP_DEBUG( - logger, "\t\t\tPredicted path (time step = %2.2fs): enter @ %2.2fs, exit @ %2.2fs", time_step, - enter_time, exit_time); - // predicted path is too far from the overlapping range to be relevant - const auto is_far_from_entering_point = enter_lat_dist > max_deviation; - const auto is_far_from_exiting_point = exit_lat_dist > max_deviation; - if (is_far_from_entering_point && is_far_from_exiting_point) { - RCLCPP_DEBUG( - logger, - " * far_from_enter (%d) = %2.2fm | far_from_exit (%d) = %2.2fm | max_dev = %2.2fm\n", - is_far_from_entering_point, enter_lat_dist, is_far_from_exiting_point, exit_lat_dist, - max_deviation); - continue; - } - const auto is_last_predicted_path_point = - (exit_segment_idx + 2 == unique_path_points.size() || - enter_segment_idx + 2 == unique_path_points.size()); - const auto does_not_reach_overlap = - is_last_predicted_path_point && (std::min(exit_offset, enter_offset) > max_lon_deviation); - if (does_not_reach_overlap) { - RCLCPP_DEBUG( - logger, " * does not reach the overlap = %2.2fm | max_dev = %2.2fm\n", - std::min(exit_offset, enter_offset), max_lon_deviation); - continue; - } - - const auto same_driving_direction_as_ego = enter_time < exit_time; - if (same_driving_direction_as_ego) { - worst_enter_time = worst_enter_time ? std::min(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::max(*worst_exit_time, exit_time) : exit_time; - } else { - worst_enter_time = worst_enter_time ? std::max(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::min(*worst_exit_time, exit_time) : exit_time; - } - } - if (worst_enter_time && worst_exit_time) { - RCLCPP_DEBUG( - logger, "\t\t\t * found enter/exit time [%2.2f, %2.2f]\n", *worst_enter_time, - *worst_exit_time); - return std::make_pair(*worst_enter_time, *worst_exit_time); - } - RCLCPP_DEBUG(logger, "\t\t\t * enter/exit time not found\n"); - return {}; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger) -{ - const auto & p = object.kinematics.initial_pose_with_covariance.pose.position; - const auto object_point = lanelet::BasicPoint2d(p.x, p.y); - const auto half_size = object.shape.dimensions.x / 2.0; - lanelet::ConstLanelets object_lanelets; - for (const auto & ll : inputs.lanelets) - if (boost::geometry::within(object_point, ll.polygon2d().basicPolygon())) - object_lanelets.push_back(ll); - - geometry_msgs::msg::Pose pose; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto range_enter_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto range_exit_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - const auto range_size = std::abs(range_enter_length - range_exit_length); - auto worst_enter_dist = std::optional(); - auto worst_exit_dist = std::optional(); - for (const auto & lane : object_lanelets) { - const auto path = inputs.route_handler->getRoutingGraphPtr()->shortestPath(lane, range.lane); - RCLCPP_DEBUG( - logger, "\t\t\tPath ? %d [from %ld to %ld]\n", path.has_value(), lane.id(), range.lane.id()); - if (path) { - lanelet::ConstLanelets lls; - for (const auto & ll : *path) lls.push_back(ll); - pose.position.set__x(object_point.x()).set__y(object_point.y()); - const auto object_curr_length = lanelet::utils::getArcCoordinates(lls, pose).length; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - RCLCPP_DEBUG( - logger, "\t\t\t%2.2f -> [%2.2f(%2.2f, %2.2f) - %2.2f(%2.2f, %2.2f)]\n", object_curr_length, - enter_dist, range.entering_point.x(), range.entering_point.y(), exit_dist, - range.exiting_point.x(), range.exiting_point.y()); - const auto already_entered_range = std::abs(enter_dist - exit_dist) > range_size * 2.0; - if (already_entered_range) continue; - // multiple paths to the overlap -> be conservative and use the "worst" case - // "worst" = min/max arc length depending on if the lane is running opposite to the ego - // trajectory - const auto is_opposite = enter_dist > exit_dist; - if (!worst_enter_dist) - worst_enter_dist = enter_dist; - else if (is_opposite) - worst_enter_dist = std::max(*worst_enter_dist, enter_dist); - else - worst_enter_dist = std::min(*worst_enter_dist, enter_dist); - if (!worst_exit_dist) - worst_exit_dist = exit_dist; - else if (is_opposite) - worst_exit_dist = std::max(*worst_exit_dist, exit_dist); - else - worst_exit_dist = std::min(*worst_exit_dist, exit_dist); - } - } - if (worst_enter_dist && worst_exit_dist) { - const auto v = object.kinematics.initial_twist_with_covariance.twist.linear.x; - return std::make_pair((*worst_enter_dist - half_size) / v, (*worst_exit_dist + half_size) / v); - } - return {}; -} - -bool threshold_condition(const RangeTimes & range_times, const PlannerParam & params) -{ - const auto enter_within_threshold = - range_times.object.enter_time > 0.0 && range_times.object.enter_time < params.time_threshold; - const auto exit_within_threshold = - range_times.object.exit_time > 0.0 && range_times.object.exit_time < params.time_threshold; - return enter_within_threshold || exit_within_threshold; -} - -bool intervals_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto opposite_way_condition = [&]() -> bool { - const auto ego_exits_before_object_enters = - range_times.ego.exit_time + params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] (opposite way) ego exit %2.2fs < obj enter %2.2fs ? -> should not " - "enter = %d\n", - range_times.ego.exit_time + params.intervals_ego_buffer, - range_times.object.enter_time + params.intervals_obj_buffer, ego_exits_before_object_enters); - return ego_exits_before_object_enters; - }; - const auto same_way_condition = [&]() -> bool { - const auto object_enters_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer && - range_times.object.enter_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - const auto object_exits_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.exit_time + params.intervals_obj_buffer && - range_times.object.exit_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] obj enters during overlap ? %d OR obj exits during overlap %d ? -> should " - "not " - "enter = %d\n", - object_enters_during_overlap, object_exits_during_overlap, - object_enters_during_overlap || object_exits_during_overlap); - return object_enters_during_overlap || object_exits_during_overlap; - }; - - const auto object_is_going_same_way = - range_times.object.enter_time < range_times.object.exit_time; - return (object_is_going_same_way && same_way_condition()) || - (!object_is_going_same_way && opposite_way_condition()); -} - -bool ttc_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto ttc_at_enter = range_times.ego.enter_time - range_times.object.enter_time; - const auto ttc_at_exit = range_times.ego.exit_time - range_times.object.exit_time; - const auto collision_during_overlap = (ttc_at_enter < 0.0) != (ttc_at_exit < 0.0); - const auto ttc_is_bellow_threshold = - std::min(std::abs(ttc_at_enter), std::abs(ttc_at_exit)) <= params.ttc_threshold; - RCLCPP_DEBUG( - logger, "\t\t\t[TTC] (%2.2fs - %2.2fs) -> %d\n", ttc_at_enter, ttc_at_exit, - (collision_during_overlap || ttc_is_bellow_threshold)); - return collision_during_overlap || ttc_is_bellow_threshold; -} - -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - RCLCPP_DEBUG( - logger, " enter at %2.2fs, exits at %2.2fs\n", range_times.object.enter_time, - range_times.object.exit_time); - return (params.mode == "threshold" && threshold_condition(range_times, params)) || - (params.mode == "intervals" && intervals_condition(range_times, params, logger)) || - (params.mode == "ttc" && ttc_condition(range_times, params, logger)); -} - -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - RangeTimes range_times{}; - range_times.ego.enter_time = - time_along_trajectory(inputs.ego_data, range.entering_trajectory_idx, params.ego_min_velocity); - range_times.ego.exit_time = - time_along_trajectory(inputs.ego_data, range.exiting_trajectory_idx, params.ego_min_velocity); - RCLCPP_DEBUG( - logger, "\t[%lu -> %lu] %ld | ego enters at %2.2f, exits at %2.2f\n", - range.entering_trajectory_idx, range.exiting_trajectory_idx, range.lane.id(), - range_times.ego.enter_time, range_times.ego.exit_time); - for (const auto & object : inputs.objects.objects) { - RCLCPP_DEBUG( - logger, "\t\t[%s] going at %2.2fm/s", - autoware::universe_utils::toHexString(object.object_id).c_str(), - object.kinematics.initial_twist_with_covariance.twist.linear.x); - if (object.kinematics.initial_twist_with_covariance.twist.linear.x < params.objects_min_vel) { - RCLCPP_DEBUG(logger, " SKIP (velocity bellow threshold %2.2fm/s)\n", params.objects_min_vel); - continue; // skip objects with velocity bellow a threshold - } - // skip objects that are already on the interval - const auto enter_exit_time = - params.objects_use_predicted_paths - ? object_time_to_range( - object, range, inputs.route_handler, params.objects_dist_buffer, logger) - : object_time_to_range(object, range, inputs, logger); - if (!enter_exit_time) { - RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); - continue; // skip objects that are not driving towards the overlapping range - } - - range_times.object.enter_time = enter_exit_time->first; - range_times.object.exit_time = enter_exit_time->second; - if (will_collide_on_range(range_times, params, logger)) { - range.debug.times = range_times; - range.debug.object = object; - return true; - } - } - range.debug.times = range_times; - return false; -} - -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params) -{ - if (distance < params.stop_dist_threshold) { - decision->velocity = 0.0; - } else if (distance < params.slow_dist_threshold) { - decision->velocity = params.slow_velocity; - } else { - decision.reset(); - } -} - -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - std::optional decision; - if (should_not_enter(range, inputs, params, logger)) { - decision.emplace(); - decision->target_trajectory_idx = inputs.ego_data.first_trajectory_idx + - range.entering_trajectory_idx; // add offset from curr pose - decision->lane_to_avoid = range.lane; - const auto ego_dist_to_range = - distance_along_trajectory(inputs.ego_data, range.entering_trajectory_idx); - set_decision_velocity(decision, ego_dist_to_range, params); - } - return decision; -} - -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger) -{ - std::vector decisions; - for (const auto & range : inputs.ranges) { - if (range.entering_trajectory_idx == 0UL) continue; // skip if we already entered the range - const auto optional_decision = calculate_decision(range, inputs, params, logger); - range.debug.decision = optional_decision; - if (optional_decision) decisions.push_back(*optional_decision); - } - return decisions; -} - -} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp deleted file mode 100644 index 455cee272f7be..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp +++ /dev/null @@ -1,116 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef DECISIONS_HPP_ -#define DECISIONS_HPP_ - -#include "types.hpp" - -#include -#include - -#include - -#include - -#include -#include -#include -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ -/// @brief calculate the distance along the ego trajectory between ego and some target trajectory -/// index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego trajectory index -/// @return distance between ego and the target [m] -double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx); -/// @brief estimate the time when ego will reach some target trajectory index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego trajectory index -/// @param [in] min_velocity minimum ego velocity used to estimate the time -/// @return time taken by ego to reach the target [s] -double time_along_trajectory(const EgoData & ego_data, const size_t target_idx); -/// @brief use an object's predicted paths to estimate the times it will reach the enter and exit -/// points of an overlapping range -/// @details times when the predicted paths of the object enters/exits the range are calculated -/// but may not exist (e.g,, predicted path ends before reaching the end of the range) -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] route_handler route handler used to estimate the path of the dynamic object -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger); -/// @brief use the lanelet map to estimate the times when an object will reach the enter and exit -/// points of an overlapping range -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit. -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger); -/// @brief decide whether an object is coming in the range at the same time as ego -/// @details the condition depends on the mode (threshold, intervals, ttc) -/// @param [in] range_times times when ego and the object enter/exit the range -/// @param [in] params parameters -/// @param [in] logger ros logger -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger); -/// @brief check whether we should avoid entering the given range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return true if we should avoid entering the range -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief set the velocity of a decision (or unset it) based on the distance away from the range -/// @param [out] decision decision to update (either set its velocity or unset the decision) -/// @param [in] distance distance between ego and the range corresponding to the decision -/// @param [in] params parameters -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params); -/// @brief calculate the decision to slowdown or stop before an overlapping range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return an optional decision to slowdown or stop -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief calculate decisions to slowdown or stop before some overlapping ranges -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return the calculated decisions to slowdown or stop -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); -} // namespace autoware::motion_velocity_planner::out_of_lane - -#endif // DECISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index a53129f372e3d..79bdefee4c4c7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -53,7 +54,7 @@ void cut_predicted_path_beyond_line( auto cut_idx = stop_line_idx; double arc_length = 0; while (cut_idx > 0 && arc_length < object_front_overhang) { - arc_length += autoware::universe_utils::calcDistance2d( + arc_length += universe_utils::calcDistance2d( predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]); --cut_idx; } @@ -102,12 +103,11 @@ void cut_predicted_path_beyond_red_lights( } autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const std::shared_ptr planner_data, const EgoData & ego_data, - const PlannerParam & params) + const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params) { autoware_perception_msgs::msg::PredictedObjects filtered_objects; - filtered_objects.header = planner_data->predicted_objects.header; - for (const auto & object : planner_data->predicted_objects.objects) { + filtered_objects.header = planner_data.predicted_objects.header; + for (const auto & object : planner_data.predicted_objects.objects) { const auto is_pedestrian = std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; @@ -125,10 +125,10 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( auto filtered_object = object; const auto is_invalid_predicted_path = [&](const auto & predicted_path) { const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; - const auto no_overlap_path = autoware::motion_utils::removeOverlapPoints(predicted_path.path); + const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path); if (no_overlap_path.size() <= 1) return true; - const auto lat_offset_to_current_ego = std::abs( - autoware::motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); + const auto lat_offset_to_current_ego = + std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); const auto is_crossing_ego = lat_offset_to_current_ego <= object.shape.dimensions.y / 2.0 + std::max( @@ -136,23 +136,21 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( params.right_offset + params.extra_right_offset); return is_low_confidence || is_crossing_ego; }; - if (params.objects_use_predicted_paths) { - auto & predicted_paths = filtered_object.kinematics.predicted_paths; - const auto new_end = - std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); - predicted_paths.erase(new_end, predicted_paths.end()); - if (params.objects_cut_predicted_paths_beyond_red_lights) - for (auto & predicted_path : predicted_paths) - cut_predicted_path_beyond_red_lights( - predicted_path, ego_data, filtered_object.shape.dimensions.x); - predicted_paths.erase( - std::remove_if( - predicted_paths.begin(), predicted_paths.end(), - [](const auto & p) { return p.path.empty(); }), - predicted_paths.end()); - } + auto & predicted_paths = filtered_object.kinematics.predicted_paths; + const auto new_end = + std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); + predicted_paths.erase(new_end, predicted_paths.end()); + if (params.objects_cut_predicted_paths_beyond_red_lights) + for (auto & predicted_path : predicted_paths) + cut_predicted_path_beyond_red_lights( + predicted_path, ego_data, filtered_object.shape.dimensions.x); + predicted_paths.erase( + std::remove_if( + predicted_paths.begin(), predicted_paths.end(), + [](const auto & p) { return p.path.empty(); }), + predicted_paths.end()); - if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty()) + if (!filtered_object.kinematics.predicted_paths.empty()) filtered_objects.objects.push_back(filtered_object); } return filtered_objects; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp index baf07e4b06ea5..3b2ae11718810 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -19,7 +19,6 @@ #include -#include #include namespace autoware::motion_velocity_planner::out_of_lane @@ -52,8 +51,7 @@ void cut_predicted_path_beyond_red_lights( /// @param [in] params parameters /// @return filtered predicted objects autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const std::shared_ptr planner_data, const EgoData & ego_data, - const PlannerParam & params); + const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // FILTER_PREDICTED_OBJECTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp index f5d68c4fa9bba..564bf5de7ef2e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp @@ -21,15 +21,13 @@ #include #include -#include #include namespace autoware::motion_velocity_planner::out_of_lane { -autoware::universe_utils::Polygon2d make_base_footprint( - const PlannerParam & p, const bool ignore_offset) +universe_utils::Polygon2d make_base_footprint(const PlannerParam & p, const bool ignore_offset) { - autoware::universe_utils::Polygon2d base_footprint; + universe_utils::Polygon2d base_footprint; const auto front_offset = ignore_offset ? 0.0 : p.extra_front_offset; const auto rear_offset = ignore_offset ? 0.0 : p.extra_rear_offset; const auto right_offset = ignore_offset ? 0.0 : p.extra_right_offset; @@ -43,10 +41,10 @@ autoware::universe_utils::Polygon2d make_base_footprint( } lanelet::BasicPolygon2d project_to_pose( - const autoware::universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) + const universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) { const auto angle = tf2::getYaw(pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); @@ -59,22 +57,15 @@ std::vector calculate_trajectory_footprints( const auto base_footprint = make_base_footprint(params); std::vector trajectory_footprints; trajectory_footprints.reserve(ego_data.trajectory_points.size()); - double length = 0.0; - const auto range = std::max(params.slow_dist_threshold, params.stop_dist_threshold) + - params.front_offset + params.extra_front_offset; - for (auto i = ego_data.first_trajectory_idx; - i < ego_data.trajectory_points.size() && length < range; ++i) { + for (auto i = ego_data.first_trajectory_idx; i < ego_data.trajectory_points.size(); ++i) { const auto & trajectory_pose = ego_data.trajectory_points[i].pose; const auto angle = tf2::getYaw(trajectory_pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back( p.x() + trajectory_pose.position.x, p.y() + trajectory_pose.position.y); trajectory_footprints.push_back(footprint); - if (i + 1 < ego_data.trajectory_points.size()) - length += autoware::universe_utils::calcDistance2d( - trajectory_pose, ego_data.trajectory_points[i + 1].pose); } return trajectory_footprints; } @@ -84,7 +75,7 @@ lanelet::BasicPolygon2d calculate_current_ego_footprint( { const auto base_footprint = make_base_footprint(params, ignore_offset); const auto angle = tf2::getYaw(ego_data.pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + ego_data.pose.position.x, p.y() + ego_data.pose.position.y); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp index ebe7ab0fa9d7f..88baeefba6f40 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp @@ -21,24 +21,21 @@ #include -namespace autoware::motion_velocity_planner -{ -namespace out_of_lane +namespace autoware::motion_velocity_planner::out_of_lane { /// @brief create the base footprint of ego /// @param [in] p parameters used to create the footprint /// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the /// footprint /// @return base ego footprint -autoware::universe_utils::Polygon2d make_base_footprint( +universe_utils::Polygon2d make_base_footprint( const PlannerParam & p, const bool ignore_offset = false); /// @brief project a footprint to the given pose /// @param [in] base_footprint footprint to project /// @param [in] pose projection pose /// @return footprint projected to the given pose lanelet::BasicPolygon2d project_to_pose( - const autoware::universe_utils::Polygon2d & base_footprint, - const geometry_msgs::msg::Pose & pose); + const universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); /// @brief calculate the trajectory footprints /// @details the resulting polygon follows the format used by the lanelet library: clockwise order /// and implicit closing edge @@ -54,7 +51,6 @@ std::vector calculate_trajectory_footprints( /// footprint lanelet::BasicPolygon2d calculate_current_ego_footprint( const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset = false); -} // namespace out_of_lane -} // namespace autoware::motion_velocity_planner +} // namespace autoware::motion_velocity_planner::out_of_lane #endif // FOOTPRINT_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp index bca849f806f63..f520a564519f0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -14,36 +14,46 @@ #include "lanelets_selection.hpp" +#include "types.hpp" + #include #include +#include +#include #include -#include #include #include -#include namespace autoware::motion_velocity_planner::out_of_lane { +namespace +{ +bool is_road_lanelet(const lanelet::ConstLanelet & lanelet) +{ + return lanelet.hasAttribute(lanelet::AttributeName::Subtype) && + lanelet.attribute(lanelet::AttributeName::Subtype) == lanelet::AttributeValueString::Road; +} +} // namespace + lanelet::ConstLanelets consecutive_lanelets( - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lanelet) + const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet) { - lanelet::ConstLanelets consecutives = route_handler->getRoutingGraphPtr()->following(lanelet); - const auto previous = route_handler->getRoutingGraphPtr()->previous(lanelet); + lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet); + const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet); consecutives.insert(consecutives.end(), previous.begin(), previous.end()); return consecutives; } lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler) + const lanelet::ConstLanelets & trajectory_lanelets, + const route_handler::RouteHandler & route_handler) { lanelet::ConstLanelets missing_lane_change_lanelets; - const auto & routing_graph = *route_handler->getRoutingGraphPtr(); + const auto & routing_graph = *route_handler.getRoutingGraphPtr(); lanelet::ConstLanelets adjacents; lanelet::ConstLanelets consecutives; for (const auto & ll : trajectory_lanelets) { @@ -67,9 +77,9 @@ lanelet::ConstLanelets get_missing_lane_change_lanelets( } lanelet::ConstLanelets calculate_trajectory_lanelets( - const EgoData & ego_data, const std::shared_ptr route_handler) + const EgoData & ego_data, const route_handler::RouteHandler & route_handler) { - const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + const auto lanelet_map_ptr = route_handler.getLaneletMapPtr(); lanelet::ConstLanelets trajectory_lanelets; lanelet::BasicLineString2d trajectory_ls; for (const auto & p : ego_data.trajectory_points) @@ -77,7 +87,9 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( const auto candidates = lanelet_map_ptr->laneletLayer.search(lanelet::geometry::boundingBox2d(trajectory_ls)); for (const auto & ll : candidates) { - if (!boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { + if ( + is_road_lanelet(ll) && + !boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { trajectory_lanelets.push_back(ll); } } @@ -89,43 +101,65 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( } lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params) + const lanelet::ConstLanelets & trajectory_lanelets, + const route_handler::RouteHandler & route_handler) { lanelet::ConstLanelets ignored_lanelets; - // ignore lanelets directly behind ego - const auto behind = - autoware::universe_utils::calcOffsetPose(ego_data.pose, params.rear_offset, 0.0, 0.0); - const lanelet::BasicPoint2d behind_point(behind.position.x, behind.position.y); - const auto behind_lanelets = lanelet::geometry::findWithin2d( - route_handler->getLaneletMapPtr()->laneletLayer, behind_point, 0.0); - for (const auto & l : behind_lanelets) { - const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, l.second.id()); - if (!is_trajectory_lanelet) ignored_lanelets.push_back(l.second); + // ignore lanelets directly preceding a trajectory lanelet + for (const auto & trajectory_lanelet : trajectory_lanelets) { + for (const auto & ll : route_handler.getPreviousLanelets(trajectory_lanelet)) { + const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.id()); + if (!is_trajectory_lanelet) ignored_lanelets.push_back(ll); + } } return ignored_lanelets; } -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params) +void calculate_drivable_lane_polygons( + EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + const auto route_lanelets = calculate_trajectory_lanelets(ego_data, route_handler); + const auto ignored_lanelets = + out_of_lane::calculate_ignored_lanelets(route_lanelets, route_handler); + for (const auto & ll : route_lanelets) { + out_of_lane::Polygons tmp; + boost::geometry::union_(ego_data.drivable_lane_polygons, ll.polygon2d().basicPolygon(), tmp); + ego_data.drivable_lane_polygons = tmp; + } + for (const auto & ll : ignored_lanelets) { + out_of_lane::Polygons tmp; + boost::geometry::union_(ego_data.drivable_lane_polygons, ll.polygon2d().basicPolygon(), tmp); + ego_data.drivable_lane_polygons = tmp; + } +} + +void calculate_overlapped_lanelets( + OutOfLanePoint & out_of_lane_point, const route_handler::RouteHandler & route_handler) { - lanelet::ConstLanelets other_lanelets; - const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y); - const auto lanelets_within_range = lanelet::geometry::findWithin2d( - route_handler->getLaneletMapPtr()->laneletLayer, ego_point, - std::max(params.slow_dist_threshold, params.stop_dist_threshold) + params.front_offset + - params.extra_front_offset); - for (const auto & ll : lanelets_within_range) { - if (std::string(ll.second.attributeOr(lanelet::AttributeName::Subtype, "none")) != "road") - continue; - const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.second.id()); - const auto is_ignored_lanelet = contains_lanelet(ignored_lanelets, ll.second.id()); - if (!is_trajectory_lanelet && !is_ignored_lanelet) other_lanelets.push_back(ll.second); + out_of_lane_point.overlapped_lanelets = lanelet::ConstLanelets(); + const auto candidates = route_handler.getLaneletMapPtr()->laneletLayer.search( + lanelet::geometry::boundingBox2d(out_of_lane_point.outside_ring)); + for (const auto & ll : candidates) { + if ( + is_road_lanelet(ll) && !contains_lanelet(out_of_lane_point.overlapped_lanelets, ll.id()) && + boost::geometry::within(out_of_lane_point.outside_ring, ll.polygon2d().basicPolygon())) { + out_of_lane_point.overlapped_lanelets.push_back(ll); + } + } +} + +void calculate_overlapped_lanelets( + OutOfLaneData & out_of_lane_data, const route_handler::RouteHandler & route_handler) +{ + for (auto it = out_of_lane_data.outside_points.begin(); + it != out_of_lane_data.outside_points.end();) { + calculate_overlapped_lanelets(*it, route_handler); + if (it->overlapped_lanelets.empty()) { + // do not keep out of lane points that do not overlap any lanelet + out_of_lane_data.outside_points.erase(it); + } else { + ++it; + } } - return other_lanelets; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp index 8618d808d7d40..a7729deb539b6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -44,6 +44,7 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane /// @return lanelets crossed by the ego vehicle lanelet::ConstLanelets calculate_trajectory_lanelets( const EgoData & ego_data, const std::shared_ptr route_handler); + /// @brief calculate lanelets that may not be crossed by the trajectory but may be overlapped during /// a lane change /// @param [in] trajectory_lanelets lanelets driven by the ego vehicle @@ -51,30 +52,28 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( /// @return lanelets that may be overlapped by a lane change (and are not already in /// trajectory_lanelets) lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler); + const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr & route_handler); + /// @brief calculate lanelets that should be ignored -/// @param [in] ego_data data about the ego vehicle -/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle +/// @param [in] trajectory_lanelets lanelets followed by the ego vehicle /// @param [in] route_handler route handler -/// @param [in] params parameters /// @return lanelets to ignore lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params); -/// @brief calculate lanelets that should be checked by the module -/// @param [in] ego_data data about the ego vehicle -/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle -/// @param [in] ignored_lanelets lanelets to ignore -/// @param [in] route_handler route handler -/// @param [in] params parameters -/// @return lanelets to check for overlaps -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params); + const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr & route_handler); + +/// @brief calculate the polygons representing the ego lane and add it to the ego data +/// @param [inout] ego_data ego data +/// @param [in] route_handler route handler with map information +void calculate_drivable_lane_polygons( + EgoData & ego_data, const route_handler::RouteHandler & route_handler); + +/// @brief calculate the lanelets overlapped at each out of lane point +/// @param [out] out_of_lane_data data with the out of lane points +/// @param [in] route_handler route handler with the lanelet map +void calculate_overlapped_lanelets( + OutOfLaneData & out_of_lane_data, const route_handler::RouteHandler & route_handler); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // LANELETS_SELECTION_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp new file mode 100644 index 0000000000000..c375bcc35c1ee --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp @@ -0,0 +1,166 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "out_of_lane_collisions.hpp" + +#include "types.hpp" + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +void update_collision_times( + OutOfLaneData & out_of_lane_data, const std::unordered_set & potential_collision_indexes, + const universe_utils::Polygon2d & object_footprint, const double time) +{ + for (const auto index : potential_collision_indexes) { + auto & out_of_lane_point = out_of_lane_data.outside_points[index]; + if (out_of_lane_point.collision_times.count(time) == 0UL) { + const auto has_collision = + !boost::geometry::disjoint(out_of_lane_point.outside_ring, object_footprint.outer()); + if (has_collision) { + out_of_lane_point.collision_times.insert(time); + } + } + } +} + +void calculate_object_path_time_collisions( + OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedPath & object_path, + const autoware_perception_msgs::msg::Shape & object_shape) +{ + const auto time_step = rclcpp::Duration(object_path.time_step).seconds(); + auto time = time_step; + for (const auto & object_pose : object_path.path) { + time += time_step; + const auto object_footprint = universe_utils::toPolygon2d(object_pose, object_shape); + std::vector query_results; + out_of_lane_data.outside_areas_rtree.query( + boost::geometry::index::intersects(object_footprint.outer()), + std::back_inserter(query_results)); + std::unordered_set potential_collision_indexes; + for (const auto & [_, index] : query_results) { + potential_collision_indexes.insert(index); + } + update_collision_times(out_of_lane_data, potential_collision_indexes, object_footprint, time); + } +} + +void calculate_objects_time_collisions( + OutOfLaneData & out_of_lane_data, + const std::vector & objects) +{ + for (const auto & object : objects) { + for (const auto & path : object.kinematics.predicted_paths) { + calculate_object_path_time_collisions(out_of_lane_data, path, object.shape); + } + } +} + +void calculate_min_max_arrival_times( + OutOfLanePoint & out_of_lane_point, + const std::vector & trajectory) +{ + auto min_time = std::numeric_limits::infinity(); + auto max_time = -std::numeric_limits::infinity(); + for (const auto & t : out_of_lane_point.collision_times) { + min_time = std::min(t, min_time); + max_time = std::max(t, max_time); + } + if (min_time <= max_time) { + out_of_lane_point.min_object_arrival_time = min_time; + out_of_lane_point.max_object_arrival_time = max_time; + const auto & ego_time = + rclcpp::Duration(trajectory[out_of_lane_point.trajectory_index].time_from_start).seconds(); + if (ego_time >= min_time && ego_time <= max_time) { + out_of_lane_point.ttc = 0.0; + } else { + out_of_lane_point.ttc = + std::min(std::abs(ego_time - min_time), std::abs(ego_time - max_time)); + } + } +}; + +void calculate_collisions_to_avoid( + OutOfLaneData & out_of_lane_data, + const std::vector & trajectory, + const PlannerParam & params) +{ + for (auto & out_of_lane_point : out_of_lane_data.outside_points) { + calculate_min_max_arrival_times(out_of_lane_point, trajectory); + } + for (auto & p : out_of_lane_data.outside_points) { + if (params.mode == "ttc") { + p.to_avoid = p.ttc && p.ttc <= params.ttc_threshold; + } else { + p.to_avoid = p.min_object_arrival_time && p.min_object_arrival_time <= params.time_threshold; + } + } +} + +OutOfLaneData calculate_outside_points(const EgoData & ego_data) +{ + OutOfLaneData out_of_lane_data; + out_of_lane::OutOfLanePoint p; + for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { + p.trajectory_index = i + ego_data.first_trajectory_idx; + const auto & footprint = ego_data.trajectory_footprints[i]; + out_of_lane::Polygons out_of_lane_polygons; + boost::geometry::difference(footprint, ego_data.drivable_lane_polygons, out_of_lane_polygons); + for (const auto & area : out_of_lane_polygons) { + if (!area.outer.empty()) { + p.outside_ring = area.outer; + out_of_lane_data.outside_points.push_back(p); + } + } + } + return out_of_lane_data; +} + +OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data) +{ + auto out_of_lane_data = calculate_outside_points(ego_data); + std::vector rtree_nodes; + for (auto i = 0UL; i < out_of_lane_data.outside_points.size(); ++i) { + OutAreaNode n; + n.first = boost::geometry::return_envelope( + out_of_lane_data.outside_points[i].outside_ring); + n.second = i; + rtree_nodes.push_back(n); + } + out_of_lane_data.outside_areas_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; + return out_of_lane_data; +} + +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp new file mode 100644 index 0000000000000..b9048cc358a07 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp @@ -0,0 +1,55 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OUT_OF_LANE_COLLISIONS_HPP_ +#define OUT_OF_LANE_COLLISIONS_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +/// @brief calculate the times and points where ego collides with an object's path outside of its +/// lane +void calculate_object_path_time_collisions( + OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedPath & object_path, + const autoware_perception_msgs::msg::Shape & object_shape); + +/// @brief calculate the times and points where ego collides with an object outside of its lane +void calculate_objects_time_collisions( + OutOfLaneData & out_of_lane_data, + const std::vector & objects); + +/// @brief calculate the collisions to avoid +/// @details either uses the time to collision or just the time when the object will arrive at the +/// point +void calculate_collisions_to_avoid( + OutOfLaneData & out_of_lane_data, + const std::vector & trajectory, + const PlannerParam & params); + +/// @brief calculate the areas where ego will drive outside of its lane +/// @details the OutOfLaneData points and rtree are filled +OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // OUT_OF_LANE_COLLISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index a6b34a1566e19..ca7ed3b9dc7bd 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -16,11 +16,10 @@ #include "calculate_slowdown_points.hpp" #include "debug.hpp" -#include "decisions.hpp" #include "filter_predicted_objects.hpp" #include "footprint.hpp" #include "lanelets_selection.hpp" -#include "overlapping_range.hpp" +#include "out_of_lane_collisions.hpp" #include "types.hpp" #include @@ -34,11 +33,13 @@ #include #include +#include #include #include #include +#include #include #include #include @@ -56,65 +57,54 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) logger_ = node.get_logger(); clock_ = node.get_clock(); init_parameters(node); - velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_interface_.init(motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - processing_diag_publisher_ = std::make_shared( + processing_diag_publisher_ = std::make_shared( &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); processing_time_publisher_ = node.create_publisher( "~/debug/" + ns_ + "/processing_time_ms", 1); } void OutOfLaneModule::init_parameters(rclcpp::Node & node) { - using autoware::universe_utils::getOrDeclareParameter; + using universe_utils::getOrDeclareParameter; auto & pp = params_; pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); pp.skip_if_already_overlapping = getOrDeclareParameter(node, ns_ + ".skip_if_already_overlapping"); + pp.ignore_lane_changeable_lanelets = + getOrDeclareParameter(node, ns_ + ".ignore_overlaps_over_lane_changeable_lanelets"); + pp.max_arc_length = getOrDeclareParameter(node, ns_ + ".max_arc_length"); pp.time_threshold = getOrDeclareParameter(node, ns_ + ".threshold.time_threshold"); - pp.intervals_ego_buffer = getOrDeclareParameter(node, ns_ + ".intervals.ego_time_buffer"); - pp.intervals_obj_buffer = - getOrDeclareParameter(node, ns_ + ".intervals.objects_time_buffer"); pp.ttc_threshold = getOrDeclareParameter(node, ns_ + ".ttc.threshold"); pp.objects_min_vel = getOrDeclareParameter(node, ns_ + ".objects.minimum_velocity"); - pp.objects_use_predicted_paths = - getOrDeclareParameter(node, ns_ + ".objects.use_predicted_paths"); pp.objects_min_confidence = getOrDeclareParameter(node, ns_ + ".objects.predicted_path_min_confidence"); - pp.objects_dist_buffer = getOrDeclareParameter(node, ns_ + ".objects.distance_buffer"); pp.objects_cut_predicted_paths_beyond_red_lights = getOrDeclareParameter(node, ns_ + ".objects.cut_predicted_paths_beyond_red_lights"); pp.objects_ignore_behind_ego = getOrDeclareParameter(node, ns_ + ".objects.ignore_behind_ego"); - pp.overlap_min_dist = getOrDeclareParameter(node, ns_ + ".overlap.minimum_distance"); - pp.overlap_extra_length = getOrDeclareParameter(node, ns_ + ".overlap.extra_length"); - - pp.skip_if_over_max_decel = - getOrDeclareParameter(node, ns_ + ".action.skip_if_over_max_decel"); pp.precision = getOrDeclareParameter(node, ns_ + ".action.precision"); pp.min_decision_duration = getOrDeclareParameter(node, ns_ + ".action.min_duration"); pp.lon_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.longitudinal_distance_buffer"); pp.lat_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.lateral_distance_buffer"); pp.slow_velocity = getOrDeclareParameter(node, ns_ + ".action.slowdown.velocity"); - pp.slow_dist_threshold = - getOrDeclareParameter(node, ns_ + ".action.slowdown.distance_threshold"); pp.stop_dist_threshold = getOrDeclareParameter(node, ns_ + ".action.stop.distance_threshold"); - pp.ego_min_velocity = getOrDeclareParameter(node, ns_ + ".ego.min_assumed_velocity"); pp.extra_front_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_front_offset"); pp.extra_rear_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_rear_offset"); pp.extra_left_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_left_offset"); pp.extra_right_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_right_offset"); - const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); + const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.front_offset = vehicle_info.max_longitudinal_offset_m; pp.rear_offset = vehicle_info.min_longitudinal_offset_m; pp.left_offset = vehicle_info.max_lateral_offset_m; @@ -123,44 +113,82 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) void OutOfLaneModule::update_parameters(const std::vector & parameters) { - using autoware::universe_utils::updateParam; + using universe_utils::updateParam; auto & pp = params_; updateParam(parameters, ns_ + ".mode", pp.mode); updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); + updateParam(parameters, ns_ + ".max_arc_length", pp.max_arc_length); + updateParam( + parameters, ns_ + ".ignore_overlaps_over_lane_changeable_lanelets", + pp.ignore_lane_changeable_lanelets); updateParam(parameters, ns_ + ".threshold.time_threshold", pp.time_threshold); - updateParam(parameters, ns_ + ".intervals.ego_time_buffer", pp.intervals_ego_buffer); - updateParam(parameters, ns_ + ".intervals.objects_time_buffer", pp.intervals_obj_buffer); updateParam(parameters, ns_ + ".ttc.threshold", pp.ttc_threshold); updateParam(parameters, ns_ + ".objects.minimum_velocity", pp.objects_min_vel); - updateParam(parameters, ns_ + ".objects.use_predicted_paths", pp.objects_use_predicted_paths); updateParam( parameters, ns_ + ".objects.predicted_path_min_confidence", pp.objects_min_confidence); - updateParam(parameters, ns_ + ".objects.distance_buffer", pp.objects_dist_buffer); updateParam( parameters, ns_ + ".objects.cut_predicted_paths_beyond_red_lights", pp.objects_cut_predicted_paths_beyond_red_lights); updateParam(parameters, ns_ + ".objects.ignore_behind_ego", pp.objects_ignore_behind_ego); - updateParam(parameters, ns_ + ".overlap.minimum_distance", pp.overlap_min_dist); - updateParam(parameters, ns_ + ".overlap.extra_length", pp.overlap_extra_length); - updateParam(parameters, ns_ + ".action.skip_if_over_max_decel", pp.skip_if_over_max_decel); updateParam(parameters, ns_ + ".action.precision", pp.precision); updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration); updateParam(parameters, ns_ + ".action.longitudinal_distance_buffer", pp.lon_dist_buffer); updateParam(parameters, ns_ + ".action.lateral_distance_buffer", pp.lat_dist_buffer); updateParam(parameters, ns_ + ".action.slowdown.velocity", pp.slow_velocity); - updateParam(parameters, ns_ + ".action.slowdown.distance_threshold", pp.slow_dist_threshold); updateParam(parameters, ns_ + ".action.stop.distance_threshold", pp.stop_dist_threshold); - updateParam(parameters, ns_ + ".ego.min_assumed_velocity", pp.ego_min_velocity); updateParam(parameters, ns_ + ".ego.extra_front_offset", pp.extra_front_offset); updateParam(parameters, ns_ + ".ego.extra_rear_offset", pp.extra_rear_offset); updateParam(parameters, ns_ + ".ego.extra_left_offset", pp.extra_left_offset); updateParam(parameters, ns_ + ".ego.extra_right_offset", pp.extra_right_offset); } +void OutOfLaneModule::limit_trajectory_size( + out_of_lane::EgoData & ego_data, + const std::vector & ego_trajectory_points, + const double max_arc_length) +{ + ego_data.first_trajectory_idx = + motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); + ego_data.longitudinal_offset_to_first_trajectory_index = + motion_utils::calcLongitudinalOffsetToSegment( + ego_trajectory_points, ego_data.first_trajectory_idx, ego_data.pose.position); + auto l = -ego_data.longitudinal_offset_to_first_trajectory_index; + ego_data.trajectory_points.push_back(ego_trajectory_points[ego_data.first_trajectory_idx]); + for (auto i = ego_data.first_trajectory_idx + 1; i < ego_trajectory_points.size(); ++i) { + l += universe_utils::calcDistance2d(ego_trajectory_points[i - 1], ego_trajectory_points[i]); + if (l >= max_arc_length) { + break; + } + ego_data.trajectory_points.push_back(ego_trajectory_points[i]); + } +} + +void OutOfLaneModule::calculate_min_stop_and_slowdown_distances( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, + std::optional & previous_slowdown_pose_, const double slow_velocity) +{ + ego_data.min_stop_distance = planner_data.calculate_min_deceleration_distance(0.0).value_or(0.0); + ego_data.min_slowdown_distance = + planner_data.calculate_min_deceleration_distance(slow_velocity).value_or(0.0); + if (previous_slowdown_pose_) { + // Ensure we do not remove the previous slowdown point due to the min distance limit + const auto previous_slowdown_pose_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, ego_data.first_trajectory_idx, previous_slowdown_pose_->position); + ego_data.min_stop_distance = + std::min(previous_slowdown_pose_arc_length, ego_data.min_stop_distance); + ego_data.min_slowdown_distance = + std::min(previous_slowdown_pose_arc_length, ego_data.min_slowdown_distance); + } + ego_data.min_stop_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0UL, ego_data.first_trajectory_idx) + + ego_data.longitudinal_offset_to_first_trajectory_index + + ego_data.min_stop_distance; +} + void prepare_stop_lines_rtree( out_of_lane::EgoData & ego_data, const PlannerData & planner_data, const double search_distance) { @@ -202,163 +230,140 @@ VelocityPlanningResult OutOfLaneModule::plan( const std::shared_ptr planner_data) { VelocityPlanningResult result; - autoware::universe_utils::StopWatch stopwatch; + universe_utils::StopWatch stopwatch; stopwatch.tic(); + + stopwatch.tic("preprocessing"); out_of_lane::EgoData ego_data; ego_data.pose = planner_data->current_odometry.pose.pose; - ego_data.trajectory_points = ego_trajectory_points; - ego_data.first_trajectory_idx = - autoware::motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); - ego_data.velocity = planner_data->current_odometry.twist.twist.linear.x; - ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel(); - stopwatch.tic("preprocessing"); - prepare_stop_lines_rtree(ego_data, *planner_data, 100.0); + limit_trajectory_size(ego_data, ego_trajectory_points, params_.max_arc_length); + calculate_min_stop_and_slowdown_distances( + ego_data, *planner_data, previous_slowdown_pose_, params_.slow_velocity); + prepare_stop_lines_rtree(ego_data, *planner_data, params_.max_arc_length); const auto preprocessing_us = stopwatch.toc("preprocessing"); stopwatch.tic("calculate_trajectory_footprints"); - const auto current_ego_footprint = + ego_data.current_footprint = out_of_lane::calculate_current_ego_footprint(ego_data, params_, true); - const auto trajectory_footprints = - out_of_lane::calculate_trajectory_footprints(ego_data, params_); + ego_data.trajectory_footprints = out_of_lane::calculate_trajectory_footprints(ego_data, params_); const auto calculate_trajectory_footprints_us = stopwatch.toc("calculate_trajectory_footprints"); - // Calculate lanelets to ignore and consider + stopwatch.tic("calculate_lanelets"); - const auto trajectory_lanelets = - out_of_lane::calculate_trajectory_lanelets(ego_data, planner_data->route_handler); - const auto ignored_lanelets = out_of_lane::calculate_ignored_lanelets( - ego_data, trajectory_lanelets, planner_data->route_handler, params_); - const auto other_lanelets = out_of_lane::calculate_other_lanelets( - ego_data, trajectory_lanelets, ignored_lanelets, planner_data->route_handler, params_); + out_of_lane::calculate_drivable_lane_polygons(ego_data, *planner_data->route_handler); const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); - debug_data_.reset_data(); - debug_data_.trajectory_points = ego_trajectory_points; - debug_data_.footprints = trajectory_footprints; - debug_data_.trajectory_lanelets = trajectory_lanelets; - debug_data_.ignored_lanelets = ignored_lanelets; - debug_data_.other_lanelets = other_lanelets; - debug_data_.first_trajectory_idx = ego_data.first_trajectory_idx; - - if (params_.skip_if_already_overlapping) { - debug_data_.current_footprint = current_ego_footprint; - const auto overlapped_lanelet_it = - std::find_if(other_lanelets.begin(), other_lanelets.end(), [&](const auto & ll) { - return boost::geometry::intersects(ll.polygon2d().basicPolygon(), current_ego_footprint); - }); - if (overlapped_lanelet_it != other_lanelets.end()) { - debug_data_.current_overlapped_lanelets.push_back(*overlapped_lanelet_it); - RCLCPP_DEBUG(logger_, "Ego is already overlapping a lane, skipping the module\n"); - return result; - } - } - // Calculate overlapping ranges - stopwatch.tic("calculate_overlapping_ranges"); - const auto ranges = out_of_lane::calculate_overlapping_ranges( - trajectory_footprints, trajectory_lanelets, other_lanelets, params_); - const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); - // Calculate stop and slowdown points - out_of_lane::DecisionInputs inputs; - inputs.ranges = ranges; - inputs.ego_data = ego_data; + stopwatch.tic("calculate_out_of_lane_areas"); + auto out_of_lane_data = calculate_out_of_lane_areas(ego_data); + out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, *planner_data->route_handler); + const auto calculate_out_of_lane_areas_us = stopwatch.toc("calculate_out_of_lane_areas"); + stopwatch.tic("filter_predicted_objects"); - inputs.objects = out_of_lane::filter_predicted_objects(planner_data, ego_data, params_); + const auto objects = out_of_lane::filter_predicted_objects(*planner_data, ego_data, params_); const auto filter_predicted_objects_us = stopwatch.toc("filter_predicted_objects"); - inputs.route_handler = planner_data->route_handler; - inputs.lanelets = other_lanelets; - stopwatch.tic("calculate_decisions"); - const auto decisions = out_of_lane::calculate_decisions(inputs, params_, logger_); - const auto calculate_decisions_us = stopwatch.toc("calculate_decisions"); - stopwatch.tic("calc_slowdown_points"); + + stopwatch.tic("calculate_time_collisions"); + out_of_lane::calculate_objects_time_collisions(out_of_lane_data, objects.objects); + const auto calculate_time_collisions_us = stopwatch.toc("calculate_time_collisions"); + + stopwatch.tic("calculate_times"); + // calculate times + out_of_lane::calculate_collisions_to_avoid(out_of_lane_data, ego_data.trajectory_points, params_); + const auto calculate_times_us = stopwatch.toc("calculate_times"); + + if ( + params_.skip_if_already_overlapping && !ego_data.drivable_lane_polygons.empty() && + !lanelet::geometry::within(ego_data.current_footprint, ego_data.drivable_lane_polygons)) { + RCLCPP_WARN(logger_, "Ego is already out of lane, skipping the module\n"); + debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array( + ego_data, out_of_lane_data, objects, debug_data_)); + return result; + } + if ( // reset the previous inserted point if the timer expired - prev_inserted_point_ && - (clock_->now() - prev_inserted_point_time_).seconds() > params_.min_decision_duration) - prev_inserted_point_.reset(); - auto point_to_insert = - out_of_lane::calculate_slowdown_point(ego_data, decisions, prev_inserted_point_, params_); - const auto calc_slowdown_points_us = stopwatch.toc("calc_slowdown_points"); - stopwatch.tic("insert_slowdown_points"); - debug_data_.slowdowns.clear(); - if ( // reset the timer if there is no previous inserted point or if we avoid the same lane - point_to_insert && - (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == - point_to_insert->slowdown.lane_to_avoid.id())) - prev_inserted_point_time_ = clock_->now(); - // reuse previous stop point if there is no new one or if its velocity is not higher than the new + previous_slowdown_pose_ && + (clock_->now() - previous_slowdown_time_).seconds() > params_.min_decision_duration) { + previous_slowdown_pose_.reset(); + } + + stopwatch.tic("calculate_slowdown_point"); + auto slowdown_pose = out_of_lane::calculate_slowdown_point(ego_data, out_of_lane_data, params_); + const auto calculate_slowdown_point_us = stopwatch.toc("calculate_slowdown_point"); + + if ( // reset the timer if there is no previous inserted point + slowdown_pose && (!previous_slowdown_pose_)) { + previous_slowdown_time_ = clock_->now(); + } + // reuse previous stop pose if there is no new one or if its velocity is not higher than the new // one and its arc length is lower - const auto should_use_prev_inserted_point = [&]() { - if ( - point_to_insert && prev_inserted_point_ && - prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { - const auto arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, point_to_insert->point.pose.position); - const auto prev_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); + const auto should_use_previous_pose = [&]() { + if (slowdown_pose && previous_slowdown_pose_) { + const auto arc_length = + motion_utils::calcSignedArcLength(ego_trajectory_points, 0LU, slowdown_pose->position); + const auto prev_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); return prev_arc_length < arc_length; } - return !point_to_insert && prev_inserted_point_; + return !slowdown_pose && previous_slowdown_pose_; }(); - if (should_use_prev_inserted_point) { + if (should_use_previous_pose) { // if the trajectory changed the prev point is no longer on the trajectory so we project it - const auto insert_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); - prev_inserted_point_->point.pose = - autoware::motion_utils::calcInterpolatedPose(ego_trajectory_points, insert_arc_length); - point_to_insert = prev_inserted_point_; + const auto new_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.first_trajectory_idx, previous_slowdown_pose_->position); + slowdown_pose = motion_utils::calcInterpolatedPose(ego_trajectory_points, new_arc_length); } - if (point_to_insert) { - prev_inserted_point_ = point_to_insert; - RCLCPP_DEBUG(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); - debug_data_.slowdowns = {*point_to_insert}; - if (point_to_insert->slowdown.velocity == 0.0) - result.stop_points.push_back(point_to_insert->point.pose.position); - else + if (slowdown_pose) { + const auto arc_length = + motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.first_trajectory_idx, slowdown_pose->position) - + ego_data.longitudinal_offset_to_first_trajectory_index; + const auto slowdown_velocity = + arc_length <= params_.stop_dist_threshold ? 0.0 : params_.slow_velocity; + previous_slowdown_pose_ = slowdown_pose; + if (slowdown_velocity == 0.0) { + result.stop_points.push_back(slowdown_pose->position); + } else { result.slowdown_intervals.emplace_back( - point_to_insert->point.pose.position, point_to_insert->point.pose.position, - point_to_insert->slowdown.velocity); - - const auto is_approaching = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, ego_data.pose.position, - point_to_insert->point.pose.position) > 0.1 && - ego_data.velocity > 0.1; - const auto status = is_approaching ? autoware::motion_utils::VelocityFactor::APPROACHING - : autoware::motion_utils::VelocityFactor::STOPPED; + slowdown_pose->position, slowdown_pose->position, slowdown_velocity); + } + + const auto is_approaching = + motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.pose.position, slowdown_pose->position) > 0.1 && + planner_data->current_odometry.twist.twist.linear.x > 0.1; + const auto status = is_approaching ? motion_utils::VelocityFactor::APPROACHING + : motion_utils::VelocityFactor::STOPPED; velocity_factor_interface_.set( - ego_trajectory_points, ego_data.pose, point_to_insert->point.pose, status, "out_of_lane"); + ego_trajectory_points, ego_data.pose, *slowdown_pose, status, "out_of_lane"); result.velocity_factor = velocity_factor_interface_.get(); - } else if (!decisions.empty()) { - RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); + virtual_wall_marker_creator.add_virtual_walls( + out_of_lane::debug::create_virtual_walls(*slowdown_pose, slowdown_velocity == 0.0, params_)); + virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); + } else if (std::any_of( + out_of_lane_data.outside_points.begin(), out_of_lane_data.outside_points.end(), + [](const auto & p) { return p.to_avoid; })) { + RCLCPP_WARN( + logger_, "[out_of_lane] Could not insert slowdown point because of deceleration limits"); } - const auto insert_slowdown_points_us = stopwatch.toc("insert_slowdown_points"); - debug_data_.ranges = inputs.ranges; + stopwatch.tic("gen_debug"); + const auto markers = + out_of_lane::debug::create_debug_marker_array(ego_data, out_of_lane_data, objects, debug_data_); + const auto markers_us = stopwatch.toc("gen_debug"); + stopwatch.tic("pub"); + debug_publisher_->publish(markers); + const auto pub_markers_us = stopwatch.toc("pub"); const auto total_time_us = stopwatch.toc(); - RCLCPP_DEBUG( - logger_, - "Total time = %2.2fus\n" - "\tpreprocessing = %2.0fus\n" - "\tcalculate_lanelets = %2.0fus\n" - "\tcalculate_trajectory_footprints = %2.0fus\n" - "\tcalculate_overlapping_ranges = %2.0fus\n" - "\tfilter_pred_objects = %2.0fus\n" - "\tcalculate_decisions = %2.0fus\n" - "\tcalc_slowdown_points = %2.0fus\n" - "\tinsert_slowdown_points = %2.0fus\n", - preprocessing_us, total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_us, - calculate_overlapping_ranges_us, filter_predicted_objects_us, calculate_decisions_us, - calc_slowdown_points_us, insert_slowdown_points_us); - debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array(debug_data_)); - virtual_wall_marker_creator.add_virtual_walls( - out_of_lane::debug::create_virtual_walls(debug_data_, params_)); - virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); std::map processing_times; processing_times["preprocessing"] = preprocessing_us / 1000; processing_times["calculate_lanelets"] = calculate_lanelets_us / 1000; processing_times["calculate_trajectory_footprints"] = calculate_trajectory_footprints_us / 1000; - processing_times["calculate_overlapping_ranges"] = calculate_overlapping_ranges_us / 1000; + processing_times["calculate_out_of_lane_areas"] = calculate_out_of_lane_areas_us / 1000; processing_times["filter_pred_objects"] = filter_predicted_objects_us / 1000; - processing_times["calculate_decision"] = calculate_decisions_us / 1000; - processing_times["calc_slowdown_points"] = calc_slowdown_points_us / 1000; - processing_times["insert_slowdown_points"] = insert_slowdown_points_us / 1000; + processing_times["calculate_time_collisions"] = calculate_time_collisions_us / 1000; + processing_times["calculate_times"] = calculate_times_us / 1000; + processing_times["calculate_slowdown_point"] = calculate_slowdown_point_us / 1000; + processing_times["generate_markers"] = markers_us / 1000; + processing_times["publish_markers"] = pub_markers_us / 1000; processing_times["Total"] = total_time_us / 1000; processing_diag_publisher_->publish(processing_times); tier4_debug_msgs::msg::Float64Stamped processing_time_msg; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 310a73c04d643..5225a6dd4abd9 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -23,6 +23,7 @@ #include #include +#include #include #include @@ -46,13 +47,24 @@ class OutOfLaneModule : public PluginModuleInterface private: void init_parameters(rclcpp::Node & node); + /// @brief resize the trajectory to start from the segment closest to ego and to have at most the + /// given length + static void limit_trajectory_size( + out_of_lane::EgoData & ego_data, + const std::vector & ego_trajectory_points, + const double max_arc_length); + /// @brief calculate the minimum stop and slowdown distances of ego + static void calculate_min_stop_and_slowdown_distances( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, + std::optional & previous_slowdown_pose_, const double slow_velocity); + out_of_lane::PlannerParam params_; inline static const std::string ns_ = "out_of_lane"; std::string module_name_; - std::optional prev_inserted_point_{}; - rclcpp::Clock::SharedPtr clock_{}; - rclcpp::Time prev_inserted_point_time_{}; + rclcpp::Clock::SharedPtr clock_; + std::optional previous_slowdown_pose_; + rclcpp::Time previous_slowdown_time_; protected: // Debug diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp deleted file mode 100644 index a1a722bb07f14..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp +++ /dev/null @@ -1,127 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "overlapping_range.hpp" - -#include -#include - -#include - -#include -#include - -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ - -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & trajectory_footprint, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet) -{ - Overlap overlap; - const auto & left_bound = lanelet.leftBound2d().basicLineString(); - const auto & right_bound = lanelet.rightBound2d().basicLineString(); - // TODO(Maxime): these intersects (for each trajectory footprint, for each lanelet) are too - // expensive - const auto overlap_left = boost::geometry::intersects(trajectory_footprint, left_bound); - const auto overlap_right = boost::geometry::intersects(trajectory_footprint, right_bound); - - lanelet::BasicPolygons2d overlapping_polygons; - if (overlap_left || overlap_right) - boost::geometry::intersection( - trajectory_footprint, lanelet.polygon2d().basicPolygon(), overlapping_polygons); - for (const auto & overlapping_polygon : overlapping_polygons) { - for (const auto & point : overlapping_polygon) { - if (overlap_left && overlap_right) - overlap.inside_distance = boost::geometry::distance(left_bound, right_bound); - else if (overlap_left) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, left_bound)); - else if (overlap_right) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, right_bound)); - geometry_msgs::msg::Pose p; - p.position.x = point.x(); - p.position.y = point.y(); - const auto length = lanelet::utils::getArcCoordinates(trajectory_lanelets, p).length; - if (length > overlap.max_arc_length) { - overlap.max_arc_length = length; - overlap.max_overlap_point = point; - } - if (length < overlap.min_arc_length) { - overlap.min_arc_length = length; - overlap.min_overlap_point = point; - } - } - } - return overlap; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params) -{ - OverlapRanges ranges; - OtherLane other_lane(lanelet); - std::vector overlaps; - for (auto i = 0UL; i < trajectory_footprints.size(); ++i) { - const auto overlap = calculate_overlap(trajectory_footprints[i], trajectory_lanelets, lanelet); - const auto has_overlap = overlap.inside_distance > params.overlap_min_dist; - if (has_overlap) { // open/update the range - overlaps.push_back(overlap); - if (!other_lane.range_is_open) { - other_lane.first_range_bound.index = i; - other_lane.first_range_bound.point = overlap.min_overlap_point; - other_lane.first_range_bound.arc_length = - overlap.min_arc_length - params.overlap_extra_length; - other_lane.first_range_bound.inside_distance = overlap.inside_distance; - other_lane.range_is_open = true; - } - other_lane.last_range_bound.index = i; - other_lane.last_range_bound.point = overlap.max_overlap_point; - other_lane.last_range_bound.arc_length = overlap.max_arc_length + params.overlap_extra_length; - other_lane.last_range_bound.inside_distance = overlap.inside_distance; - } else if (other_lane.range_is_open) { // !has_overlap: close the range if it is open - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - } - // close the range if it is still open - if (other_lane.range_is_open) { - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - return ranges; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params) -{ - OverlapRanges ranges; - for (auto & lanelet : lanelets) { - const auto lanelet_ranges = - calculate_overlapping_ranges(trajectory_footprints, trajectory_lanelets, lanelet, params); - ranges.insert(ranges.end(), lanelet_ranges.begin(), lanelet_ranges.end()); - } - return ranges; -} - -} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp deleted file mode 100644 index bc5872db16e03..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef OVERLAPPING_RANGE_HPP_ -#define OVERLAPPING_RANGE_HPP_ - -#include "types.hpp" - -#include - -#include - -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ - -/// @brief calculate the overlap between the given footprint and lanelet -/// @param [in] path_footprint footprint used to calculate the overlap -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelet lanelet used to calculate the overlap -/// @return the found overlap between the footprint and the lanelet -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & trajectory_footprint, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet); -/// @brief calculate the overlapping ranges between the trajectory footprints and a lanelet -/// @param [in] trajectory_footprints footprints used to calculate the overlaps -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelet lanelet used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelet -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params); -/// @brief calculate the overlapping ranges between the trajectory footprints and some lanelets -/// @param [in] trajectory_footprints footprints used to calculate the overlaps -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelets lanelets used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelets, sorted by -/// increasing arc length along the trajectory -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params); -} // namespace autoware::motion_velocity_planner::out_of_lane - -#endif // OVERLAPPING_RANGE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 96c54064e296c..8067d9e8b3410 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -28,52 +28,46 @@ #include #include +#include -#include -#include -#include #include +#include #include #include #include namespace autoware::motion_velocity_planner::out_of_lane { -using autoware_planning_msgs::msg::TrajectoryPoint; +using Polygons = boost::geometry::model::multi_polygon; -/// @brief parameters for the "out of lane" module +/// @brief parameters for the out_of_lane module struct PlannerParam { std::string mode; // mode used to consider a conflict with an object bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps // another lane + double max_arc_length; // [m] maximum arc length along the trajectory to check for collision + bool ignore_lane_changeable_lanelets; // if true, ignore overlaps on lane changeable lanelets - double time_threshold; // [s](mode="threshold") objects time threshold - double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range - double intervals_obj_buffer; // [s](mode="intervals") buffer to extend the objects time range + double time_threshold; // [s](mode="threshold") objects time threshold double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object - double ego_min_velocity; // [m/s] minimum velocity of ego used to calculate its ttc or time range - bool objects_use_predicted_paths; // whether to use the objects' predicted paths bool objects_cut_predicted_paths_beyond_red_lights; // whether to cut predicted paths beyond red // lights' stop lines - double objects_min_vel; // [m/s] objects lower than this velocity will be ignored - double objects_min_confidence; // minimum confidence to consider a predicted path - double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in - // the other lane + double objects_min_vel; // [m/s] objects lower than this velocity will be ignored + double objects_min_confidence; // minimum confidence to consider a predicted path bool objects_ignore_behind_ego; // if true, objects behind the ego vehicle are ignored - double overlap_extra_length; // [m] extra length to add around an overlap range - double overlap_min_dist; // [m] min distance inside another lane to consider an overlap - // action to insert in the trajectory if an object causes a conflict at an overlap - bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel - double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle - double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle - double slow_velocity; - double slow_dist_threshold; - double stop_dist_threshold; - double precision; // [m] precision when inserting a stop pose in the trajectory - double min_decision_duration; // [s] minimum duration needed a decision can be canceled + // action to insert in the trajectory if an object causes a collision at an overlap + double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle + double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle + double slow_velocity; // [m/s] slowdown velocity + double stop_dist_threshold; // [m] if a collision is detected bellow this distance ahead of ego, + // try to insert a stop point + double precision; // [m] precision when inserting a stop pose in the trajectory + double + min_decision_duration; // [s] duration needed before a stop or slowdown point can be removed + // ego dimensions used to create its polygon footprint double front_offset; // [m] front offset (from vehicle info) double rear_offset; // [m] rear offset (from vehicle info) @@ -85,98 +79,6 @@ struct PlannerParam double extra_left_offset; // [m] extra left distance }; -struct EnterExitTimes -{ - double enter_time{}; - double exit_time{}; -}; -struct RangeTimes -{ - EnterExitTimes ego{}; - EnterExitTimes object{}; -}; - -/// @brief action taken by the "out of lane" module -struct Slowdown -{ - size_t target_trajectory_idx{}; // we want to slowdown before this trajectory index - double velocity{}; // desired slow down velocity - lanelet::ConstLanelet lane_to_avoid{}; // we want to slowdown before entering this lane -}; -/// @brief slowdown to insert in a trajectory -struct SlowdownToInsert -{ - Slowdown slowdown{}; - autoware_planning_msgs::msg::TrajectoryPoint point{}; -}; - -/// @brief bound of an overlap range (either the first, or last bound) -struct RangeBound -{ - size_t index{}; - lanelet::BasicPoint2d point{}; - double arc_length{}; - double inside_distance{}; -}; - -/// @brief representation of an overlap between the ego footprint and some other lane -struct Overlap -{ - double inside_distance = 0.0; ///!< distance inside the overlap - double min_arc_length = std::numeric_limits::infinity(); - double max_arc_length = 0.0; - lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length - lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length -}; - -/// @brief range along the trajectory where ego overlaps another lane -struct OverlapRange -{ - lanelet::ConstLanelet lane{}; - size_t entering_trajectory_idx{}; - size_t exiting_trajectory_idx{}; - lanelet::BasicPoint2d entering_point{}; // pose of the overlapping point closest along the lane - lanelet::BasicPoint2d exiting_point{}; // pose of the overlapping point furthest along the lane - double inside_distance{}; // [m] how much ego footprint enters the lane - mutable struct - { - std::vector overlaps{}; - std::optional decision{}; - RangeTimes times{}; - std::optional object{}; - } debug; -}; -using OverlapRanges = std::vector; -/// @brief representation of a lane and its current overlap range -struct OtherLane -{ - bool range_is_open = false; - RangeBound first_range_bound{}; - RangeBound last_range_bound{}; - lanelet::ConstLanelet lanelet{}; - lanelet::BasicPolygon2d polygon{}; - - explicit OtherLane(lanelet::ConstLanelet ll) : lanelet(std::move(ll)) - { - polygon = lanelet.polygon2d().basicPolygon(); - } - - [[nodiscard]] OverlapRange close_range() - { - OverlapRange range; - range.lane = lanelet; - range.entering_trajectory_idx = first_range_bound.index; - range.entering_point = first_range_bound.point; - range.exiting_trajectory_idx = last_range_bound.index; - range.exiting_point = last_range_bound.point; - range.inside_distance = - std::max(first_range_bound.inside_distance, last_range_bound.inside_distance); - range_is_open = false; - last_range_bound = {}; - return range; - } -}; - namespace bgi = boost::geometry::index; struct StopLine { @@ -185,68 +87,52 @@ struct StopLine }; using StopLineNode = std::pair; using StopLinesRtree = bgi::rtree>; -using OutAreaRtree = bgi::rtree, bgi::rstar<16>>; +using OutAreaNode = std::pair; +using OutAreaRtree = bgi::rtree>; /// @brief data related to the ego vehicle struct EgoData { - std::vector trajectory_points{}; + std::vector trajectory_points; + geometry_msgs::msg::Pose pose; size_t first_trajectory_idx{}; - double velocity{}; // [m/s] - double max_decel{}; // [m/s²] - geometry_msgs::msg::Pose pose{}; + double longitudinal_offset_to_first_trajectory_index{}; + double min_stop_distance{}; + double min_slowdown_distance{}; + double min_stop_arc_length{}; + + Polygons drivable_lane_polygons; + + lanelet::BasicPolygon2d current_footprint; + std::vector trajectory_footprints; + StopLinesRtree stop_lines_rtree; }; -/// @brief data needed to make decisions -struct DecisionInputs +struct OutOfLanePoint { - OverlapRanges ranges; - EgoData ego_data; - autoware_perception_msgs::msg::PredictedObjects objects; - std::shared_ptr route_handler; - lanelet::ConstLanelets lanelets; + size_t trajectory_index; + lanelet::BasicPolygon2d outside_ring; + std::set collision_times; + std::optional min_object_arrival_time; + std::optional max_object_arrival_time; + std::optional ttc; + lanelet::ConstLanelets overlapped_lanelets; + bool to_avoid = false; +}; +struct OutOfLaneData +{ + std::vector outside_points; + OutAreaRtree outside_areas_rtree; }; /// @brief debug data struct DebugData { - std::vector footprints; - std::vector slowdowns; - geometry_msgs::msg::Pose ego_pose; - OverlapRanges ranges; - lanelet::BasicPolygon2d current_footprint; - lanelet::ConstLanelets current_overlapped_lanelets; - lanelet::ConstLanelets trajectory_lanelets; - lanelet::ConstLanelets ignored_lanelets; - lanelet::ConstLanelets other_lanelets; - std::vector trajectory_points; - size_t first_trajectory_idx; - - size_t prev_footprints = 0; - size_t prev_slowdowns = 0; - size_t prev_ranges = 0; - size_t prev_current_overlapped_lanelets = 0; - size_t prev_ignored_lanelets = 0; - size_t prev_trajectory_lanelets = 0; - size_t prev_other_lanelets = 0; - void reset_data() - { - prev_footprints = footprints.size(); - footprints.clear(); - prev_slowdowns = slowdowns.size(); - slowdowns.clear(); - prev_ranges = ranges.size(); - ranges.clear(); - prev_current_overlapped_lanelets = current_overlapped_lanelets.size(); - current_overlapped_lanelets.clear(); - prev_ignored_lanelets = ignored_lanelets.size(); - ignored_lanelets.clear(); - prev_trajectory_lanelets = trajectory_lanelets.size(); - trajectory_lanelets.clear(); - prev_other_lanelets = other_lanelets.size(); - other_lanelets.clear(); - } + size_t prev_out_of_lane_areas = 0; + size_t prev_ttcs = 0; + size_t prev_objects = 0; + size_t prev_stop_line = 0; }; } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt index f1eb7ff047fdc..ffc06aa8cc2f8 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt @@ -5,9 +5,20 @@ find_package(autoware_cmake REQUIRED) autoware_package() -# ament_auto_add_library(${PROJECT_NAME}_lib SHARED -# DIRECTORY src -# ) +ament_auto_add_library(${PROJECT_NAME}_lib SHARED + DIRECTORY src +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_collision_checker.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + gtest_main + ${PROJECT_NAME}_lib + ) + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() ament_auto_package(INSTALL_TO_SHARE include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp new file mode 100644 index 0000000000000..bf471c62af969 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp @@ -0,0 +1,69 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +namespace bgi = boost::geometry::index; +using RtreeNode = std::pair; +using Rtree = bgi::rtree>; + +/// @brief collision as a trajectory index and corresponding collision points +struct Collision +{ + size_t trajectory_index{}; + autoware::universe_utils::MultiPoint2d collision_points; +}; + +/// @brief collision checker for a trajectory as a sequence of 2D footprints +class CollisionChecker +{ + const autoware::universe_utils::MultiPolygon2d trajectory_footprints_; + std::shared_ptr rtree_; + +public: + /// @brief construct the collisions checker + /// @param trajectory_footprints footprints of the trajectory to be used for collision checking + /// @details internally, the rtree is built with the packing algorithm + explicit CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints); + + /// @brief efficiently calculate collisions with a geometry + /// @tparam Geometry boost geometry type + /// @param geometry geometry to check for collisions + /// @return collisions between the trajectory footprints and the input geometry + template + [[nodiscard]] std::vector get_collisions(const Geometry & geometry) const; + + /// @brief direct access to the rtree storing the polygon footprints + /// @return rtree of the polygon footprints + [[nodiscard]] std::shared_ptr get_rtree() const { return rtree_; } + + /// @brief get the size of the trajectory used by this collision checker + [[nodiscard]] size_t trajectory_size() const { return trajectory_footprints_.size(); } +}; +} // namespace autoware::motion_velocity_planner + +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index 5dbb872d99ca9..a96587c4465d6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -15,7 +15,10 @@ #ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#include +#include #include +#include #include #include @@ -37,12 +40,9 @@ #include #include -#include -#include #include #include #include -#include namespace autoware::motion_velocity_planner { @@ -59,11 +59,11 @@ struct PlannerData } // msgs from callbacks that are used for data-ready - nav_msgs::msg::Odometry current_odometry{}; - geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration{}; - autoware_perception_msgs::msg::PredictedObjects predicted_objects{}; - pcl::PointCloud no_ground_pointcloud{}; - nav_msgs::msg::OccupancyGrid occupancy_grid{}; + nav_msgs::msg::Odometry current_odometry; + geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration; + autoware_perception_msgs::msg::PredictedObjects predicted_objects; + pcl::PointCloud no_ground_pointcloud; + nav_msgs::msg::OccupancyGrid occupancy_grid; std::shared_ptr route_handler; // nearest search @@ -79,7 +79,7 @@ struct PlannerData tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states; // velocity smoother - std::shared_ptr velocity_smoother_{}; + std::shared_ptr velocity_smoother_; // parameters autoware::vehicle_info_utils::VehicleInfo vehicle_info_; @@ -88,7 +88,7 @@ struct PlannerData *@brief queries the traffic signal information of given Id. if keep_last_observation = true, *recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation */ - std::optional get_traffic_signal( + [[nodiscard]] std::optional get_traffic_signal( const lanelet::Id id, const bool keep_last_observation = false) const { const auto & traffic_light_id_map = @@ -98,6 +98,15 @@ struct PlannerData } return std::make_optional(traffic_light_id_map.at(id)); } + + [[nodiscard]] std::optional calculate_min_deceleration_distance( + const double target_velocity) const + { + return motion_utils::calcDecelDistWithJerkAndAccConstraints( + current_odometry.twist.twist.linear.x, target_velocity, + current_acceleration.accel.accel.linear.x, velocity_smoother_->getMinDecel(), + std::abs(velocity_smoother_->getMinJerk()), velocity_smoother_->getMinJerk()); + } }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp new file mode 100644 index 0000000000000..6e84b63a3c7fc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp @@ -0,0 +1,70 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/motion_velocity_planner_common/collision_checker.hpp" + +namespace autoware::motion_velocity_planner +{ +CollisionChecker::CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints) +: trajectory_footprints_(std::move(trajectory_footprints)) +{ + std::vector nodes; + nodes.reserve(trajectory_footprints_.size()); + for (auto i = 0UL; i < trajectory_footprints_.size(); ++i) { + nodes.emplace_back( + boost::geometry::return_envelope(trajectory_footprints_[i]), + i); + } + rtree_ = std::make_shared(nodes.begin(), nodes.end()); +} + +template +std::vector CollisionChecker::get_collisions(const Geometry & geometry) const +{ + std::vector collisions; + std::vector approximate_results; + autoware::universe_utils::MultiPoint2d intersections; + ; + rtree_->query(bgi::intersects(geometry), std::back_inserter(approximate_results)); + for (const auto & result : approximate_results) { + intersections.clear(); + boost::geometry::intersection(trajectory_footprints_[result.second], geometry, intersections); + if (!intersections.empty()) { + Collision c; + c.trajectory_index = result.second; + c.collision_points = intersections; + collisions.push_back(c); + } + } + return collisions; +} + +template std::vector CollisionChecker::get_collisions( + const autoware::universe_utils::Point2d & geometry) const; +template std::vector CollisionChecker::get_collisions( + const autoware::universe_utils::Line2d & geometry) const; +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiPolygon2d & geometry) const; + +// @warn Multi geometries usually lead to very inefficient queries +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiPoint2d & geometry) const; +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiLineString2d & geometry) const; +template std::vector CollisionChecker::get_collisions< + autoware::universe_utils::Polygon2d>(const autoware::universe_utils::Polygon2d & geometry) const; +} // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp new file mode 100644 index 0000000000000..df813db336a9d --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp @@ -0,0 +1,176 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/motion_velocity_planner_common/collision_checker.hpp" + +#include + +#include + +#include +#include + +using autoware::motion_velocity_planner::CollisionChecker; +using autoware::universe_utils::Line2d; +using autoware::universe_utils::MultiLineString2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; + +Point2d random_point() +{ + static std::random_device r; + static std::default_random_engine e1(r()); + static std::uniform_real_distribution uniform_dist(-100, 100); + return {uniform_dist(e1), uniform_dist(e1)}; +} + +Line2d random_line() +{ + const auto point = random_point(); + const auto point2 = Point2d{point.x() + 1, point.y() + 1}; + const auto point3 = Point2d{point2.x() - 1, point2.y() + 1}; + const auto point4 = Point2d{point3.x() + 1, point3.y() + 1}; + return {point, point2, point3, point4}; +} + +Polygon2d random_polygon() +{ + Polygon2d polygon; + const auto point = random_point(); + const auto point2 = Point2d{point.x() + 1, point.y() + 4}; + const auto point3 = Point2d{point.x() + 4, point.y() + 4}; + const auto point4 = Point2d{point.x() + 3, point.y() + 1}; + polygon.outer() = {point, point2, point3, point4, point}; + return polygon; +} + +bool all_within(const MultiPoint2d & pts1, const MultiPoint2d & pts2) +{ + // results from the collision checker and the direct checks can have some small precision errors + constexpr auto eps = 1e-3; + for (const auto & p1 : pts1) { + bool found = false; + for (const auto & p2 : pts2) { + if (boost::geometry::comparable_distance(p1, p2) < eps) { + found = true; + break; + } + } + if (!found) return false; + } + return true; +} + +TEST(TestCollisionChecker, Benchmark) +{ + constexpr auto nb_ego_footprints = 1000; + constexpr auto nb_obstacles = 1000; + MultiPolygon2d ego_footprints; + ego_footprints.reserve(nb_ego_footprints); + for (auto i = 0; i < nb_ego_footprints; ++i) { + ego_footprints.push_back(random_polygon()); + } + const auto cc_constr_start = std::chrono::system_clock::now(); + CollisionChecker collision_checker(ego_footprints); + const auto cc_constr_end = std::chrono::system_clock::now(); + const auto cc_constr_ns = + std::chrono::duration_cast(cc_constr_end - cc_constr_start).count(); + std::printf( + "Collision checker construction (with %d footprints): %ld ns\n", nb_ego_footprints, + cc_constr_ns); + MultiPolygon2d poly_obstacles; + MultiPoint2d point_obstacles; + MultiLineString2d line_obstacles; + for (auto i = 0; i < nb_obstacles; ++i) { + poly_obstacles.push_back(random_polygon()); + point_obstacles.push_back(random_point()); + line_obstacles.push_back(random_line()); + } + const auto check_obstacles_one_by_one = [&](const auto & obstacles) { + std::chrono::nanoseconds collision_checker_ns{}; + std::chrono::nanoseconds naive_ns{}; + for (const auto & obs : obstacles) { + const auto cc_start = std::chrono::system_clock::now(); + const auto collisions = collision_checker.get_collisions(obs); + MultiPoint2d cc_collision_points; + for (const auto & c : collisions) + cc_collision_points.insert( + cc_collision_points.end(), c.collision_points.begin(), c.collision_points.end()); + const auto cc_end = std::chrono::system_clock::now(); + const auto naive_start = std::chrono::system_clock::now(); + MultiPoint2d naive_collision_points; + for (const auto & ego_footprint : ego_footprints) { + MultiPoint2d points; + boost::geometry::intersection(ego_footprint, obs, points); + naive_collision_points.insert(naive_collision_points.end(), points.begin(), points.end()); + } + const auto naive_end = std::chrono::system_clock::now(); + const auto equal = all_within(cc_collision_points, naive_collision_points) && + all_within(naive_collision_points, cc_collision_points); + EXPECT_TRUE(equal); + if (!equal) { + std::cout << "cc: " << boost::geometry::wkt(cc_collision_points) << std::endl; + std::cout << "naive: " << boost::geometry::wkt(naive_collision_points) << std::endl; + } + collision_checker_ns += + std::chrono::duration_cast(cc_end - cc_start); + naive_ns += std::chrono::duration_cast(naive_end - naive_start); + } + std::printf("%20s%10ld ns\n", "collision checker : ", collision_checker_ns.count()); + std::printf("%20s%10ld ns\n", "naive : ", naive_ns.count()); + }; + const auto check_obstacles = [&](const auto & obstacles) { + std::chrono::nanoseconds collision_checker_ns{}; + std::chrono::nanoseconds naive_ns{}; + const auto cc_start = std::chrono::system_clock::now(); + const auto collisions = collision_checker.get_collisions(obstacles); + MultiPoint2d cc_collision_points; + for (const auto & c : collisions) + cc_collision_points.insert( + cc_collision_points.end(), c.collision_points.begin(), c.collision_points.end()); + const auto cc_end = std::chrono::system_clock::now(); + const auto naive_start = std::chrono::system_clock::now(); + MultiPoint2d naive_collision_points; + boost::geometry::intersection(ego_footprints, obstacles, naive_collision_points); + const auto naive_end = std::chrono::system_clock::now(); + const auto equal = all_within(cc_collision_points, naive_collision_points) && + all_within(naive_collision_points, cc_collision_points); + EXPECT_TRUE(equal); + if (!equal) { + std::cout << "cc: " << boost::geometry::wkt(cc_collision_points) << std::endl; + std::cout << "naive: " << boost::geometry::wkt(naive_collision_points) << std::endl; + } + collision_checker_ns += std::chrono::duration_cast(cc_end - cc_start); + naive_ns += std::chrono::duration_cast(naive_end - naive_start); + std::printf("%20s%10ld ns\n", "collision checker : ", collision_checker_ns.count()); + std::printf("%20s%10ld ns\n", "naive : ", naive_ns.count()); + }; + + std::cout << "* check one by one\n"; + std::printf("%d Polygons:\n", nb_obstacles); + check_obstacles_one_by_one(poly_obstacles); + std::printf("%d Lines:\n", nb_obstacles); + check_obstacles_one_by_one(line_obstacles); + std::printf("%d Points:\n", nb_obstacles); + check_obstacles_one_by_one(point_obstacles); + std::cout << "* check all at once\n"; + std::printf("%d Polygons:\n", nb_obstacles); + check_obstacles(poly_obstacles); + std::printf("%d Lines:\n", nb_obstacles); + check_obstacles(line_obstacles); + std::printf("%d Points:\n", nb_obstacles); + check_obstacles(point_obstacles); +} diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index e458b81a53ca8..9a08616b8fe7b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -85,6 +84,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & "~/output/velocity_factors", 1); processing_time_publisher_ = this->create_publisher("~/debug/processing_time_ms", 1); + debug_viz_pub_ = + this->create_publisher("~/debug/markers", 1); diagnostics_pub_ = this->create_publisher("/diagnostics", 10); // Parameters @@ -99,7 +100,7 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & // Initialize PlannerManager for (const auto & name : declare_parameter>("launch_modules")) { // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter. - if (name == "") { + if (name.empty()) { break; } planner_manager_.load_module_plugin(*this, name); @@ -135,7 +136,7 @@ bool MotionVelocityPlannerNode::update_planner_data() const auto check_with_log = [&](const auto ptr, const auto & log) { constexpr auto throttle_duration = 3000; // [ms] if (!ptr) { - RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, log); + RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, "%s", log); is_ready = false; return false; } @@ -278,7 +279,6 @@ void MotionVelocityPlannerNode::on_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points{ input_trajectory_msg->points.begin(), input_trajectory_msg->points.end()}; - auto output_trajectory_msg = generate_trajectory(input_trajectory_points); output_trajectory_msg.header = input_trajectory_msg->header; processing_times["generate_trajectory"] = stop_watch.toc(true); @@ -333,7 +333,8 @@ void MotionVelocityPlannerNode::insert_slowdown( autoware::motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); if (from_insert_idx && to_insert_idx) { for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) - trajectory.points[idx].longitudinal_velocity_mps = slowdown_interval.velocity; + trajectory.points[idx].longitudinal_velocity_mps = + static_cast(slowdown_interval.velocity); } else { RCLCPP_WARN(get_logger(), "Failed to insert slowdown point"); } @@ -368,16 +369,14 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware::motion_velocity_planner::TrajectoryPoints clipped; autoware::motion_velocity_planner::TrajectoryPoints traj_smoothed; clipped.insert( - clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); + clipped.end(), std::next(traj_resampled.begin(), static_cast(traj_resampled_closest)), + traj_resampled.end()); if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { RCLCPP_ERROR(get_logger(), "failed to smooth"); } - traj_smoothed.insert( - traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); - if (external_v_limit) { autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( - traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); + 0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } return traj_smoothed; } @@ -385,13 +384,21 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points) { + universe_utils::StopWatch stop_watch; autoware_planning_msgs::msg::Trajectory output_trajectory_msg; output_trajectory_msg.points = {input_trajectory_points.begin(), input_trajectory_points.end()}; - if (smooth_velocity_before_planning_) + if (smooth_velocity_before_planning_) { + stop_watch.tic("smooth"); input_trajectory_points = smooth_trajectory(input_trajectory_points, planner_data_); - const auto resampled_trajectory = - autoware::motion_utils::resampleTrajectory(output_trajectory_msg, 0.5); - + RCLCPP_DEBUG(get_logger(), "smooth: %2.2f us", stop_watch.toc("smooth")); + } + autoware_planning_msgs::msg::Trajectory smooth_velocity_trajectory; + smooth_velocity_trajectory.points = { + input_trajectory_points.begin(), input_trajectory_points.end()}; + auto resampled_trajectory = + autoware::motion_utils::resampleTrajectory(smooth_velocity_trajectory, 0.5); + motion_utils::calculate_time_from_start( + resampled_trajectory.points, planner_data_.current_odometry.pose.pose.position); const auto planning_results = planner_manager_.plan_velocities( resampled_trajectory.points, std::make_shared(planner_data_)); From 7f3b71699667f1012b2322e5dcfbe8a799d5d0e7 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 28 Aug 2024 17:16:21 +0900 Subject: [PATCH 126/151] fix(out_of_lane): fix noConstructor cppcheck warning (#8636) Signed-off-by: Maxime CLEMENT --- .../src/out_of_lane_module.hpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 5225a6dd4abd9..fc0cd4ac539ca 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -30,6 +30,7 @@ #include #include +#include #include #include @@ -58,17 +59,17 @@ class OutOfLaneModule : public PluginModuleInterface out_of_lane::EgoData & ego_data, const PlannerData & planner_data, std::optional & previous_slowdown_pose_, const double slow_velocity); - out_of_lane::PlannerParam params_; + out_of_lane::PlannerParam params_{}; inline static const std::string ns_ = "out_of_lane"; - std::string module_name_; - rclcpp::Clock::SharedPtr clock_; - std::optional previous_slowdown_pose_; - rclcpp::Time previous_slowdown_time_; + std::string module_name_{"uninitialized"}; + rclcpp::Clock::SharedPtr clock_{nullptr}; + std::optional previous_slowdown_pose_{std::nullopt}; + rclcpp::Time previous_slowdown_time_{0}; protected: // Debug - mutable out_of_lane::DebugData debug_data_; + mutable out_of_lane::DebugData debug_data_{}; }; } // namespace autoware::motion_velocity_planner From 97b094935ceb3b0bdca5c2214e3727409f61b8fa Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 2 Sep 2024 11:05:32 +0900 Subject: [PATCH 127/151] fix(out_of_lane): fix a bug with the rtree reference deleted nodes (#8679) Signed-off-by: Maxime CLEMENT --- .../src/out_of_lane_collisions.cpp | 16 +++++++--------- .../src/out_of_lane_collisions.hpp | 8 +++++--- .../src/out_of_lane_module.cpp | 14 ++++++++++++-- 3 files changed, 24 insertions(+), 14 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp index c375bcc35c1ee..aef035200b6cc 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp @@ -129,28 +129,27 @@ void calculate_collisions_to_avoid( } } -OutOfLaneData calculate_outside_points(const EgoData & ego_data) +std::vector calculate_out_of_lane_points(const EgoData & ego_data) { - OutOfLaneData out_of_lane_data; - out_of_lane::OutOfLanePoint p; + std::vector out_of_lane_points; + OutOfLanePoint p; for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { p.trajectory_index = i + ego_data.first_trajectory_idx; const auto & footprint = ego_data.trajectory_footprints[i]; - out_of_lane::Polygons out_of_lane_polygons; + Polygons out_of_lane_polygons; boost::geometry::difference(footprint, ego_data.drivable_lane_polygons, out_of_lane_polygons); for (const auto & area : out_of_lane_polygons) { if (!area.outer.empty()) { p.outside_ring = area.outer; - out_of_lane_data.outside_points.push_back(p); + out_of_lane_points.push_back(p); } } } - return out_of_lane_data; + return out_of_lane_points; } -OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data) +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data) { - auto out_of_lane_data = calculate_outside_points(ego_data); std::vector rtree_nodes; for (auto i = 0UL; i < out_of_lane_data.outside_points.size(); ++i) { OutAreaNode n; @@ -160,7 +159,6 @@ OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data) rtree_nodes.push_back(n); } out_of_lane_data.outside_areas_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; - return out_of_lane_data; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp index b9048cc358a07..33f0842c56d36 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp @@ -47,9 +47,11 @@ void calculate_collisions_to_avoid( const std::vector & trajectory, const PlannerParam & params); -/// @brief calculate the areas where ego will drive outside of its lane -/// @details the OutOfLaneData points and rtree are filled -OutOfLaneData calculate_out_of_lane_areas(const EgoData & ego_data); +/// @brief calculate the out of lane points +std::vector calculate_out_of_lane_points(const EgoData & ego_data); + +/// @brief prepare the rtree of out of lane points for the given data +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // OUT_OF_LANE_COLLISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index ca7ed3b9dc7bd..e51980d60dbba 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -225,6 +226,16 @@ void prepare_stop_lines_rtree( ego_data.stop_lines_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; } +out_of_lane::OutOfLaneData prepare_out_of_lane_data( + const out_of_lane::EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + out_of_lane::OutOfLaneData out_of_lane_data; + out_of_lane_data.outside_points = out_of_lane::calculate_out_of_lane_points(ego_data); + out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, route_handler); + out_of_lane::prepare_out_of_lane_areas_rtree(out_of_lane_data); + return out_of_lane_data; +} + VelocityPlanningResult OutOfLaneModule::plan( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) @@ -253,8 +264,7 @@ VelocityPlanningResult OutOfLaneModule::plan( const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); stopwatch.tic("calculate_out_of_lane_areas"); - auto out_of_lane_data = calculate_out_of_lane_areas(ego_data); - out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, *planner_data->route_handler); + auto out_of_lane_data = prepare_out_of_lane_data(ego_data, *planner_data->route_handler); const auto calculate_out_of_lane_areas_us = stopwatch.toc("calculate_out_of_lane_areas"); stopwatch.tic("filter_predicted_objects"); From 02ce3a56539b3f93bf884a87d05f900a79e8e444 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 2 Sep 2024 19:40:41 +0900 Subject: [PATCH 128/151] docs(out_of_lane): update documentation for the new design (#8692) Signed-off-by: Maxime CLEMENT --- .../README.md | 182 ++++++++---------- .../config/out_of_lane.param.yaml | 1 - .../docs/ego_lane.png | Bin 0 -> 17530 bytes .../docs/footprints.png | Bin 0 -> 28711 bytes .../docs/object_paths.png | Bin 0 -> 26240 bytes ...footprints_other_lanes_overlaps_ranges.png | Bin 127593 -> 0 bytes .../docs/out_of_lane_areas.png | Bin 0 -> 19244 bytes .../docs/out_of_lane_slow.png | Bin 110077 -> 0 bytes .../docs/out_of_lane_stop.png | Bin 183400 -> 0 bytes .../docs/path_green_light.png | Bin 0 -> 23635 bytes .../docs/path_red_light.png | Bin 0 -> 22819 bytes .../docs/ttcs.png | Bin 0 -> 28315 bytes .../docs/ttcs_avoid.png | Bin 0 -> 31503 bytes .../src/debug.cpp | 41 +++- .../src/out_of_lane_module.cpp | 7 +- .../src/types.hpp | 1 - 16 files changed, 117 insertions(+), 115 deletions(-) create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/object_paths.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_areas.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_red_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs_avoid.png diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md index 54b7cebb7c8ff..0b6aa697fcbef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md @@ -1,129 +1,113 @@ -## Out of Lane +# Out of Lane -### Role +## Role -`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects. +There are cases where the ego vehicle footprint goes out of the driving lane, +for example when taking a narrow turn with a large vehicle. +The `out_of_lane` module adds deceleration and stop points to the ego trajectory in order to prevent collisions from occurring in these out of lane cases. -### Activation Timing +## Activation -This module is activated if `launch_out_of_lane` is set to true. +This module is activated if the launch parameter `launch_out_of_lane_module` is set to true. -### Inner-workings / Algorithms +## Inner-workings / Algorithms -The algorithm is made of the following steps. +This module calculates if out of lane collisions occur and insert stop point before the collisions if necessary. -1. Calculate the ego path footprints (red). -2. Calculate the other lanes (magenta). -3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green). -4. For each overlapping range, decide if a stop or slow down action must be taken. -5. For each action, insert the corresponding stop or slow down point in the path. +The algorithm assumes the input ego trajectory contains accurate `time_from_start` +values in order to calculate accurate time to collisions with the predicted objects. -![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png) +Next we explain the inner-workings of the module in more details. -#### 1. Ego Path Footprints +### 1. Ego trajectory footprints -In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters. +In this first step, the ego footprint is projected at each trajectory point and its size is modified based on the `ego.extra_..._offset` parameters. -#### 2. Other lanes +The length of the trajectory used for generating the footprints is limited by the `max_arc_length` parameter. -In the second step, the set of lanes to consider for overlaps is generated. -This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets. -The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`. +![ego_footprints](./docs/footprints.png) -A lanelet is deemed non-relevant if it meets one of the following conditions. +### 2. Ego lanelets -- It is part of the lanelets followed by the ego path. -- It contains the rear point of the ego footprint. -- It follows one of the ego path lanelets. +In the second step, we calculate the lanelets followed by the ego trajectory. +We select all lanelets crossed by the trajectory linestring (sequence of trajectory points), as well as their preceding lanelets. -#### 3. Overlapping ranges +![ego_lane](./docs/ego_lane.png) -In the third step, overlaps between the ego path footprints and the other lanes are calculated. -For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`. -For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored. -Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored. -Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information: +In the debug visualization the combination of all ego lanelets is shown as a blue polygon. -- overlapped other lane $l$. -- start and end ego path indexes. -- start and end ego path arc lengths. -- start and end overlap points. +### 3. Out of lane areas -#### 4. Decisions +Next, for each trajectory point, we create the corresponding out of lane areas by subtracting the ego lanelets (from step 2) from the trajectory point footprint (from step 1). +Each area is associated with the lanelets overlapped by the area and with the corresponding ego trajectory point. -In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects. -The conditions for the decision depend on the value of the `mode` parameter. +![out_of_lane_areas](./docs/out_of_lane_areas.png) -Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path). -If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. -If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. +In the debug visualization, the out of lane area polygon is connected to the corresponding trajectory point by a line. + +### 4. Predicted objects filtering - - - - - -
- - - -
+We filter objects and their predicted paths with the following conditions: -##### Threshold +- ignore objects with a speed bellow the `minimum_velocity` parameter; +- ignore objects coming from behind the ego vehicle if parameter `ignore_behind_ego` is set to true; +- ignore predicted paths whose confidence value is bellow the `predicted_path_min_confidence` parameter; +- cut the points of predicted paths going beyond the stop line of a red traffic light if parameter `cut_predicted_paths_beyond_red_lights` is set to `true`. -With the `mode` set to `"threshold"`, -a decision to stop or slow down before a range is made if -an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`. +| `cut_predicted_paths_beyond_red_lights = false` | `cut_predicted_paths_beyond_red_lights = true` | +| :---------------------------------------------: | :--------------------------------------------: | +| ![](./docs/path_green_light.png) | ![](./docs/path_red_light.png) | -##### TTC (time to collision) +In the debug visualization, the filtered predicted paths are shown in green and the stop lines of red traffic lights are shown in red. -With the `mode` set to `"ttc"`, -estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated. -This is then used to calculate the time to collision over the period where ego crosses the overlap. -If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made. +### 5. Time to collisions -##### Intervals +For each out of lane area, we calculate the times when a dynamic object will overlap the area based on its filtered predicted paths. -With the `mode` set to `"intervals"`, -the estimated times when ego and the dynamic objects reach the start and end points of -the overlapping range are used to create time intervals. -These intervals can be made shorter or longer using the -`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters. -If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made. +In the case where parameter `mode` is set to `threshold` and the calculated time is less than `threshold.time_threshold` parameter, then we decide to avoid the out of lane area. -##### Time estimates +In the case where parameter `mode` is set to `ttc`, +we calculate the time to collision by comparing the predicted time of the object with the `time_from_start` field contained in the trajectory point. +If the time to collision is bellow the `ttc.threshold` parameter value, we decide to avoid the out of lane area. -###### Ego +![ttcs](./docs/ttcs.png) -To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path -at its current velocity or at half the velocity of the path points, whichever is higher. +In the debug visualization, the ttc (in seconds) is displayed on top of its corresponding trajectory point. +The color of the text is red if the collision should be avoided and green otherwise. -###### Dynamic objects +### 6. Calculate the stop or slowdown point -Two methods are used to estimate the time when a dynamic objects with reach some point. -If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. -Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. +First, the minimum stopping distance of the ego vehicle is calculated based on the jerk and deceleration constraints set by the velocity smoother parameters. -#### 5. Path update +We then search for the furthest pose along the trajectory where the ego footprint stays inside of the ego lane (calculate in step 2) and constraint the search to be between the minimum stopping distance and the 1st trajectory point with a collision to avoid (as determined in the previous step). +The search is done by moving backward along the trajectory with a distance step set by the `action.precision` parameter. -Finally, for each decision to stop or slow down before an overlapping range, -a point is inserted in the path. -For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$, -a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$. -Such point with no overlap must exist since, by definition of the overlapping range, -we know that there is no overlap at $i-1$. +We first do this search for a footprint expanded with the `ego.extra_..._offset`, `action.longitudinal_distance_buffer` and `action.lateral_distance_buffer` parameters. +If no valid pose is found, we search again while only considering the extra offsets but without considering the distance buffers. +If still no valid pose is found, we use the base ego footprint without any offset. +In case no pose is found, we fallback to using the pose before the detected collision without caring if it is out of lane or not. -If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter), -it is skipped. +Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the trajectory point to avoid. +If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. +If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. -Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible. +![avoid_collision](./docs/ttcs_avoid.png) -### Module Parameters +### About stability of the stop/slowdown pose + +As the input trajectory can change significantly between iterations, +it is expected that the decisions of this module will also change. +To make the decision more stable, a stop or slowdown pose is used for a minimum duration set by the `action.min_duration` parameter. +If during that time a new pose closer to the ego vehicle is generated, then it replaces the previous one. +Otherwise, the stop or slowdown pose will only be discarded after no out of lane collision is detection for the set duration. + +## Module Parameters | Parameter | Type | Description | | ----------------------------- | ------ | --------------------------------------------------------------------------------- | | `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc | | `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane | +| `max_arc_length` | double | [m] maximum trajectory arc length that is checked for out_of_lane collisions | | Parameter /threshold | Type | Description | | -------------------- | ------ | ---------------------------------------------------------------- | @@ -133,20 +117,22 @@ Moreover, parameter `action.distance_buffer` adds an extra distance between the | -------------- | ------ | ------------------------------------------------------------------------------------------------------ | | `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | -| Parameter /objects | Type | Description | -| ------------------------------- | ------ | --------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | -| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | - -| Parameter /overlap | Type | Description | -| ------------------ | ------ | --------------------------------------------------------------------- | -| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | - -| Parameter /action | Type | Description | -| ----------------------------- | ------ | --------------------------------------------------------------------- | -| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | -| `slowdown.velocity` | double | [m] slow down velocity | -| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | +| Parameter /objects | Type | Description | +| --------------------------------------- | ------ | ------------------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | +| `cut_predicted_paths_beyond_red_lights` | bool | [-] if true, predicted paths are cut beyond the stop line of red traffic lights | +| `ignore_behind_ego` | bool | [-] if true, objects behind the ego vehicle are ignored | + +| Parameter /action | Type | Description | +| ------------------------------ | ------ | --------------------------------------------------------------------- | +| `precision` | double | [m] precision when inserting a stop pose in the trajectory | +| `longitudinal_distance_buffer` | double | [m] safety distance buffer to keep in front of the ego vehicle | +| `lateral_distance_buffer` | double | [m] safety distance buffer to keep on the side of the ego vehicle | +| `min_duration` | double | [s] minimum duration needed before a decision can be canceled | +| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | +| `slowdown.velocity` | double | [m] slow down velocity | +| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | | Parameter /ego | Type | Description | | -------------------- | ------ | ---------------------------------------------------- | diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index 67db597d80752..5d36aa8d3f018 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -3,7 +3,6 @@ out_of_lane: # module to stop or slowdown before overlapping another lane with other objects mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane - ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png new file mode 100644 index 0000000000000000000000000000000000000000..65cb73226465ae3de6c27b35562d35c57c5906b5 GIT binary patch literal 17530 zcmbt+cRZEh|MyWTp^y_2*($>jiv)`ZhCH&b_`CIsu_%ImkmZE};1`KvZ4+g`T z#Jd9ilKS1n1pK)9Nzk3I#)}d(@2BU>3%1CK>7_U#O+ELl0v+OTNZ=T{? z@hU3ivlg=zml|mQ&9?ol)S@{e_>6CC^fS-PuLN*16d~EGZ#OngtKQ=Hj0MF;hWrj8 z@|}`Jic3-~1--eKS8uei;pR9?!%YX z$G9VQ-WEiBBxj+aa`R|#`3!&m*K6-N_!0!p!J0K3hZ$S-T&?DstxX&*<*qh-rnA3BZ+!QBzXo5 zX41=ssYH@bhT82SoStpWw6F`R-b7b-7P6_A>vR>eVbJ7KK1)|9m}Kn&^exg0$M~5F z4;=l{ja%{dx0BZTxP&D9-U>fTB_}8EVh+HLj~`Y1*v^=3ru#hAu%q{4m1OPg_TI~v zFU>R~3Kq?CwH}76j+pGvlbSG(+PWV~6>L95*461O)F94Q3l2R#9)p)$K_9h>WiN>R z5^1fRYiiFIsp-tIH9dTQ_^9>E<7YI-qSqVRYXLYb@yC&okv+G^zQqKf5JKlyNcru>rIr`-=c$$^MVTDmKVX4}Jqgzx ze}1OP{<3n|?Y1a9D;R|gFV6zIZjxMHUXG38NK!J&C28=G%04hH*v28zF2!`Z+!Wt( zZeVeeskNS50Xt4B>($p49Ua}$((;Y0vgWO>c~b8U>JCRyYhp1~` zCZ9hk9PHuJHp2J(l%`hABW-y8a_q17Hl~{}Rhx+^;e2Uf%@>*-i@mCRCsdD8F~umi~FXrH`VYp^03KCge}b#6~&vZkAd0|_AQc!t(U?y zGyHkL`+l8s;~?(7|5lpo1%A_GwIHCL6v_KnoH(4uoM^e1v`y{+v*92cJV`pbS^6`85Qu#~Y zj^xzz8K$XebL(wsDMDZG&|Lp~w5RmFE;QUtjndJ&y1MNnpDI1ZT(c^Vy}zT}gfD9; z+va+c{13K%Biu4Y=pQC!Pk+H?S6r|j;s4-rjlKd?`DmfGibA0V{r#5zjv{{7_sJqx zU~G`-t6Y~vhFbqdq1rsR7l#vAWK!XLFTh;HX@w2VKI@TOehk?#`Vs!{@6{aG&R60d zTPD`aO&7lrr$nc}Pd3|{z4k6V54UDBoAEiXnFqsY8=aSWlh`qB`?VRN?}qprj4LB` z^T$q4PYaY&$jHg>%D!XlaWle3ys0juIbFUu#X+1WAdZ&m+s@ijl(bEMzH&}2^xXNQ zDyxnk(hfhXmm>(ly-6KP;zz)RTA9mRJ1;(oUDhqxY#FxG^g)WRN8 zCyJbtp5hM$!!@I${%uVs2&^K%5p!ZpO2t~CjTLX23Nv4`yVV@zaU&^FGLx=bBl>t zw>L+SOD^@<1X_@v!6g09-@heeUc=YU>%UptgRQ6uKL2h-(Eo?TU+-ZO^H!dHGhqie zVbHQ=o8!R#e(e0C5r^sH`l3g13Qt*={GUpb{c#qlD!%3aocV9tEufSGPr{x6u`7|6 z1zTxsf=y_tQ7*7Xqh}GG#{6meV@-!y_fGupN0ET7{5vY3I@0;;sg|~`wnPfwJ@eMh zhY|6a(!5pX(&R&ua$^jpUsWiSK9|w>?2XdwER2rkaB!R|ZvV46Otu4x>MCw=xVx%} z%_R|?&0sjKzxPx4<>uv<>NiZ76QkmtR)hxz24Xf(7LEfETFWP8YPPioZ{NP{sl)^J z93gbO#cgfYs^&se(yh>-e1Byq&qHu^(y`5ca{o)=py6qMj|Fd36)m3J(OrC_JQ(fp z=N+HqBfq(mJL=!+)(tC~TYUf8lWKf-qN1Oeoh5IjV%*GgeP=WhKb`NsIb&pKNTn*Y z`rOeMrZMatgadN`P3oJzV8^4;7 zFv-r@`*GJW)&WGf&7F7l7*G9xQ?Z&atCrC+ZNVJCts~B{v0ahZd!5q7am`Cgic92V z#_isO9lAc8b(a_nuUuU^yT=6F*{%%hxyM@yGp=8{%f`I8O=a(d--7V+Z+*Q5i@INE zlU{iA?FNmw&*3NZwC~&KZaVdE2Ulm^*^{nL*4@8Vn&NI_0i^Is+F9+Mm%uir1oH@E zzrNW<+c~4SyfSs)7~gsA^1?=(sNcRVVP$t9!HeC!z(_}LA{ezfsoRr<*STXav(o4SbvR6kVwPJtg(#PVDbDPy<>6K=aN z)T+-44+qxUP_fWh=h0O)R76W+Z*PCIl<w0NY;VlJ6~1_n?A z1G;-&`{elcQbLI4( z@F=DxMO_`8fs~MnH5H?qtZ|*!VXzko=roDKxq$)yi=CV{dD5J~sh}G~f`WpF*!zyn zPTLl0s8*`;`DY|oV43B{mFw&FY!S(Zh#AhO-zMvk6exf8>}&-mqmOIHvM7Qga_C)k zrx!jA9nPrvZ6isCPBu4<+s-RRE7&qsoKIF-f*1<@6?7Gq6#zY}GTupNKv zK^~3o_gKf-a|Hjo{z-bf;{NXH$WJRe6bP8dbuBHeEiKu7BHc#}ep_do7u+c)A|&_Z z>Qb7h)M7l8H`XwfmF4AG;v(qFm1<6D9xtU_tj(UUThbrT9GrXkonJ(7rB>v|h0WWK zZ6BRJ-Z#m>{|LtBl!-qdwazIg9y(|}z@%_poGca>v*Tkhm?K7w5&q5DHm>Y!b?BP| zgVlapJuH>UgrUC?jydvtZnCEMEbr){TWqZj8qF4QgL#TpzisOCQ!Sjx3N7Xd!FJ4v z$JbM+%;@C$hIjqE8{+CL)phhbGmZXI!#s|6{eRyOa%gtnCLHP!&P3(L-6425&~h^I z`77}F0j>JKhz`H~{j2sgTg24c`)nu=2^5%sfPKEfX6q1Z?#DgJMEVfu#`$NWTd#F1 zF@y}dm1;;??b6Z1TN#{2jr<)!A<){7=R9dpPl8(VY3o~BI0aS1_x5!CckUTm#zKPV zNMP~rB}z_d^WX04ix5*7boY+vc?;dqj(rlu$K23+KGWhozq;D3qkDm@vM(cC&@~%* zVKYJ0#SG?td)>P4?BqaogfTZ(@>oG!Xo*6dvF@85NG>}I$K%lwBpD`kQDOFtnk)Wt+t>YI(=VI$(a z&R=SkYFF9NSJlsWDcjv=9rSh!s_0o3o+Zm*exB!~Y?p2~`d6UprioYc#W|W?SI}|h z)CGG@rQyR3y02PmXBkr}F`PTA+d&5Q&Gq#xg0)BUkq3^`UM=d&!^5Qu8f>IO*~JF6 z;V<0lv5SgN#4&9LGtcJ{XIonr8%w$?L+@usO<9wa%rvFj+=o zWT64$RUk+E^2Nh|fBTuw*4!J9dDjDwKKq@ClGxkX?e2Bn6a1>r2l8wQlrfdF_{_Y? zeT6#=pcD|q-gTsYQgtA+xJ0Y*jMyI`EU!+H;=6vq$@9Q_)OL@)zz2%7+$SEa+k+eV z8{riGQ+b-7joQ%oO>louko4u@XnUMV6JL28;i@8YF2&JFCo0>t))JH`Z_<70eR_!1 zi&qN(OXUBX8rIX-L6yemwn@95>hFZb_?=NeHOA&y?7gl%A7Py`7R-B*h0S@g3P&o*E% zIkpB1Gq6D~U#<=1$shT&>T%pruhQ#V-T|Iweq?wVD6M15UUJ3S=?6>w#)`E@$%0KN zWuHqrnDLIK@j1nIJ1zYBr6ZY>!l;PZGpjn>pLA4P?LK>4R$lIV&@|iPx_ZYS)GSzR zHx0t~c=zvU>FJs0?#fV)wF(XhgfNn!7ViU(rEc`M#bQvQ6{+PgD|eLYR)(7Dm5#=z z^f#XzYy!uGmHts(hP*h&lIaE)dCVT?)i*ua8b%o4 zqYJT5E_{G8fMsqnF#t7s+p~#NYw(B@-+nT?q7n}{4_Kr7=7Y@*<<}9fJH3@g_-w~! z$d7As&dSUOm?GQ3LL!P-pwKfnx?j2qZkW|g z)jQanjcs~DBk40%Kn(9R|EQ@22d)rkhVvGxA$O-dcxsvgtVd^z!+}% zjogG1XO_X;^>0BpPR~^fZTz;r-B{0fwU6dU7wVHef6L}6U&4u27=R<*&Bps}f1tk> zunUzKB85Gf%pw*Z@3cb;^;?~n$jr+$Jn6FUrwii_W>QZ?u0F)CS`~!lYdKr1W2Zc^ zW~?(MVh*eCY?8^zbO;%gWsrVHFR{BnI_otW73flT=e}J%Uuy%ImhUZ|7+m0a6^g$l z2UV4qKbovN8s45M8r*vL%I`cr_oIwf`Npp`hKKprvjeB#cS9%`t_37gdWcXwMK~q2@EP@y|yy6qNa&pH}L`U56 zMD+uHRCE~?70A*?G~i}Y;P%H#=eVM-_Vz0zzDG+b^Q)R$RaH&yn<#%&o@GzfW2xFk zv2^FHAR@`R8&?&-9o}wfzWt}rGM^Y^xy7Uh+OLUVBmAC+_d>rtr|K4Q>e8R6`Qh|Y z%is>DvMs;yjh?NkHvb$NLvGxV`WG%PnqN%J%@>aMK%G=kUao3K1_|7)F(v46*>$;ld{ghQ)E7K55V>p8DdnFh#Rr&D+2I_iwp{GA{ua zvbB!}MO7s7&zZZyy)TVz%zN3Ii@BLq26#e))WV~3M_+b7;g4!ZF&w2D<>~FssaaWB zc7ho_7QIW(c|*dYq7iE2uO*y*&oOCkbtBHJJkrBBe;j!h-n^Wc`$T1=Z^^kpLve(E zh8}Lw@s(Yij-c&yTiGuq_a&yH>%=q0r03co9laNDu|0e;GC~eh??3qSeNq`&)EBe) z^!@?NDrc>6&&$`*F}BilY-Xm;{(1Aq8|6Bsl_y$1*92sTc+(84hnzAS8bJLH$3GqY zh4D{lHksR)Z5!My+Xapy23Nn<06Y+p%Z-9Bo#Mt@>Q}5ql*=TJ8Jk=o$3RKALZnA4 zYg-2A#V*3LXU^WSlAy*UCMM=#5#2cN>+9=WZKuu(n|;T}qR5ws zH)0i#>v!{bVCM*3M5`_c8*lGvr}UoWtSoBd_+<2w>Arlnbvo;<^{n45)jqvZ9u8$c z1n^-t-yG%Is;cOwZs!_T?!;(f+=6IVh9$-vF)zvtrXRuoBzQ;E8I(h>TT;J|l6KB2N9|bGnt%cB%$a*HJfLiUVt5WYG&Q z(N;dggNV30npVsuteq4g6gxt$YeDKt`uFc~Rz$W#;YCGcq?B?PIt32KiQ>DnC6 zU`=jl?mnS1B-inm3D@SZDSH?z`joQ$`^phOFKHh!e>fEGe{a?A%5eigL=PEQ_q>GY zrhig_Kww2hLo43xGeqKjxJ74F#wuP;wYYzP3{%Y_^geNP$bFp#u$`|_86VS*jSPK+ z1~v$8u#~fAQh}h9YMFp|oa*{clFjvVFNJJZ22NVPo$$S8rKZOzxvkcY{LAv zm^id``kF$IDb^$y2i%(qK9KoSW3lZ$AbkrM=P$S#Y#1B4w&46}_S5E=nAf*7-s##w zhG;S8?$*F7AaK;!DBZv__kC2cSxS|!S=g8P%hJnf8vU)R@;%6BzS^Y^)dl&Ylfgq9qgT^jSVM`&c z=$;w!JCQY~mdC$Q+Suf6AfiB8lL!SZ?p0B;5b{;>rT8F#HL#5cx4f-U#vktNGY1Ld zSHkqaY#3n|fSH4q|Sb7piP#6%t&=}B7EceBvx!@NXk!Fy2|ZyqU~P#*ssEr zmxbRpBX4Q`QR@n2(|RaDno-z`*9zZ1jJ}18YP^49y#|x;J3R#1U(fTs+s!l7c4V)S zyh9EFZQqYRX{@@D@04A80BioWkP^Fb&;O*Zs`*sQPL(yqyLZ#iNPG}=PA5iu>Ki71 z4J6IyAR%<2KVBpi@*Hn)yTELAVI1ybvFhd8;|@$uU%Q;tIjzP&mASwo9z-n1>>aLe zO^rQwY+<;G}Gs0Fn523(c|JQ#Y{7&!f>21H$&*cQ2ZTl z?L?N6<@(_HKe73n!j<8-r33g^ums3WWQo`52Cva9(TxAalA6C4o8RH!`S=C1B0@0} z@j>h1O(rcalo&Fv$-?q}1FZ z-jBUq#}#)0D!vf1jbG(c8IGL9L*&SR2+v_+wR+FZmI4hnhPv!rgW3clcXwo)jx0r@4fB&pzJ<4AdlCV^3hUFyb+3pyr2=78VtsKs#s1ZKpWU#pyqQ+i)9n2^kDb1kuqlru;dL&O;ilQcReno-tX_t9{_3cOtm)&R1y8JKD|<7Y;V2Jo^xxEWt*V zIi7rlG4sfEl^(dy;g)Ia8w>%*#~T5wc{T`+6a;;)?cRjVSv_Av*ee^h18nyu$xw|o zf_O0cIZ~NN zjrG7!v9bQ*V{k?w6_rZ9$aekFg^3@l&J$%ubhuq3K~SA&b5|{)SWA-Dj74pru)JKG zzR}xVQ=BJn9zHcTMxlWZwO9%#0F1Gst$sKgzHCK6v%MIJi#X{cQ5(#)z?bycdMqv> z47nvU?4RfB3?Y10v_k2rD%3>+Ox`kY(=S(AOs1BWRuSzyVC{RxjG)+`$w;6zX8Y!- zDy{`R>EP2#Si2s?=gp+moY$M-c)q)srth*jBjNW6l$2W{x$BVgnQko0OXW%GE%imq z#oaRJum122s*rPw(Bg2hkJ19?p0f;o<-h0K#tP{X>a#)R>%!1tzGOdj$QSmd{>FXH zeYrJkK6wJEaty}uG>{XF3ft_~DxDVbyk6Mxh4~o5uL>0*5G643GSY^z#9Z0Mg?w?) zV9L=++XYuADfc%e(5v7#faVs^t+0zwg%v?#{hMp5I33UNl^4f(B?_%MM$G*|q$jwVtzVtY0h&<%`FaOG8c6CYG+W}qtUsGzbm#W=M0*h#=a3B~z_jgg>zFZql^#F!R1Ih+q(GaPsmew;*oHS%STq`XcKK%&Ri{r{ zF@*4>IWG^GSJ}MyWNRh}^>7Qtfyc=R%`+EKkZH(d6Z~cYy_?-J@JwBW@4j1XgVz!S zueDMzobW%n0FP&rQ!qccMERh>gZP`n^YW1NX?LK#YIWnf!QfxL1nu zPp3M?buj(cxm)J*FD?~A>KTL)3wQ1Bd*zvSxtJd6(f)0-xkLtoEVVgG>FXY(1USk4 zaklD4n_Ph;dp)50LAxWRDX2{WBj7F_?D52&K&|zDi7^-%_T#UunkMK@8bKfW(x)F*Q*;hGDK+g|X41KO<(o7P-%G^gIh%*Xln9+cFpmzGTX3ee2?fCLL10`A| zH@Lcf3HqU@jgjQfi)er#Vc+e?%``I_wMjFqu0Wq(Tyzm2wmN?$*w#u^*)T)86Hum9 zu&QVFQhG$fR&Sa!)fns}jF!H-jL$0AAW8qZ)OTq7fR(bDp?>SOyBSuv&_Ko_!n>{l_ zw+Zp-(i_xYdDncDDQ&Nzq)?ZsSH=;z68epe@H3+&v*I{ z<)!carQ^ZLgnY~^ze0V%{^~J&O~`5Ttt6-!0-xY4;$mtlYZp=saR-FkG;9>@0&O7n zfiTMqn=OU@Zp>4NJo8m#$+-|XD=4tMdYYz^O=FV!>XJA!(8FEbj-vu`Hokgta8)wV zn5Dk*f^^_ItR-)R0D9m-d;3i=5EuB)IVGwKk0FWgyqi2b=lK?*HXT3QMSLJ$b7tE-!moa{3TE?u~#w|555pT>%1 zPk`HKJru}L)lVh}30(G6hx4GekD3>R(+j6teNUdx9_!SMbHMQ@Cnvd#n_mcK%&P_7 z1lbqNLsdP|eb!fqu%n@&p{uJ4fHoQ!w+C*`bKo8088L3;WMtxlBW~0D{T{caC_+n0 z2KxI2D5F^;9w7Y6Se2^u7ArrswOyPZ?Ia+GQA9xATM-p&{#!Tv=NdPrrly96HCl`> zCNQmqYsXVlhQ!xE4PHHi`-f z9c0X&GW&6=T!FNheY5qXqNJqDj7Q_=nU`;|9wYti!NLB%-6S(TilVK0)V8Zzrt`+_ z=jCMnV|Iet+Izk^VZ8TR{)nE`wRo(j`@Y%&fV5c5&SFo(VFUMT$OqEr0!#F_w3O{x zq-=GhroLBQ#)fa+=R_rHiKER+kU(KBMXV4Hmwi`JVq3E+Ht=DsA^!7gn(3_xg1lGDpUAv65Qi2!3*)$>nO;IZ4T7Vd;DD%%IgtFr%vUs71S;MZ0l
Md2#QV12}HbF|XtybrFNP3dYU(K$k3~uJp#q$w@>Bf8f?Hp&73eG#BD*R}dL= zJ;}Sx6I1q28LEoOQ8FKxWemLAvzTu;C>6B3FZu2N8(%`Fgn$3O^ta+=i(Pu5ezDe5 z@mq3`S7l>DJ4@!wPEKZUEtVujFe)Zn_Eh&hj4vqx4rD`O>nUklU@mL+G7pNd;|G6q zSgy|6u=IEd+miD=DPbseQ78@x!5#e$k1X`n<0A|Tv(V=pObKtH>?6&2g(F40MWg;O z$)G%$1Fa4pEv+rIKWGvsxqe$}tTaaK)|Icj&Q!~vyyE&T44V|y69<=Xb$nlPk%3=( z$aM2~LH%G`uKPgE@Y(`Y=q2`A@V2gnKAJrcr^gQrnDvUIiPS}^2xcr* zmaTb}>!2-ou_fWeHFDihAZ5E7YRa5oBS@JRB_$KZqdjtH7HZnJxG1FnxGlfj{;`_< z`u$<~q+IGP=PtptFDy<2=<-G{D?JJ{&v;d97OLOAc||23&!`yhs;UW>)lQoCDdtBS z=;;x2g$zjp-C;}Wu>k8Vv5_ieQgnvP`bZLxjMrriE+>%Za8V~DS&HLy^Y?djq?g!+ zR;;BDa9@~Afe03-QD{RM`oXqjnKzd;qVuD9w~)!532$l0)>^ly$)A_BWzSKe+bvOwReR7Xg7rV)42oeXvuVz%Nrk7WTU&EQ*Dllqh z6GX&W>Z`-)osEPVdg<{3r9TiOK>Gp9ua0rc=(qBT2s?b_A5JeP^Ca~HzAvb-9+$|P z%D`)VkZkak!@BK~60*oHVam0=#zGrx^lPWPEd!3 zKmn(74ES=25V$%;D8M1Q38lu^|8ZR9HgD&)t2HpCkTZn`n|^rq#d%4|M`?tAaEAk( zJCabz;Kx&W^mk8GO$Xx!!W2X}3Xw9QK$)&T8+l&Mh$|I`UZRW+J(T8tc)1fZZuevX zz}n8;_n7gRwYA5{~t&HlSwi6jjat$#d!MM_oKG5Bnf&So;@ax zAp!Y{#zVX-lXaH*uc=uGpHz<0=Yn{OuFho@eS~X2`BZY(7eV+$62mNV!I#j(SV4~( zYi|#<)R&i+cPT6`u_gX|nmiarO-+3lKLj*#7WcTJtXY9=aHpO28C*7=i7heky`}!I z-@oZd8Y*5+*11H5-6kSB`g_P4F>krubJer~7tuw5wyJ5YP>%m;C%C-4?9z}~Xw$kp z8MAOwPK%enAR@rcd1;7VEi>D`+S-8qx9l0SaK4?=Mi@AEc?HZ$3dJ6O}~Q_6NSq8Ql-ub4XFMnQmq z#zVjk#G^2e;5aEyw$yLktT!lUjX2B^AC6B;A#AYFsC$b%8E1{~nDfjQLULl(+_bd= zbs~BGe4wX-GWNdrh8y8yKMRd3Q_z;$+BFTCv$jd(WOeSZJ&=|Zq3h$QAa4EJsP&$p zeU>}#7!}1WR}c5q(hHZIJqLG0us6A-FLxXCMZKi7wFOj5F>6sgvg*048rs^d*AlR( zg=cup!ng_RfIVb0(c6pP_ITv8kEA~!tA>Px7;?J5diANLg&Kh?2W2E|UG9DjK1bVt zA-b`#0Z5`A99X&*;jwu{@!Hfq93u20PFpvrxt*V1tJcF1(~oOj%n84RDr37zOm~Tc zed8E!Ug+akU7r=;$Gg&M`66#$U!6XM{R+dW+0V) z_i6XR<%)~Rte;oQCq^c4v_3K2w%Zo=OO1N+I{?X`sKI;0uc|pZ;NBAO4zgmet^@UW z#-5$##jI2hQ*tJq-knd2(Wilj^NSsexLB#?<7^(XP`WnKkX_qh)on`?Ldb_1%Q2HW z68Ex$&d{pxsD}gAJlg_G8UnW?M}9>zI`F8Da7THyJjh96Wb;Hmp^yL~&DVmx~*pO4c`@?i=! z1CVtEWZzMD|EXd`I}=|cARy?W&6jEJdgSzue8F1G7tv1c9?FoOt)gr(6&em11=($Rasd%W}y=&xjEZfkKBoD`z@Az3$Z}k zXI0a0wX-vbh|Oiq8AMl?y#(5!#GJqe#|PBJ@RVQ@Dd75xcL29m42?z$InI;`*_&xl zgw`6^`$N|(H{pyXCFvb?57w|9UU4}Ybu*=sinVf`NG@YnBi-bsygV;k# zvd!GdSt7F3cM#0TUdELoZZqkxJ|7vpNSFQQ-nx^uSng|T0Tl1+056Qs#KB<$B%5C6 zry?Z2XXWl5v{>4ynVEBxQ0s3`;{uKFT-E^*$nWkF_W`H)X>y-OL zMGbhXQZEwt6qbrmbx2_v|7~obx}_+vNpD;;je)-#w-Y@7HOX@-`iDxb_OSX;U}1rq z@F;O;Q8fiF`x~QKe_NM=6YzQ;d+|hQ?YT*q=<5LUSYw@+YF(kAj@@^vL@rSv?jvas zOsxStWY=)~&kot5!kq{hE>ooVyJ=OVG(lh@(A-Y8MCoO!Me(fWA6{AYIH+CJpSgp` z>dt0V9Jfopz?&KHHe^Dvk|c9`tx)0yxSA*aOV)yS)!C2m9~>OyE$sP=??-gelR(9d zI3n!M^aoQ4rFgjRn|>=kyg;v(jT1kLP;oZCG?nHeLK3W7a0LBZ)8P15QI|R|#UA!_ zCd$v<{h(iH_NSY#jSX80df8c@etyzIEQXZk2lfnC%$dsC$?09pOQ~+BT-N!J_nRk9 zZLBmLKlzPx7C()yalQ=2vRB>Yybj#T>Zt9JOn!-NW{CL5!|6pMjB25g4p#Y!)YS@{A%TUJW7UaEGY)NL0}s+l5kY4PB)`i6$$d|O^c zYoa-{z1V=C{L!pt>N2Sud^(UDtW=S+j{j+UlwOGCK}fD^swY~kCU>65dc%=@6bn)- zjT>tt-A6^=4_P0uG@pR(O&8#KeXItC_NqBQD=fXA8ElxVQSAMM-x%FA3S?hBcfo=| z+>T*N7$fsN(T#qwr-v3d0(N_ss@wmDutoq1Ky|!%lqK&yzgG@Ubg71_gDfMgC5^7D z8o4BLP;$1Kgr?lJE!(KoDeWQ}n+x3_>>$3*5FW-g{o|Ie3F7(y1ZJ#ut;k%*mTAD5 z2HJ5%^$G4!SIW3jJ%90*1i%H4y|BeRiLB>`1|G8N!MxbO!!U+C-2|23(wsv-4Nr_i>cWihV&###T z5#sd1p6bkgE0+c;8evzX6h~3~1qim>^}^1}0`HRh(U6migM&Y#pPR5|+%A`X(QWc8 ze&^AVr+)I$l$NZz$8mO@70D%)d-d)$oXXR7?!}OFMn#|QTGPH1y8XY`gUfZ4lP&3o z`5#5(E~d-=$2;l*n@BM8AV#gL!>KpJ$f(Iff=Fc5L9B3RGSt(Xi&mjrj12%sI8Fkx zEMZoJTsQJqx5XVn0Ut|Zn=XhzsL9ls^O=P@?A{4kCp8w`klNW^LW8nJ@{UdVpHdPf z*}IiNBmkIr>;<@79o%-44*Zm-8v#)~=;}Yq%R#gzouZ-o@)E}PWJzcOqTbSJYj;un z_J9(Cb)d+kdh=nuW3TH*|ME-@&^?u+pGSx~-I2TH3o>V8Q;G;x85xT)!O0o2=VCn* zEgJ+iho=pulUO|EYEJR>N}N21Y%r{xO4<8%qn+C@C4UdB_11$+S&vm(!|%+wcoEbw!jm) z#Q~j_wgm{ZzV9w`n6clvcp_sLcjM+2FIU%mYAP+S$)wMVC#Ia3>?R5ZDlx6#vv28M z0s41B>1Jo5QbL<~B68P9wf!A7Itz+E_665h!Wf%hZAbkU%C0^|1QcRW9MvVh7PG*O@*rkzVr_Dd$i5oevhYYH{LVpH zw?!KEQo>yfuY1&EStD{;<1IZuJ)t|Dc`J_eoZnv1DGiYv#!@aK_yBAfuKZOv!UKPM z!NPwPceQcAdWkinokDpaTCsv7xC(&yk4uhP2Pqb^K-R7ppNL*+oDIV$f~|~EQ;E*~ z_>4O*Vfqs|L04HB^sZz3CNQ?ygB*mvBm#j1?C@Fx;%hrQJ55bZ_ZSlTEfd^XRYbe3 zrm~kCDozfu3qU@uuAi}|B9Qi$RDOKH!`_JGrq{_x($;KQ@joSdAD3_jHn{(dN$PSUi0c@LuL?l6D39tSTfkd`$C z9aRNvbM~Mnt?x3Ua7+wc zjU10!-|=Xvf}k+2!c5qqQQWy!x0v2WFyB&EQu1fVQ+0$woik%ZAUX_G#&2k;O5dFE zU4^MotBwS|UuwuMVTH?vn!aefjf^udZ(9*hQyUqLd_z03Vx zP5=DYJJBzadcrp#x< zoGAyrr}wNq4xo>;Ev`n^QL7Vcy_MYxk;Nsw2T#{X{LkzJ(G&@(`NiqEtkuJwOOjF7 zFGUc~D60+XBL3)Z5SycT!mDQf^v10@;q!T<^F{5Vpm2 z&H4^}^^=VTBV#th7LS06wM?b{I5=aCFg%FL__@>4yx=^tCvJqf$CDdIbU*tGGRoH)3eW3uj%qQ*#_wyf{bwk2oEg6?%GS~PELkA*!;m~|X; z3f;D9BXxIp4nQDFN~DPS*9$j~t{OHFEeE*MK!RwNmK>zuDf}352TO_l!U?j__Go60 zYuU+xiC=hRyY~*&;g&VywzYq~ANUt@;{|eqK-dhIgCM_EU>k7R?B$fhUz6oz2}?eb zvpgtazY=A#VK%n!4Hcy}6IfjJk-84r-4=(+Yc^O#I)qT?6s_b<* z>H=va=*>6?JEo_nb?ZxLh%s)yv+h*#+M`w@w*$W(_$VfaDVPz8p`*xWe1U_8(yZ3? zMsSjeM6o)t{|_*QLK}cUN)ZEWOmze99|RRCK=BUFRG2%iRzG7Uu1enY&PG{ zt_t5)6EL;1F%*D2wF76$OTi2&;K_B2#fooc$;NwdvttsEQV(boN)x+Nt_ zGNu$(HTv`qt!nO1P7dZEVv)B{(v4nwf1&eDbz<*=eR7d7ttBxF^w-Z5Z0g&NK+?_777UOQwcC1F&3Me?i zH4o0dzyVgQ^-xjWg7RML`I`gJZ5Tion+FnN91GApQFjDr%%j3Q=)Q|Z$74GAq>l_U z0Jve>u2ZUAd;3i1rGo>fzFGT_`AToMNLrEjpo@)H(> z0l8TCBX!^4-TTSfl^E3#Lj!}}e5rz4s3Q@=%rJ7RA z9-@Q}ojbnP>FOlcL#K$vAGTL%hJm)GWEvFccfcVC;3`suufl9xTwQ;@;3wGfH-Yccckbv%moQT zZEY=U1UNx^KNI&23;*KB-DLS>_qj}@uQqfwA_;seo3m2 z@)knrpszAwRntRp0vu6io6>P=A>fbvDqZ@$Lc2~)!vY$P8kLw1?q=VU{fh&P|DMHW z!LnzC+vnyli^8`ncfgUVpSHEY3Xw0qeERfNOdJS}jGX)kwB9Zm*}%*Jx-vb%n-*14 z67`}=YdB26;Jnq16}=7IIzSh@+HOR3td&qv=fmQx0Gt8jaXvkJHmwF0w))FTGDnED z_k}?NcfI52p?Hd&;PXn%kXOlZ0JOKA&ENZ7)(zuxz8sB{)lb2Ew8JuCl3WD z06}LE94=wY`AlT)p6g9{IlljnkpB+oYeL<@h+NPe1e9)#Vl4@A5Zo%(T0OARBcG)| z%z4gCO=WVRduV_11IPjUATKEBs-%;gwl@8QPs0;{)$gOC?}H>W$9I3c#(Hp`rF|?5 zuN^d908R(ax@_Op_$LK8-Yy;0`Lk9fCj2`$p`TN^4rqS3N8C{_&`^gn;RSNF9tO7IsqpgP zu?xR;Os5zk zZYkivOzPZjOVhVsAqOqyAkCmSM^EnkEJtSI*U31rRHh=o!tRdXR4#Bbp6}mJ+NifT zfgU^sJ|@-m5?h#q7hR{LCL-Oox4?nHtTgIr7r9mNz?aLO6N6(liJ-|(4F0ZN4^{?C z^_&iT1x%NS)J$Ijrh*GGFRutI|JOb1YjiZsfKkK<7=B>p7QaICRzg6Y$-kgcjS-E> T)*PUKflE>LsZ52mN#OqghXEdX literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png new file mode 100644 index 0000000000000000000000000000000000000000..a04727eb5b718ffb3e7f6c0ae3807a0726a26596 GIT binary patch literal 28711 zcmb?@WkXbL7cK^hAYIZ(H%NDflytW=NOvpUT|;+@G)N0bch>+S4BbfAxq04m{=wNF zbY|GI?^=1SYfYHqCn;n^d_*`nIArOM;>vJv&o$xTo-H9f2cM+&I~jui-q?TCa)N`y z2CuO(p4Hp7tir*O!byvZsJiR#FWY?4S@2-K2}u-Jj+cNWn_eeH^M|t;^Kj)y@6kdB zM#5ORqNhHfp!{&bH$=-Z`e2!mh?jGN@vmDN5liC5?*R6fX>S~VVafY@!673;J<&`Z zF&p{|RDM^-q(uu@=#5zXo;MzJvoKj}-jugSsxpZ=Zoz4>S9qZKqVHntam|9f~ivK;{q z4qx|nB46s<6kGk?oFPS}_|r}VzBpadBrZp2PmhF;Qh?K$7@ANMTv@4}0o(}9ySKaG z@9T$6L|j5Im+v;{uGV{Db_gwohetljOdlN`X%H9=dA(B2((o1T zAA7zPU`LnqcXoX!g?Vq!(EQcw*SEK~*8%nqSb@t&a1W6ix5mC6P`?vGQiNwYkP{I| zC>XI@1h46*7*lu53p)pgiT6uos3Hh(jK58pM!_{UHrM^3Im>~=_3p}H$gM_@Z4AR7 z4NhC5Q#T_slQJ=E2^j^2SjacyJ6(q=oy&SJa@qQDZ6G)UcX7uFLRgngF{2I@FP5L~ z_3}@Le1}!Mm+#@e!lOvAp_e8NiZeY7ALj=%J}|sTcm{{a?Q>ISxXFYqY^7IfH^OVpi zj1aRo^Zv{JPq&%cgL7mG5H;#s~=&=6ZTJqX^?>C$Gv= zm>d7^tx8a@vbbUOf3MYZf3S!Cngm-7XO-XTP!fd%9T2O>e;S(6(m_+yJh`*86G+fN zcIdCqPgA#2h!9ILDyk1^ZpF2Ddc?VCRJVVjkrF{b0B1WP8yws;v_hwGc6OE(GJLq) za_{@t8SvWeV9{l7meHmbJgqp}*VEAO>mxXt`|B~k_PV+{A9{NvY%t`qL&?STrw^s7 zyY+MW>r0BPPxHuBUblC3b@lbt=k3X1tc(0_&>_OlBHLIhw%k$(aLtA+SKm;*?Tyxc zv_B8^@61^}GB7Zh(@^aN6LCFQgq?fd`wB5j7b*)qUXL}}!Sg*S;c~862nrGJ%{Nqj z90cbZZyS1g`Wqa^FJoB(FJ8R3zrQ~?IMA5MhllAy!5Df$MkY$0v)Q{>~(2Nw%F$7)|M1Z7$CY)p2!MV-w0z`lW6ln^W zmzgp@RaR68cwez3$?WXuj`K!nUqm?6%AdmrbascJ?#VWmcUQ`{w8O#uQqs^+(9js$ z-DQ2mLk!wI9#_}-CQOQkV6TsJyV=hovh@rj!#gAB?$NWq>+sOlC+^#7a`S(?m4l^C zh@nJ-wP-{+od_kloN20Ej!di^V{lejfu#A_*hizmIZH*qz3~?GDNTw-@skSaXyMyF zac6~`UtGA>BS|l3VJ^NoBg~aue8YC2`gdol7$%OLjioxbxJJ8xLd^eBr}*uv@2!nb zJ{{e`$V59QjCX9880e4lYgA$fyg(qd&b&TbqnUD4D&-_s*lLT_`t?ms*MB-+oKtr# z)S8?A9jDj$q1)lBr;ZII^xv$GowVKL+S*!ueZ96z_QG}g)WX8fiF?h$7Y;wsTuUrC zXF&tnz8X2I^a1xUPayxzEw{F-4T4QGX_Gtb=*ul`3bzh9`cebe1vzZ>kbl#qDnQ6) zEU5$>{_Z$?y4ctRg%S%g+`Gjr->MKj8BaZ`1j@XbnSZ^#MGS9)F3^?Cw|;nCuE-YR zn0O$`6i;0qE|ZfDt+%B4^BrAlm8%4Q6V@Odmk`e#Z$CT~mI|Rx(4rr;2jwc37{;U%$rNkwz)MJl zROWX}iRzjo%V#vbH$*I25$BfhWUP*x}VZ>w>7w7Ol(MokZV^Tu~XVIXvm6$7K{=liBuDrLG zetFm?720+nV*xGKMXZ55U3ebJR#~jPB^51Aowa)62c))@21EOp_GwAp zw&vE>pH=p^qnU1d@Be4@v9u8}l)St`OqFOb`=%-2wSuUO&u&|wFOAxgzW(>%iD4`g zGbI|01bd+Xi=fnm>VsBxXB5%Vj&!a^Cx;VTqRnh!wC8YGeN6BJG>9`;-_45UU&Cyu z>XAfgpY8GdZx{p=+WrEX@7-7?P`PI7Ii`-)j&25B1B1OIzekzYDCOr?PuABKTTWz= z4pHbd4)x5V(^FQY0Vv4DlAV*~Pp`|vOx;@lfU0U4;in_csWPlO8qdx3r|pj>5%T>b zEHq<{hzP|0PiH`(>DrBF^O}rsl!gI_=z9e#cWt8hv>nZ=|n-q)x5`wXjs zzIRs_Nk68&x$j1E$zH<-*4kl1CvQ7rprA@uSP5 z4R51$QLyBnFv1XE3SXlT{#oL(mD7o){jShxyUgpj(LZ`S%1-m-WE|AhlNXnKcK(TR zpm=$DcCE3jexgbsARyRG?ee?;Yis<1Lk8SmctcIiZwDH!t4>tkSUZY@0T|4bwHIr) zqjA;O%iTRS)b(gZPrDEDDrl4yPVq(DM{$GcuePgM9(xrAOiU{RuKVwpwKO&VV3~Mb z5+^PpuMH;Ad*|0hvmqk_2dFx;v9WP>V4JnZ>o{{G zqn*)AzTL85dc>6EIJzZjX;KUb%=chwIJ4A^t?^YY4w=jZ41d6e)v z-2B_A*fF-Hz<8|mP_9}F7sXRVfBQ-yTd<(i)BKjYuxO@AU(et{EI@V3MvE}9J(D|=H%$M~s; zP){$fu?(KG-k zJ5{U@BAR>tbh(_@U~HmA^zI4{PCvtzUv+o|;=G`q&(+k~-tnOrVIagE{_}?v9RzfO z4_E8(V`ma%aZl4H%nK7I!;iw4n4VUx)_NBv{&33tcsf9x&F{4Nw$Hw^_(usC{_5Vh zWAzdB@fh`{`M_a5RN_7D3p$xBp9-a?VDqacL$CQccP|w+_2Z`9!)6$D);q$d>uxfo zeIr&n?xTsfcZQuTVohl&tuLBmTu`;<{`FRNN_?W#@^?=V!e!+-xw_8g!W92jH8xg) zttK0UIeIg$%2BN!vl0*ig+RROfyZm1$1Q^gn1KxK!qSp8-Y;wp zZf^I#zu%C_6e=H9a<7Kc_9rJN2L}hI-I~1jN6Vr7{kdAf?`CQh%sI>bZ`jjorfxB7 ztQieVd3pK!;}D@l&3F|zCY4w%vs^6%K_Ip9aR~_tTVvT9=-@voCJ%#Z5e{ zs%WKO?EKJcNpm#G4e?uq6LxCxy>GrTXN6>BWx0-0D50U#MC--~(#72i68{EwAc9_x7AR2CiWrII*-zDI8{Ms*v*~timhX$(VW@cvp zB;YD!M&6OdH{}j|DA~}*W!7hR>W{|{Q5`0NxVkw)1s3(Ie6NQLMz_v@4JV81pP!%q z{re?4cD-!bCQ5++XqLc`%Io8$dAY@FCq{M4%d(>XQm9?E|5B*>rxXeu>j>M10uhxc`JMMPND|z|5WSQI8+1Y=q%-juR-wl*kwwKw7{5y&9^ZxQB zvNoH(9|Tb=HS^g+j!^4PEQ&k=F56>=^ZkX|%C?KN_U1T`E0R}m?6GHCV<5V72O)Oo z5B)Y?Ha4e&MGl{Q#-~FWZt*U+SjLzXcOuDWnHn1)Ac`Sy1Q5~zi4CSt5&q}6peV;3K6H^XCfk0kT& zb}LqRL_@M&Dsl#RDT74c`zS3Z_;n*QCdouaMtWb=X3uDR=}G0u_yhE1%ll?Z=w8JJ zyTyL(Ij*1FNL8iJfprZOlIEY`y^FyXpl0=XWMri6;bt!&Ai&#zE7z2&4ewj4OoKCI zWSp!F7bKlHyI~)c(*)p|w^Xd*TYSQS>W)O#P(b8-Pa+H`aD~}9}eXmU|tM2#B zh3H$jxVSDu{H{X0bwVe1sga5K1p3u+c-}3&0DmoX@6TFFo`3|pfJb2IAtw>1f4QRNSrDFp{ zb3yttQ|UXie$vlbrv`r-gtfV~bscH=M&N62Z|{}lnF|JO)W5VQN0?0YmR9Bo^-zi^ z!~5s;hUx@nnSPzXa9NG*GY+_ue!~fmPf5Nu!Eqh7^@@s2`A8#1dZn;f#;Ue@GutS5 z5~dJ)Px{)-EVuc$(Op1#xH^(5ndf>Gm+xspHcdKzSMF8YkxvX^w(87Z0SQK6VI3JkkCSA=jpk~+G|0NwXETe5@yjzZMJLi zrXotPu6%x9bJM4DP%d1R4XGYMjw)d{89J4;CvmRtSXA{#WlEhV6l=QwC;%f|l=hae zE5;aP_DV9>;lO39hU;NDWE|U!Qq=aZ&wi@mh3{vGkU$n_z>Y5(=*}a(alels=3Zi($AcD(h%Kdz*TJ0AHNGCVp4maYKKo z*u5-uE&RRbJ-$R{lN~7xp>DVXXzVn_H9JCA@~_u!39fK|$%$+fs78P}7$1+lqfLq$ zJar%OAZ4(|N^qT~ha^kZuvwY*a@Ez!w-z=*2yI5{Pk&gsWTnj}+r`P$L?v>n)zeO{ zA*%*NeaBZi;GK*0@hz$2ujTV8iTBQ{*j9G?^<9L~a?BbxZ<84=VLyhG-`LglVq+lT zj_A)f!a5G5XQ>$k9~sXS!iAh}@kPlEaDmj(1;N)S!gxlgb4;S@`@oM_Cu%s+5v2U$R z>Co1UAVF2#N!33p($D$sDw&eDFW?_Owp9TnCH_z||t<7q1B(5MA zmy|e2+ficR>e^^1%9&VPh`$Z5v&b{TsgjVS)NjsCB1%PnXyH56u7#gD)g?uzY`h#$ z)quE7q?wPjlngUOz9T1_CgivsecF+xYbjA}5Zsa6Z%eryLf@O7Hl!H%YK`K5mG&Gd z!6$nZ?|%9I@yu*9M*UpD>|w}lUhW~N1=`F1p@_&jqfrT!W|6btpO$?`6l@A2bT$&= zSSwp2|Jm9Q(mh3)hz{KpD|ORwQ=qiV-^W<>^+UR~nU2W`8%W!7cnxFEx(ucy;C-bSlkAny^bjxnTY{K*UmLd z@p79}1GcEBsAtA$3dQXSr$HaGKe<|3S;;ia5zDylK%1O4bDkF+#(U~4OS*=ol%w`Y ziBTPGOiw3zM_mguPiG?)+_A(jjf8Yy)Frtt*1ruhB}>!lk1>0Q7%w^LjhB3h$fZ@n z=?i>+>UFVi=;^&uh}?0b67O`*ZOLHdFaKq!J#{{Gc{#b`xt`OZ!7Wj>%}YlUlfVwS zsi`UNZfH?fQlXvfl*(Ctb$?d6fcl0ZeoWuBb%q>Oy&pUXQN({QF!ZS(z*TI15X!`_ zK807Y{>(J7%O=yk#&VR3|BaB^Y74);Q^SFb?7Z(KtZ=MwtmyndrYe&U=d?084yX=3s4GIazb8vwD-< z-90%=K6NqnsVn|cvE{EJKk-)I&sTg7b&$=X8u?n=rM*lIar+4V9 z5LcgP!aP4C6EfHT{pDoh8x=b5cYqcY{So^xw7Z~d!L+u{if$QH3Q6()y6J>gS8u#2 zy;`&WJi^Y2Cha{DN(ePIbuqY#iZ;|fPB5I9Woc>nk(DetHBspx)-p{KCnPqK5u)fk zc*jvyANgLk@Qcx=1VkPQvalR4T31TrIse<9P^6g_&J-DxIKa(!35grJ;QXwlnMInh z=&NU0BBmx=;*$d2`~L>`H5u32T<+ zmaM6PBxrqoeYaGcW5vXn@j0H|nE4K&Ot(8fQ$_uv@ud0*V+R2UnMYLSl(DjSoHnV2 zuEW$1q~#>Z;@tUtuTM>*yA4^~cc)7q9v*`Ewo@c+km~o*K~&Y9^cR5a1V3scH4GH3 zM}-b@U%G~rNj9EUhU2j?HF;a5q+1S;4ZUYpgCa<)3wi!MapxzFk<6d4P$hl@`q2%} zXw>86Z;v=x+(!zTC7ah^su?D_)jQ>3U29b^R9rG%5bN&0pYyJv1BuV)>VX020}TLy zwYs1DZE^zG6<^=llTb?pbsL?dzvO~oOkAIB)f*&iAWh!dAB^bY}lvBe7qg1}9oPqN9Yj+=K=@1W&SKCKJ#oZ1?GB0shf zF~5NfB*hTBpM$U+NkRYet>=s<`AyJB!ZYR1!o>26$s+}F6c}J7R+>}^(w}5{k(LRF zh>~8<5sSy4-d8k==POx0BPJrs%*cooCj(jsj$-k}De_Q25|%$$?j~xEJO3#8_H`K+ zzOTu-5wk%%bZW}!;qIE*dkqN)DG>pI^(^t&qUv>+k}t$(kso zV}e3kav>BdDyqB*8eAP+#j+1tiN`oDxxaIhLr>hj-Q6{xTY7uzj&wxeGNYiPme;Re zUH!a1rIa7ZIxbeo-n5jEzOEoG(BF9O?C5xUbG`>wr66!V4Rjs1{Wu83-(04a?jRc! zJdlbG%8?0HU{_ZPC4Jerk6%gm`;c9;kVh!fiHgU(LK5ZYC`ZYcO*B0^CpO=^j}&C` zp_`m!7-7fO&X2~F_)%rd8G9csEntYs3$0ZX6G}hsuIioc-R^H(4n_c|mf?3ACy}od z!VuZF-pcufJr?Nkzr}iMU97%o zQ3T~Q3<~CWUvIW_dy_tF!mjo*?7Mh8i3YV?auYp|Dpx*5ZzeDGr(>?}dSRf16k1Dn zl2A_Oi>K;HhC_@p8e}97kI3T({~+p@tN#$kijpimhUqC^Qs76)9HsZqnl@3iJq4Ff z;Xh?ws@joCoa&|lh_1kf0cTxXTMG>c#`nv~{088(F-iM$zWPv`4;&^9?(@2{4>XkTVy+|Hw{;ecah z%_vl*HkHi(?h}irEg@Z#^X+Bm2 zA!?NWYBnqnWsvS{`{-EF`)$1(chu0P%8;YtsXIv9xIW@1Y|hiZM>0k2UaRu({bXUM z%8n0nih?HY9v4+lJY7nMRQXIB#OyV{jUMY?O#%StDILOP(&cvAjJ&A_k@JAb>EE6R z$LH}W)&q17+^no*ZPEdqe?a0o%0~KbAL$i9^^*#sI- zDB296y$048HWdxJR zM9KZY<-uYku*(eUUOPE)IIm!-ja9gk|MY3lyh6>F(D#(}dOyGQY*Vm&==#G<9Cq=i zOuFktBbIr${rQlVmVnY}|MnlBDd3SVP+an>!$m9Ga|D0#&^<#4$*^C@8W{dZ_buIX z&ekHwHMXANoV_N>sebE@G@5Ws(hBLT=oHvE;|cYq`QXdlv_JOBAwHdd4!g zC^J9Rym^|_>IALf4>uUq5!hrTXSLjRoP75Pj z83Chqh@*FkUd=F%5=$~+KY5Ecn&nrbdi>_mpF@RCKUg?uXT+U-_v$zm;-L5r=uyCn zl)TMrWO&#Y)z-1~|nmJA;Y!~8*)31dNzA33roVe%Cqlm$UgolicahH%enbJC&d@@U$7`pS?DuU)i zR=Ya8P)H)7adPEi^mOT@n$gDBPVMIF#&B1EsbtecX18YCrw z9&XGsSfj`nt=VgOZbwE(gAisF24ikL_J3J0`)6QC=nOJO$mhC$3~Vhb3Chdot?Emf zzT^E}{Wxq$sD$tM9sXJlA()_&6#bLHCJi8ROZD$GJf5#MKE>H7Cn$KDV^qIs7mrD6 zdN-PCbocGiX*X;nV~K8=J-b<&d7(EqGXL}dLnwOLNKcK0wx{W!)&b`&8`bMe07!DI z)U~8DLkXL09hne=n$!iOcXlj^w}f@%i(Fr@Ok;+ak7n@rJ@Av{!wQNbZ~g@E&4q$; zqUT}L7O}v~2>>?@at-VK4PwRIxw^WVpMPh*rY@xXczk>mD0*AxRSKk9-KhWfsE+tG zBd^2Xmyd$6*$73!G>8P;2)QCnZ+SK|c+Y!z9s?nGUEd)YTEr(1*zI?YglM|%NxjLM z@%58!oiAZa!w04J&#UNfr%^blTBclv-=p-X0Pop_#C)7EC_OUfy~*Zi|G1;zH;A08 zjW);xtd7k7Nj!+I+Yi?4Q#I~4xz3P~2*le#t=+gUdf-(N9ea3|pigrh)<&`d$KyZ7 zFVlWXn&N2M4=tZjKv)L9K-9XMab`Poxw^J=SYu^k+fe=eV%SymwHY++{n}lZyj91z zozI@ml7=njGX6j@XRK9Sp5oFl6ID?6Qh%kYK^ZW_!(dO&_vT>uNKboq(t~UI;>RPX zAO9P%^F2#nz1#f#`!_(-uF`)&%!#pq#U_jU6XxhXkkY|VjCjxj!nLlh=jc2pM%Xv~ z{Usikv?UzA&0|7Jj}k`cA_&6juho-0bXl5s_L~=aDOU8NW~D6&BR+Is{#l9LaOc^k~HN6L*1)*VEGj6?7jTA5;=S zU48vzHEV17!C+W%QI0N$Vz+z|C_611?L(O6E-7gh(M4_cDcAIiHzHez}C ze#0_BWsRRWrFopEu;APDw+wl9FAQn<(%H;YDsG|rtGg|s#~xruD%Zga%2?aIfSO24~xlD>6^p;tPVf0E9MS~r@u1Syx$Cisq8ySb(XD!XFeK;(5K zxyoGUuXciUTlEc;UWX%e`5Tzh{VQ}nL#XH;$*rR0@sp-2(1omRsyNlki=aGeLiyXp zbPB_TkZhsrl=;0$gsHHH5-l3pX`!IS#-7vK*lDf~;^d0_U9-&jm|6!y}ds395$Jy218b1lblqlqC#@qFy?kIr|icJCG|g`d)V zTw%60qo6s@(X)-yl9D%9fz1+hmxl=U%dPT$eI7V00NHYE2*gUu>5gRqgcO zrBSKxa}7(G!Ste&mf2yjTJV{MQqp1yT{evkh>`($%$Y?p^YG9T(9+xyWVPZ_8p6VA zv|IJv%5+=t+^gt$x+HwgM?ulYUP&`V&kQY4T>P{aeXwgp1d2RFSMbm@Ol%IH5P#Ct zrpchrg1$WdO5>-u9LI(UO_uaZa+UllVMxmN`e-YKTuF{%fchjzUq67T7}W8>^@I?v zK3p_1>osFV^!z>fdE+T>g{n-8D0E&bb&!#a+;^fdGbUx;5}0hePs@H-zl0HyD?|jXA>1)Z9;W=G%DGgRc~!n2+nXsQpwc6F_#3`< zeCQGvZ5r=Sf0Bd<;>+w5F`RIv^a(82qsUn-TFRWnDjkCM4%qMCf%~=M-^HIl4wN(L zw_02V3!M$KF}Gj+jbLu4kyry6o=4IGFMeY-At^=}ILLHu96*4=M4t%eyw&y?C=~&w zC0@MM<7{)3;8P)SMPnYC$aeC=@FW_(bK`O?UtrQN)?W-Ub4e=GTa>wlRAhZdN&>PY z&TdRea@uF5rZ~;uSSgYhh^;v#;%l}5&SQam9Sk@~4H(-XCAMupaI7@X@&JYH7qtc>6(Bx0!oMowB8cMZbp^nGBurIYVu% zv~Oyq#$nzjvPwD`<=Vy!C@NU^a9Hjsl0R~a<)W>Qk0uP*mSpSAzf+~!LZR#$nN{ME z@ApHzE?RE6%xb>F?YPo{`RCS2Dsj0^+SBQo(Iws&(h>%uJjTM&mFWsGLjx1iZJ_qG zW3G=y(_h)ey7013Shuj326mpXg7uBAC9iP{3dd>XNmitU!Fj&gZ>sl}c}bC0Dg|lw zcbyRI0*K_Kk+=@i#^;c`;u{2Q$y3|(ihR*>{A+V@3XCTEwGP3v;r`k&K{1`P{{GnZ zn%4oh)n}Ab_@B;a)C-2>^rG@<2m{qNH@PRbhyC*Slzx!A2b68%nuXYL_#L94l2Jnd zEWqx#Xd1J;ZcjL<{R2f-(5D1`rX+%x-3q7dO|DszGdl;lc&bEhE6=WI5z}-#1{6vc z6=+6hf6j3GWr2YZC1fTtaXDGd>h{FqZs>~C75W#u=S~yT)uL1J(WVXYcR+j??@ABCTL4V`=h6T_g!4Wij@{k z01kuDb6Z>v)G4zO8P2D2XsN3=EF+;l-YMQ&j#JTR-}rIswb0eG>$6kXkRzj))=x~U z{1TXZm|<1SBcHwD@vm>4fS57-n8|&@Za^l}A*S`e8TLc(UcBI9c%)T_==F^IhYu3J zwk7UkQYDKE?GD0!Ny3X67Px>EjQKJAEm!o;V??bO=P$_jun$EeW&j5#xWx6+&#cxQ>{QWG*@qJ01InoTXj zB?(KK_0)%&!7JSHkM#73AE4tXS{RUy_dK2?Yah+Zlr%bEE%~EqXPkW~yxCp53?$fe zfKt4M=H}+6t~1O4$Lz>goMz&AM7_wQtQlJ(^SdL*h*J$uZLijQjBM*^b)MMSj}KFK_)dIlPbIqBg)zs`u!#zN3Ei<1RFt7WOzr7`Y)}d% zBqmPA<@oRc%@T9^zFC_fn#$p zCKPz2<;cD$?oQbNw2ivjyzw7|CX0WN`I54(5@*!*EEfD@g}z*WR!d07A+}IYmXeh3 zgriRZ8U84n8F7l`?X}SPDpCm9YI0w-_e()EP(hP*^W#yLB^%`2B~nu|7Gw+IuDf#^ z`F2yAeJ_`+xsuXgo~tD&6FGp#{m@Eb$l!PEfUqNL1HiAQCZ0vlDT*z38)dv03+c(l zf_B1%LJfV7pvOcts-b$mBZ06Gq z$Xj^p$_ixy^|fzFLU{&$-j6WwZJ<-=&LF=ON=yzN=26sQg|I7-3{GL+C0)aq{j@|s zPxt%@ubPl&{~@PV78jY=Qo<}QKwC0n;s^%_7%0XVh!47Gu1oe;mKFK_m&r%;EgRlf zi_)1JEaKu=42b2)iOI`a)`gz}&<2MNFTWu35T*qU*`&6Mu2KCO^k0GwyXll)On-?G zCxbrp8ucy#xVu(!gHM08`KBCC$%<@HltYmbGY)lXkqEYv;TO-!K|vvvbk57hoWCT? zblpm^wy{j_UKB;x!MU4Gb&JLkZYJ)#c#kxrI^kBP$00E=}%)XHf=QqpI#WMl%0R zQ+m@V#k4MRI=-81n6OQiqDMj1w{2n*cLvCuQvgWD&ik!x^Y5FpQ&SbixPZY}4hasf z6MqxZ-5RJ89tunj|NcMqMrn_i($CRRLOlE^229idE|fCdNp%TxCmQ71lWtF zj#-2V`K(~J<4R@Xv7Dl(6UfQQS**UcX}bQZ8+Af3ntphb|Ch4o_u2kf-ZnH8ZC}69X7B^<6+L);8Ymlk0P9VL{W@+}uzj zD&DBK??IOY2y?9GddTk)%FRJRN8smME%_CThd(Y44)Wq_2R>6U!!qK{s~lRt#cF;G z%PXT1;}RL2z1C`)pIV*Bsmo^Ymr&@hw=Zl6YyzsQKe*`P(_UjKF`=>x2pphA)v0Mn z_XG0Cf7njj?;}7$jN1I74j8EZFIIKJfDL^6+@rT61!E zB!e6ZB!j_GPiUvHj#F`|TO#bPYH=kxDvBrN79chJ{>K2A0m$Mmov&~Ui6q@h{Ho45 zhgCKyAadQVT()xw2r!b!gM=hT|0a(2Q4A2wSm#{(Vo2Ob0&NFH0C&p^MQoEq5UON8 zDy*TAQyvj2dV7IB@prjJ{2w61GGdj8TMu;$_yD!2`?5dlo1|k)Zt&S`VY`xugQ4*Q zDq6D80@SWsXyhumJ?MlRE{QY=4IR*OcHW9ctK~~qG*6oi+Yr#Ydoi{Rvs1!oDwzr@ zywxB&GOvb2>%aVk5&G63KWZK8d+Yd$QDD6BIJk4AOoGVz{mUl-IHl@CTP-MT+xgut ziT@i=@I4)du+_Bj&-Fy$X6CClBnDf%rEJQt}t680nY1}6JzdOa}60cAs>Xj3h8-^3D7I6T>!ZagJH{~Oa z5gj*4w~Xc$8CH$e(8v{Qta@z8`;;Qt`U8~bXhj080cYqr7Q1T*1}PT?duBj| z+T2{V=VqWrpJ5BVqqc#MS>97q7+_{%8k~7qzrudnYO#zRVW049MRit4MEo97eM~S$&BzqYCgP1FgBFxV4KiysIyRc^&si}4loX$=_XTw3EPoXZSy+dThj&eGCOSMV z^fefYN|lAVzJNhiZm?62PRJ!U)Rx4J89qC9Lxteu404wa=Fi_rvlB-?M_x70I(}SV zU&kAuA7!QeMPVrJ!6P70*=m`XWvy6`95CIps6NQ+^04>OvJj(U2TcQ=hEj0k__8jYU0-k3wDe!`}Z8Yyk(!FesgOSD8CKqjt|oI%Gcf+I6GYd^W{IERxz25 zfS1;o^oNnMsl-NJhNs)q2i+CxJ(?t$D*a4wRZ5m&L=*75$Q-6UV@dj3Y9fb1`%z|V zei5*OzK-&6PN%YaCG)Q1C@t=04PGWmeWW2`xPF`zrduj8P1fe{J#@-mM-HVSL`m1M z8y_X*r70s!oMs6)xnEUe8is6LtyM(JY3e>fHCnOjd{qT8iwaZWUJVv2y6@NnfV zjy%Ui34u-QXEl;m^e%g}(5#oAtLGI*raLMsw>ID!gG~~auxEE#(7#}k&ibxkU9km(FIpRJBx_z;*_-I>hJtL&Xrk+xf zq6jr=p`mxLU-4&PW>Qk+(Ok+6JTM>2nn}UK!Non7KrUfeO~qd{dVwH}Y&nB16}rG~ zC1rC#NJIp?P(GK-eQWsV+p+j>T)n^L%uROLiN5sEO!M18sk(%GLQ6A0lBm|eD#v?K zt-NRsXR+Pl8bTZ^FV`yKV2p;Ag%?~)(;c4M>2;X=d^Y*(s|``*kwST>z>w5RG zE2-$FiOT=VSw{;& zB#_Q!cdB(NA#$jImO`&2wjx(j|!->`)LA zF6aOP%+4fGK0o8YfzC9~&PdqUh>H^t)cI()+=Ms;{$SVbR_#8pkD$LuQGX-k9Deg& zdCA~S3X@*5^Ufqdpu+m)kfwh9`l_k{f~^>Vi_~FeUOv8b_TbA>u*UY&q)N1jC(bMC z>3OA}-s;CE{`Z-g9dNk7>*iIioB|rkNBuO=r$b}YKo>&R-jMy#0iO~6jR=AwYWV${ z^8N)3hPFgW!OrG%0~pZn(c8{vb-+OLfIVJUPsI~(RUPBA|Ku4+0Oud|?b{4~59L+c z7C<1+%8oR*kfp#tnd2wROVRfXvui!>LRy;J-cbHk1j;gxLmhV!?TP(sr7-*kOiWB$ zrZH6?Z%Qg2zU^bmiGP=uLyBm%YttrN-CrpW8iPC$zh*~tR6q6OM2o%U`%V`{xM#ZE z{DStOxuwN4mp3<3&t=;Yt&K;&>)T>VeI%gJ^SnaLnyq-VL#{H-^)0~O*SGyo+oxpQ%OlW4T{KjRxy) ze8~p=C)H0%VpMXY2fOk9pbHN?v=Bav=;y2B2v&Yn6qYYSz=0@P!K1A{uzLJ{O~kO ze1X=(=QF!Oo|03JLIb`{1n>#@=n$f!)MWpgUB@T8D8^cOk)xb0NyLfi3Nw6D{Ho); z!cH1dztw%BCY1g4RRE=Q=fc7QVj*en91R@%50D(3%pjg)BT9>ej1Ufr)UQp;dlm5- z>#{0DNXRfEP%y-Ce1afbOA$pcSv=)CiA)B4XM%iu zIv0X@PrX#^4WQR)y)UK%FrHn{beH65$bnreW&}B1^A0)rvJCkCwW1soiW-hue=vU8 zVyVctA|*JBS93q~YSZEQ2vM9yQsk%@BZQ)O^}FN|2Q|G~uqe{e{~1c-OOz-0gI3qC zRQBt=QK0)3kilEb#WiP(n>jiv0~)vgaIQAIGPv*Z)sxd=(*!n8d1tav zmPrbytU#&G5V844Cg0(Qx(=a%ji!M%Hc&u|S7&Euora2%i%-n(r8(T3=#=?(v-HdY zLkbL9ZvQSLnFcysX%3}wdO0IPFiGt8@5}Ypa~Jyyr4A)I%L%C@(GWK$i*ot zf=d0~RY_C=0Zv|WlQQ=+6=!XPT)jW2X2XZP56{hg-&E-;<$_&eHOVCNG-do!Rhjf; zUgDS*ejalkMA3tlzo)IF3DS%GyV16uBf|e1LTi8=M@F_2@PG2(hHV3?$0pGbM@{>+ zss~})lQJY!wc6|P6E|94I4f!+0)8PNW&D5#<>=$%D!t95D%px(r{Z?lPdzLH*g9Cr zvHoW7Ef!|!!j~z5W>4aFjz0ZKdVU5|0z1eGQJeEiTAk=I7{@h;bej62Ctx<;;9N&PLZC3yMSrV0lHrkm#DzZ)mZ`#b^=tHaodQlImgcRkUv?TdYjSDzn zP|ez#t1LHvDf>}`EG;c<5?3TDhwSCoWW_3%#Hg59**q1x;$>bcEVc37B0&r~i)& zFi-$PyZT7M%E?LPhr=IWL5&kpdhhTvg%*9`096$e^yX-XI;|>2rRlp$YsH$rbWCfw z!cN(JJ&OKZ7^%7?IzBl%nH)BQ3=Qr147xis@)L{o6Vhtx{$dQGfZnaTSOELf3#tH! z!g0|u$gr9mMji(!N1=MyCA4Lt9F=VFrvGiw2hfoLSPMR-U2E({|Al6|YEBVEv}4p* z^;sOQ=m_U8fK*oWci)@!dffB77h*a>`M*y%WY4{YV^CkosRO^(GlR7HL@wnKS?K@ zZL@k>@f(1;fJU?C-$2rLoyL52L1i;(#I_9SK+;-R4~zqcw(vV$*7dSp=a2y->?gB= z(bm%rJ2Frc$uG*0Sp`G16qDz`Qv22iKvPXP70e!cU>D38jz3SHBwwCghLcDJ&>uh( z>&ZbnSFuWI(7~P!WD7r+>VMB^DFI=cWdb|-AnS7oXtq9B_Np>OOG8De4+0`pRFmM! z`Qs5PMT$&S-Aya6GD6(Ap<6cqTxNmT%5jQFy7T1eW` zKrQ=IFr(wMaMJIL;ND;48PSKu!PN|}13KGPtvcl&N{2>Nga6x0dRA)f^@u|p4rdYi z*J0bBfGS-q^|0i3TdDnk9yeqkv?~U7Tm_PyE#&#Hq26i~VY&Hy zrM&XtXCR(bZo|`Vipt}*2!TAI?IyZJR=7V&^GsN;K`V)Z z4nk4@XwxMn`yVI-Do)AQeE@zm;aD$G>_(N(ae1=8#~*=Zi}>~VBr@Myr)!Mq`scG* z+X{pr(HkNMJo@q4H49{M^%s0DE?v>tsn*#H=GTm{P!E0X`EXOBRxit?nt ziJVQ5%Q^7!boGWFJIkQ+lr0<2Yqzxc)oUR`uA=e7T}(wCAop-&xQq$Opz{le?Cs!K zG)xnv1m!>RV5;mi;Tc!#4@IKG@>QgMI*;bM9Z4xkNzhzb<4a)6SN~Qh`6ETB1wclV zOS-rAc(4LG1%2WKhLYEUpMKTD{WqbyCRTgPa)5={=HAF!_m59;pz#wpLpb5uokQfC z=g&Y(`)HP)vyQ?1HW&cz)3ny?z8Rv6CBQ%o3aaQS%m1udmCxCn=W6_a+WPKzs{8QoQ+KzJlqeJuLS>V^Z<3J6 zxXIpIvUk~Anc0z@5e_=Wk*p9ZapHusj(tM*dakeg_dKuH^LieCoL+Rk>-v1I>v~`7 z{dKfdG#=gl?{4MJKm)wh_K-p{$Jl*tF0Sz$JT6edxXRGV^}u7wc%}#8yp1rUMtE)BlDq zy)VCD217>a9EP`q&Fnu^xVyRg>luGjKtvb+*t~G;!)&yanw_bszk6)M#!T6b)A#v~ z*Afu*G`*Y{J2dp?EF^ZlnEf2~7AA>=GTAd@$obdBm?xF*1TT0>|tL;%^VvI>yJW{kbFQJ^g(CZuP;mPmY>oZVV#a_rfLL>Y^!yk@FD{It_<# z+#a`tdsNyilV~gQOv%^9x)>i6oGvlM(KXHtwfieQ$~8^|EdE29SZj!l8kCy4Bqk}laUJU+uczTg;h>O3sIZ0KEkx&JN(=`w%| ziz+I4hSEVrOa;p|4vG8@R8yq(f5XDOeaOR`ncw#S0+MesE^%*ljs-UJLv^9)k{#vo z$|b3?7o2@a^Qhq3`eiCOcly1+z!vPstoiwQ7}ww}mz>WQ6c!F+C_g4%;Z{yfgQU?Z zQ#BLh{#jnDaG((zfkF%YpHEqTeu+wX#oQVS6dDbudE&0|rO=vsRMh8YfEI}s4P4}D zgbk>5#zN>4^&5i`y`baa(ItxG|0&j4_v`uNaGL^mDI9c?lf!*nW5dC?^%p%WD{C$J z)c^do_U%Jw*6D>y$T1%`F0!4{7sw#_@6?b#ZggzqyzS=MA;J|3GXdurghW>;Srx>hz^64mEQ&{Bak64-cAlAqMSh;|NlHX^ z3JP!&Q25%_yh5k&UG?}+FLw$;k>&O1nJE(z*eIT9dQJDh_!g|s)2t^Wnm049{azr4 zlrQRAYDr0npL8W}Xp|g4HP9MK$ui#RNh~X;Ag{W!wT(@LN+(D+zAKok?3lfPiu^vk zel-kn%0)!I?fEPO+)vzRVcGt_pMXVC5fMMsh4fFRvaTG12$aId(o2Z_&iXyViW)iw?=oo`Oq1AhBU|G?=?h4x)k1 zqd$sqUOz)he=?I>JB9r#dmTAGB7)B?*AfXpUSZ!cbdb&j0SGoJavJlAcebd>z~dai zs+RL=Qk*>t5Ir4P)TM8^|5W(&FcTIKFq?i4LH?NMs_Y!>>|VQ{gGNV3m&NOBE?!Hh zymowrC^12#Uwiq^=c2(k&=XdOMW4@}@^x^aXw{=e7IpG_0kc@ellSzJ!or1>PfKMh zA?CF0xMVsSBEYW7Klm8g6*D0>tS%$o_Z4aGXK8;bAyLqer;nhiI+FAJocyAVxg2aV z6iWu?4h#l;lfmQtpUKuYv}=k>Rbw!@yrDjT@ldZGi#m+hlTbgeJ1K;0pcfVbCI18T z9|WwdtFkk97`(1UczZZywqDEzs1!d3`ki~0raY;GwA!-n*?*(bAA#*^6bczb=UtxG zn<_OqFPvz=Q(yH=+61L$@8ctWId(ziR>$Tn_Yd-ciBaOfiw3mbMx{}Kr@(b%WiVl)Cf>z@T4v-EUfML zjX2bmm-kJrQczOPuJ5>s_XS?iP*PIjNnPJNaCCH>cT0D!tgPHSI1E00PG9=Wx4#gl zx)=JYYs%Ky+1LPK)`F&?F5-Bz@6z|Gii!$Y54iK*88|n4;_A4p68^2#HF0;C|Ud6<%z>($dv;>4*@T+ zQeL)%Z_bDS?yCL${n63OR4&wnZtk7WMycfpGN0p5rG=oErx9~gSC6)V0t+wEc-2avWM)S8QHJvyPtK7~ zO_f%;JyWX|HF}k}i~+&{BO~LRH)(FWt-GBKI0@0mzaQo-1j6NvA^CjZ^nevHO5)yY z7L77*(b|HVU0|~($1qRZdgjP)_ z^8?R-E&BK_S4aepkk}!iL%EZc6+12I4Zua?4(kg zTlQgtsu?*eJ=%MA*zB1g_zmC2u>%qd&&eRw+CeBdV2yCY!{QPLi@hqRH#d39xSSmv zK5_prRxbcPf=Fhhf>qDgaar~u@El$7UO2lVE$#MWaYNdmDUdKWzp}EDjQm`5SE=~@ z<0n>dad9yr>zS;HlarHrVBjO?$G=+FmK>^kabM8W-P|jS~4T!&6_t;jX?_DYoA}R zD*ch5sSZ2}@c)wHC*6WZx2HACuNDrAF!2MS{@cKvk&b*pZ zEk6eBGwVCCs&&0N69$HcdV1X!0+_y~(S_3bzAJBA(i8SlG;L`N|NR$+jy@9Bp}piy zr>y5z&#sT1(``Bm9xg72#w%L1h>*2F6P=x%ANfA=^xa!nSb$dJo5^XqIt*a{e;U#PqGQ$N8Gmp@>8a|y0kLYz%Hk+58p}Jx$7Drqi4uMS4x81 z?akEQ<%RKD%!~Vk>a462@m+(z)?u@2ier+fPG6&PcXux@!mW9$FSG{7s#?|j$UV~` z?|K!5E(UTKM|)NlY}x+otQ8;KAFq2k4?6YW&V8DVDsja1+WLA=H#Bh^*ssWz#~O9V z93c2S01$(O^~K;#jFpt6bGE!bE;>$81vJ@#^@hAKUL-KT_@&k@mHDR#U!CN?3v<8! z-VbOQAj%yD>m#`gYJCHPZ?yD4n1@?*bhh8}X>Qr_Z2{7{`v;rO>!m=nX4`F%G8iuY z&Xo|iOMuKpPtQGd^>b8G272=g3rhX*Kw zzxi11=psTQDJD>l2yJ13C2vN{4zzS2`vH4R+Sre!@mhN~H!VC}Db#*Y+&zmMJ`t6i z>O}0Gldo@v>XSMQhMx2k13RUAcg#O5Yd+1=#!AxaOxfLM?GSj#U3%=p9IR>_mzR$= zosWh`MlgSvJKg|=#`U&$S4)1_*xTDXJ9FegWyn2AQ8;5JMZK<};b!a`Fd09zdM}zb z;`UmK4!2gu$Fjx@9mngyw#YDEjX!Q=f8zOHiV5w8F7KX;g#A6RCox_{jM{@GnX_a$+hke48;1WGNJs0CoY9q=1OB*&9(hT|=F>oIZ zb)EMu1k#{b0-pR*a-he%I8g9|fusEaWVms?1h?2nZ3*-!>)!FW*L5ZGpnoS`DO%Qy z0NB36|C(v8Io6&mzM-u2_Uz93{|{@H9+zu4vI|i)}XZD z2fV#8B6Lf0b04il1T*N*d8eeNQiU9+^Dfm^Rec#6O763g@MAQB8y{0G&^*T^$qZ|> z0qlBzF0uIh{&^xkZh){Zpla0I`VX%KillPQOA@9)z;`TefbU-!sVRbuMp(BL7OsH~8tdM8%)266jHljh!1$xhMV*QjQmh+$jL9h%tAe-V`j)V48OJu);j zpR{)p;^j|uMaO9d_l2#O!nVw{|oo2tjBYAop zbT1o=g~y7E+gzG01SALZSRgyIu$VRG~ESP9U(rIa9PcX>qxB?ZODj+c|Gq7zS#Q>@Vmj{!uTIdcXUGEH^%@L;dWU`_o{T>%Dr;#VBh zg=cC0cuCq-U!d}2fQ>$2RkPz4;O?${#r}kL7&BK8ZZSDf4E1>qA{ieapZ$O%5DOHP ztD*Ixpx`>0{OI_{8>{SSuf&hvZhkoDKle}5Gs%9e|K7W@CYX+aqd)=S$ZU1bikB1Pt2XQBbC$l;XC;Xj67hljy< zEUfQnmV6sOJp2}X8oFUxfI2A0Z%z4>X}QUvD$2$%(wg`c(Yt=- zqkLl@+XL8d#x9Znh~x}_yM>=FCSTPtrcw&T+AhqUmi~Eed;f$?4jSxguT>4~3GLwL zNnVN9HK)mp>@oDb(|AALoB`a}*z&5E*Wu-y2_pRaRihY*$I*Gv^-a*`2-_L_ducO^R#KY8Q&z@~=)~WkVQt$X3 zetf~&+}sT5a|pOJyT9nXwB7MspH&-?eR6-eXR}F7I;X{DisT&2w7pC>iAu@0#TKur zt)sm_u+?&Z*{U&?^t#Jg@>RjAhm$K<$3~v5DCep{O0my5#re4 z!qN8CzxH-_zP#E+OoIN(c=N6L8jNJow+|oWc~bF!eE4FpgZS^$;2%lluzuIgAKC~=*G?7 z4t~z6c1RO1bNKG^lj^kJUXnnpN)amGvO81>nij_(_H}4zX4Pxu(^&J-QN1T`i=&|@ z)B8XIcITa6VuIz1NHdA581Z-#J-6F~d2?*hdhXh8IR9rS4;}_N9h`F$`$)t2HJ?$H zLoJxa!>%iZd!&j@B}E~Mrn`3!YkjG!0h`CB0^Cer4gxN94E@3+eLi`(*%VMT=)r4b zQ>zbFx?9&o03`9;$b3qWAId-3@5c9~B`IEoEKIR46L`Le;nOAe& ziu&qQpPHKbnzI3#3BXq@ZtM;ZZ{{4W$s8Sg3G8U0WJi?Xh6nSh$Osz6D#ykLoM^lw zl?h85oq2&~WCWf0j-Qd_r0CHdb@lZVUQ=fcaaUsRfIFS3R$#mTLn4k^=KKp&x^CJ;hA!~X=oZ;I zQA&crx7!y5EAlc3-U|7)4P_tIjin>M+x*3gvAcTRKvUd!Y;KJ4e7f>tGt*WjH=Iy=E2As;w@>B4dsch3d<4qm0j zhVoJ1C6)un_pMtdI9NKrL+=x;62wxg@kh-=cCjs}M94`!{nKM1;MWqD{+;U|1sKiO zFK4RPo9&4BkiT)K`HM|)X%C%wOfn$CW}}?+mn>b_VOE%@Gyy8;3^x59C zhF(SxdEYHT_y<>qFKTN`4Ls7tNO+6r-IxoZ|6(mUd3V*a|~Y5g?{y&45y!%C?Ul%)YJy=QLaNBt7`U= zHjCxdFIQPh`lo`nj*flnO?`c8Rl!<==z9h73U%g!W?@d5?BwTCjU=i``XF3~-kA>R zA^BY9fY+tPQwJspsrqxHRV(`5>h|TQF;xLA#w9_)-LFunbG67j0<=ExS+vJd)Uak% za{!^4Y-jKD(o(b7#|>~CicR=!J5_SkvcvgI0lblHW)S-54fWLz`KA@;V97FFWj?)i ztiyKZoY}PG}xBMildMjx-UH*-!sWW(sx! ziKG6Tq06yhHlR7+e>7;CcV;upbX6Rdy2``P>9webe#i)w#~9oXKsPsM?ej+=%#cFs zJ0r`>d=!f2H6s*3vN(6Ow%e+M$F;wE-!8+7NfWjlC^f9C!dwHqoN6FG4n%X^${C=I z?wG!<3eky&hfb!k>Yq^MV})1LXs2t0nNn!49>(DmUze7G8>_HQN2a2IJ~82->rO~U zM#kR*4|`{@gjhpueqlVl;tMwAWe+@GOxtO06GXJnJpeTTAORRoD+BZUl+rsE#AMyD zuqrg#?Je=$!irOo=C!;^?5^E@%_&2iV6dDL1P-ZFjqLq7GBQxs=IlXO<>IAx=YC${ z6Z?L9*Y9y5)6XT-n2|ch_)Sql#`=0dmDgL`7X|X{h~*^<5s^sFibCN{iiaVA!zY-B z6x1}d{q^xPzk?>~2{hzwZ*&v6&2sKn|6Pb+fEyby9DV-9lxPe;RY-SevzIfWm&MGv zCFF)iUd36Rv;VW_%XJi`uj@*Q5;9%&QjAwLBT7p%U0+nPxOCKr%JC1=v(H-|4p5+e zAF%Y-JT$}H&wu50zdtoVrJRB#w(rR4fE^NiHVu6$_Y;} zKWca<-7j>?NMsiq^oWV{os4(ycBKs3aVk< z`2|J{Hs1+u@IHvauS??GAq>MWdqAT@TkY*mj3Yj{l{sf1kRuhai$lZE&m0&1Vj+K2Ig4nsmzQ*TfG$9bTAa;LGrl|I1ysXsWk`VfSsAv zRFezGI+p2*a}NXpgnv^2PZciiLOMb^$GKl5y1=YNOMHz}aqas*e&W&|KZ0_Idth3u zt*wPF*Ww*}tKAHFX~@%5Now!>C)S~Pw>v2XoKcGn7z1I7*WiQc!@j(<1=4^)A@vwA zs&^vA3%XnkbrbTP>KkGH4SFZD;^=~{1nF_^kIIL)&+y5SejuRujtYg1H^4O? z{X85W&t7c65_NA4HQ6pStn6W@MEk4+DcT?&Ud3hGmi?%ERcc2UmR=ZnQLc?oe7UZ$ zlqFa&?bGq;z+6=VpHtxa&(;a-;iL1Xutc0)Z3H|s*hYe%t82{!F}}t1d7*7-sea1s z!&W&K1BtA-DbZ#lb!{4)JC}XZ0O7WpFHFyN8b2lbuu2B@&&6U~NX^V5-Fv`YY9P^4 zFJ=1Su#6xDYerx8T6?Z&9Vd2VE0{A1nC00s=(F5Pc>RiwMIDxVTJC*h9^VrNk(fM= znxq&y^P(HuliuU=o+(kJehDE8Q7pYtKZxhzB#KTXBE3d`64>-oEEQjz{U_B@ImNQe z1^kdQ$NebsOxM+(?bAx$;w(vQtFJikNvEn@Vh-&_RK1j+#n4xLO~Nw2LreQ&?cjZ7 zzd+#(%NS+VuUcvvH2>T1chDuW!70@S6&NmuwbCWh`Oex#6dB->Eq8?GZ}jU%F#CPY zqN2j=c|LfLhV&wHv*dtz!t@@NtG9x%dT`~1fVOx%V&gOUYe$gnJ_l7B+lNH?}Zqv_P^f;wrs)rt8F( z7!{$NZGI$t^;cuq#Zkig6C%f7Pj57Mt+G(@cjoa;XNH@y^;SFL6WC%M9%+ArNZx>l zLpW!kphL2%FzGex{mZZVMKSH26lLVbNGkaL#j>IzKfV3|}YirfSJq;Qt#o*ix2V8Hf zO=X75{ad2bHSvrL$!+-Xcaj8Smm2~a;VlDPmNgh=QXw__db}xJN-t~}8b#BX$PXg` zVADP4eosJ4w$uQ%guHE_QjDb@mKYrc1s{BvsaLkh z2?tYC(R+zpTf>j(6kinDVhs9S81zzFc4n`%@wI1dG*rAPy&3d?;k~Ef zRySt5J*k9Lk_Avr6id}Mp@D~BfOhTQJHQgW6WD-s#DJ%Zt`?u=C#_qeHA#H-pDMuP z--=4>yO*HFlL{52h`Sm|Ff6EhGa0N;RY7Qk1KuholHZu&SxgllMPi4%7-5nP>-96! zH(P{((ziLAxCfb`Q}Cb)T)+JX)`6aS5@))GD6?Jc9dkaqq}~~*l9$>EXIz~6U{?zj zN^q_h6>rdx$5h$X_Rvw+yk6yR9UB{CCcRgXP_dY&L2=a)?_pR!L5#L$`RWe&Vf%EQ za-Cr2j}`)Tjw069l@kr2`mYC(wmGebG}oi@)@y36Y4D_)$CQ+cGf>`Ei?$X81I4D? z*w`3T1uwrS*SV-jwQ7~lPNkP}QSk+W%*5kZSLS2e1P&D^TipRUx?+CV2$8ozBfC+^ zE!F5XV8b_V3Gi>Ck9*c5fU<_{-4`K8cmIPST_Y$Oj5+Ckvc3Q(%F~Q_Np+n?Il%!x zJ~kF>tgEeUFiztcO;DUN6m(H{33NsWK7O0jC;j7x!J|jf9Qvj=^Q~&cWMpKSY6}^=%C$U5_CV$}KJX;!`N^0nK(Q`Hd;*jE!7tZoPNZ~Ow2P{b zw%pU5roZ0lXC}!(5@hz3bA+RU_2%a2<9^024ei^cK~8}K=YqDsORGl9D}>6Qpw34< zzn{5|aDP`U_9tXE{mm;(u_FV{Nh zqVw+hDNE<1vXx8_TgH86rdkepJ$h8Lz7n_2gv!^9IMn0mXiv(HqV>xWCKtd;wW@J5 z0;#mLS7JN+GDJE$@9U*h8eru2+OS>*oa1UFrVL&Re~@u;w8EZ3NJ^sy#daCs@Ev{r1&iN@!{xnL%EyDH11-u2D@`YSZ<*(-gx7*}%`4}kwnh1Q?oIF6#aPeJ8f|RX( z`LKg9zZ^NLFMdoYt+PfNcWOFG@`<| z#faaRJ;8Hy6Ro!lF7&Vl8eJ!@-g;a3A9m^1S@PD|?Q=!|<47(Y;I zqV5)eofQ;ZC-6!i4Q$Eqg{8=Sx^7pG2kV--4){bbMVsqV<5kmrLbqpCUCGB%NDi5aqk zn%niGFi7D{$Mf;4tCX1r(V)IAL2(+^AE9-38f&OsvysXfxY90|u5&wjIY2!jALfi4 zgki+M5O-08zoX{00uAlAVWHRvXitC=5nWi@uLtC;IZ9(j&eql(QF)pr7U{Flx3GI~ zIB0xs(Dl_YC;QzK%ze^(OEr}+;LyA^K9vbk1`xah)E&b^60u^@$-%)U-73A1;0=*) z%8bQ%yL8A|w#R%~S*hUa&7(L=Rqiasp64LE2NN#KOG`hn{=N>sJ%K$Hp2YNY(0K{C z1Wb2q!b>5{S)i^3KYl>kxWC`D*Z|lXE&@pgd*2R6wQ!eyNBpq66h)g;{iB=7ANb02 z-aw%R3J`M}KHcI4zj-HR&tHIBh8CQ;&1Hn*hdpmV=4cPTw{NOY+$pZbrFd~^a4Sx*6nA%Tkz&P)dx7Ha4lV9d+zS+U3lij>^t*T7 zn|W{EUoVphOmedKI%_Zet+f*NK}i}Ng%||{0-?*wfK@@Dr`jOUlSSmGz&pwP&L4q4 zuN-6`&L9vz@IOAzlRCSWRS<|0BnuW-_b@nE_H`iL_NBjuj_G2)6~iQc_KDO1*@8Bd zSA3p;73J)=6V7i(h9jN2I`1um!(dp`hqUH*jJ;YtWs6HQ8k^--%niB?3lUxV^esv2 z8uMoq5P_DuDqlRBkU@d!Hlywj^|CTQ#3Vj}KGTAD$30RquizU`$VGOJEH7HGhJ8dg zzafoX41WYUwBLKL=nzv-(1Spqls38e0J>dpo>Kv@-2b0mYkzik2Q`(ACMG5hE3z7y zne{F`2Z31G-U^u|GUC z-#rh=B6#P2z1KYI6vjVsXXDxLO|))yoBg&&$<7@9T>-M$XtL1X?7USHtXFVh zc+lQ--yY4FxgVfJegd+o{7_3r?W&s6A1-QrtujR5Uyl_80(mDVCs!T{nwlEv(&gAb zuNOZxmzTRU4G8Vz>)i4V4P|iQFtK|I+EKT0HnUE7Cn&f`?x@Z5xR8Hc^G0Q2Nu9{m z?)Xhx>~3gN(Y##76OSjO5bq$suj#QyX;A%(bvdxGM;aWTDvMm zW<^C{8kS<3bc4+F9u{7^D%G_!>&_5XZ{F>Nl`L+fyK?$FWv-UH514utp!@NIK+z7a zM08bGG~lgFtl;=z6Dh%tedEyuLnB|x+!#-4&Ghwrf(5eP$?bxh!+sYqzq#K_#CoP) zmpwxf>-3F7v&8@z@98Q0cOS|$cFxKj!u7);{?H3X2e4(T z(w5U%!Q;3ywyQ>EVKbo&jyx*o0%FACV%#@xdgoT#WXRi`#u&z}f;2nAf%=|i+OKP?O z;5i%MOepctWj@s0ehV>ey3FIvng5$NPWAVLo);5)SrL~2;<4~&AP?QIi6DUTc_D|g z@AKI}xZP`5?jOUV7;4zB@F%itarV9SH!%se2E1As>kcfOyo%BEs#w$x?8p+I zX3R3u#&IMF-y4bHr~rq*Mj`T8NPI_ha9)j4x>9z~YVPKi$Sz!JNLnrVIrwv@^#!rL z5B>dUpfzSt?$6T8fbr(H&p^aQ)zJ^(r?MS9jMUb_WAw_TWhP2zb=I@x`YpU194cM! zgk1OV(lBb|O19uXRrX&1w}`AZI!_R*ekns+!(T5;xHQ^_t)(%Nm9E9E)kxaUi=m;x z>dq<8nSxi)Wl>bU>K9U?h}8^jc?PQ6bb24AW9g%Okh$TRCq?b~VwaA%fqo15+);tc z@tQcHukO$Eb8KL#St;&jy_;}kHBzQ;@sY%Wg zC;Ba$kgTH3#C()A5zWfFPT+0je1s+^Z1`6 zE^IZ2g9HvY8l14gVmWYXzO9|zUb9k*pt^A!$Em7g{iH*EmYX?Nta4SARPH;Tcon?O zsUo$^Lqgx??Og?-_uz<#h%I<43g9`+s+W4~E|8GiRwt3`2PQo7@oJ^2i;IP@Wv`bo z_0b|HUXMxeqW8I&s>SuG*|tevc-r|V`wF7LbhzKwBP?Tq}6xz|?L;JG&uDtRd$ zx<>H{!_i~yNWQ#!6uMuuv?qY$<)z3fpnCuySmS&bjtJKwg1XIf6a z<6wkv+a+y`Vf$JN68p=D-X-i*bekFZ^1(}S<=VbHnxJ*bSr@++tBdQ*q?xA+KH#o811zsQ zceHUT1xFdzohR0V@hTiIm>Wxjrehy(WDfSL_@F+MJ|V%4?z~V&iqxtKVn~E-2-D;5 zjn+xW1ut>r59RqjnKLBt))KXC!?z4+X`!JqZN^7ohet=IkIM@>t4n%Zm!Eh}bIUj* zk{U|lbn+-`9!cPs^q3K@hC<|g8WQUVAGS>c@-e121~!bLWV*8Dm5CH+58s2UV=TS; zEYSmEveG+6D%6IZSGm)pi5nVMz&vhA0aQOH0!=Z;n!7utobM zo*Pp$GqbI$dhmYU&aE2}Wo>D?rXs1MWR3m)gh!jR=b<=^h{1!*Y(vYz zlC@Ev>WEqlVc*qx%hswD4Y7XyMu%&9!FOl(LJ}haUe$^Y``IL_I_BS!U>mEd8XZ@1 z^&*(Kc7Zr5u1nX9USLZ$G02}bK_x!9X@ELy#NL(&+SBmPBL_9CV5CaT%6!(FAHVvD8^+?}sxTC=OLbz17d zCz>Ty?29#{OC!2)ZScfZzvjg_6X(s+!U7$tXxE(8?i^Q<$cv%9C3vTD`^oL;Y}gJ7 z^tM-ih~!UOrbo(Y!B3;#k#}XvnWV z!LY*OhXcKD;h()f^M(o+FH4jT3S31!_MG~jwQFU0CxjZnM`n9@hqUXV<>s5_()3c+ zs*ajJr#!JRuD*1&6$^m5dq?v^3kTQ!?oA_1^@s^@5BZg?t(+O&$~Mpu*5C^-UxS7j zv&j6>HV+|)CKk@bANQBg+q9&)i_zWl$*|n%#2*-QKMiSW#uq&8@G;y&x|Y>@9GuE1 zk+W@istMaNSlC9n@6p;;E>OLC{K)~!m9JrU>hWy^)9Jb?#lX(H?GB%KacLzp%~n=t zmPK8oZY!zA{7r@hO&n)pc)pZwt9x4*cK`J-I_Qt#Tu6o2y6KzZtG{ts9~lda-`i~w zaR|i#p7`#m@;UwXyeo?Je#V7hO-&8>2g6_rmpKqB3` z~oMJ^+k|;l4-^+!qp+mga`4kM^eA4q7ZrGEs{i zX%Ew62K>1<{IFsEaAIOYtw8Cpy`#NV^J(f7B{E4^mNu39lkY6~Lvjc0H8wMNCNE!p zQDiMp%3%6Rs1QjvBcMSt!E{8&I_)pQ#pS&FJ5S0juKF%5)oXvH4eIgsv5^2(qOeKl zk`?5U!uXnA|o{5m`<>O7#Xnq|p3jCP;SbYHl5Si*Xgl?Zi({fVL# zQ4qee^h;17#ePqMoGbZ}Y)$^!aSB^)#i8!V?|G$5$Zr zQgYnJ;>T`4CQ?$p`kE0Pb}Lyzr|xi1w(M7}Fs?*#L*Ly{q)pt$s zc7czpt-Lvw+e1Eto9PP4!&&JCx?8=sDa|~lc1&f1qa~{5^3%rKy7{8K8-<2?g}!wv z;dPJ2w|-5k*A%ZFBSX#8?_90VcA@t8{sDq&qm0IJizLaX5kl&ZjwT}#94}^PXD!Wd zckWcuG8)Og4JX1`O1H}N0nr#v;R16D2sGE$a&sAIGlMpnG@r9scp5FeF$F`|%-prSk$+xl$ zuy*s2?!S)@+WRth@rS(1P(s-YMvHiMt>b(9`bKOC@*l+1wEV86w1rk{-N+O7ZW}T| z3lAt|r1jF(A_c5T?A`BL_0Ug`m+p_JH`6XttNpG)pvx^LxS-tsc$2&viz{^g-TCCS_ULpZi%nVJ# z37_W>0B*C8*$?9vSDHKT)ZdL{q@RzsBEDYq$XV@5VD7WA9V==_C6(*u=2IHiM{w~p zjyH8Gkdm{dZ#&EJ`MchqJznU~Xy03hbt^Xan42B$8I*7?Rr*>VB7(y5yEQGsEH*!pN1a~j4ApIX*^fMq{SAAW5xxbZz{kb2m+ z@96C)-3qpuH=`Q5)@dVHWxhOYShYJ2;{s@&TYRA}$}g%6*1~;7ZPYNIv>oJ|XB#oJ z`sOgpR=KeBvp6uTJ*R*39jq!@1A}Rz0$BFIHQ)Gb)6jlo-E4}NzC=CKR%epzpVb4 zQWAi0WHA`~>B=g{s}sMBGWM^ZyWBbMY1fQX84+d1`pYl6nn0c~!ZObA9OHt8@D<(% z&fxuxw9BlQTQ8Zt+a#^-5Jvd!AF3HSLfals=;`Luiv^x1ABNH-_IDyloJC|Pk{2U499T)(dXgK9?3-K{HPC;T?2MrQLnu*R;l`O zPTj-Pvgi(nC-LpddkdZSYR+nqwlIZcL_KCbW*3^|5>J~J%FP|jmf0HX1B3JA)_5uJ zSB~#9o6w2nXGgrb8~ALu6)0K{_y`E1IvxbDM~e1by3H0lszwwE%+{Z@#x|vTv@*oB zU}I45pb>m5UBErwypeNbA2E(*eM3vV;(Oc2-ge>J0ToK-cZAo^^~iz!FGkq!ww1B5 z+pJr49j7fK622K>L(VVJFy^dJJ&P64YbqlJWw3)lA2&8z+_StdHJnRA^hLd4-pazJ zc5iMMqWx-*Bl)@s_G3%NO3P^*Dw1krv^|Vh%Qs5gVYl-I?dIog8sDcp&j%+G?0s)^ z!50bk{+nG;_y-?U=nYKEh|evWGLNoY8CV z=Ma*C@6oC3&oCtV;;>#IUQKx5G9X?hFPB?Uq`40|Eltk+JcQavYf7Fjj^1u{tHPBh_L?v27EiP~{*Lgx;(iPE(voFBGYgVIoar^| zk))^4Wq2P~T5zHE*!!@V?q9sAa~&Bx8{Ofz{wr)^mCTg&ar5z-eVxw}U}A80=dX@; zGT`LC2L+gMm|i|CyoQ} zPvN51PYyGU_7wDp$Estlvclvs=kHXvE&hh2u<2;Mudi|H_WY5w9EX-9xY~ASM1_0b+(IP&y-Q(&ge(Z{U)o;;7 zi_wU{Z;c+ReI5B?AtNCF4ayOr{ge=~{K#O{h{V3TK_c;Jsw`a`n{jjqX#^j+4Ueo5 zK>n1JDMZ@}lKm`co}Yt5T%wKPu$It$5X`r~Hk!_Vo?CGr8rkrsoX*1hvW>^dhKGf? zOguSdxHKKYcp0ui5bOgnd?8824kzu5?#axzEcIXXaW6w4!)Dh{#jlE_@{;fqjr2!5 z3c|u(g@yXM5eB<$ga1-o`M1x{PX>d5Y)glUZ~FDjVv~7nUlR+8qMf25paE`!+bu2LID&9W-kxkr_JrHRMO9z! zvz3J^tzHG}*DZL)6Bf-Zcp8M;>PkqA5n_vXEza9YYTw4518#^%Q=A}iQCvq{MW$sV z&NaQdaHIRat2BwEbl)#C$0>IL_F8Sbz?NX9E^vzX(c{!yxIGLot{;roU)mf67B5|w zerNd0PGyJMCpyAE1GQ?YGwZ4z@AlTf$+4FWBl zz#}a#u5+cq@eBkVlZ)0Oolz`9rousF6g*$;n;)G&XqY&>f=BMSiQ&Ww6wp1;PTa$nJKs~BubxOp?&NMnd&pnfXBQL{R8%M@ZmKio z74M<4x5g;YnL@UZcA6g|pm*zlb2ZS{$0y%rMZ^TcnZYVu9{fqpxHf!u4_(#iQdtQ5S?1!`lMjBA?+N}rREyMk(@Ys@p3i<>gfanU{-G@+QJcLdMu+hZec6feidjUz*7YSrYQRp?|sCu5Bk&%&^ z3G;Ym0f4ZdyqbU$!uM1+Lt;E8bB#+y8yc-EFIQC_4LtdsCttc69eR6v8%4@b-J8vb zy4h9j<9Y0^C43+7@TtJ>C#xo1SibN7uR=~n<}Rdt=7Ov0;gtV>2dPsmqd1Db2E@lmpZ+3P|mBaoN9RoK*`6brjv$t z%gsGUOn4|=U0vX*a7iizAoqFJ)2=$EFD*?qnlRWqF&fR=tYg(4Wz;;=Q!3GPvQs>E zPK{~k?BwJvd_0ML$Oj@(R$aM*-9K-ZeW|aYpg=0>2e4z(C3$*U!vHT|wP=QzZfT=f z9R#X#5+Kh~)1VgM7ZptzNIqVPWRDZAsjh~TbG6_4jcwyqC0s6bcR$yCX2A5K2>?E- z@UIZ*z@S^{jk8nSa`wa=7RH!1it6 zZ;@KTb>=gGcUt9oRrqJG**@Fr#%ORws46u4;6+XCu{uR zLO_VJJ&N4@ycU|iw7f=XDy5u%aU{(>a#N|Qts%`eC_VusS_*lFJ4T_<-`PveZ@E$+ zt*s14tGuwmWZN=L%t3z13~wKe+kTfIUw(h5hod3)fhsJ#)5sZ}5(cm&GAOc_@8e<( z+u!Ll=Q^#Kc%uDZrU`-6yxH+1-%oFRY%o)u_B+3zBMHQrrX08D(_fA)-!55LTm)uf z`ib0~e_*&+q3CFUpM2|9oYl!=00ZG=?y^H0QBh;*cvE1!a*Csp=GH;4l#4k;IE$sZ zzFyM~>)YEvv(ct^=kc)(D-2vNtj|u&|_>(KbeJv zg_PeZDAdc#>u9CTx_vPYu-W6!g-~<7ZGX}!@wp=NTW4&GDU6hl`9}4d`5#uF{EjIr zz5dfeagY+sGf$IW-<=Z^iXe8Wj&yNWH$|n?K07{<8HGa%88qU^f!CZWgEbMFuWz8o zy~_IW{ioVlG*uB*i}u{w>RoB|u+75govW29T4ex4ehJD8-achp**!S_`lzjDTPB#YW z>o{6V(@mO5{mZWUqzK}PhTc_bY6H}2Z(OaR#i9JVa0zvQGYZ>y!PCL?+uQ6rTh(EL z1q?PX89V+~u)2M9Uh5w&+PkbV?|7V2t95>}lKQrc)8}+6qLpn*sPDQ-DE;}r>< zGE|tjk53uHi&&%2EHvcr2OPr>RmS>NZ739aalcbtJ-jFCH$o@EC8@j@xJvpXgQ>E^ zA4-WuORebLST*roVh^Z2*l<0mFNyMj7~I-wYKvm*s?ua&=oJ2wuJfh=2@$ehs_iA^ zlrZ_QrX`>F!KTEv+8>t160~ZWg`U!@NT5!^}Oiw*00f=d9aZNAl0Z!^4Vx zE#(S~{lpL~9F=t|qa9In{;^xeyx{z3ASe8ZyJRDEo3UcB&Ak6@Kj-bW`vV5au=mZ_ z!!WF_xbG_aXn&vi4nkEY+T(8T>2jy?s0_z6%knzumX@0Gu)25HS=l(wHr)Jfi*j}< zPkjcz_kFCjA0w*FtCdp;rF;&m_(M|3Um8E>yvma#xdzzkH#zJpZQds{tRY>mB~?ry zA`X8(6&D|ECzY3%pNaflTQjsK@Vgy6-8EJN<9!YJVz9X4AU#RWYvytS;26~`ac^GC z?@%t9j)W4c&=5Dj#;F;H2`C;&(+)WaWNby2sp27S>pg7gYy5Wld+oEF%Bf3+Icl%4 z9SUgUABW@|29~>9I2>Q{)$^xKdZWHr-}DLGD0aM0x?y_bz@{ODnfjVX?95lvbsU;_ z<)tk7lZ>abduzZ6jWWI#B{R=W?g7W5Tb;4^(CXEUU(oz^)kl-Cip{|ST+~V@eNX(L zgr8VZs{NQNo{e%{fti`eWldJ>=3Cerd2}D-`o+^Hep*f9GT@Su5(!%!|4F-dm zL5CtB{gpWm5A3UiB>RQ{u&57R;eR1J=Mt%CtAUs2T?`M47UkgMlm^$}*5oc&?5vbW zyoUtF=wu_r@zeGR%h$xYPqt&evmVEVmn+YZFe)kUFh%dylDgIwDIPuip{w3qT^Kig z3HU)al3=0CgS~JY8=LFF{>?lA2@ki2V-aIXMl~GYJ)svpks3Y!fQPXF!~3o<_$vZ$ z%uJ7;Tw_$Iwt+E1(0}~QO-DF}z$qO(rtq`7^RX)!3`d12ffLQRP@8nvr1|`&BMhv7 z*{~^sJh`h*iM6-4a9K-2LekdO_UmJ1OUvThujA33`7A8Jo?b>MXC*IFRUQ7cJezq~ z%WUw}A&t11$({J0to^8xt3fENU07X%9 zWm=rBAbD}>X6J2;me`cx6Fi~&V`cxl3Xx11TAVQOoGNL@^;QJ<0;s_OC|4Zc(POXQ zir+q_-6>4fMW3FUSGLa@aOs~4`0WL{1ZBvYfzFUqf9Ap7-rnE8e^(jzg<3c|awN!M zPlS*0Rn9wLtAj&m##kEnx-4mi7 z#-8Yb!09!%xZ+ZF&lg+j>B{N8J}!@Qvtl93d@~_qIP@$jxSn6Hu4W)u$g?}AxZ z*iA%qEPTiVY^Yo*U*Bn8uZ3LgL_4obIu0%W>`8g2crjC^Ya%P|_o6T|5?yf;Q6X2( zFDbF!=4bd8p+J#lpqZ#xW2^vq{SdvTD&E-KJP1oa|9H#*#Bw^Hx?b9h!pp}AbXL+SHr`_7xZ;+#of&*avaiXbX z6eFV7(wLee4Nh>1Ri*o7JZx6xp`pREiz-W4M^kJQ@LV^Kfcv%DcU1Y?nT+0e0~yxk zRy+|L$_x60lo8d(jvHyQ0KkpJBrT0x=bJ_hE>arO+=qYf?tYB3tz0r^-3(uahFVx! z!hfS^Hka4%lY#M~`@&>2ruC)O*MQoK(9K`^&b7m##qx>@cDB*pjeD@m&NvmX3!x}k z!B96FiZXa1R4OT~!hwAjh;LhdvBx%gc*Y7h2^4&>58{d=aue?!sXBzby~|VNuC^3y zb+}%BcHHj$XPJH{?0$9bk-7~~1bZtQoxc)4)VueZ%NfFR7zRwfwVASu0pUwokb6)n z??-2C&Hkg?fiPUmF2jXg!cDodceQSqs`&U+abw%~d0GCR_qWg*L$0cZaUH_yA>M?R ze51ch{h!S-U%&5N6@fR*M(KH92uAac+MT3x<@5si6FHgx4|-SOA`+W;jYbev?r4#| zwLb8CHj5NbB$=Wzm%p}`e*5>7o<=`5TI3uXTiEx0cf1WNOKszA??Az@NAbTfmUSzk zio-3#tBS4lH42#`t5n5OKAa2Z5Bk{ZGx}z>5^~%vVEavD4G^tKMV8uF~h8u)-|ZmF{sFe`4^Rjyx(V z>YWZuO--#d*8FRzxuF^7`Nb#|#77+hVVc0<>I9E4>--RId%+-Mzh=e7q{~!L92; z9rN33F!-a=_b@w+zq=Ry{HZuh6o&Jq%5)h^x*K)I2&no=P3`FHbB^G-j!ION<^CkF z28|bAzqFxA1@b7|EB&-#6ASY*lURnT%C|X|r4vEIKOjI`!!?EppiDeW+jzWQ=0Lxn zLB~f78KrbaCIdaj+dKmi!)XXpouOTIsD3zhEN@Ois;M0KbkY%auiIfLLhJ>odQ}?) zaX_6md^7;WUPWTAsd*g>j`!Opv!>x93&Wa_!RL}F>E`PssQJ7ZiN8t{uN<>>otYzg zcZPXm2&|E$plK?99LHSlIo$?cV9?xzx2*sLMnkO5)Rs zkbc+$!Kw`|0xaBw)SS5Zcw^rJW=}*7+DhI7qj5jsxt2yRfF!y02+CwcNVqDoCPbBz zw!+Vr5&Z*oU)#<+CM5MEB-#_Zx~Wjxo&m>wC`L+b0=XWXdyNeMgqqYj8R(`SD%aPs zf^%JcydxQrktStv-L0~EisMS6wANEn+~lmKqJ9PK!l17K{M1pm-9T8S)#LMMg!Hi`3jkvik;7 zSnA_d>~E>gb&n_zVZ;4G3)%nHf~Z_Lx}$)sebRk1H~|%a(kv*1P{)*&mCZPljH*(A zYVJ(%9J9vFDI>2UDcz3@UvWiAD*0Hz46KnDW(qIe4ct6?9DAaMqT}vrI9PlG>xP=1 zcgRO}oOH%zU4w;EzUqFtzrLH+k8D=rSstk~LTte-G&aX;1K6_A9e-^d&Jo7C49<-g zcSf>CD*fkXo5SHwO4v0qm$B`BcdmSlGTxU_c6JMdgWg{5*BK*(vt7%}d*d+z+}sbH zs2l99KP6Q3de*A>>V6>vOOx%3gpEr~=qS06HZ65dcjr^6rnc1}+A&X^Ql918{Zt7Y z0ZG7-sQrVaDRXc!l`6YPRbybOoHgdFMfen*cYpE@BkrB{#y{L2ta$guVaz3o@;2G9sAsp74Ek zN!W7=N^V;*wPFUF+iEXB@xDakg&+Ee5>D#85K){G5bV_~s;*c{;nYl`?-;UQy(Q#R zU~Fvk&S&U&YciRHgCJ5kLk&+v>|K46<%0W&8(A=6;xt!1)vqMg%A5~+y;pnA6%Qvv zqJN=BMT6_g-Q}y@%a8QuV3&R9l85^>8II})@10tIOJ{@<2m`>Nh#135@{*^vvnn2j z5Mkq%#>}9c70;Kw2)wYtJM6l%lywO zXU_Fm$L`F)kK;bvoo0(Ky5iMGDjMqRDNCsIYtgh;9Y+?lU#S-zmdRITaHZ^06;)!M~tWGi7 z+cPVQvNAGU8>ikg=I4y3MoeR=#T*QZ_tNOv(*R%2sN%of#@kHK86R!82D^AVPPh$z zl}?;i+g(vPqQJ_#X!dcZHpl(4?7Ht9UZzS_Ze-Utjs3=YjQwNe_C59!`(dl zedLXZGNMhM9!F57t;VGDbCDS_8QEdWe4m{z`vIlFQ-|BT+V=$2j9mD`@e}Mj`FJKJ zbgwn>aAKWh_hR#c{z!;ohbRkp-CD5 zO0122%1Xqhp5%hi@r@i2&1dH$|?D1cEh_ie3hjQrxzj1OU3JC{4{m z$!Ktf+iG~U)Z`3&vpzK7{>|J>OTDMsIZJK+pCfo!&>P&ak}$xIE`$=KeVr#C;J!De z8vk_sa}!GI5}^5LT)1`xok@YbC=fTjpIqVklQ!+Fv5D#9;xct32&KFY%vfAy#S68F z-vP>OzB$stPq8!3JT2}l92{b%1Md2qY#!$JX)008c46({F9g6Wh<(Sf+LXXzz@;vKq1eiO}DeY$8gamApr_A&E5 zdZMd?wd3QA9gZv*+)eHf5gM8Umh=PHq$p+LNzT(B$fjOred4kxNwu@cn)1o7>q5zV?eRyg8DO2DQg# zSzR~K7v|n|IB)qrWhCw=TQ%7?b|rY{Yy1jRg3wbRb>%`_^xX@MG&D@@KkHAAz0uH! zCPX=aDf@_=!Zrd^e@xla^5W)hhgt}3ugqQb(r4Y!W+^gx?RhI_*%Ljs|O}O?4-W%Il@Ei7JmSag0DdN@nU;@xj^pLr7 z%4{M&e%3Ef(hNBS1-%a!c-CTUadB}=&l+8JzukyPClM0Pcc)CAzH3ng`;;8f$t*Q>U*_62f4*4Gli;Vjr^++ z;JgsVJvxT_G?+8RBunogS4~4h#2;)TnA9C9U-dc*NE~n{Oz64@)w%V7D>yzfg+}H| z9jGb@R#+l3t?pVP#)5P;9Kw3~%5hVtxL~##wG6eJ>9_qCNe-WCDngnbH1}3My zsxf8ACM5GVQMSjTlv_|nmLFj<9pBR=QakE|PbIQKSN!0I#1AWJt5@it59KK-DXLm# ze@I_qlW8}QUv^e|MPd4<-UdNfPBW%U_xB|S`Gd>c0FRCsP0>#oK!a!biElIZN2NFO z@c8<9-QHc?4R|Kz9{8_!$p=$+xWsqedTsjwj4C^}{-A>>E%?^W)r(PTbY}^^gKQlj|wX#hmdU z9E>suUt#GpY6!T-D0JK?Tf1)?l$y_2SXudPh9o3p`zkMk^AhjFu7y2FQJK)?{KcPUgs-#Spoj;sC%byad0eRCPH@R|5`t$r{`EB0;aPQ|>btybRjd7PHav4b zT3XvM&*M$C^qvus&E#7MH5*AwjZly-?Eb64yz<1FxCc*AvIq8$;GwjX6vNGr!m2U$ z&0E2S61qN-K^jG^rvX5lL8uJL1PXmag@>fz=Ep7pNg@OlfulrpE_0f_nqA=%BL35x zsHZB!nEr?FXF7*|r7E~MVFCj2C+L{bd1{V_q{mwBQnoq|`|m(bOr#OQ^iP{>$}%9? znm?Py1mc>7&-s>{iE>B!inInqB!XHY1Mhf#z1$`}$-`r_uKThkxi%(xlccB`}5L?f512T>*pQs`Zp&tUA-S$4cd)*9=EprdhP?D8lcozgYWpFdzckk$2FX>^L49U*Dpe zl6nGm_I6lWMb+Y&f1>;9JSBnz+>uo09Wrl>(P?i$1JAW2Z(sQC&EUz80EvUoeG7E; zamMdl9Q`v;7qRd>LfR%)!xI=%Fawr4TmCs_APPr#4Pd5&xHT#hL2sJH&*1$9G5y)u z+giXF^tQp*O{DdJ2{ju$>YxiF+QELW@5Dc8wZnLq2kNQuGqB34CYnhSM7+n>uCb+vZAzl!o1f z)1dxbV5%_^LFmrAO9N;Jf4yZYc3fj>rPOz6L`3bYUcWDAUOaj0l~}P5N(T#$q9D5J zclgc6&^vOMRai1yjjvS1Gi8J5zUIkvIa?j5 zmIez*lp)s0U~^;4&zKDb?7U!w^EmrXE6o)DQ@~Y)9vq($yF@+()xO;Jbsk*Sllp7s z>ubhIGaAZRC$_S%?u&4OzCdN|-!v==+ewbY=CIt|dU=9>e*1X$bdWYrBFgAUm11yu zxco7IG=OT;RM)_4noHKe3`Kn{@|N=GBx_anCLmNGtM@8K%?1P1L8-|4XcL~))Ky+3 z3JI9zfa7k-i=>$MhAB?|yN;4v+0FHmn*+Hiwfl8nFNP#Wl8@0w{4~8|;J?qsG(ymf zhn5z!_tKf7{>Huy>@A)uO$0npZCrl-nphIGG_zj+1j|27X)b4$o6lO-2=9wSG}fmb zTj01Vl~MkDT`%osQ~kF&6c)IN3j$56PE$FnscArCG~xmA8`RBTCIHwgZ4@?kpf#PX9{ahW<9Aj&0X*sZ@PEo%} zi7iQuUv5(ID*8gUentWVAyKTZu9wMaso71FJi?s*({B*(&99%*-byaMMC_E9D(F~S zcS|dbK+!(%ZaYr^LA_C`hwo|N&t+r~zaaP}@K zaOxl|HxuwdmUd_4h^2{^;sXtm-!0(yek1>PTi+Cp$keCjYDjI^Y}nME0M~rdwHp+- zf_1C(()fOxhEg{^K}cJjR&-cy@m`p|@q+TtB@hVo2AJ8fvD@=uLnA@GkhtF#-%B4H z`~{5fZjjX@cIVu=4KJ@q)^(Q?%Z!Z;HS*T(vY^pPU*FQK3`8*O34!+rx@aLOLGm z5bJ*W-GtZC_OQg%k}ceJ=J1!s4Q{{g--9`aOHp7V)ZTx>aTfTNj;m!P5g!KRP0!01h?c=>^P&p4KtpghSKo+{d z9JW*W*XIlF7oQHP!^nc(|g#VQG@R6?R~p8g(GhDr*ZzuMA=32;ZH-sf45$Pa!ae& zmU}CQ&L%s?%X3MG5NF*Yzr^r4L7kFd+|5y_EiLdKD7k87LTQKapC);id{hsgC*%r#%zF6%d!N zsp+J4$;bCZN2hsvLrr&*YX9Jv5%p6l3^2E-eqh9HIFok&#Or^u)qP9LOrE|UWXXw; z1CRjmKWRAq#SbXFW@St+2SRekkrRMjK?qW(lKTGPJD>&JRhOxn|L7#h!kK(GuGHhf zstqA=3vrH9Co)+-`evs9FbDL#-GjbNdaEK8paZm!ZVvyCWf-q-9jD)o#g;=t5K^yk zKfPxiVE^-QHZ1i_J@g5;Jx&{U=Dd^1bg6IfT}H!7nUU3P9^ZX(cmvgP7^{X=6EI`NB9dELWBVPMw{)B;)3*u_PcqeOhWB6VDR^LxiX#$WW-thKYyh{Z1L>+f0mL)D7D!C{_0C4 zjqV(m^l!m`Ugkf(=Kp+MNbD=H_Im!mWXCBSM-3Q0#MeOq-dl(%-`~o=4F$)4{%q*X zd{F<-tRsFxLu^yswSVb(8N%IspqgPM#&FMdugyb<4-;M(!xo)|_!H-6AW-Av^mLaU zFvqrkJ9s3h8+e}JEnn8|Kz8!ZpT}?h;PDt9^SbxkbIyI9bDrl6g@#;_ z{n3Mu>)DV&p0P%7GG*DFGri}cuN#*ALuo!dHFtQ|PWON?2a?$2ITcD%pL2tnA{*@m zUd%0ug-8yGz6rupZf-Z1o&dvU4_^zW|1b70HFScEtP`D*m;;XKht|t4i4IL&+hR`&EKck)K3YTQACzOyS?PR z2?XNg{~A6M-4nsb1}S@e)jFxNd~%!je;(rh{KWr$rXucx&NVyAo+$b;*8J5F*mI~l zklv$~nN7e{fkm^>h8+b2igN*i$N^S~i=HE8oerfW66yJ!2Tz_D;@-K- zr+3%`cEJ7nVqg860Sl>SATip5b<<8ZFcr?lt6K!qn5601v zP=xK>`KPx6(jr0Yt7x(v>JbKWE~Lp-MqACwYU|;MnO-i{T@52pOTYE>tN4q>Md!a} zPVy92!~7kzb%aMmoUw}Uay3Dr82=n+-MNE<62;$tJ$+4rP8|oG+xE%qF@MI`aY>kZM z*}UrE+@YQhIkQi8fQ^u-4hX|=I%QdA7!I7woNdW#t=yWL*`33O*avQCJH>i7}-mGM#(*#F?&=YO*e?%zbBh|dtV(i z^}10auV;z}vk9||^K@Ybu(ujXpVdesIcr6a_^z{ro}C@utLixCiOn*21r_080M>}Y z&#gJ3)EF>qTTfA$YV#@5(o%pXT>atsi=0;ArJofD1O0ycOg+c&N&>#7_Rpbj?Yn7w z1D-VZqah$$5HTvz8uD?v%61txbOC`gIvnYpG{}10!*veihLPRCJ+=K%U9fHc^+Pj3 zO}Gm)9$I7wS+E3-Wh7rq%}U8x8+9eSu<*tfVm84^c<-9F3ZU{mG-eY@*VD$8RqPln zuIXK*Iyi=3$%>*7smbP6R$cRSV*)$6!`WVc?QNw5WHc=vSOBGCl!TDIvm1Kwc4AfT}^Ki|>W`9q^@HsA(hm8=Gj z0~*Vw>8L{BMepAXl}^9BaQ1YHjt1@>7~()17Ww`)Y4uX%V!?AWcsReSC`G5aYtO-)T}YifSm{|FZ6I)#~0c zY6$POv@XJ0r)@kG(K+`tI(tae@BMkAI94gMhn(?Ut>#;D6=hJhYtV}1ReHDYBFdx9;xLwFJvO{l2grVno>z$5I> zZ!@M|0G5x@?B8oR9iI&YGT@?h=wlhZ)9M~n_UzQvd$oQ?CDZqS6tPNTB&7~=@_R0N zh4DeQ)YFcFklrl8cujsLn!__nnJ+bM+0&qk4Jzn?!0w@ES~xb`oV)xD=5ryZka*-i zT#6Z7s`6}?N)oV22pqVXCf3OZrltW1+A!4?+jvbuTun`F*WEjISs?!@pE$9;e}MfP z)My5u-}b4PieXQ?+xZx9g^6BFvBhy~Y%(b&( zhK7RK^4|=?2oyk{!%nB3Z7Z5~VP~(e8$B1&^Z2%MC-_}gW0z4{s(1~)xW$|TJbSP-Bk z3f%Jh>l2(WBQz*U<%mvu$uO)E6V2}K^_YHKa<=**tV@^XMsz+Qm}WD;~QY5;gb-fl?0CEZI&`Yad#nkuj; zE_xtF2g!>>O;lrmVrGxB@6N*aoVzQ&p$bc%%mmtT`t+*(r|D%now!=JfXhSyYXIwv zarb(R!Gr}1;0cR58dw@Bu78TQ%y|Qs*kLa#BeOoysNDGZ6=^OKmev)`+)lc^hq7kd z8e-k)?0OuZtwZ^>*n#k;$bGPbo zD6O_EGJ_LN2%4-n_33X(h!jpa)>ndezL4xCk4uJHTQ$VF+R0CGP_zNF3_E2pKfrr% z4&dF!;x%QGV=mCc#~XVNuhE4COOKi{MbGg+=6r0%r>O?4C>OqJ`Bwz!nxJBe4qieT z!cF1G@Lo&OD%l0cBhE&Padp+ivC*83Zm|{Tl41|Gtt*j}I(J!Lr6heYEX%;j+xs;y z6Kxo1&|tW%ASW))6s2}q(YLIss-5q2ETxl(p~W*`xDi0ez!PEwNVM{r!TE<}fyU!Xs>Wfv-3oRl&h zEy5o?dIZW$ZI^4C4pm#^UyjZ3L?2n-;{hHZ3KZgWt|mzIg+mc}VNt!_Lo)ObdD9ZJ zodYaT$$v1<4DO($3ZwSXAUOT<=v|w&tJH1#+(r=Ym;(|FBU-iCelOd(%uPw@^Ts-+ z4PEKnfXd0}GNk0Jgd6y_9i4Cq_`m&`oRG9`MTln3gNLx{WH20_ukFEwlsYyln@POJdGfv z@fIsG+LB;Y0Im7vnW2OY4t2xksg2fFs>VU`cGRG>t8!M1wU`g!fA?mA(|C8gufLxt zO2BL7Mz;tqpJRV%b29ha>IgD!wj_S}eT%IGOH{Ak0>JbJFt(VM4BsV@O>ZahZ`|jC z7^DxsvOW)*5I1s7>|Wm|Zy!8=eoD9hE79yDdstMCt&!x4wdcD<@$q&hLl|4Mnjp}7 zknGpQ3n93H(mf}_X*6VFchWh(w_W#UL6sQU`0900bIXGx|YdJAdBzF_3RrU&CI|kDCs(Jo9TzmzkZm3R9Tm92FN1>bqkUJuN=6X^}21ns{G>0+8E4= z5uD@9^DhGfCQ{s1NMzO+=x{&L$!b3#J&l`aG5=k^qTM*rSYDpgVQk=4%KfH$;U7)nSq?}LlY-LGkdZr5+{cq4j7mov{|Wl~9w9k2;WV6_ zoXUSUUxGgWq$GBeR%S!6>~qz~ztYNOQ%71`i>~SH+LwSx@U9v#_??~4m(;Uv zml?o-Nm-vGe8>WxdDyiA7|OeqrKM@VP9{Te>2bt74{9`kWkX#lLAiSoRuuKiU*a%= zkuPAyjxPc2>gDM{u|eTa3C1jYBDNT&$Cd z?mvNHz75W&kGzl;=H`;JDjp!+&|Ceq8V;a?N=6v`{m{?Z{>8G_o<|><8JOEQ&J6Vv zsMkg-fz!W{*0n{1BCc^n^-7Ppa$N!WgJ#bz&nT-C6;~0C7=Uz{Xy_Rj)-HOlbr8N? zjg*A*|ChyNXn2j|d;&U^GAkp!pgo5rnlEkdBF)*aeY#%{)vczfwQ*mA z#nbha8~lV%P6uGwWLX0a(UUpTklxF|0htr)J?n61VG4p4#6b~w^f)XWg+vP~zsA^T z-7e=(K;%cY3m-HS2E~kjjBj)>K+><#hbN=8$@4J64*i#j zj)cn2&TmFmXHU~f2cM^YVJEntF6Mjty5Cgp$(NO5m%4RS-xR5NZDFI?^+)g6f5bA{ z^I1msKRohLZi`_Q%2iE19eTENAIbC~0V#4$ZDH>AAU6v8nZWc0rQ4I>tV61KvORBk z#Zm?wnz8BFv&Am6F$=6b3vcnb5^lMME+k&cD-!#*>wN3G&qN?_-!ji&F<()E5{q%bO)QNJ4?9u zzgn&UGs!Fp@rgKcUTR*)qTfiWdKJ&V=V!yJw(e;?$#USLTCds@nJ2ySeg?70ARB23 z5-=7nij5A;qI{I?6qpojzT;wOCRn-nmt9F!x<)G&KHw{#zV#tAT`%HN*pv8))8m}M z8;TDcF9x}UlT->lQuBZVRnTx6^(^=)m<@|Ndw%dqa#XXIaNV0K>MoE8DKIVehDy>C zWv?XWmH+0kq}YqGX$HAyS;J5&UGKpCj=)zZsfXp}>V`Bd!r{YFc&w32*O^yy;_uK% zt}Auslr6{?O6xxmx$==i-8w@o1;h7NM@4Y@v7#5N=%vF$$lIDkqZnN^wONh$p)o60 z#VF1jwPN3v_9`x^&(V;uR^B5oPbE{TFUEt-KMXF{+|yE&eX;kwNoSi8UbXngD+(um zbc^JT`FrsyQX}uyiRzQtmG#q^++aM`d(m9B2$avE0`n#|<(GK(7`pJgt42XVsYcGQ ztLV62Ta52O}zL7)IeTAT6JbgXKF6_rUguZ#TlMBmPA4z2Ao;zyIpQqUi*17*D=G`!~w zm>c*$eW0$=OEjvhznC2U>wWpS6{?3j*6wA-^xL22uJTbs6Z@WCiwg=@!_$8%vHmV+ z016*E*|LJ)^?aPHU-DXjf!LAxS85{rrCv?YbqaD?x)v=MXD4u$dI}6m8cxsV3$j~x zqPv$}eREj?IscFnt=Dui*B%%$7M2f~Yx$J?CxG1(AYT_2MUj2tl==$7IwXP4qtBaZ zFz555Ebty{k_SS!;)tbBb^6&jjX7z zAA49HP6UA+JUaX5!}@^Zn)!jc8reYAsk%90ablh`4%&FMMS394^|CE+bezNduA$WB zm;MvVUQL2nBg&&i+n(^WMP)n5r0HHwQ0UR^FT?mrrmw87j)64Z>HHEWaDcD%@>Q71 z%x@%-ZMed1su~*pjy`S#fz*wF$(-X&zQ0vN?kataZyMdVCQ%Gjm&hwOH&Q4?3yw|r`>_7UQ0k`c zJrNH%9$%C>ll4u`6I90X>b)ajW=K)=jGPa?T6&OxX|&#dD4lCuIy_s03Fw-*I~@Xt zleYXPDljU>`%7^cR>KUkXz+%X)sXT{$QRDGiq-7)erUN)LYb%4pywMX0t{7riU`4s z;?cT2xBY{2ojcXD(5dDHi|+F^MQCL67mk~z=XWnajFXpZ;%3gO+zAf;qMrZ-E6bId z#r?^wE?V{(KVrZ*PVW9Wnun8;j55eS>r!Xx_N9!g?)>v+Qo0w2y=or~p1fhxs!ypD z)TAl-7B1$TDym$Xcx6MEg(W2~F^?yCLUUE1_;Hl}Qu0coPCVW?#>OrEy|g zK_FCsew3iwpE%!feShjHCA_YoCyL+D)^Z+|Y0Fx!QKk7Wa&ErU00%YdME4~)PPj2O z_*gPA3pxAl#XZ{i@XtW{q$EPy2|8LS?>;DvfZq8&DP8=n*Wx6}LJ!=V(tg_YIV*e` zB2_-_iYAluWf_G%DN9Pi$2d9Bh!yQ48ft^Q>fDupmP-a&z1gPxYCs-=+w}g1q7^6` zK;oSR3lUu517u-Qto-YbI{}~HUY?YX?}JCHGC3EYyd9eyI(A0Zp2I zN!>2#X+x_8pYdiDR-Whix%^$cI!~s3v4!PipO7Yg?Rx=9*P>NF$Thsa$2dg@yIoaY=o}IUt-$apzI8NwN1K%ESYIee6>@zv z>k{Q6W^XI$GZ&Fg>!Q66D-1KLw|;DAH?yM7?5H;8OizSG2Q&ICZOjNEK*E)$4Ug_}Ff?RCre5sh z7yOTA1^%pjqmmKwQ#wTl96b)Yyc^m6DxCatTcHwDJGjiQ{@qmuGb*Edk7i0v506%} zAN5QXElQr$$Y9pGd($?r-x-hg$#6stEbm$l>h`(%%Czzf@{eKtwbrJ!Jc;`%& z;mD;?I{a&RSU|8}3RUm>^I`d;iH7t%5n&{ox&k^;7`t^Tlu6z2TXA5o`L-6eq1Qa$ zSw2MvWEJt~a`V_Tk~F6U;~kNy4hbFB2T!W76ickx^#0{4<3CXeCv7Vf(T%R|xyk@k zlII+51EcsMRhl*48^R<|$WiDqH8J67o6->F%YkX(?4`IjrI~NVfdu=*Q2=AQx9dy_ z)D7JoF{_&c`1L>98BR2rrvV_jb|YFa_s2wGA-meHuN93Aa=>1)1XH^*r64CKPML+zN1ZoIyf?ArLAC%6A0J$juvDyhfUv#3BGfH7Xu-ECmG? z5IcgT*|vVO&`mx?-<{u^Gc68s=REPJsvH0&XFA*HRqNGw_|c@`0@azd9;jdj8F9Bw zm^t2t%aCpN&+*m_9=$oGJ7e&laocO{ z6X=eVIRi2NFM~X@DMwEvZptB8l=!3U;3UbJ$V6cIB0^+jRAhAaq)We)Za@4n(1VK6 zimu|h#9alko^2^H^Xu0WI?gWB6yp(UARV>tSsUX8fn57S_~cOP?8I9mZGG~^KZEB1 zIHzTWnFW|t_s!ITgHR^5uVMUN++E7|x@qRBWz1cybzhSY9=N}r^U3-CT1;YU>!KQ4 z_*Bl_mmKS$mU#z{E*)NRliv*kF7h`Y^<~~%-Wl6C*0?TIDZwIXUWpV7WDED7kfpZ+ z@#Ar;DFA*j>f$#N+_8}~yzd|e$cA<0z`u2TEg=DbPY%|G#4}~T8E=*_xyJhFuMp3h zPj#fgt-J3MjkJj3^67C**>gV`_x5MxL>WH?71%2H?Y$^o1JU&n2jq^>Ms zePNfZ858Y6s#1$UjPLQZ?XQh3GyW-T?R1w))wycJHD2|ExPM$;UM>!tH{g;hE&UEA ze@`4lcL|5O@qo)7G!ERg9Q5CqJS8Rz&tBMDwGcx!?D+GsPbJ-qS^$F*Vl}SN6T$iJ z_$unWITiHr;>$J=p|KWK8C~`1R!jjFenjr>jx*AtX-a>C#3w~*-jx<4^X=#1@7rYn zgaE3Mj8q}Rt{m#|1M(RQ$law(Q- z{T^$Z#N+oGYW<5pDlnHB+@;j}hXY+PT@E(|zQ%BhaReqVohQ1LEIzGAUXEkvo7|KZrSLkWkuIsRG&i}TZP28H93m>V#u*R?dDMmHU zCwRxIqRlUa6OWJmbANPpYB8M!)~w*nSM;l7&Ds6c={rfs8$?Fssn6*}h%p zx4*W!zOL-EHM>6%D5gwfx@N`%+?8JbGjccY8h^`Wp!CvUQ=qwBky#Pcf2W8MKus)B zD1F>4n0W;3H_lF}B3a+XH+eulTCnX&bT$_~)%EMw)eXx=SHTD1d;ShZ9cy+ z^LO@v-}Y}_Ifp0BEI>Yx$c2ssVf_pRfo#6Oqs^ueY9K=J9U599gC386RY|1iM7Dca z1$fKx)D)4@v(?<)+#aMl7_up!9Nlc3m8?D?7xnw@_dE{tW0awKwlDVcurctIMLC>G zpv&Wxr#z)9`K3Q!KU2xSX6Ue*&{(=C_Tz~7)Aadn;{Y+Re)?h-Ne*O;7>wA$AP|(` zpWA;1yec^?rr3mw&o1ox#^^#IkiqXADrP3nhl1DueV{TSj+oBtc`PUwHLstfP^S8Lr8ZI-Q6*W5aNybW8Z4KY?B6WJ>&QSBKRRA;QQwdqorB>&SSAW%d2x!ce8qrdh_N~ zhq_Ed;=vvZgL>4#OGN@_XJ?c5lhrw=5S*EpF~7WpFU6WKynARFkWTJapDrDE-DFY2 z@3G=P&&YG5U{I*>;28Lc@ z?gvY4bycz@$|Ey#K0(`=_>`0-K~C~;#-pJ1Gj)QYAyq@Y28V-@XI@xp$Zjg`1G(zH zzND>A=h715Hln%S96#5 zIQNqz-0X51BMk{7P?z)EA&5c56PC)7p*4OmMHIx66ag(4K1*G^F-fRBGIRIfYtnbn zY}sMJO&cG-2Nps{;J21DF-Rt1|DBHn+a-OlJ%m_5ux7VFN|~F3F%{Kc;@*=jj%eM* zb8&P$_+~6z+eW6VaQSwe7>15G^bZJd?GnDY{#kC4CphGxA#{;QgL3;bO?7Gwg7WcM z7O9{cI1zBA1Z<*YvVP0QOioMnGJ3Vtf2W%=red#)W{vi1#`5K34zUijnb-VczJuCc ziiKY&ruMT_OZLG4*#WkZ}EQzK?5aaCy6IXM_gy8$SO6 z#rr!YU1<+Tbm03>9Ni=~-`;fVj+;AB{p45Puh-~oHbKDM`I@l!=Z=Pb=oXg03kpzP zN*dj9mi@QbKksPSDH2%k&@13y$lJVmk$k;T;N4q7dggKkh_m7GmS`^RrqIj}TVse^ zd_(b6YHx4vB`J2Cw7SFQ@T+1(?)*Iz;lH6UdzjSNbN8O$+LMk`vVsQ+LQxNPg@(?* zPXfB$!5eB%bw3KHjzW=;m{?3!5ovJJZgID_lv#UgIHNh;3q1%S;KKMf+V}PV z7|}yOhe^RKcR5h`g!xEyIq)+Q#RhTXc%p&>K! zI}bw}2e=Q3iHQ#;K~9)Qga54~OP7RwT(J4hR@|?AUw=3=ZQ@7k)2h;*#gWF#-R`E2 zGhKdG;+QM{#@%fK?q38N({>^q9^VGal%OByP-#sz|90b}yX^-P2(gtA=B(sadJx$z z&{TtfdWoE#{}#0|m485>pb}YQvetS`fJYDB-BX_nO>46F@6!$7({?CZT!0^-OP|-U zF4r4(N4oEs+zmGB7211LqhfFjk$YlWwVBoQaFLMyicEZMtg=eCMg_eHu_606h+15o z65{*Qlp{|Rtc<}0N@ zbDguvbLNnEW+JHyTQ>rauX`(+H%W%?SPTjBzs!ICGVn!!`Y|$#JzU;k@S2ze8$ctC z61l(A&K2W=p9$8KW=DsIpPX%RAw(Z!ot#Rod}t+LctI{qK8Oi1qvQMK*chPu2vCh^ z&;;8K)A)AD7mK_HOaQo0`1oj*6t2Yn9jrwpyt;ariu>E`{}5sr8K&|7XQ@Bh<2t`` z_>HseJfiE?LpTi#%DzC`V*MvRJJLwB9C|U!FG%9MnS(9__GSO=9VQr7JcbwBScq*l zV1FAM>sti{fSGtZ@0O&{dM3>N`xXSEciP#sO|fz-@LNBX@(_5Vo}Pj(GIxKtl@U+Z zJxM4H)h}^%RvyhWSG;ncE;+OQ?>iD&Q9qd93t`8RY;iUxzn2=pf8_2=y;vC-{I&2Z zV2$U0CIe~}U!=lpVOGAC#&M67Ds_mhMiT$eqenY+!p@_IUjL2f<3pgAYZA>GB5Q0U z)}5GQNgwKoP4-#=nFaU|B;>!H{=(C^eW@&diXxI#*-xNZTcYwGoPw0xFv;1qA+YG* z`|WYBS#Hh-ZhE-YW0Lp#Q0q4Zs{JYRf~#~oxBeD*aD&pm!UPa15DM0C=Y`4LU7i{( zHBrZ$D(fKUOfJ+ELkgETpp2a_^SWfl4 z7`HVZAqCauw$42N`?+snPrAwx6AW4@T#;yas|!E5)gz${WvVj>i+`8~qI2q^WIy7# za?RP+P(<>FQS;1uzBJqT z5E9Y@Y)SKe#;3oN+9^{@LV!5|wV_w$jh11eee*K#|7M$O#EoEmr`;OsAyc?Fv3mDwNs-|30(ajWqH$dJ#j+-kQy`2Qz_ zm;1p0j*z{Y9Vj2w`R@4%_zV|?Eyc#Kv%ayhQ1c&7iCY3`OS%eb(6&b-caRKH zpc?{33+hzzAD)t+dc|icJO0lYKTQ!wpGRL~4dI*)!xW?7orfBa18L@CTZ|FVd9-V) z$-v-GW3tO-KP}xy9D0(vkHnYOG|$ieX}BGtJAF{xtc71U9VT`XZ&^j)?-&aXin*4* ztk8Vy{mfSJ5g4ErC$zI3e`fV~u2lciXAny(cT|fLQt25_)1UiU{>A1*G-L<%^Z z37(xsYx|~ngQ6$J4GoF2_x`=EbTow*E&nCj>g}_nhVmR~zXuPOuOu%B`X=YU5z-0^ zJ5pNP|9cbU&Q*z0w?;xKf7EHOsL23?Z8?^cU!eUA0&qyeO#*Ejra;nO&MAYt2q=RD z9>cmvH9-7Q;G2{4FC1uS>WC`a{yTgN7-4iFY1UKALdMbWB^s1NgA}RKY`}mv*7|KF z4}On~?8z;K6G|d8I|j3wn?>DYQgT+dG9V1^LS16G&dvhpq#Cl~DU(OW*@63yKFj6q!76K0m*5LPa{^ z`TeKuO1*)pc_s<@Bm;5$W-pX;jVASo)$WwmZ<*pzwRZqK6N67k$o~8gZL&YOxX6Th z@|G0wbLQvF4l}BI*=>cUJ~MTt_kVhmYayke`qZ9i3c1 z3a+a|MX#<1w%eokLG~skqn#I<6`XYqB2cGGn?2{_tJ$pH^dQhI1tmL0GOPOCp+qs} zkZ3_=`~-YfrE-T7ySx%x{hRt6>C|dO4E&9rd(+98d8*=-K0fhZNM`jNERla4XJ%N? zz-Q=`S8|j+{(?gf6U3Tp@yi!hWx$Xq ztK+2rL!u)>9Nh5YBz+-Z)8b+FhzMn~78?$b5Ah@QTSsM@3Rz67;4?qVvZ_CGQ#Cclw5Y)x2m=9pvAuaB*oz0E#95V|`7%R1RX4 zM;pA3&-<^lw`^xVo`wL1=EVmLs}`Uj>weJkJF#Zx!^6(4z{Q&>Dt2`hVtQ>+@~lFp=&=4!}|r z+*UFW(zk&_GE@#=oMS(4?OGlYvE*+Yf52#TRzmnRSO3+N7H@64tPkXx91=f6yUYAqF0nQ`clv8fN zqe$=#)QVyMUidE-MxA`M>{n5X650g{^Y>^ncYYyLX=^iz8b=bnBy8Lv#wT`|pj}^C zK%o$v+h6Bqu@)9$M+?V0OX{)jz>3G%b~3TcS|JO@J$E_mt2Ph@+hdH?XLF{a29 z9UY0v0!3zqpEwjga#8XZ(}j9h{)bZ~+eGSGygza+5yYi)> zUyJ}MjV-?6LnYTWF65G9JtYtrtIjz55ox z-5x)fMnL&+46AyJ-FBuNjUB5Jdrn>sNcLPE}KgAw{kg~ zH}zsm^~y4QZ$fmcOAJ!0$ZJsD4D!`Ub&+C7j&Rzh8p`a|)PYOMLBFQdrmd~9IJ^2E z<%tMtc^o~A2&(HB)gFnhxO$6z7gdDeBgT*|3tK~|)M^o~&_>~$K|+Dd)Psi$y}eH+ zt3{p(2}wYupfAzL7jsH!YScu5IBzx*SwRp5fI$^CBPfZO#q9b_V#dcJo_ZlxKV7*2 z{2Z>(p>QAv4R}vf(hmEx@a{lhKP8bLVv?`6a8!EYxYi0{;J70862BM&w`Owy z#CQc&3`TQ=LPKfQ;CgaV@Kt%PnuYi=0EInxk}lc~&&}Ui_+o(`i_+-PG&x>6>$)*NZYD*Swot-Kmx%FT@6#n}uJTsJMOlVQ(D{f6X1Tjw;f@jRvJL{3A8^PgKjx zIY_nHaqX3v7@ny9S_NpP-r*W?9^4OeqG|97WbrO6T5A;3h3auoLq zQY3QK-175(=IH^cnK_NujLU9AIDhQCO~T|0Xlu z@4~Ut?{Rg9mg$pg|4~`@?zd-b0zWzXpvhEz=y7FY0dWq+15d0beUxF2C ztwEU=EFeA24FollgH#JnA&_Tq$!9>Isz>> zh0KXSGf}ZijNLiobf)-{Y-9T!e~+U_V4|HHd?j=xgn~lP3$4zY+WIHN8cqlYdVcC{ z4O>k5&aG{)xKF>mO|O+)Squ#5jj0%-<|G(`)bmP)kuI;nrLu&^W~_7c;Kp92Zm2cBg%a5$HMArta2YSR~ zdG=uS9vjSqYxIn9?T*!_vzDS`L-`VK=4vU219`{q0Z_&g7>qw{b9rKR%KDSB@6@$f zBx{|QSX8Sl!9(qnpYhj@Hw01q0DqmVu^lZ*yCRGmIo7Dl&P*rW(BNkE^|*}eK;(Mq zH+hAR?{Yu15G|XB>LNKxI6F%Zk-*!=@!Q|clD3uD-5x$YzHXP z)(O5Vw3_x>5kM_Q2)fVA#bOr1T<`$I6KitYz>%Z85RlM*xZG>;Dpsqqa`Si7$t+(K z1Q}VJ5?vVVpfBWwHWrroz_QnM{^6ny7pzae^flHsyL@IpKVEI{HC*wJdC5m7DvFeBNh+%UIE6Ury{=_=y{Q6%gb(ie|p^|*mz# z%RyEfCuIq`Gvq0#TmVXbhn2rh^!h6GX3hBKAqsykOOe=fVo!hZIcN@nt3J+}MFN3A zqvQ>&J_PGN`)(h+5OYXl*WQVz_s89>sG+U0*n4Dgm_^R`QnIwMjT^vF9zU<*(n}BB zzx?4>VB`5|!66q)C$BY{^(iCcPNGYh_Mi4ARn^4|NFa~`a+gXAo_G^Dbd)I|@- zWo&57a!|Pavykbg`iPRnW~ApED2HOvV&8>7xokf_Z9;q;J#wI0x%%VDK?C&AV8df` zvLAK&X?qX~<#)H-ekZ_X$nO@10s7ikER(4k0bl*ZB%?Tl0DOBK;PH7f^)2zUfK^FWcUQVhwQ#cJ+QM=v$NefL+8 za3>MlKqH>_&$rKiMu%6WeRuzEP_aaNttE{9?-A>EKKJycSomSxmp(O`scLZHi+ zez|GnBoNmh_E`xJ#Qw!a?PgHksDZ=Oq(`YRsecLHnNeEU(9lp+6ar63OkCJ|jv6O) z;{*0L#UN{MZ_~*}cKJzZh%r#u#7ml>4oI6~rbl@11FO_HgA0@;!bLCko2tPc6`H)4 z5eml(+Fh{-3w(U(TCL2YBJ1h;JB(7VrKQObU%l?+!vOtwe?<}-M4U%#xlzX5Rw)BV z*dQ24yX0;d_#Dmr;i4M}9?_@bIz0NTqk|-19D)X&b1xNVDzBak1PD?OkfnUF``WPH3(#f^ij%7lmFTih*=AM@3sMz*QN-) z&lld*apJ&nn{d4{>#!Xgbvpnjs(=}XLZ9i?*e`qmDoHfD^=LHWzgoq#{{LW?PA&hg zj>GThjX)7nV@L0dPzI**9|pGCJka_N7UzaJVs+lzRo|)rFYYBl^q-)8G_uL-nI!w; zU|K?{-TKPpvo?9IPgM_o|6VsKr;n~rR+w$}h=tqCG`js+9}Y8ndSN2e*rov@(P}lk zY%`2&K8^9J^mbY1bVb&jzvyF|Et{jz`TAUOzp!yY z1|;k2>&Khp#^=7e^BAb7BYRKOc(1M6YdGfefV#-v#FIY2b^l0JepO=oeTW{=T;+gP zuK#3r8QEo*{Z{+&mfCJ@43!PlKXIyEF1^-ey(0+$;Wj9pG;6at#ksoKeoTKFsgagx z*hmvsxIQ`_#Vs9(`$oerA?)_q^-dW z=I7rw21q5de1`fwuHGCaLe=un;PP}k34nDOQMH4o`>0>xbEFU*aKSy>O?1+nglWa9 z?09mU=*;DBIk9W6A8b*g*yNt;C*0^@R8(Fj6tP!~_iX{7QeR=82TKlXyb7GBhn=Cn z^IXc?>>$$cfP9SG^;hVyr~R)Npem44l@}k#%u1HUSyC&H_Q-p@=(Qf!nSp_m;_%+s zf#!-m(n-NbM@RN7EAIk@_XU@Q4FZ5#(BE3T4gx`XHi(_G(seth>F<(5vVrX$8~nvw z#-Fd=-T|!QtBz^#s!MTND?}{7Z6yn}ET^NJn2-RM$uGEQEa=W(Dk5L%jSKc>=Kqc% zJ^%#Ti&n*pj=5^;2+{@JvWS_sAjaFG+yMPo*!9~pmrqeaF^odag0_OXe*iqhV7fZb_2%b0605cVdZ8NcGG=->%{KSH)v3CImNIo9egG%wDZmwD~u!sJiHq6N>FFeng zP&&9@VObn{zNy1V!)E413D}}xf8B+;jgNI+JscFX(Qa0wOT$BC) zT*Q(zAW}}DeLjKm042Oax?52WJ}$_}f*arCEv%*3vn#}p>RWW6y~_I383(s;a*Fa) z{xwszH?zBHgX04;rD9jMtcw^;Cnbf1jJ~mhd{Y^uQyUyg{ni_F3CDayPyIhh2Isp# zYaC6fm#x*)7H?9~0dZ&}w#YS4UnX);Qa2g9G9IwvL;I(I&Dv$-lR?@Wn4i~>Lh|R8 z&;g`O{#i28i;U!(xMqqf9YpM2mLS5w9mz_!;>k8GrlEOY6(i6R8Ga(L%L z+m>PNQ!9uWmJjb7R)WRi^CqB(m+yTYpDMpQ-kB}A8M&q>R}qz#NoR$25&So3`WNuD z6wmSljX+jC-Y4z!p}I4$MaQ1XqtqK}z&MnWa8YlW!)4-@VL(W~v9WO=M82wd9?nV) z#M3&unsvH`i|$CZaiD-R9X|~Z3;f%E!0u1^t@IQt>3Kr0iok|RoZ#d+l1WHj#8)rP zy6b+Q|%RVYZ*qD{f7jB9?E zx}EP7uDj~)Y(oH0C)&)~$YfPUA3L4rWy$q(8#V*G-I}bKlsConvC7=lDSGL0}A?~ zE1|V7+NBOizYwoVLKt-1&h|s3f|xhfEsPo-37-(XV+N&3zJjm|X|gK-;n-&hCfK*& zP(v>JcPERB(A)eGcJ``*;9<#sM=&d`(KNpzH5(*10?1r*&`cj6uMeU9^#hjhjH2L*k41Y7aY5|* z-_uFYQaGGlU2pWxgiwJ{v?Q-vUfELvC$gmeA9aa|iDy}9?5qls^rYll7*h1e5)%h# znf-g=j-}W>MZwPQRyLNrG?-=VvcJ zIAn=<9M`I!e{@+cv_w|2)dNCrVn~<+>I3u&n65&>VStkg=0Q%H1Lc-fPBC)CeV{y5 zpOK%+-sP-b^?|kse&|X#t57&+DIQmH3Q*(=c#fxMG|{c`l_Kyw9X-QKp4YKC z_DYzp4#_&q=Y++s63S}x)akBeaUMG=^9S=lT+CeKPIDdj`H zXp28QwotiafAXxWuIRo!`>S`0muCYdUeWhx95qIYbORzFK2}O9xzOr5l}p9>!xuH1 zYN)}RqXpY1^hmv9>0Q#Cu9l6^Krnzs=mH#I8Css#$0 z3Ed%6M!?@?jub$lMj}jX{z3ugq->ex=^`gHK46jT~n*4vz2ii@Zcp(I!5d zjStFSSK%%(kYIq4hG*tOO=p!Kr?Ur z$c};np){)tlKs{~ChAbm_wu%uXmW;wm%~)c{VzJq)SY1`habqX!(~wKq9B8_HQ)-5 z=!Rf$!-U{H)ao~*HfL(}riNXONj?MgeCg?acD}+3IgtdZvLEwBnYAA1p&G>eSfi#p z*m$Y8v{LasT!wk#8EQD=UO|HW9oVCyl3u5{n!H-p_5m_;BN^ohN1<&ZAWF*)HK4pd zE-lBZjhQR6{S{~_d3pOZn)lNtu6H!v*8Wl!L@ur901MAAC@8q?=)`LG`ad)-q`iW9 zYZiAKB>^=y|EsTGvRPi&DUz2g@Tv1{ww1M4;3Ae)Gqok?CVyNc(aGdL(Edn0G-~4_ za)h(4U`&?_%MN8&VenPTDPS|MON`M@?0P`k-oDYI-wxwIDK(WtU8(#F=%?y zrBtB6`$Vnj^67OyONLv-vAim&egmN-kc`~ka<=5E89v_c@$&kU!iH=hAf8aI=Wv`n z7A-@g_Wi$59q5Z2C$OEiFw?`>y5jZvKDLeV?C6Jg4*DhQy}rL}-8F_yMJ1I8#y@_- z`Bxn6({&M#L_du!JO7*+kFTKV5I!9SJ?;q&4J`rMQ4O7kZ;SnEX_-eqx2;5{6Au&w z@pl=22^EXW+J@5=4!@}_)Y;5Z+Ak+TputPnpFJfu1^c|emvW@BkVvVMc9wpZgi3u_ zjM}s3CPkQS%-wmZBtlvik{>j7z%iftyrZ~?!qaYz#aPXpkr`JfVDsL<-JstYJjItJ z9cG2Lh3bNbH0n*6tmlQ{2w*ClQ zj8|+$23fI>7)`dxEaJuzi?%tj{ozxg4}4EU`u6! z+xeS*BpgOPv|;kLF@oZU)6Q_Mg&uv7)HfNmA0?kvDK1+G@~G9H%=?U)p?-;8(FcvH zv@dsPfUbI~)-VnKU@=%-bv#REm4+%KgITK&y4@O|-}t?eineDTQIYs)(QG(#-&ntM z3E;XSNQ-EDi=>mEV1Kubdu;foyu!;XZ+V4H+&TpqplDL@quoXQlqUEGo0*;>ZjZO) zDLBW#foh>Fp2Z~kCbK?WbD9_;stpeZd*!j}k?Fk65iY3E)eDMUCz_Ki-N$#{-KsLFLDL^*QiL_J?Sdu( zaJtt3b@jTic4-C`lubdMSY238rH@ivTB2tzvSrs3=Kk|=vAGuML6Lew_C1eZGuTVi z=H(0a5@Ct>bkWOKMkwde(i&Xn>!GqQk zwGfguuPR$D@(6*;^@si*(QuP!8@$7t;VBMPlvNCdr^T@?)~Z8uPn(oTz7BWb3dK_H zpICuF2I>@H$OKC_baA_%GlMEad7(RKCTM_FFvH}w45pk|)@sn8V8VOM4V5rEXRx$= zV_CwY%K&D05!oBT#itLE?L~fMi>(kU9KLUubTIGRSFTlQr_e|i@{PNnx3~Y%l!u&@ zvY7JZbwzwuwQCh+>$+uCyM`t2xJ$8mL{UU$bdl7ZKQOM9m&#omzDPZ#s4CI_M>BUd6{2D z`MMzmInXBMRaL_oM9*v7XZbl5V9eZ4^or$;f+Jz0#`lf$O1f){^FQ!|9;)SaJXjhD zoTr@LOXN@sd7D`* z4P8m2w8raKK;!xYsc^V~VVvnE!#dN8@Lo!LPak}|Pe*cAai;kMmAp>3Xh4` z|4_jM98)h`o&8v>q$r|NhGa0`J%|u3^5g4`8XQZoL4}_2EKzD*= z|5EMP`yeKvPkHt#<(X9#AaVF^M~vuL(!^yaPUu$~&Ke3u;kl`3d4qWkcAyjSZBw~u zru`tPM3~e-EkWnjR9p4HMpJ?#l^uKru~o%d#YIQGWc&0ku+%x~m?-9vCSx%}G0d zUw4H|8p`nEF@j{kygr1hL!4GCK^6B%8Wa|~CQS6POOzu|AX|2XQVI=6{#gASi!Qa% zw$Uyi;+v)(x_{DjSeU|%(u^WNu9n*6d3sT*JR|2yMlX$-IEDORe*R`A;x@kebT}Xl zKr=3Z;j1j5*{VJ_$Pj`I3tkdfvc!4x{7>Uh2>kBScc3|Dg}53>lOZ{_o^Jn&O1@&T z>?5csDOjhFvZQJ&iZD_CwOu@UAT&xUVWFvptfND;iErL0E7SS4GwnJ45KaA2%&%eX z^oCShM0q!oQT1^k!$f%(mye=1h?Q}u%WxNN5941e4}NLyf2Cm#6!4}Drz*Q`5p;T; zOPkX6k9Px5;1o@CkeDC8ffdcJl5VeJ zpJn&i)73RgTz1D7SqhGp!~TBwIHCIH{z=kUfb*m3f&rkz0NHt*HJ0}Yv09(My!@i` zUX2u((Uw#}(6;Zw0fzX&fLGSo& zHn6fD`NBcl`(iPk;Ah%XJa4?C#;|k#8aAtAF8|)x&w|iq7}P#6z*Qh|!#H|yjUT1P zrjn=j(#Cs)Ksu>ImdmC7PGBS^WQdXQ;vP_&ISB~wv{oPP>rlh5-uMA)3KsU2kF2Qd z>>^Yy?8HTPVFjuX3Xe)l#gOG`>0{I9kCh=bm9*scl72DtZO=<7!Dhy`d8_?BPJT`6UJ z7Ya>|h*BAjvfzVk;Jnke_m;Rc0@|klh zj_tS~xN^2F5wB8rpTHz{j5CAW(R=U1$QYUVZ#LOtX}Q;4GoRY|7dYzeIBn4?hK7c# z-$*d>rNqjuh)L}7mqiVV!f8q{i9D8FJV7|J6F7swr~Ts?;} z8y`g`8ygesZzIph=-Y-LA?BChA0@x3=?0px@8HeRmR?7GCS#M@oByu27feH~^!npH z4?J6f`fYT|FLJWn@@h38a~>E>1$febYFT zU=ZhVyU*^t)MM^ImS}UZt>7MeTQB(Fk8fPOXoI828^0KvuS>mZ$Fo%I5-&V_X2W^F;L3<)2*5_mdsFDD{L2w4NU&|5%9+Fx#USixIFVT zel(C|JIh*kaasPLJ)b$Z3YJP_3(h)jh!;xeJ(e5Pkv-RyeSlsn^m0bn6s!X*k~LO1 z934EopW}q#^J{Ol3X@K$_P|B`H9rYgJ0>-|G+9!(Mr|hHLA8pkpIke}y0A$+EH_yi za8j#dO*0g|?8-nh{UL%BxU~h;!;U!abw>k{NWt9N#1c?Vm`$!v6jXi}TJUDzjgcbI zEhi0_vGB6)OmN?dLrK(bbb7tP$I@5l+I2!#tb0gnfN_j$RPgJ?lW=yj)h%l)> z8=zW#h2}C6U^~p`K(ipOM~LjlcmW`VHh|@+x6;VM#TB?0cJh<@eTSZ<%q{oVs&z8~ zq$7-nDX*P1u=nxP&Gi+KWV-a9vo|GCsfre+X0ZYfbQ7bJYQ)hu>r6wu3_G>DX+QD9 zE7>z?${SzB2t(Mo0yR*+aDemCsOvM~zAxhbQOcfqP?w|uKZG$Kz?dER6KN#rBRs|| zcUrtf#jXknw+(Q?!K*~yGR6z{qS!dQ=P0{3ECenFdxC$oW>IAf0Qn*b!Ot5VoK(hJ zS~*O0`};P|VV$=g4Hy4oZ~17+;o~^bmJ%*<52n{U`#}j%hJoqnCeI5OFRX#%t;xxW z3E$LLIYVm`6FOd1B&w>amnzTVA9i|9aVb2A!T~P2oekrcLrE%C8>xlZlm@97w67io zh^j|jK=Sm-f#^VN_R(aBu`tQ8W;RsLk@k8wtjh!QIjg=R-mBLbUER?c&w12;rHh`n zJclIsKGj2ay8Tg+32;js`BvwwAsWSrft@70^G)Mb6#lc9FXf@xbt2O!M2KgkwaSrjmEq~Q^j)*j&M8ZXZT&j01Wr?_ zBVpGz#V{U>^TdhF`}6k!TNfN+C=sj@dQbo<-bk}HTd;H_e zX3vXb(vk|-2($^?tMI>g!Ojy#{hY@WxFH3c(^XQk8s&wFTL7n^mQ!1W$f$2Sz0iuu zBhvSdd|srurhj&^?TDW@+!wD)lOt%oV+#9h`a%y~^jS0o=*YApi#@d_XagvA?N8f- zZ0y44uV#|)zI|bn14%GaUj3|~?(S6qc~yxElu$_-nm-N>4Ly*1YvgEkFf+UTj1WRC z5F$)R7FB2khy7*@viYi5 z&1RG-oaBDA;x4grS6harjE|3ayh;mo4m1)++uya3c6p1%xE)BKjJnd1A%2E>Um7RA zY6B1*=hyl22A}3en}%gk`B*`r~_+-KVDh6U#n2l%eRo zVT&5x*C0R{8MINc9>L#v^PhJ-d-i^XF|*_~L-!q{I=Vs6Jp=J!_hfySga6_QWm+wXveu`nL1(GOu#k6?E^xf_4b z3K=0YSFcrb`H-XBA4DTl{zM|}ttLGPxL>G=1WwTV=DKFqYZ6_{P(TkeNo1u62r=R7 z(|m{dJmN{be06m-r9Dxt%K37uDIi$J$1mTJv8eB2LyrCHr6L4igLgNGe-*QLNuM3F z$lEW3;RlB7zpLQ+^769W{Szeef@l4@54f-!C%L1$dn?09EYDAlm0?CRx{$SeAHcK=b(r(k!6E*#H~EP5Mf+{ct-kkIgHO zROH|fAJ9U7s!lWNh#t%$Z@Z?M4y2?Hw?Q70O4KTnQ)ve)CMXXlLN#xh?*n>jLbfhS zDZK05?yhzK>t}$pdUC{XuE51TGJH@gW|OUvQ4;B!6jN$ZJJB8wKi2KAC2_(7THc3g z&5AK0Qu4)}9+mei*|B}_e~ijch;0;-LQ3T1HeXo?Gzr^2T29>C+k5tYWVhgKs@^%s zFrU*g=cBOAATRpk6)QVfcrt;IWyMsNBTyg&&yW>1aa>bMjvyr3eId!)<}xaIUT4@= zOCLyN?hI5`)@regk0pq(!z{xj49uuS;|LJt{0u-;oPsvK z?d;~?#39=U+Lyt$=_ZI6#Jf;dho%oi<5a9ya$K(Z>Z*a|U!h}_|LX;iCof@z!PLED zdt+Q#TKuaUG|sQJXXd#XBxS!1Jd@QcWF=X;fkbfrtr1~Id8Irbc?^VU>{%#&l5MR!k#9|6wC+Vqn` z6n_BmV}YhVc@kJm;D%4ZOWT*1{=L{)hz@22ucbxDfYb#+Y@cS5wWr!(z`0%U25g&)!jo`&U{BTX(MqT|z;w0JZZw)b0S>BaK^Umzfe zJkj>=uWZdKGP{U(*ZHHO%|07aWnBD;C!Pu@1YDBSPnu639DW*gqPqR71SO)^>jXQ^ zEhXoWa2Y38SKHak)k)-BO5RuJ2Q0(G492IAMe-C#;&CE371|*}k!^&x@bk z6qi7d#_1%evPPJT0i{sbcZk#d0UAmmR=75y78OqDb%905JI&a62m!XnCcCw?ia0>w zeFFk@C%}JrVS&hPw#n`f>8-5|(NAhvu6) z@COxu_4kI%x(6AWYkeM+-U~e?^kU?Yx!Lesm*D(B@NV-8e7m zpw(^*xjY`e6gir79Uz+?;;Bz147;-=Vbe2aBIVvIS_IsulU#G6Mb* zUMB8;*~NS58ndN!w~D2Yf8n6WuIG?07SXX_S|}-Q#H|+LVcMj()era?Yq#!29%uOn z7sT`4_bI;&`db~qBuuvwoo6rvpFL~i_R|0^Sq^ieqq4*iSu$-QuN)-Bls&i#NZU5d zQq5m*Dp^qx2qz11Tku)rOlJ67G)MM7zngH~Mo zE!1@thTAu4DJ~~sWHR(CMR|w6&kx5o9X#j z$=rs93znNhvWw4CKqXc)v7{ZncxPIwjek+B(4MzCrWBicd#vSuwCyC-S zhc{dE$-udQET!jZQJ}$ zoaYz0^e?KFJ#d2H+?E9*at?{MIUJH>j;ovNBk%qvythiaTrYT`K~A#tP1aa|?MuUc z3}+p!iU=}^-0Q`lHMMJu=l6Elsrm#PLDeWzft!;RsfN_*4Tk6 zh5bL8zB($(?hAK7noqjB28IUdmWH9bySt@RrMo2s8M;FnR2l@NLAtxU@9Xd0d)E6G zYi126-W|_=_H&w&dz-5L0|(z4a}W$BcI(OfBNZsT^@f*aHoUlUb0+)RC7J$QISU+W z?(+&0J7!*K8D-miNnGqh>)P=<(62+|Qp?~2?<$9~R8RT`+tig!LZj5%w8F1gZJx@4 z|Ju>+VX9yJ=gIhj=l=wRPKr-7p&AC=)MHO179OQo-NaPhh#iTc)JGKxZ`d?)9S66pjur!vCuilq==m{5qQd^*+UN^? zS4lS+!gCATrinW3ygm0nb$aRNqp-K7DlA@XZc=(%Ha!=)=U~$Acl=j+U{}=~8KX$( z167PGeOt)#)##+oxxfr_P{CcSe9@a}-0$IIkn>c|^%u#H`Ac^@@!X zj7n~iWWNFr7F(qkc=7D9Q*y;%_@JV+?0-4yiTX=A=kM<#`-Qq$ZZ{%g2CeVJP&R+;WYGDW^&iS;#D2Y5BFH;XR*BAr72i)H?L z|A^zq`1Pjm#Z1!i>*L&uWWjAMW~U>gv>OriHcX3y_|}l`RYdQCyHsVs z7=-!*uhoDg(f(V_Dnh=zCf z;Gf8ZG~a~TCGq^W2)c#w%~X5TVE+E{4Y}*SXO;=t#|}j3|1SM$VD`~m>ETtarYR)t*mtE z^D&_^c9rF>L>F`Ke|(eBjV%$l96Jv~D+hzl2Ziht7vqkW@6}zr+SwzP?0Ju=-HC4) zrR)3zenmus@Ds=#56z^!5jm8j=vR>+5TFI06&?}Rv&!4*gB|pR`m=C|*f?k~PZHtcs&KVZ(eM(uHGTFdN&Rpo34=&s&d}(DUTM+Q#)bAE3K>i zXdiN{7C`*EVsFo6d1-Y)0C_7SI?aA%fd4O0_Gg;m5rj&;Eo+TVGx&aLiO5)*QN{23 zxE!YX)l$=ZNS#GnQc6iF#@>F5y{pCScUrguA|M~RwqWV!$sw#b+o183KZK4YLtijy7&%ljZLHE zl9g80qCbw~P_tagI;(!7=-L0mQP^(&FVz$J!_WaeikdR^%^@U)X{H(JPW>x#ZjZI? zN$pR?5B}WGBcnKm*DOJNT)JU6Fjx8hKY{_g>P1S15=7>uOTE{;PM3usPR7CB9?-Rk zDy^yll7x#4bQ}gm=xfHG{D4!D8vli-*u<-JlwW~`J{ovRViKs1p~+<(Z#wkSx9H?1 zJth$%LZQ_a0^?H^WknG(kgo1$F3F5kvejjtfu# ze8?}HVD3vN1fY55=wBk6Ee&k$hNuaS^Z6%3X~|&cqHw|p1(1~+yQaH)A={1RVuMWr zXRj4lOjNO(O@9TU?Meqt!?9AGg#h@^X$rHlT4~}J+dOoUzW9bFUkP9*rFJw~Z|Po4 zE=-C2ec$*~Rr9Dfd3N@2bMvWOVKdS2JOr}BE-&Rdb<~rxMhGGPlFovk0p8zs3R3{u zTA5WFnFQbrH8$17qn!5~D=K1W6v{bDU)|B^Us?uzsL0!zeQIrh3`5F*uB@XyOWZ=E z1&g%>eaAq^AuOhB6w+(4y)D13(g-^U&-Sc-x4uBIys>){6TRBpDO+7 z0v|$54pi!ydarFBye5utZ7;rBmI3lpfOHfLCOwiYVJRMpqX5`nTAE~0GeROg-~CgD zAmt|vUCyUdD~~WGReP=@^LN#R5W5K77cvLHb$7dM?!XibGT2SDq3K07QwV$l0tK%G zQ16~v14H60k_?=Qdf2hl^!z+g%nXaYp{61G;%`NWN;sCxT?;-_h?^9j-zw8MR@NFB z7poz(%)b3aLW1fS^PiG& z1LHHe5ci9s&*~f9S$Qd7!O8`BxICJR`?sbtX$%t`x(qeieR!Rw5RlpG#o!EExOv!S z!sux19m{JRN;7EG*(yr6A-z9>@?QV=B5Yd)Ovw(bCNVXkjtNz|?r-ZJiK-dWM~@(e zMmm=r#C<*;i$O3;qN@D`X4QXpQ|adIuEI9(Ruywl@4ga)XkmC~G&@FA6QNW%i3SJU zfAB?ydMIu1gP%7xScg|{ax|MSgVmtepOC21V zC$j+l12<_)#=t}=RxGp;cWLkq1So|kFR1CM*iypQfi72D{V$XHYKAN*-kSJUQ2a{s zthJ|rVH2I1!`3BztvGr0Z&a?QHQt(Ok9Y0uS`{h|^iqUz|*=}s1>M_zhZ7rNxfW%YI~Eod7XXQq0|;IJVf z>CRdnD8_`wZaN&(879%&VSgB-v+1HP$T215z910;)z%F4)RvP}o`rj=p@RUYqZ6x==!R|` zAX^K4FwiCEa9-`|{G$pm7Cx{T);-W6Q5izf(jcpQCwt%2{9+6+2(l5f980`~gjMH$ zkBuD+FcDkOpF*C|u$@lT^*(tzntk$&Wf6;fbRKwJyspsdT+JLwTQL-PYLD7PXP3a6 zc9W9^@cHT&?bGPOC(-P;BUKG$*$wO3L&>uUw=OQqFOnKuW?z#tx{`+iiFgvkKlTvO zVPlUZN6N)ZCxNxNf{O>?=KaAb3;0ous1lC>L+asseYUAWUV@tcStN?vhIxbo9hL5@ zo|$|l8p*nio_!BpJhSnL2QFq>a@c1L`ETxu0X|+G@iIA@HY)cwc0DF;g-KU(*A+ks z%b53jkmJc~I(BjygCFLU6N%tech3F3{D=7O(Eu7z`LLXsT3+lfP%&->4+E@OU0q#u zb#-J!DScWSuSjlupS?m*%?J3FACo&y4OCG(F~Ahk!SeBUiD0F1 zMWDe9L;zIK{)s|F|N6T+UwCPcj*_eM?hE0!fDF&~NDl~DbEIP*vXua+_aL=MS^jS! zWKMJDPV-$AIl89g29R>{78+L2 zR`%X$Y)_*I;4>V4Pc4_l+kb?v0Kl&ZC(-jM`*W@xyMa}0Frg)-+FwH|l$tB`tU+CrQqTpIBZ#-NdM1yw0gCOPwokRqxs?w~QlP=~HI0dd{VL5}A zv04Xk#Cy1Gj+xER$~@S8(wxpolOzrU@G}UqQc+UB=5s$rErYhqOQqJw({!2hN0m$m zj-_{@hR8Vv-{mGpkasXv&{(D1HxL+4HTQ%Z^5DVJX1mAg{Vn^q$Z872l#_q)NatoInfWr%+f)@izBq#7mGZ}%&5NS@0{j;UzOtYafT zeF@%SSHm!rPF9~Po2@L3+JdOJLwH#g^a_2Xu7+jYZV8&8 zh_Q==5FQTp2}VL1T6B!3r86FF*E2uXi``!9q*ZO1lS{pMFqCiqz0@4zzb$Rlzcz%- zWg=Q(q%wIjqtac_E~mQGKBY}=%3L=R5k}0xIP$t2p{+feL;UWKBow_4uAt ztWk{aLxpS9W2Z8O7qG+(gdf9zPz!-|WN;)OGq47N<}G_oq?}SNt&n<(t2dR(yQTyL zpcAr`Zc47_K1)Mb#>`f$KS8davkP!W6CjfkOF&z(LjmIB^XGJw2NxfomaeY6ZCM%M zy?FcfE#Ri}a&oqsx4!`bDe8FO*;2 z>OrG~VpbTPb=4WsNY<*r(BCEGO^{HSQMhPA@t>nm3HPsS%d4~)ZdCNMcFG^2@-^!N` zICM5>GW`!@{Kar_a&_|7`BD=`wPxJGYy+IeKPc^;yg&3Q?96SQ-0trrv|L}j>z+zK zjz>Ce$xWNy*Kx1IfZaG=Z7MxTqscIQULXfVvi=BcrX23Zv~9%*y}GDb+SJw;kmC^6 zHJd(l)&;aqE{RQu{0C1O^6p`pWpFO#H<~5HM^B~&ZyHy&Ep?WA6FmqQfMO4GDAzas zYfw!R7Qg^%akW|k<3Mfc@!?=VeElJ zCfY^S=G z=AWoM4>O93wMKC~R6A?E_jkrP zNpQ`6zOF@(mRFiX=r0PSsR|6+SH!cLaWhE@{&_FPU&_QBj*k8>qpV_|-bMZDn%x)15Or88$mR8&=Gsq@prD zHa6BG_~i2NKizy)0r!#W+tUEFNVjHG7tGbRaMp%aI^WqfMnwp7L{Ujf!EEg5>=&6%c|gEl338- zXs67{*0yc$er50ODZLn2#aeY<+~=rPUKTZ7A!T{~pGSf%ITNt4)kUq<8}By#EMwhc z+EV{sKa~RuUE}!IGNO6=VFl*5#D$?{2!i(k)<+_w-s893VJH)sM>8tM_LC}{ z@Dfac4rfYdblk1q9UL^n?&Rb|%J=em)al?#rjx$vdtnVmbHSrPIH!VyA>x>$<1p6A zQt%F%c{j*9x#(VzY_8i{`1J@Gdsu|8N8L{*_C)7?#U`KPRQKTrO%aQyu4YvAxWmN6vV`?!(PeqipR7L^(Pex~Wsx^ptJ?mdR~>U0;j2o<<+s+bi8;GL?5V#1e-h1d|R| zIi$lwg(<{>UxX>IannV58;kn;Wp>|OM@69)GizySoiBnwUtzGm*6OW-QUoDmI`RvF zD2k|LIP-EEVzmg(YsK^;f%}IOVsc~E)TwB5LC(CdSLNm5X7uHSZEdYhO%|^&{oi?a z=WNbmy&5zth2XMM2JKvpeZ&+daUvr6A0c7vAgme2Pe zrwqz8y(A?o>*UKI3JzsWamUB0jk)#8SW{swBXpx{NU)tM!_sgwlrV&ZICYCY6xdiq zuTgz~xSApi?7~Q2R$cxP6CaPQj@zi~Rpy!)2zwH}jLQI_Xn4@|3jWGPLR}px zI(otpJ{UCr_b)=ogvqlOiiUPaT4Ar;+$T9r_fl68$|Iho>!*o$S`((48WW9~*0k+7 zOLy8Ysf|^~c#b8eP71??Y}*m3#_N)7)CtJ-58m#F%*dF&!lq)v^x65B)WNk(Qd+T= z*TJ6&Dk6+PNAy+N>Xet%Zd~D~7i4qp}oISbk8~)zxi$Hfyv{p& z`KRwWrs+UMPkErAQBya3y5MkA+&jY`RiFyuBK2(?wXiF=Hh_=0-O=YiD2PKyNQjsB zJFjS0{rB(n1o7%@%B3N_4;_JUr&U#6pwiOHCp!mbyr>jI4H9ywfZ3YHewikDW+Qjd z;m+0FZj6Tq@PKO5m-H2!N5K@%&SNzt!*K64Gw4Qz&Q&6M1h$ZLgJ4n%FM)gZgPXn)> zC&ACNvr0kPJbmDhzwPufpT)|8v>MB!j4~!IjYswzb-fxqerUq1zS zz=Je3wd0$b-@K1aJR850A4<4WU8iFHSlpIe#3n_s+9{1v+q8lfp=O%ZdcCXQp^!jP z4J<26$;sJh#V~(mUeVEop}9Hb@Q}GYOA);xNr0*>q38 z8ZyvmQ^e)XtnU4g{Jc3$!<)y4A-Z4_M%jPb`Pkgc>3V-kEh+^(odxGG;+465268ggqYp3UEVKGzVr}`l6G)#0Ad0w zE2|d)H{i4b2Q^?_~jf8*k8UD7QSgsHZoJz2AOZR*K}VT6Ydw$jBuWcGE?z`4$S zBqs-*%^c31dV8L+x&=kTrzceucrsY^B~DKZK9iv3KA;wa)In&=1_3u#rWbhs} z0DHLe8n;esX69=ayL8~uos}@02>d;X^3PMPIJ%k#2;URn! zei{CO4mLK--&JMJs6tSFo++Z|ohD2XnH4AZk>MeRmc=F_4J&=FI%VJumMG&FVT#fK zVbi6VO5|46e?~}I#9ABui(?SQSf|!WF5+ORHZJeFq-?8qy7togZyuE!-mGuIH$$mu z$CLXPe;LXiY6kdLW8QRpB{PmZdL37-5e{0^RD&;Of+tdda#c!|!vA8^ocjIF$}Us* zw{r?6st(V5hO&oEqEZyT1>dBkHDntjMrB|N%G7s43$jft+I{zGD@2W|WH8Nbx(}=W zEmfMc8+&Qy>DgFPGBESwgYi^s{>`7W&s3jjY}KONfHzG|=U{)ouI*OX^25K8-U&1j zB8Bw#_s6QVd_tAcZo|1_XH9~G4^Zj(6hp}VvdQ(d`E*EY(v39N@^zON%;w(x&7!0A zOXmuo$TKq+S8oimIy<$j)k3+EvZ`O%SEg_VpP=iV_amWi@SBElmljJ= zw-&sUMg>vLTy<;ye%)^he9W@8HvgnM(^g*?XW#sL+=)$YD1q*JB+ESLijK#yivvlI zn2w;KL*WxbHz)@;op2|Ea0hPfXD2E>2i$u}4=#|V?8uC#ev%ak!W_c{jhE!7%c-qn zTj!GdC0BQ3&+kR7k?L=g<{!Y3lZpP-*pv*%9@E*kgvYV z$o%NObA9*|FY^ha`MJdN6G@4+D;^tS?SM%VLj z^Ng3VeNs*Kc-3~uzG7}QB#w_SfsfC{#W^qNs#K)gCS;$|oDS0YMR}K2KTg#zD*-<* zY(B$WNohOlyHz{CQTh5zpHqlaspdP;Vn%=4;|f-CQofR6W!yf{FVF%9dx{_QO~qs`sW!ZZS7QL}m&#ZfD*>7jca#~}nT-R1kah}Oq`{f~ zD4dCwH0fq?qW~J{Vkf0pZ<#>4i0Of0#y9ff?zqwP#e8q2EqnjUZauHs>qeapUMLNsi?d`@u={NlT6~)nT$}Wj6DOvx@;5Y;xC@Jp1C5?3E(uCH^mm&rZsjSQdAxe=^QqIq~`dd&?KK3F;E-qVFo6!*&MbgCM^ z_C29jY&N@elSS<{DEdF+B{(MPh(UP*xM=HxA}SF|9Q^y<(2#Ff6v*IZGF4On7II`O z5+^D(L%LHvqi}mWV34!a^A2s8Qck{rG@~~tDd|@mt8lMoc?>oVg-V>3dI6__$EV2; z4RkFYNpfoWxdB+adW)!`@0AZnJ+nkIPSyPq6F*4A%Da;3Y3Yv>lab*yxGLuf+c7aw z51xE8EyU4X3fdjd=VL9RBx-}BYd*j4?UkZQitIDjo=jd{a3xbz+ki553S3){o=yj3 z2P_g@k#U|o3Fqb^4W5<2y|=bG%*md84ZD7Dz9&tM#(q6g0KV}JUjK?%l~i{)x)dn?R(WFZ-#fXSA#d=4T_} zVfL|~K2hm#yieSaK0OXusLaL=loOV;E4#LY?~zwu#|LK2rgzeJSubhYP(_;>R$d>q z)t>s!E=nP66Gaz>-{4Ax@WucE6)9+*l4Il8W)uIv%$$MU2Yn;JD*3PiR*9zjhVISS zptPTwW-4gSXYRaVSPyj8B-K1`)|L#-U6Vk%8k;4Zu$`S<4QgXQOgQ!HXksVEhh5aa zd%WWFFWM>r{RuqM-Pje2$W@QoVNOI=P#ckNMiF@XC$$(ea$89aZx4RzF8)Vjvt0sx zQutpYkkq$$eNz=VReP{5ElSu{Ps&Ra*QR;~OEdD`cL+}o9ex)5Px7?w#7OAR$8NN{ z0J4Is()F4Ky&)v|heJ)K!z#QGw;^uy0Z&td_dq;(CuK&0m^(2sAw^?B><-%7-(RQs zYy}u%N5`WS6;ZdQmdD=S-oe4ao(RnQw@CW>`tjsKA2vS4O>V^3SmpiMd@~>|y+7K# z5>N}PYw*qfU}>S z{yc0piT2ESg{K=4(tfNczu0~xAoDN7kl zHxfe^sw`t;Y7O?o3h%s6kdTr4LaS^|Bodb+O!)9O+X9|r{lXKh&F!_(TFje0mgolr z7#r~t1}XnzySMNF`99!c?Pr->k$!TU;^aE^+_VOosjoL4PeV!y z@Emy^hQ2u;8++*A34hQ{Tmd7Xie*OV#?}TYu)~f&&0o1vL7EY1+`$O)u9Y{f%0Bk_ z$fx=^ofakdi1V@aAFn2fs5!+vHhM!@L6L7n#?J6{38=&FK6Mu+<0^KBo%zx#;)P4mOqD zZ=Xz!rwqN{idgklhO`B-yTS^wu*aaoe|mO~-JV1t zj2V%qS0}no%KIhYX)gHr1oL(E^~vV-MCJ81nDb@Cgl%lRWX3RygxU4;I|Om~elumV zT58UnUc^DIf(l|qoSae!T!?;f_$3=+f9%(9h_96$$xt_W*NxUcE?^7QPusn|{>=E- zfNOW}X?SE%k*YDxOj)ZOJa`!dk`oXMDF$dM==SyeIQp>$9Gu_PL*r2>-wOvG zuezPi(NL8vDwHrE$)C#vktjOgtaWdkoU+2+`2(L$GLZI*k1=x}4ZJx{&VH*au;bwd zb~1NhfkZFU5#p{t$Z>c=X4q+!9bx^=(x0l?;NAn0bQxqBTKeWDOHIW$vRj>VGsR*# zqCq>}aqG9?tB*(R`EL`c>T43vj=g3X;YrybXwAKnLe$5feycvXF?n(2j&)C9V*VVz z)SU=C%GB0Q*ELY6tV+vB10HE$c82zfZ9r=k!@sQ@ud0>-gF+gos`RCpV>4~Z@ErTZ2L9vfln$>k*N#j#V-?~)ZsXerEL z5YB0lnxDgzmlKmeL{Z~=(x8jr5n0CExyArza78F9{ZHz4{E=OavrIGy;81rZ`@*%{ zmwJ0YHUE3>x&*HI@_nBZVt?|LtbFQ5TzxrP?Ek9L>at6NeIlOiv0MBn5UUp7H|Zcb-z?rr{ch^?NUk;f$h zwd46a#jueGu!OyW+xN+2lb4GRW6{ZO8-y{Gv?%JjK#*BU@_sf-P$X%f$B?3TP^m$~ z_2+hPwoal_SAabza`{w31e{Cv(~Vz|Jq|lLSUD#U$B?KV1-n-=tSbQ1MCfBsmX?-&ep#=jaJ!R}-ODdE17fEfGAlWLm;an9R0b^e z>b@#waGE?6+|r5)^8J1-4ZTqC<~7#0c}+HH`}P6jJb&7BGu?VpH#?W0o78V zHP7U3QS6A{BM2aKu$}>&I98D-%A`|hWF!)?Yq3=eOcmDB@GI~cet3a4H5zfcPoGSi zKO^0}Jq_q!>pLg^=M+)Yk9?M%wq+a+LkUfUXXabH&DPb*?ArXUVL(ct?ZD{qr~!x- z45ctAVfG~oddi5r0X@F%um1UX+IgK9Rk)R)G{h~vptV8D1&QkZ^fTROGpOK&ZZFxY zxvImUcSZ8d(W}E*Gu2agA`K0&Veh>>Jd7-++OfZYe?IdbKn2vY(0@>y_1J5J#IamZ ze>+icwEC%g{+q!!EB;Ty6sqar_obmV)h4@=umKd9bIKY&S$Siv2XkxNi&91V)zwwx z<%#W@bad7)ldk3E0YRa5W+o;$Q^zA2Mu)bKA3rMUZ}1UeHLQC|N1g9XuOfu7uRLrV zfodS3F1%p1|Azmvk=F4+jI^|tzta6;QBX=w?Lm;hHe)BLC)LhB@fe+STh=jtH6Y+_%Lc$-m;7l7C(c)#` zV{6Ey1g{XLagv+XT-;&`fIq_`DMOp4YrWzXdh1l!fCm|FuSLu?FkJY!A z0CkeO^0YU{pF*<9(YX*cQ%O>Wwr+Sql`O2%->jN52=$)Cq|<^Mzf_i7Wi!qtI9Y0? z>rWfGyAh-lL;KR-ieu4j3GYAg8wiqv*yPmn6iPDQ@lEYdh2@zyl?RGS1q1xBqLPY) z5r;XCJm^wYtm@x9WskWhL}_d#MU1+(H1~ErHj}QU)zxuCAyN|hR;(~Q)&LD6P=5d) z`EqeD$Bd`ImomKC@$g6g;EUTktRDjxHo@{irddtvvM1U6quWxyT$bkfMLFxn%@^9; zB*mSZYaLs{NIPP}*6?AYadE)oZ((uU-+!{&Apmgl`FNU|+On4BIf9PtHQ@k9gXW;z z4%2?~Lw^}X{he!GB*z_MV&d0!Rw=$XY?hr|%wny=XE{Ld^1>(N8Q4bFmO?r|WszH( z?T|h4%PqrNgQ#a~1`9IgUb>dQwv7$#2Ej3J`PHWp0`FzIG>doJi8=qK5&?z#9U71; zfU=1;F4hf)KX$&}_!}aC!iTE5>BK+{9fo4=tBSin>!Ei84D@;39wjnZZ+{k2H5**T z;O_pxJ^3{UP6QQWZ6#vYb0(j{J}~dx|)(lyltj#b(x)m{W}?~BA@dk z-Vx-n;v!o6wtw}3boiXctApMO|JP_8gzDhKhbF#iVjdUTp!rlO>7lMUz%jT8`ND>*RZ&sd*VNu1A|n%a+vpA9 zb$uEbXjMw+y4lOU69TDD&CH;>x;XxBnPJGrAtY|DwwzWNRMY$Z?!%6%_z)^>Dm-j= z{wbSf@yJ;1>yi*UN71Z}=0tLHabY*Vd8}ohhqRrC#TyWXvdWtfgY&^?gHMf&Nf{dZ z1W+Bi1f< zsEUouFAbNg|A9=gv>53K8RJ+XN>@AGAJ+Hw0D1zm4lD4(g#|FH^L0tk9vH!euSjm) zD|Agy*N1MWYd=%_=md}x^{P}z48B->k+1nXA`AC&UGwbl>}8;#VW2T}`sR19`O$k{ zXASqXJL{*jjh=|ag-p>u+$NN5euRLS_PE}u<-dtC*BB}4h$Z29luqwO74~Wt#m&s5 zN&RBRm)}~Bd|FjdPb+THV5R;h74`}7=#m;meOh=Q1rPK&2OjD49sG9m+s_^SKMagKvEV!|MY5;?Sqf2Z;H>SPscG6fiJW~K!!!v_ zNNE41ITbgs32ws48A}xGWxoaVB7@J7gA2NitIN#pt&U~mQ+2d&Zf{KK>l$TB%QR z_8tln$rLz~5_agYsdWg5Fi0C*2Awj`3K#fzPv!TB?SeXkf*=n4Lgv0P|16{d&4n-k zZhug6#5Jtveh^1$`p#WB?D7v_W_c8A>G(6ha3WzBMV@tW9-N5IE-W~eL!xxk_IB3L zvc=`KkAjo}<1pd=WA3R5xEt>6MQHvSl5|S>DoQxSb*psb;YuE3EWrkezT@nFj*rhL z6QigtECROU!TB93s03e{1-;3@tq>B0_&v9BdWTO#NQ20&DphnM%)n3}n~D{hUb9*6R-!CW`~X+p#2Eq90#Sd?Ud%fWGxC{==Szq}iN@h3Z86A4|dO&DMV zT6$aE$|TcQsSsj(NwMF)OY|1ccQrpEib$_0_tPKBlohLj&<+)GszZ9qfAZktN8|j#V8NOqcm!f|H}G#+<|Ynx@H=)LJn% z{uxN|1c8ti^PQ6hPn493N&;sXRbSY*?BQ@Ac;9APRT@ZBic$;1Z&w21R(>3jUlIRt zC>#JDnJ?HYYO&W5N^|Zb3{2wciiL$mmpG%BKJ!b0;<19Da`Fh;2ny_dS%qVZx!F;; z&@!)_;Zw9JcXdiKt!@y z`AK|o5$62X-aD~q^YCaX4=x`ZXoDaW$bLT}S2!bfe~D!$k8M>MEE^g1%drpuiogvd zG1PLl>sIi)z@F?K9qoLJcXQA%k3=nPzgub0KRK?tXueaW=SuxBbg?Tozp+uM6h%uA z(`U{(mD6I(^?LaqjF4qXzE(q=(II7dets|lEfko6u|$0kI~`@$7wGHocl+|#Mz!Pg zd;ADtaT8GdY6x)dsah|J98#grp@qT>SEzBd6q{_>r5=5NYxf_dp#M3ltUOC0H0!!G zm?u@}v6{k?IOZH=*dI-?=U7=yvI_qLx+5qyW>uE7p+`Hzjmmb|dbU{H+YHw?;Ko5OFx>7rpGqVqg9sHN59QrRbM`lp4Msh)8!OYcYT}{+ln(Vo`2vIT9rKt|PkyfN-#=Wb4Z~Ez=ahiq5=cr1 zeeLeH`bstCg@+rhlkl5Zo? z;y51__?KbHP5eAIO_qU4~u5D{Ng| z&-_;(R{#h`_r-8a2hPvmU#PtucrbCyw|%VxCfqY*OLZ+f=2vQ_Eq~iyj zG#`(P>|qcQI!iPKMgbWUcFduCS8WPuECf_k+V~jXX52|}IeC0Qd|WdM$sjw}Id-|F z?hG=3mly!36whURbC(a{*gwvvs-N0mLV5g=Bh;X)B-JGFYo-zv1I1E!5MW7w zaoYXb71ub;!#7~udw38(auM|gS^fC9P{|H}Bs6mvU3h_59l#{m^n#?-FgE5V`SRqa zOcu0TQ=9eQf=rE)MN@|G#M64o50fqRlhB6X9=9;)_|8gc2H7Mt(t8VpWaq{N-C$qY zmbryU2!$upJar!D<4A#==N(@-3R_&YY9vYi4Ad1ab#LeHYBS*;3sj8|frq`|?`2G! z>Ujb97O4gt(AD+zd4YM4rdn2ViShjzKAY`F!CwE*{Mk4I04c!PaD&%tbo4ko4=Lo~ z`nvP-a-xbAMD=*H-w&SWgdi?lAfX=8DQWywj;v<>qMa$>{#88LIMwRAebk`MyZctf zKi(gyP?FOo6|-c1^`~hL7r2!vq_u zf!>OIzBAAu=3wu)(=Dz(1(^^boEf9ONjPam0eMgE=a)=*C3`aAh>s-ebU;SN zhuoVM-rGhcu9t?ntB+MeaX?3sH8>k$nbeU~k&%*ij53kH$~7Mo01+f`!$BUFEfZPU zTww(DTNIZ?`*XLO)rOe#h?s}B%5jwuIO4Xf6TFnus7 zB2>bMH4m@4U&k%|O_jQ;cYS^O{bd#g-cdGZnVV(P(yE)QsGGNRIFzum0!s7-Ox2|Y z{%p=(!baXIRbp?*YkHoW2{K-NICDki)<)-5Vg1^=FadR5VC zKZ>Tfm-{Wqp5u0uueOLgj4D#{s!s*<1|C@NYb<)0t&MsF?b#Y$O=o`c*y%xX|e+UOEfP`wG@#u}5R84tQ!|28ga zpl4vPz(~^EbXnT6I^iZlVZtF?z46cE0-VQyB#L0963G72>LrQ4TgIeA*)%uIsQ&1< zQa{R)?Fz?TT&=QPGpJhX1()r7CwZ4KFmG~Ixx719(?l7DS+c**ZH1WD_Q9xISZ+rx zQxXf|96lX)piSlJyP~f0(g_z^oGKHE<&#{P#cyThAot^}V0(i7gwUihQ7nbO2%G%=scS}Hz^haZ8WTjcHZsLpca8WuCY5c_YA?pV(Ot(OS{kHC0% zh(2Kfg_IQ{fb3d@$sd)Tk1e2jaHq?2r{`%NNrQIMoUDJ^SyC$0wwL8XGuBbW6eS+4 znMO5>03=5^S5t*y#t+&G-38n<3J%jr(UfzH?_(0JHkJ(Jnif_0DOXSw_RDU9a8ir? zObrD3V{csC)G?1&zQjjf7a}M`_<1;Rs+EuTdyLLEi4UAAr0>Sj-I03$T+QbcU#BTx zN*yY|1eG{hT&1jbwF))sdC35-yCS&WBQy!PWe{tH=cwx(b;1E^VgRv@g>4guIo}eo zO1M%>IBn?49Io=WWnN&I5vB%{KttUa3$>UUjjbw9U2-Bu86yLex{=@ra$;p9D|Of> zT#Zf&aS0SIHUL{>n4GkeUf}8LU@t2#g}ZMne+Eoop3doP;dm|K=Jxd$gRfQ|)JE4~ z1c6KfzKq2Xizql0S^P|BSa*{>Ov)at-Zso0ctqFe(PW z#en}2h0CCCU;x}0bjukJ>|RWtZXfI{!vLy7xhuKwCk8P`JN3r1Erg5IY{!t!9L!K< z_m?o0-e@qdJ!hBE>6^Yr7W{kd(a4Wl8XG=&>Y9gG2;zygoDz&c^s1(viy#x5NCc{A z(L5q&t!u$i=(xD{k6Ug5iY!3=feOhFLy1ntL> zN-*@ZxHfj2Q_>{etGpsfRcV1A7UiduWvIA!SNYoqOQk zE`qP;QDark-;3=|D-QB4i^C2FzSq>SR{(d)voI+C)>@3^Iy5tR=WI zm10TjPFblUcZp(r7b_I}WYN*GzNY?zcAEgKo@%*09{#AdRY+bvdF8TCO_TXNayO06s4gXC=w>BYHog6!4-Eu}|a!A@Jw zwe?6l{VF67R^Ig*#TMP{(G&=j1&LEb%iAdi)1iXWt?HGVwB+@Z@({!lj&_P9nBU5A z>t_{%V)Plpj^Ih?%Jh@V!FEbhmHMU?{F~gAgYOkrChBUOT)tW22Rwy;3S}T?K<)>B zZ}KTQ2V4gTI4Rh-NMDGkd7J450A-z{Ez6g5uzo+ginX+@$Es&63FRTc=$|gpy00WE zNOka9M1_O))v+4HF>L`R)^Y)mKmu_9-q6~jE_%6O##4j^hG5MLbNNs9dalypz5IddlNxrbktd4`xTq`$yEcTrG|@hE@j`kWZ4EI4ntX6j#Z zh5y=xh?<^8_Fd>SwbLJq#Qg2@Au_KFD8f5wYH)l$RJH_(Zt`PinkUaWcqtvu^r9?E zWu`UK25%A}%nuoa18Tt5EhxMlJ(6|xUG+1-`T&X%TnNgPOU)Ukmj2>gri5n3b)a>00qOBor=!*MhjaACfj7M{j^K zS}>e@=&S{vYH2`%1|&h#CkyKYn^H;C%3g|r;cqQo>*K!Jyu^qIp0|M2|w;&KY zm+6ug4iy?u6-8Yp&};1*b~26tQWl=Eqy?^dPC@f-_=`6>MAWh?zH!_Nx73-@ zIJv}Ydyrxc*oL!bCHzp%^iHiDKK(Y%n9G%X&>98nc?dV$n)aU0NnQpj2U7+-*|dxJ z9xy`D?B9JHfZjk4`;(rbC;nf9svsSSw%SCCIMj_(<}=f6o&;A##^)#Y2Vw{fLGUK6 zkFP1_;ub=GW8X9OphVt{nVP=x1E~Q{jSL9DV!lIoK>DaV30iG*6d+Geqj_j1ndN9R z7+U|fkn;*uQ)&4-3!}$C9cM!3hf`oi>?TA35o9ARmIyK!^a?H8ICUxevHhaLA`Q2A z%0S~pe832+23Zz-s~D@$@2{806exbI@a510$q&E@!8WgQ2g5jtOq`7Zk>cI^R3;4G zx|HN{BvTM-d!T@Ts_=OtbN@x-O;9#4w5k)s<0yR;qJH0)>LjWEKub*|``&W?C*IO5 zKD{X=fYbMCF* zn7NHb*dQGl(k-K=Cf*<=l$rMs<-#@np@+DJhzcWheJ$ZyL1xtSOdG&i63T#a6K84k zON>QyX=Fjz?8F09Jk+KhR)sE6AhpCR1m_7Ioo*8a5M6wJURs0gZ&|%5OHu@1CQBQbqM^d#DCQ-7pgZ zQBcqjwgh51BmK>EU}amJWouhnZwbZ4CUid5kSWl%(XG z3p0Vt%fjW*mi#Q66idwUneIZkc3*o zIRXSy73jTzD(*S8it&<#G3TL9X8l(h2e=l$eR~!tYwS3bs8*6Z;VP!c2yI>O5c@OG zos)ogj^DZRM%9!hZEl+hQK69>;hl-J7?_)U`+aSuY2zm%YF9q4+Oa18Vtox6{xBM! zJTmo3@Ac^PQ_dSV?t9UEnej3BQbFWK;2%HPxds9cqdb94Dzh(#c2eQ5OXn1Vy^nwL zofu4UrSmgqs>VHai)0r}8sjhNd?tM1#R4-;L)tFMQJT4T6BAB?sD{&BN6oFw7D-=3 zKaY>)69>Fjhv|AYG)y!RC9*kVV_u-B>+I@E+^{t?tA)T&2jE<>il#6Y2Fooy^5(gb*3U6>k= ztvZuLbbi%1!#ocTsJdD<`u@zZAHPSd9h9ZIENXHlyUP(^=F~V{sf$<5tX<6IRg@Pt zAhysOedF#bxdXj}yvwYb#vMixur0!NEt7(2K@P}^W2xgQp{ZrWgBH?|FcZrrn%9J2 z&*5wn(0e}i7iW{TvvyZ5+c-*1a=ZFaEbueI{cc?ctt6}=j`)zKT^3+Ft!obz&%e9` z#N}cTJx{xWRh@_D`bpaTr2X>0a8sal2?G(hs}3&pSGIP53(uGYULv6~dp;E)FH`r; z**ZejUZ&`WJKfl*;xj+Z78Oxz=u73F&;9&gwD?eW%*_IsfT5bZjK12RDd7-d*7A#J zkPJ2WN*M0{NuDZU-i?$b_x1Cg8kSZ46KPEiPqe?mxl^e6t~}(~@C!u&4A_)ywKFCv zZlbyc5j(MVgpg;RwP7!fg9zLL^uAPR99HsDh`-%hHH!_;B3R~Qd&qM`*`2~?U0!hT zgGPZcDmZUUayby5{VLYZylb&TWrrr?K+FN@U762}(H2oSdAs zl^}%yfAL}UsfokVVj$dM>C#n9fQjSf+ui6i4ncl?LH^W2(_;42#kz+zionFepMo2? zZcI`?nq_+HzQ3Ucs@3=}+E$_VGVZJ9o@VB>=H|2?yiV05C0T~#iReQW!f?Kom;v2R zV|Wl^Pc(jpA3sM8M{oxPq2KTmyUP{7NUhQ z(R7rIi?JiA-7x58jF+IsnaUxP5>dxw2o z?dg0I(ylY8j?Of2tN=mD<^RogSjzVHxSB1F?yCj6 zY|RRLLt?Sq^W>x>6&+gHjFW4i0U?NQm&xO>PqmPN!O4N(mGTiWutG#Kd4KU(61LZg zU5yhg6f4}h$Kh6h<>yCzRt2h* zam}7}SUaI{=bn{d-*_oxSB?5CJoiKt>{}iEuX@~6ReXM-6T&laulKaM~WtVCe%}&|dH77fa^%$&q4_-i->7OSh14j87uY%WkWpmv(C?|)dFRfz6CmWj}>`(G7y4&OwxzyVk0W(Aj zvsLseT@{RvFQITSOc`zBL#5dp`7MSuHf}=pknzIsmvnd(Kte?3N7ZDlHP3Dl!@-4n zrt?BduRSEO2B)?wHLEYgwTi<$hygA7H#MFu1<~fjO89eCpyC2i_oi~nT0W-cqm4|% za}Nu$NOa0K`EB|cQE%e=)rGfHBAxK3T{))@LD!pniF!H~fB3Kk#ZI z(E_Z;23&6TzT%?ZCwqGZN&04{YLtTB;-h(h50q95wai_H|>-lM!kNgfsiJwrVMailZgBWucc|&+0 z!NqP&FSm2a0THXeWfmdLLEShqqsK@^EU5b1)SMCrGMUTY~ZYZ z82_hwY0K^Es1GJlJYHGi@$s<|H5gP?RdoVz-C0kbopFGeguMuY1MF5jT1rZ&60X2t zc^2X%aj~a8%lF&qhomp#{7aI=rkGjAqKShuFwM1%n(g|YCCkR*v7?PHII&YEFgm~_ z395hx)%piuG+yY_*8!Vq(PumMTp!3Ns-CF{hr>?0ul`~+aPazbWSA2Ar)F~LYf!d` z!klX(E1j77LY0lrES34MYCkM514S7loGYWtKMve)j!}N9)80#)nVXBUse42#bP%`7 zfS>v#Y;%WkwJ?f36pXPh!#E`A&mStEv=wOE@hg3*`wK&hxBJ>816~GFokBx)q1a)s z{*dhExio+Uct>Zvqw6-?A-Q|-i0~6pC9RabP z|1x?@E|7V*W3)S`Fc0l{5W%&E4r)v1IZT4bmxb?K2{rms9Dk;?Y;6J6C8zGqG@>j2 zd!F@U6BgQgir*o7CTa}CDUUL+y{9DL4A734QfLB%q>lNN08u}?aIBpQyY z*$=^r@BoT#W;agmxLKubT_co|MCrjBz z5ul)fIFOKgmFHqX-_rL%B+|sgBe%s< zRoRjwkyT1Tvd@yKK~J?-O&VrNe1c z@ULYk*cgPHa4y9?ke*OJfM+kba3hwAI)1mV>EfUq!mmN$GLWV8W_MGT1WSR}N1tDoIeH^cQ$Jt^to5NRbh}$kMR>dIgyO!W2S)7cWuD&oAAWgc4QGsa#E%ShW z(z#VM30BFj@x{Tcw)<@o-23MV&+py{5?V58yJCW<4mcTlFuue~z-lA``auvU-*O?q~k{*nj4^SJQc2 zB|hiDeuv*-wZDm4BMf;3{pLXU?Ev5~Tt?&ZP$-kk5^Wda^x8o+)rkJ9^bEh^r|u35 z2ZKn$-uxCfo84|@4*-8wD>DBhHTV^X<;pB{9;`lZ4t)FOzhgM(9g0F$BQ%^6IHefs z?PdZXQ}2CMiF9tw}1Lx|1y~?$Dtp#r+jtILneyO z!A<`v|KD}3_P@L!+3Niww+DBT|u+kJOb0?;e#k|Mkv)LaxNqAG_*Dm9d?+ zOTNm_hj;ID4ir=}$e*Xwhdil;3=IIq>iVcRSRxHTV_L-C|D@e;w^E$|@cU={um76k z7->WD{r<2p1QAY#FI8&|f7P~-A)U`&9($gdpfYIr{;c=y0Ke%BmyPzMvkUzgm;MK! zIKNjpu#V7^l>1emuNe($PG<`LbfPH60n53_Vfs$J`vQ82YqMBFypo}}Oj$M?kGWm4 zxg`$WmJQba{O@H;$=&V+vYW8@48C!4#1tg+2(l;NrGNW(^N*F2O?#OL^1rGe<>D%?Xd^*%?s(~z~5g; z@181m=BNmMma;8L(6FKIEpdMpP|B~m)XYgwwWQY=EnjhHCqHNpc&g5Re3joza-5J< zZI{bct6R-0yGbR3V0QQ~q~f!;)icsPjFQV0g;#}Xg4il8`oAWSsTT70Je>IaRxqyHWDS211|ZI=aS>qt2`a;g`&(v`hE zuoso^x|Wv7((5<>Yeg?GD&@C=LOujZ$T>CNZTOP-9yZxC0w7!nHLXY*Iq&hA%}xg{ zPh{aFX9AJc?dEaO1-`0e*w>ltxL+*63|OOZk_k~UK1uq3#DB)Hva){GkONyzOiC3Kwsb$e9u3d z;5h=7_#j)5f|+YvFB0UhL9!-}+#q03$y8L-8@;Tojl3Z47K?qlTW_5d)8D;W!|#Qu z|Nd2JX0;}R9FpRweSz)l3l%AD^kIqAB?V!c|G(Ia8@*q&+3m*3n=i*2DiwJDWm%MnM(_F%NovhO6zbrUk`*m6)~4hIaJt-TkN!r5`i&#pHp| zco7)R%;6X+e2E>V;1gX=TNC$LdoKpY!7CtyN~WvWf?;t6VomfoR98^Q8d4<^eVw$! z2D!|k&7!V`Mn9#szF0qCwjR>h1qH3V_N7_TpWKx;NnRFiv@I%37Fw3KKzk=$k4W!E zFwm_ak4tpNIL>@FklcB<&&gRIY!Z}=@JV+e@;9f(4yByXyX`+s4wJ{c+#|D43T?@x ztf$`_VRR5(4SALdNO||9zUL!92@654F*c|vgAc@)B|It#`j^R_3%=J>=eCN-4p7+D zqoxFc{YushK8H10LWth8KAPkaJd_ciSb8X?(_F?!J1?hPHGK4R{wNcHfsk)s=+HJ} z#?z^8oS}M-gW>JP=~mV444M{dHP6HohW)?bZuui@iU9BJjQ%kse~D?kE0mp9k?GLu z$@_VJq`_TR_jY9_$;o_bbO8LS{+Up5IZA-~ReQ}uY#+@=PBqg_`np`$Qb+rHD`BmBzi;Z0zaFL0{{(K*csV(|Ihx$#A zEmUb4^sfA;-Frp}Y|?ZOZcKDG3^ok=S20(#yNURp(EZ7bu| zb^>`ypS_IMTCTq%h>A()SF%=Cd(O<1n0|fUk&P2}uW{g&Cq6LyT92EhTC1$HGrL`w zvx^b>)SWV4slOjWO9t|*Xy&ir9@mcQqtVr!9vm#pZZKVadA#xVGEep6()AJ0#+6LZ zwRpT!WMMnwyC#Q=%N=Z6Co|5TbrGhOv9KR7!6SX zjza}mAI(l4xj9Gj^0qcjSpz6qJ~lz!+GaF=U>apZIOK4Z|p8w7B)A>4< zqp`!U4I#K4kRz_a)U`%^c<@I0$<2!bvcac%AtkB5wEXw4xrs+jlIZkIQQQ}8OTBH@0 z?Xgna$}V)Pb41uysIqj`B3oS*aJnKm~x*qTCG>eU--YV>ql)c{ZpO+*W{uGQ615`03C0?HeTk4;KTo@VUbv$>M+sTBkNgl^@s`grM z1}0CRIk|gG6T1Zg2`&K6_}rX<&HPV^u6~fw{$AdcN?K0Q2C8a0ST*5};A;CL&~IN_ zof6-<&{S;*NqB{M9~aC1yX({9Eb2S4wMdyOz{`7^Mo_&c@U8+1@qfko_d+?xUgO!n zFbiE@=b51tr?P&#o0XjJP<}yYYnA=}oVn0$f*C~ZFLqE3J$wHMY&Gp@g^c%=PQ4K% zHE?94(2kJ-92Tfs98}8=%;*MqafqoD-xWW1cpeU&^Ke;H2ZZ~>b1=37@6F&QSsM)$ zRMq5U4cQ>&myscfA|_tz{zWV0_y+kGVw>|V59q`y00Gn$5F9KR6;;)av9JJe*V*5e z4Pt2g0DZsuYHI8qfTc~&qC;ELcHk`f{d-I~;{_t9Ywd3BW>0{O8C;`*e43FV7quZP zoCtM9Ucd#~WUwbQ_=M0#{|vMwCW^ZqAEjq?tc?G5L&i_WLKuZt=({FDLNE60@RPI) z&PY{6LZ)IstIZN?-FJ6ts*}A)BC=zsUDHM_sDD^V%I?eQ!X3&BkqVNRDvzCkw!igr zcKitbMH{4nRDDW@W@{LU;fn6P;kxhJiwKnZhzNKdW2s?h{P=Ca%BH6M?ahy071`$LBxI(dJ%xgMR!M> z=i`O2B7q)ppxO6b196FjJ>4RovQ1aDeY|?T=pACKLo0X+-TOHiKI)pi-np{&ob>6R zI20^Uj*WvuV(fhllj#)(HIz&u&%~z#$M0aS7CXYb;?x5a`{6NLXx9@>dmur%;$ed} z%T0TFw6lCB`*$8_aH7ib_bpio^wiPiHG6Iw;Whf>9eHC-gw9(oX z&`DvBu?t}7s>J>OKsWBMSGJ8)H$2b`@?SU0tc~HWsCImRE{>||0g$1PX+Dz0J)V%! zG}D3H*$*@yX$@jK8e9|zH>Pd-0eCv|(BecI&&a12g}y7zoI3`OqwxTrtQM0QQ;6E> zxb&E?XRo()+~?yrG!!FN^DhhjX5cUa_){a@?3i3<7Vs|2RJcX_!BIVyjhX&W^%wDJ z**!X zwGXv)8yj!9Za7`1hxUlz$xN$!@!BW1R`m4b}``p5lH?5 zY{V>x6@`Vgs{j)#H)Tad)yxbcko48FZ*;u9I*g}PItz!ry>_@Hdw~2Em9h^h#k7vn zRvtTHh;f|JQ+@_g4ydw|5*qJx%1g!u@i7dA2tVH0Z>@J~z}gaHyQrvOLbg~P80~>T znzeK?u2Y5ZWtntVdQx3=hl6kbRKgXKn$4378sHPKw~t+U z4~=|}o&Yr0cc^MyZORA8|6?ZOB1mX4`HP`#)~->>75%U2aUKm}p<};UCVwDS(L8vh3g{uV8=4cNRwmSR5Vzx%S`(vuC}CMwVSO z>Gq|O<;niVjvkbkm$xPs^{uFn^X_&;ATWjOOF1*y7{?mA^sXIHr_j*>@ZVYaeWRm_ zL_B7OelOcFE6>M`J~}%)zaw_PF~|z2$@agS6Wf1wQb7ce<_x?TiV^621e?yPC<`Rd zDSin^4IzZ`)8{8+i%g-@P}Jj2P|NBKSq*m%rLID#F;7=%>FP!PXv`8Pyj5oKhHNA8 z^3=Nn$8n2wxIz77FGZmkG+>}(bQCihx$Ng@{6H+gjq%ApkYDjUKFq3x0;xZ;XIH9m}Lz@z@i{n#Nv2!olC-!UT$*zHO=)6$dm4?I@thF`?NKMFL5Poj&!b4HOOyq>TwAVFTi3 zsZO`(?akP;?u*r0ZzoBO02nQ_fNaAUI`R7J&%z)YjR6Y__Z_l>6hg z=!2fz20yz$VO{qUhfAc%jg+2B_ zmx>zD=%}Hsy!)RAa$gC(l05&qLL^Y}?MkzN1C)X!fL5nU#SNQ6+sI0d?dGGF#6+kQ zM+ZHSjns}u(Lcr}AaqfX+rVCeuDM%KUC-jhQ(TSDNzZ%Lkkek9@F^nRpmh<_ts`4x zThW&WEM^zK>y8fJ2%nonLBTRxq$w}A;k6||L|ucl6(vlksp%3A<$cm0XUoUTR36(w zhV)-JDa}w>Sy`qjQU@QeT)WO555lRT{BH(zNj&+fXB{XKE6We(T3>^%re`Y3%0OLb zi+cTIO@@+_;Dlfeu{CVmm9EY1MqWCPQZ-MpQT4`4B;G05KM!VrtkJ^Z)cx+M3sb{+ z*PO^EWQt-}Hu>_+`=2=o`H&xMxM5XfyUCP1CDK49QDRnj3RKMA=8=24O9G?pTpNBpLml^+-ToOPdcEZg$@feH&w$$RnP@oDI~DRjvGmFE zbJngeo42RPRclsg}li9E{OCUiS`-L*bMj_7Q;+;T00NvZSS%jD;c2!%joPOx;Wa|Ig#| zZ&I1hWZ6!!&sTj%ne%@0ynQ?S>pG!XB@yHPWL2v}h-FUEGspT@n!)WweUF`Y$KSC& zglh>2%^Bv+L|dErgyojY17bS@CG}BNd0B;~rZ9Rm!cFRDlkpNqW^;SQ#8JO=b#!_k zTaH;qsN*G^+w%fKY0}b`)6qV#aZl5Y;61~R())|yMQ{2jgivV*&)Rt-w0>>Dn=0B!;KoO9L9Ahe{~nM3fOTL zSZB0qVlLKwk=aF3usF34x{?#xKWoQ`pIXOtwK%2l9@oQx@;vClW*B5A?LiOWZqCk) zb<|5rE!^DPLj`!WpE+*r9|1X29){_{Qzqm&JlgY&bBpO^rxq4;6F-}A)2qrhm`1_F zR(^gB+EA%Jf_WqzGHth)Y8*0O#uxkmmUGSCFy{FtB=vTM_Pr%5ef&VeU1M4fi`+9{ zO{md@)lDWGsq#Etw+kyBo|ghRnF5!_f0;Fs&OH^;f7Ic8R*cC0>6E{nHMyo1N`r^{ z$$ppU)IvX-`kvH#T*2)794Aq$n8(VBY-f>B$7YPAmd3IUBsBU@5_8OtdOsV1+OWM% zBZ-qdujAi$yCaUDb~LM%q%=RIF4wJ}iDMD=0TgOC?&k-NS0k=CF@BF} z1y0HE`E@5wBu!UK3zH2hi)WbRe2|WSx9_vwriv_e+Uv03;@s!2Z;O1bXop9`PRi}P z_c26*R~N@RiWM-FYBeRe2AlsVaI`E-N=RUF^6Z}SvdeSxfX5}g@7?uDarDb;y(;rV z-dNIlp6!3gCLp8D)j4KKbUU@tRSqseNeI7$WqeIW0+yh>Zp6eQRd*NDn3Z(|d>tLM z6$b4clmT*xR=>fS`deE3R{6L=myh&SC{?le9Y67%l#10XrfU1_oblZj*s zpq&CztYRp)mQ{f}UTDC47ru`Gj^y`X_0F{NHq%3+#Kn}8AlW1%|ACU zn~NKylChnVkRLdq`QR1Cox(WrT`ZIG0%wLn^c~czwrYBOJX7&Qa(I0aFimJ<^Rr`O zXlRGq`sa`p0r`k@6fok}4bXuNloLi0O*lMGR=c6m^Z;)v#}yeNOLDpsf0q6YZUNAe zRUi9|!c)b?rLIZqxcWPeaCP6}Fa?zcM~;c!VUpbPZ8l#LAy zFBRbZ)KNj?FyVDK-QsR?mN4Ff=G7COTUe+lbH7sMXv<@T&arRDNX}Jhpoy(t2pK(J zm-e`_Z_s+TJNe7U!Q%R0OOq$Y*X6E@6)Pp1h=fGVZWNeKs&j>%F_Z$cIVjLl?P+gq zQOw95+a54}QCvLNDGu7-O9P17+uU~FzpZc$4cGTth)KYHXiMLLC>NV9fG=Rco_>_P zx$P7ojMTM0>Z%mpGt+zOk)3KKN zRrx$yvBbjCwJd5DN8_5N@tCn0&8zufrM#*hicPAxLaI@6Fi=K>34YpR*6X|TFOO$& z?tEv+yvy$E1<3}m@I9rRK_16o$>P?Hvo%4K1QM8nC>>Q= zptmd_<%u6QX|8$pJu;r7EGDq0z-Q^rq=@n36|sN(%U!R~rlHg(#V8kWYq=9;8pAYt zv7XIH2jSF#7BPFZpll{(9k*oLMz?)WPk;=AC?C}8L)G*IOulf_NC6w6!0Xg+VoTFA z?33@KkNzZ}3n<{E6xi>x`9o zWknlA@*aGc56l%vCWZXl($#L0I)J?3iumx*3V3<|cx+G4_C{kU8#lSQ#Mmbn@td~h zwXS=4y~6&`qWHZdOTE26P1b2m$`Q48$Sz-QICV(Ja{<$qDptcSlo{vhVq6YJ>fT-G zMnB&exZCx)t^Y}xBk?yRbf;eFgP@RoT4=aSLeY=@BfutmwllkN-kJ$27VvOuq=fb+ zShIGd;B#HDH?UIpPQ9dPe2k=0gt{hhq`t&49L4~)_6^D3xAY<`)HSZjP~_y$qQb&f z;Hx|io7ZW{M>YxlVR$l_)WdO1sBhPBM8Tcp5z`VX;h~<#4(V?APMgHoEKAWG2pl?Q zt6gaU7x&*rCE8bablJWh4|RGpl=Hq+r^~w4$satl-;(eNoeXYiUWB+ zZe|(*UBD>b=~9rFwXvKXHJGjg`Zj^a=hKtA=+*aVpieM`J7^bmQpfBI*@P zgPS$80u>Pby?$2zS`l*cKQ$dnv?lB>s1K5w=Gx6X)5XED`L(tX=4x?Q!Ge-Js4>Y7 z5j{K&iwW9QxN9_;VJL4RUYo~1FfX^Kay54Hsnx>>I&WKe_;T}sB=lZnE`IHI*Y215 z`&+sGgg}6>I66AoNZh`EIH8B#lEoOR5~SfNZ(-#1*89FiuN-+h!j9O8Bar01W34FK zej@@P+v14;zNWZbvNa+HOETk}z}Ib=50-M<#OWI<)ci~v(MzF_W$4`+fnci8T=rq1m~>d^&GmJ1 zBt2S#xV@2awvTo*fW*|btz66eU;E)y&ue4GKKnqb6v+tK`QI=V8 zR5^;o?J3J7I&Tu2n=W1%uSK})GP&-CoI%^}5ig01x6A_5643Y`!5yK_386)DyM$p8 z$0Y9s;zxq#6e+()Pb4yG0*?yWfI6_B0B#_%x`~ceAF!gPSly`@yLW_9A143e8%azR zSI?~7$9?0l!>6K*@wL@_{yVd%`tVfNki~&5W7h+VhK43z3he3+HHWY8bomK2b!W0=w5oki2{ZJ-59 z!7WIQ(+Q|@BP*2lL1Hqgr5H(7JxoU{BS0KFCA1M zr%W7Ci}6E^1Bn&~BhE@7`BBJbJ3{9GGP7!t>ZVY+qtQO_`hyY17PPP*?$WL$G8*rE zAZ%wa{mPM&=F>Q# z7gcL<4|kfzL1^R2_R^;sVQA0ekV*$qRxsp@@MCiU|KBpg-n_x3R8 zayMZmPsWqE2U0ia&eG<-CN(LJ4=; zv5>yCi6Ao?#^ur^HQ7NB(XLBPrIGkWA|x98?B5oDr8j1ZrmS_A#rW}u1F4W>G>ocM za>{INF1hYWc@LJf3;{cpL5hn|U^dZ_-zPkEE-@u(T~xNI`Yl|q^i`BlPgU=3X^RHm zaBH0YyRgvcv%LE`A7g%AJR|5#qoW)Kqs_qq7jGi<-e)TxtXl#(4%g}VH-L)5EXK!l z6gW8)`rU%&54o6^TWOO^df)zOkeYmBChvSvW+$mu;0Kmke$s?ocw2Q7;25gyjRWs0 z19I||Uu2B9J*neG%-rQI6!N_y8QgIc40d>L2Xqt}~N28NQ8snh2G;R)j<3kHD) zA|N&${f=|Muj;0mnIzz2i0+$X(e#umC7#&i4AN^UJ?ByFks+$Yt%x&CZM>@sOJALU z8Zo`krf5&)qMR@88{KQJCo0Xa&96}3+u4a6PCzX~GUZ83OH12S*%?HoL!+&wZG0SC zAUpb?Gpdl-mk=mVW4s}q#!1K#lo+WIozpS4b$t%_E*1W+J0CJO-%@76Iha`{zWM8w zf!Y6<`vQN2b3G(#LN^32px8-g^Az`M=lQYBxMvez~VpaCPN+F7Ah(IHy)p0YfOb$-H!&&KFsDoc~?0xhR)afEb3D z6fV7ol)+zSLPw~oqABs=>VYcJD3gYRROEG{qN)ing1L?vpYs{ipX-lC`Tw7}Wi)@2 z#B!_L*ZQPLzsRo#o6x-8MqS3wTr?PysmUHnFyT$pRNnHRbG!jNr#Q?jV4nB}{ar%Y zuqv3w##1N;{?LN6Q5BmWN@QSFmFdQrF`UK4x=oWiiCFl!hxHiF(8|s`t#Q4gNXDRV* zZr}8>UJ&4>dTm_b?dMdF7naKy0CD2OX6|`A1Q9By80V1)#u=}@$dfQ-hEOsDCeF(X z7N!#u52U#|qPG((N?lNpj88cOGKyxgMO82YKCIxduEZ$Io)Tg8!O z=B6|WM8e|aaBP3ihmitH&PS(-$-HLnCo)Z|z9yP4n3la8rB z94H#8KXWj;Bq(BKRM?-4kbi@!IE(~in2X%2wH>{^g}WvU5_p|QI2BspZJ+k{H#9dl zH1kt}A6uh}VnP!XadGCj($D?^kJt^t0$xNhX@T-6t;^E){1gBdYzK^)fAgQQ;vO8) zTD-W}9us*S0q)c8?wI%|hBzg0dvO6@Gk!zyC(9JNu@DXeR8_~SbZAmgwH5iIkJXaB zx>R=-%3ewK!n}COxISG?oWl z3&w?}Y>4A!sXieg;oovn!QsTH%uExmL=t1@j5%G8hx$ArxZ~)P&!z3@P3!e&wcz*A zow$*7R{Vz6OD2{IR{83BR;D6A&AHPh3N0E63cM|$Z3g;)v6k)kOc>dbxG2@DV0h7t zMr8+_1qcf{&^J(eeW>53MoHk!UDAAz*jCAH11@Lr_$UzXQ7SjPja; za-V5iU*gt|TG7tHa-<214o&27bgW?TwD$XbI6WG`7UMfHZb zbiE#Pj7d?sF@&ArfyIkcK24zRs%t#ldw5!t=J_0$0^(+wlrHgfDq5vTKEQ@|!{xead-xxe*$x!eaW&(fmoQ<2iAOk<>_cL$~8_{21rE3@zzRyF%IF z)-XI}iHoYsY`kmd`*!Oq*3xn1Z$F;G`mTWCP%3XAFVr9`UObgY!Ic=gqtNjOY{jNI zNZ@}iv1iCn$C|Gi(fjH*^=_lfaxpulCBz1H0Tspv7Se5qi@WYPl9_~m+q&Y{J3649 zbzq3)_5e(q<4iXjPCUl&8e2($+3#Q36vO0cvj040#fD4C7wg2vX?rG*TW*L}m(6ZKLYG93< zO_piX`S9ppb6)f|WbM>DED(5`42QiI7wERhHqNK_=nj`!e>LPK44C``iZ~#UyM2bx zZHF3;xV;KH`7xb#%AwAks2rMPFZUW}K5m=?K}HN&gxVf^Gtzr}*V8roId4d^?NKXz za+~q@6c2;Q(6jXOJ$Y^RmA`-84Cd~_o6jnDKcti0Ap3vSEm5K3}$ZSy!&iZ)?%q5Uum-n`|UzF3gNnqcE?O* zeW^O_X`wz?cC)YVR)^l@Sjm>Uqpb4Es;iAxrf0&}Oo`0L6$4;3tKFvoWOp`rA*)lHP@CT9 zsutd65+nbdFbY1ZV(Po-q?C(}5=&13s>8jC@p@>6ZVW-7rLLtVFqfef7%S$oud1Bj z&KT!A2ZIb`4JTP+T>?+Ei%Tlw_pvv=aRywPUR?YPi=_=f%GCY+m}pHa^jn)uhp6C%xuK-SVM}P|6Z_V_Jg!_@ZPmAeB9EBf z-&N2|Bpbu{%hZ_Qbu;sJG`U0S0zJ#6a5&-FAJy>c^fyxE)9bT?`}K1Thk-2p!lT=? z3J66foJM^DP`=H>?%y@3n`a|l+wkp8yPk-j=fDL38i<9Hp+fWX^F}PeuHePk(N?;~ zC4tMUNDbcnAx=8%z^7dHp&~4J6)w9{+y{4A`oWm^t68q#O=({~SYqU?G0geKQ%=x?7H>XCiJL&{{7LXRrO=i6krnT$7l-Yob(c#ZOufSs4pZ5*YJ$7F|a z3*$Pf_K2>{BP_d9tW;_H_=koXalYPw<%OM|UR>@wPQR#ZZxHV9b#Ux!E7jYJWfc~H zVtd=BY1=LXyr!T*PL4Ax`Z5W1Qh%ykn7IAg1_z2tE7D>LwRd>aMfGe^wd_()e&5Ln zISh)8G_-AsD%a{A=PtKAI}#(nO?u-qPpckXZLHGwdP{hGcyZC$$*DR8mX?F&do`%N zHmd6w78(jxMYP^((qpcGsY5qCDB|d5ln3p7`j6}z|49Q#0eV02e@tCvR8?)T21O|; zK@boSq!EyoMw&x6lG4%*(uk5$0*CHCq;wxd0SN)=IFxiF-Ed#f@7~M${(Q@|&fa_W zyfe={^UUl&f9i`g%VgU@PPXTE#UF4tHLiU*qR+^;@vYQ$M-nR96470>Uq;Uhj+HN8jOTP0|U(QqM2zZ@q*Sv47dtrir6XSUt-g$1u!~G z5Vb$BdxXVa7(rA7FD8nj$5V|%7&cs@ClQEVoZQy0VH*j90Gf=P zd2rpK)$Ln}G_PE@)(hN!abvxk`yEknV)9W;Ju3$vGb1s;2;P#h*H^4I*jNg0eV>H4 zF+5JP_lH4{jg3;B+_y=y5b2%i{-di_)SZSMCg_Tlc?)g40OW~uo9*);ZxH?_VkFKX zW}s;I-5aKJ9Kjj%SOcLiq$w9)PF#^oz_f9d?q^=0XNVOli7lK~AJ`L%$6$X_Iq5Mg z-HApq(;^^)i5{XKe#4;3IB;b#_uTCddaNoc1(ak+NCE(ORO?cCT%Fo==e|i%y2CDB z)x%bt0~b_NK!MK;EWrmQSp^%N&uY}xR##&gk@P2gF(Sgx ztgq|0dO|Wmna&EQ=&ZN1L|LBoRo~VZJdDX7&Xeq{)J*%r|D#P7xT5P1#Lo~W1r>Y&ex+uFfL{7<99q&G; zmlhi7)Q)T>2BB2EgqbmucYt25Pp+7m_iWJ1 zyk|9MxeJ-k4G$+|VL6@33!!mcZel@>hhu?$qwgw>;s#8bO;T@scuX zwmdY&)%vw>nRcT29SwR0CdKM^W*=QHf_szlwEz-<9Lkpr#Z?Q_WIS-U@4D!{2FLv} z(AlegGE%#lsc{RL$8ll5hYP@>0!^0s?E7%ZPt+k(sIkGFu78-T!XE$iFC}zfazM2P z>S6?vL}kv4*}Hwpu?}^ZNZG@*^K>vAqF5p2h8$WWhMJh8LgMyb%HioN3lSO&Z1yv# zfF8j~-xcY5``!6J&msk8X5jihSs6FUDWKHH{BrYh2}^0>`^1@XkFmq$#MS%ho`D?j zT8ol2h;c4W^;vC5RV^FcB7>7iNyn_mUw~-yd8&Ww)1C&yqwI+ML$(?wLZ(p#aD;Vv z=jFAp#L<32cWPW}YCNs+>E&v#lvWb|ls2UB?AiN;b!XxkqL z=N{9*r?n@t*<8}Buq;Y)@CF{VH*%g%%q@=jK$nH$ioQ*jRh+)Exr%peCaF=8)1@$E z{>9fJ!B z>cfAuzhCso%0DSD=XZGe%IIh-zsHX7U=wUk%It`RU$yYqHPu(aERD_c-!cXa4WlI* z6vc+RXTIYL3GPc6lnE5utvi$bR)4Zee^a0Nu_~mV?e6#cR#sQH>&oSlW97rd#a9le zIJ8siEA&3?P?mCsO}(WlQ8gCllrLYNzsq?wNb1AnJ8O~UKjKyq@bI|vHwdX_Jzch& zw!gU?=5+*>o7b>H4^OB8Demp9n8;LJr-4qDd!T8D7SyUPP2$hN?Yi^M4Ha)|XO?yS z^87r!7Cjbxig1-)nX;H*a#OvNag$!=b5Mp7*CV1Do?qH@(WC)4oI9tll= zL9ZM~0?0@k>p@0!gwpe&=YgsmlZbFHIsS@?GH_1CQ}v)Sm*?dT^^Hx9P2dyIpE4%9 z({PPGAhz6nFj`{gdj_koVApNb@@Q$~K%^;mx!3Nu<2V$J`q=*Um#+qRH?)?;A4}<# zek~qFXFO7N8?=Y7k|pJ>zEC@8kRWoU*T2D(8+k|vPszgt#o_{|-394H4Sh4((|^tH z=lCiN8#My9=Y`oo_9P;PaKmisRlcIT%T>d+6y+JG`Npm zsm5|?DPnt^`(>GA#bq^RTkOAR@l@O%t#4@#`sMw&0<)xeNfIpy6=|^i`upqisayuV zu~?SKVRXjP`_Zzk$)krJz5BRRot;vHD7rT2S7z8v4kKz*S+}`gMQ?KYUvDhhsod#u z;;U5uI9uF!YUdHF&D*Op9=NSfjj!*uh>_nEOFL^i-}zDheGW^c@2$&aK*o-7YHBMPAfc6huU{7=Aa=UtbWhmz4CG9y|V6PZc-^ ze7d~;aTH~$o3d@=;VO?s{UCvZQ<6nVN5LP~GxWv?xquuwr7R~^4>fX(*Xt;~m;OAy z@^;r{61&!3C8svQ1-nNr@r-!R(+9_wa$`Ie+Mn`>HS5A8G(nvV8a)$J+|bT;Lwoi3 zmr-*>b&vf$P4}4^6?cScFQ42KJ~zwjh^@JPbr)~C!Q0b3bHM&IGborI3Mt9SQ&}RT zskjgKc)Ve>xj+^EmZv$h@ButC`=;HC^geVMH)X7~=w2!zXKL{FhOTqKR9ImB8nk$5 zf4F|PZ`I`#-SEQq=ZK3rA}y}F{8Yy!eG?k0uI3o}%UW_0KH5zb0ThG^ z8`MLs5JgI`S^t5)j07t1=e&*dwX@(fUobk|MWndOyJjlAGWhADkznAmlW5e%rDw$d zq*pk!ca~iw96W_`shGT3H)~=z`@5k{M?*P)opZ9>e z4xLB+4jIjj!O`Sh6ah$di+vvEaF!6u8_h2N3ZIx}1+Fqp=SeEONyvK0b1lZn4;j>& zo&45iYw5HVniexNeo9>jIG@FbBK4s@X^&zQ3|d@mPCu6AM_N~N6=(3sl-Zmjaw6adLJH15vvw+u8>*J|TGzGCd`>OSujmcyLCHoQn^9bGS`jfUwrs;Ifv@Y6fa8Q zA9DsV`U9B`Sd2*CI7xjjnys-Yi*(te@Tm( zxmg=ixV*gj4%60vmOHCM>S&ai4_lh$)830gITE~7rNFr-aZK`xIzB&VCzFapsv-K@ zn3U8<>4vtt|E~td!vZO)<#_G*Ed3MSfYx*u{K@`s!k@y$O@y8vT^8u!sWC#U0=>a5 z<-1ra_j2~sAzPJ|(`(L7w9nv6W#v~Zi)p34u|4iK_b0I7_iED{Yio)Ax?e%u@83>< zNhv8|UN%agYsFe?`s9cxNyS{tEV)0Z%}JG2LLmHYQGMu<;*Ep0EHiOrW3#HR&iI}9*1rNB^lDfkZd z^d9yH#O^kB{bKr+b<4Y@r8Hj_{rU{7Z50x%E5`_iL{0G`!(0-*F+D>m3xs*PpzCkZ zN(*cji?hC$-KVIh7s4KP_hG`TXtu(~tshX2x2KCD_Wn6*ChQD1g(QkHi`63ToE5RD zB4}}#!}YKlZ~r(~eJI+=siWsi_v*I`>7uaEULMqVdNj(b@>w~Vzf=7x28dJw+y;m= zX#fwVyEeO)P)~#2I$W0-rQ<3`vms#g22*DP{%W6%Aj^4yB#^>(mudWkB^==+wi>YL zI$R=-ZF=Z1a{sg_1^@Gy{Y2(FU9xPZQJao*Sjt?4eg!Ra5h^raXBw za4t!va?4Lwb5ik@R$VRUmDyWcTZ`A`yqvK0yx=0%_=A+)Jy=@H8}HNHG;b+`3!(UY zlb^%n2FcU7PevKv8!YxSmkq9MsL*H=x+za<246-6*R&gXr+99u);Tm7*fPqn(F}2j zizmuSu8ZfWFjP+vyoNr2hwN6xb;(#(9ZY{z?vvn$2^eC-$pqdhojrZ{4<}>gD_owO zuCy>8?9Zp=HtRY`S7aCI&%1H&8JWOM(t*g`0 zG$%%}vbCkm>fiA)WAVtkUlF`o%KkcUn}LqX1*s%Qki@DcPegL-{)8G!&|F?VM@dPK z8|U&E@>Ee3jDV|SGx@jTTDx~FZrM&~yO$lKsbY72bfPh&rc(3SvuB>i+gzIBS}@u( zNV+-u67$Nov9;#&Jlc?t4_0_We#Wye>^?J17FT738w{&M{^f=0u&|4UvK@5T$;JL` z64Qnmst@1k4*5JI@SynweC`Y-XK|M-@P75ReLQSsCS8W>ysXW;WN4fMZJ0zmzQ_L z8M}$9?dXfIt5=20QFdGPAgOmL8)M&#Fh%59x^_a zahH-Zug7Pg{H=SHEILwBkf&09Is2pXb++N}b6njT0|my*zD!BHJ?FQU1%@gSSbAVvay*t-7sD-2m@%10YbvfD+nfH6wJ~g|$OZ^i3AM1S$MM5fW zZ26l`cXf=4(?&xo$a11o%Ej57F>*dtPAm1IZh2+?*EK-`CwXSwFHUZ_8YJZxfUKz( zKLG9#EBl^!upW&#QIQ2vFmbIaEEQX6`xQ<8_?dy$*a)+xRZ!2f@sWG$gEIC*Lvfxe zfFWZa_jMo3%DyO2BbI*fxU40$hnU~PO8{LVoZ)g*SdV1F1teeaNl+CUC`1N2=|WFF z8!t_O$T+ZYI|k;XOG;|{4zNyc(^5er=W7b%8X$U`kN<#*Q^-d1*Abp#07p>2q^{#R z&EjmL4V*iA8wR$gz_NAV^u*$Y?eJ(k{v>sl>=MdUgNh^QWH6aw&$G~V!8L$h3Nr3~ z6oJQ-={4@tz?IW@xJW>NfQlQVAQA=zy)FKfn5al@i3ht(tCTMX`$bQ#;<2ZscbT!4 z=`#yw+Vf@=xMol3UR1!yXdb|CYBdq(6u!d+(B8>4VmvHRLyskiS{v4KTRl#5s-(Fi zIIzP6!)$K`ijW*~1D(uPDe<)fn|)RB;ei1Lb)=Ml-2m?}vKU!p=`EfT+Onw54B^3F*{^s&e&xR>)TDCVeyxN1l zs6Jm9(=lYUwJ2Dt#iCL-lslVZF>P{zBXDlGat8Ebn)WV;*FFX2TWf|u%W7-gF8iNb zjoY@_CQx7qVYg0n#I`YQo0mySO6G(*Q|n?m;43+qW&%-E#v&t4)n~S)yMY6M}za|AGCTG>-daDqsS5eI7&jLc5m)m@+h*BCbVD-CtCpC-CymF4 zhxglAdq$+!_ugUpejEWpBsDa8*r!1$Nug*)q_lVEVPVC+?mhIyTbs$PPc#_q&`QTQ z5e4xH(HVhI%eQ*Rm?0mO-b+DN$iO zOi)9%e>00+zzpDCE~I>d=hfu69w5WY69(0Zun3?Y5yl5&F2`&~mfqgwt}221pvO^X zL5FU0ye;!+#S~HF{dJBHvOY&@D10Lr5wV#U$cd07034P=imq$XFG35JgJ>hlBPfI% z$(*nk9&J*xkdyqImzhP>u>B6iY*3p9Nm18Zax?`LosM1IP36e~*sZ*6vAU)4aRpl; z^g+nTl1Rihb&DnKvr(TxH8&NJ6ihH2J1!rqfiJ#eFBh#RklyuRTsrwhe`iTDIaR6D>y|c+S6O#BZpibs0Cg{UWad4cV zUNb_o#R8%gX+FG>pobccPDm-#{@ygl;vzC(P2TDKK*aa}kQvY~JJ`b@65Bjwd#Y|N zL)xf^-TLSg1C-~)Oli!8E@ptQo9$P?RLSVhA@=(+`pp%MACGR15)#!0s_=W_hb7@)vAi<&rT?tg2n*-ws7V_$MEsCU{x$)QQS=vB%J|Km{w(?XafJV~7xON{` z*QfSL&H1PIBg@VzG!|rsUT1}68`yl{z%=rI&WvQMu6;E1pLZe^KLsiFJUlICRN)8a zr#SzGo9l_6LE76wG(Kx6#xl9l)xOdz`lvTO7wz3L_ugn`Ts}g~-ck;>fV1HZW)Up= zv$QuFzCWO^o^GU5x6Vf!iImOwU{_Na^f&GeH$3&FCwBRb(<;N9Q%%BO#wnB}jlc)V zn0h+W>lKT{2Q>Qj5W?W?m~B~+uICk2(5IGJ=OY_|eCMuD9YhLao#UK%#O!OB8hXiS zf({2+a)&HnD$p;3{~HS2MY`O_s?U-sLVt`L|EM`$#6(<9S@wX9Ux57#ywSljz9$(x z4RiTmnX*b;(x)4eG>osQweo zD}0yg%~40}Um4DjNWoVe@7m?6=ayiYE4F)bL+hPOcG_P}2i&V(z`w)A;li7avn{CH z=sDhhqrpI8`r6r9w)AiSaFePm_beh}s~!&E5vmzjTr6YNFDe_Ws=9y)sQ)r+;n&KD*l}n4c-;N#^=R8mOgoTdn}3?v!)j|BKBMyH+tie z-Feo&2((o7{Y;=Je9wxQ(*mXkI2RiF*QLH@u|pK=j|E z(H)X3-m8(eFGOgv=b-_;B_EfhxLe4qW~pJoutju1iMq-*0p&x{vj(#3^*Y_c1lCHs zz{-?l1Tk=a@c6#jPh9I2>z(0p#uI_i?qol3PknYC?m&T1X;3eG4m}55d-~Bg80M62 zY`vo`WdtXD1d&B0ESoF0u!+7OrYfuvGys8X8r&5L>RAI-r6u<03TA9+^UQfJU5H_2I&#A_wBfD@a?-G zz_Sr}o9Mm&nM8xp_>O{e>`y4@z@N&q%6ilAAm`4pzp^dZAw6=s(Q_fGQB_gaDQ{%i zQcY%;yHint8@kS$&FvEIiHtou+$b8Uy)yq|O7* zBR}~c;=Q?K=D$JaO#p~5r3vTVj=9`M{r7%pCOI{&{h?lj50ZzI8M^egnMt=~tdudx z^Z9~qLToEM6W1GY>Izfo+DryHD%E7uD&!-HD&)x*3&vAv8$-9LVo;_vA0p=hKHwIa@SkN}5Qf?c+isO>pm)!GH`hPW_nmivIfm#( zGnxWY{`kdc`*_QGd^RUl9yOOKXcj%H&>PzlDsCfPdK~{}WXfDB|0>JoD1HxLoWNED zmh

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

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


!plsER_WS1P?J41NfhQ@d&Zw_i!X@H(Ij_91ie`J|qU&2p0H zu5`|KznvFIuJ)tYQ`nD3Nhv`erXXfi}no25IVMqO~@vW~b5a2vA}@$dmp2 z6LpBbOG69SsL$ekg+=_JpKg-jT8MAjG3U9l-VY_pe+!_hu-QQjtPNb8sTGyBNh8sQtxeL`x752CZ2GqA=WB zMMRUvcSN`gyhf=AT3AJKzTi*3tPonPiu(`ApFPOyjD~BXZkq`!GfpM^W%=sgMXOzE zQ@a;Cg-FOh=+^-@Dfl^@tFO6wtEJDEi#*Wx!@3y+2Pwp#EE(w^iE^g9zu&q+%Hb(3 z?b&6B)?@$3x}p>UfGFowSmS-M&^>G-%E)@&B@-=yjNB!}0vO|BJ zsWi>t+XuRSacoy_)_!WXzuUV?lgw~PQo*JK6{2gB^;T>BAk3|C z$7dROMfMkHkJ!+^W()utw6Rjd=C(ZWx;{*0Mr7-xfi_IlZC($6XAJ$vvULL$gLHQ) zwIoY`wf?}3sa%Hg8l1Ru5yLM<*?+#`B#F0KNkRo6ZynQj3g;9~A7TJa-3C2qVL(!H z@2%f1hm;t34nAD$>Db4}Prx1k(!~RfpSvFo*Z{-Y1jHri))SY7d$979&)mzdyM ztB02*Fl%)??f9V7$?$w2yR{I;c_^kNUB>i}TjU&9Jcp`QYEPm2*ZQG|jcH!EI2-WV7tkg4tL*-*WEejsyZkMQC@!6Qu`o{-HknX3s zHNL)KPd!tG0>$ZYoC_wtd==!{qg|-(vKlSkS;KQg(7TK5H%Y=dS%I8a?$`-6uTX{O zTzu8`#U?FRZneyHI8uK&+pMZVLN~-W`6iAe_rq$j+sAF+#RpNc_7z&_?THYcSvED# zze6fHC%k-8u!2WPeamGvx|YUgS_Ihst~*KpMN~~d{v#O&Aez^C-ovPThSqqzEbi+Db z7GzrODz56$E3#gj>^G4a3J}_56R4}m4DU+0eEE~BvaZs-_8sn**>oexZ%)s+UIivp z<)$e>+$d-)tpsO-3=kVvc)O+sdM&<7W5s3_A#=}Q$%;DK3Dd_sww2)X?%Jcdjf$K7 z6DWDM?NAcX800GZ9(vV%5vksuJE6$O4MR;oc zMN*5$-Yly*6;ezNiPwxEiXp9HF?HH~*Tb(&=;t4RJc-N6ex$F!csw{b=qHf43r+BI zzHSFJPrChK1IoW2s>8=p*k4mcDxdjX+ib5d>9wl_(Pq8XmXg^^&gZFMGFEuRZlr8Z zL+wgbFYf)JQS zouOGM$S+a0WhHc^)-s3+@^F9jNXk62)XL{;5dDX=|J4F4>S&m%$V@$NmQAH}B>B9q zfM_tsLi5*ulGG3hz?V4;hG!L@kE`~&qEE--{tnES<#1*y!!Z6heYc-|8M^jtk>zk4 z$dp8piMca*&LNdHG!DOS_@}HklPy5Q0rnDu-ip|1$mov}=0~LuF*aN0k?=c=#EvBA zJO78?blk4BoQ`-aP!o<>lQPqrtLAoDwvelp2g%E)FyX%bvXU3}J%jM5S+=B|F;fAU zX9EDY=84YQ<~l-daj7!w^@Q{ON?zsKTkY^aJ1mM=i!2W%osO#POPU#JGe*wSg@&&f zkgIKIe8gZQSu$H+<$bV{0RK zYl*Yq*KG)&7Q)-YT7OchsE=A0_W?8i63#`9^owYT&V(w>b^RJUSfG5AJ8XR_qMUf( zk0wNW`;AMqrEfgksXy&ephu+x9Ag=8B!PUBoR`5BilO&x6!{Opp*?s8y8{Brd(zu| zM#|K%uu;7VPSo{^B@RgQG5>!~^wynnR<8hyg62rVNr|+j$i5RT%xvcnI~0-7{cL7t z(mKU^zMROW(Z~aW-f5uS4MOQZTC2Ne862;w4XArC$GQUDf}Yl=Ho{BXKQ%}xdc5XE zgHjy9p5Aln&XKnYjkaI`e6Zapeo(jrjB4?rB$qthn_ba{--!%i;{OJB-}r432_R31 z($jxQBD65vf4}n&{BwYhDhImTLvIn8LzPUk|J9+9BraH3X>1`@Jp_P;a~l?^aDo} z;f)sf#;NNa^J)CB$xE8LO0FP1jT$@l6ox}!8zA2WVy6F|ELEe**kPe$Oo0Qa3lF&> zmk1PYk&yYHxPD;l!HN8p|E&NTr{urCkw+vk>BgP-H~&&Am0L$69;xZ$a~B*LYN@z(uV)g;*e6-Xx+Bn(?T&Y^1lep5EQ7$#B2NXV4M@Uu z0m}2Bh23YpC`|Ku%diXmYs;MA)Cttr;J^W=Yq>Ma09$Rm)UG_oUc?dqxuQ%gK^Ta)>5!h~a7+aV=k1Gbl7Ln+@x3!H95B$NC3BVC zNE`%^!vKu!)yo24?&&vwH_cs4Kf+OF(eRPz|D)=?!{Pp(_u(Z$A`&f1NRZWAi0D0n zgy`(*y;~)Etg;eGbRv51ZP$`uiJs^sh~9!A+UmWo{VmD+^L?K4hl}fSo!2RIX70IX z=A4DyEv;DGNc_EV2DF+TYzm+8$5~&+tD7-!+;c%4v1pnlb)d8;c5bZ6_2fD56D4_! z;SRUem5w0W`9Z8WiZtvIaS50x$&m>`@H2h?HG3674_|tEIR`+kRz&JU(-hWt%HY3B z5pd}x{8extmS%Z_e^5j@n2XYX$7SN{%SDs@)5BkOv^zvzCW*F!z6IVTCitgICdqUU zbfq&zUSj4_2-0-qz9250PT6QDiI#hY*V=FWJ1}Z~UYjD|;e1M1!*_oc25MSC%_w z?`6l6mw-t!hs*y1@NC^7q-zErSX7g~s?|L+qO!8%qft*zN&z$CQ|90)ue;ocp&by<%gR*|W zMt%IBS3^{hj!yk>4G<{Zxu}NInfR_$pUY_WGhFR1yI84drF`@Qk5YyTgZht@2LL|H zTyDi>9zkyQQ@+b{75HYM)T`q&wXkmBDkA7>R-I>fLLA<|MKzNRDCtcjkd?S}{XXbl z_8Z7>sip*rKXtA%86*UHU9L;%%3m@jMrU@91771tZ^?7MO8HO1_|>|f_}Xw;5&)Z& zp8e*XkZeQbXm_IK;9w(41I&*G2EXa#QPoSbnQ?)2N^TbF+VvRt@wm~r<|B|)3K8Gmze#+F*;cvGAa!tA58@RTJh`?FH+}s|2^>SNw$U- z=kwx}QD5-krGow@c(a^~d?3H#)YjI!$0g#m#rvDjjNU)n7v|~?(KA>c&VVVsU^pfT zBA+_@bop^JenoVt7fze=VU_phwy+5ozY6yUb1r(CPIrm&v8%A-?OBKz%?k58{N`OP zuF_##?r&wj!Uo}es`v6*1|ppwE_+cygdN`#%i}fEJKwG7jmCbT9nFM&mx(7QKbbE( zo**)9tT>gyHW@aJNt%ajzE`y7V#C=V*8OJLT;lz%Yq;x^FiyxI)7!`vWow?b-z8l3 z`q%p4iW9ZVPT|9qk01^C2cxaGbuO3lTee5B7=}IkmN>aD)K2)3Y5nexp$=IYT$#bm znO%%ff2vFJB=_lsAomZ zlawdKjAs($b$D1CsmV37JC>AWaUyJP%02T?L|1hGotHasx$;8f`F+B5rB`0B$}aIc zfJD)A>!8=jTAmL?yrwK4{$hOR7Arz0CSI;f(*8x5>z;#7<{%oAYiw^3hjRi*?x%!5 zfXazv+TBC?mLzKjUaKQ- zojMFmlBQM_GFoww%pSfb$E(Y>&8%>!L1D&@4Gi23#zxorLDpiLHq)@x25OS!i4pfY z{nNx81>G7Q!#hvf9~PQl3TueMlyk3hTxai#yv47@)lbzEaXFSt~5bfEo>uL=4WJ5$Pe971$iHY!)8;Qujbwl<5i@82HeGFE$AYG=xYF`9cKn? zsMwzw2|dhFMg{ObW51K99KaVGur~qolff)LSF1-I7o!(yOfM86iyCVUzMze@Qj;6e ze~vE+y1+M`iwVv+=Ot*zd+gcMp`Y1=cS(wynktOf?(vewg>;h3xVRo}L#jJ&?&bX0 zW@_Au^)v6OshtaXF@oO8BmeOJD|{=g%|cviMaU7-h{Yv;+jzcEz6?1`Y^8w6L%XY& zE|f04nX3ZFp+CFIojebWWhj9D#t6ful(_2LV973k4ckPCdf> zoJ%*A{Rim)A4+iP@ltVLv@1TXZVyDRP(C20 z4NkQqFCVamS%Dfhfn3_;p467ATT?sDswtE&FZH#j*-0{ZcUNg83|AU*yiap7E#u0s z99>jaI1_(Nc_dk8^k^z3gpxQkWW)Ep?@_F6-*`ekikcNTZ)aRq7xSW3OIf~qQJIZ8 z9E7mV)wJ%7=bqbz))BVdf(|B*bYd zYGZgEZLk=V>o|7wwucSb_GLYoUfqTQXDvE)FT7Ad1L3joFLpl$!IE^|Jhs9aMjuZG z4`ZLNaaUO?wYar*7uiYDO*_VQUyN2^6mB5FEP1%str1bi@PD>XLI;#Yyri4`%DMh6-{yxLm_$Wwq8#bD?nvW#OixYeLjB>z;l_$1nXOxM9 z4g)e@Kp&gjgnG?&q%`-vK?0`z%WvD2$3jV*{=_l+_;vo*UC~`TArDwTV{vTak7oYG zzZ8e)CB-p)LfUkZ|Ci$^f)zuL+PuqX+hRTmURmx}S~QYteiIZi?-2KSffSnxwjjBD z_bwy7w2w4Za)(RM$Dbnj^3@dN$jNU8x8!di(Xm3-t8m>tlr4A1fpOW~bD+85lrrbb z;`WOEVS1|P6XqKt@c8bCLTbJjs=`}~3&{~--ROw)ki4oE*PBZKg^VBh@~tDz<1_Z& zZm2rG~2Ye9@G3pAFk znM`X&A-zT$BocDth$pgzd|0Lii@vHIIx+L$Lo-C-bk`$>4e;>OBoEHW5Ey5;msUxn9y zbMQdr;oe~j%vgJ%7BqeKizwOsOqwz1DX_FTu>N>6oSwI!d%Y@@L6{))t5|{IbF8Lkp7wFwhOQFi zcY;}Ylv|Ia#=KE08y`YK?8sTG%7Y#~p506T$c#e`ELL^zELi`tqjFpEZg>t%GXgJFSSigIdEfUm zISjhYzN+FdH~f~k*sRVcx1gJf6PZXuO=Ck@F<~_d_UgQ&@QJ*`OOnc`5=C)c$spXW z!57waCr(Sku=p)jLWNg|TRF7TE1xd>x##wE;FMO(WMAaA~f1)zS#wKnuS?K7P|>B2n#*k@()w$@oM#!i4Dc|_{Q3ni%;tZ6c(VvV4R($6QFRA9tc;`fQ)f zj1i}!R7xtYba)A4AbQtHK3_C3btrmq=nDkfRmOv%Xz2DoqBLTwGt++{n}&gqzkpW%j3%9w7_H`3c#4!CXin} z`9X6I%FcM);6xN_q5vw<5Qr0nHED6Mif}nE8ZDi}pnDR9B~Ot3Mo~#eO06t7ADpa> zl2j)5Z#*^&E8O}+f9aPqWsYg;nZ)ANwh@+SKWp zs;Jm;vvhY^sf?x8SJvlxofStsSqz0e@X(V;nCUHJNmi+?O^e90aDK6`#tt^;#twA* zrpDjq7BtihMcIA%+_>tq2|Gk!PiQPeey~r)hcKKg`PyF*+7MiTx8S4xw-+3j)zgz# zZ=oi!DU6kPtm4?VhEy7pM|Xv(%Xn~AZgU#S=SfuM!WkuH@nF=U=SXJH4@lkP*rb^0 zlg4YQ`Qo;qx+VoqT_wHNcqYq9cP;wqNxZC7_N|kGr`b<@MrzFa6 zc=1S$_|f_)=MVS2!=>hrJtC+2ahrhxN)R_GC6shFHE>!Fb{FM8z73?v4Aosrjf5_o z|EhWSpn{iud}~uklHA8A;M{et#W&yAWLO&Y%Gn>Wo1EW&(VjosC%We=BgS_7-$7>H z&{fBtZuy@ap`DHUyIa`XoTxmV&gR-1>fTEj#BD*ylfw(rHF(4*RaxeN<*Cn;gM5@Z zS-FyKRr0)yBgQXgK>sRdeY%UHx6mK$Ze z?t`!87Xzp4o>QvrPZGicpgSitOVTcqM{?-9gZqs&MYn8Gm}ckHVCxf=BJ_;l#oUR$Wem8WcI^>)<>`%<#90)@(` z{d7DLKrK&*h5Z0l#`oxuS;=cT7;`4U4io^ocy4W`JhT*uHUo{t76-ocm~cXb5Bs+QT?{f&PS2vI7xfs1O%y-%T?vz@SByTWkKO&!ouM z0?`P}aYNQv9h0Sjsp+h5)se^6PYhkHh>t(i`nG7-w z)s09~44w3G#ip!>F8}2%LYJ*pT1H~e>Rb5vL9Z#+x9Ko5v#-JzvL)FY6>zbh8+6i0 zoTiO;_eQgZ&K9Y+5$HjtG+lJZ9v7}Mil(z$1wh-??PKsm;ZHM1cNwv%he0MEuT40p zV#ylnRb`$R!}WdHr)8{98V7e%zzf>Q3b-D8GCY_wU&Ko)h3(E=dHEk`Ne z-Tixqrwb2OGK~$^6{=|$xc&|>hkp6x&J^sdx5<*cZQwQA(5m03CHF#fE+gnR^o!;+ z8tHUfMB4vY6RffoSyh`00F(<{`>3mLkhcdUcqJ?YJ&;dWs~1UZ81G{Z&MMl4+5kUS zRUQ86T43*&4*0w`diY9PJ|jPv_?@N>)#AeHGeAF^dL>6k?!|Wx8QAg8w?ntYkrtC& z48~s#Q11|d2_6`|9^zS-9c-#6Ja&n*_7O5Ye`$dD$7XyC!y4d|~E3Vb@g zIBkfHZD?pw7Zw(#=_s&wV16Q&0d86X(y7%f-QZxWC;O?jJ!yg`J&y=bMVJcQ zb@T$fzy8MEfV!=|(+ETj5@t|%M2^7Qrkm%gC9G#<|GO~Ibi!D7hM>c-ru~hDebFb2 zU5;9cV7w;$I9hr|Db4rjhJh-)!)O^0$Wk7FyB=cZxo~+W-mN%9yeiEeNDW?FJ{mvk zcQHUy9K9c|hesAdoMk{{ix{h_`Eufj)z4U_ybl;(caimk1zczP{DxfH>K=gn<_}rI zP;yIiZX`AH&ve&57=^rtlsIIYk{s6tXoiYb2<2c$-(_C(?C)F*$#o0x9UW$bg}oW) z4}*T$@`rt;>e$)Y-&tL?zpIct(8;bUT+Z$DvpIPX#}8JPc=-s)%QMX{;Fg#C@pk_` z9Ud*@oZSsGfn-@L0hu&g_Nm;B4J%6GqOce%QIckU#F9@2BLN{{`*a9bnv4IM#5CKf zpL6Rh_kb$D%wApU-(8A7i}6Y{h(^&<5Pl(ca%>dMEWxdaQhGp(msx0rt|0SZkR7k0iyWEC9e6Du_8_vuoHnE2EYSJ3 zFzCQ6;JOg}5&B?vLjLW~6zS{jw4$;f*TWkNcNf-9%sduxuJYezj3|-o_oAN~_3(Eo zr-|?#swBHDZyxk*@@GGMDr~I!6K()$1^qf8&;m=7m6V3iW6yhHFiq+>za4J z7iwD=l=Y{9y3mjTG&{+o^i`j^9(DY?^}kW?%*WMFD^?vJH?vHabvycgtzo!>G0<(# z5{!pmV`|qkf7th+waztX@*VE$R|kdgbvbt5LtGPtzym;#re(@H1gH5s{*WI7tL%WV z9FA}cNjgK?H>S7I3ZCxy{T|yd?Vsx=Ue}|irw4(kt!r*{++okG<(j&;#qv}=3rO+q z&5#&?+*JF+Q!oFM_T1;Bb*lSt<5^Sof2%DurrYeT!l)Qj-;MXqwFDhV{8NPRs6?nE zRvnMyqir&N?swV!6Z0Wuo#E*dXd1m4t5OL(wkywA<1_5E*!`qoAPP(cAc(4_c&wNW zE&)hMGi*DXR3CHrEKP;6` zY2|4~xTLD%Rw?jhHe8aOc-KDn4T)lQ|kP}rYv$;usd1$`|Tuk5Hi}Av(FCy(4c9xl( zeA-VbuE4X z8d9J!Z-(8b$vmHb=@QUID7-QeJ48wTc(i+_f2JNQ^j<>gC>$OrHzL)vAMQ-w4*I*H z@?#E!)o6Z%Xjah>^|3F}{|w5R5_3}NKlA8VTExZdaUN>@AD+NyuxBn>!>_@bamcM&_B z-qJK6vGzu4*_*M!vez$1VO+2vua z4+h3)O^f_?_iAzl>JPG`M%~aU&>O@yG0Vg$#b8XCpJM?lgJD*jXKpF}Z9e z@9R6IFaE?vig-&;Vp&!QTq3+-yL&RyqW%%kX2vZ3c9p`RhKX3@!ofnUCDrl7tEzIo zySmdwXB};AA+zAD3jw-l(&##ECQTwEg91uO375RQSyqkv43eu1C(1noZVLKS6F#LCZ2qSABwg)HNhYM3 ziKK;T-+hHGR>`}SCL`QC0q_Y=Dr7cbZmfqB7XoA&B^18lNJc`4;V0SUxs|K&@_=t4 zLK8BqmLd5e2*CvcjjW}Syci1{`A@(^6s(}G!-&e2_XG4(brtI@o4mUBstYnMs1*h# z57o-X3>j`(#h$Y^7x(*p+e>?5<_06$wnAo=~P@Ri6ja|F> z+lYW54bE|WD{eQq-&b;;YGQH{Ej+N?f`*Tod3#q+{S$1{*K6Oa05?1=zY3|fH*kn& zY)(*To>@)QbL?he{CG_jJk>NjKHM--cs$&rUjmpFs{?%QEH4?M0Vw9iz`={%VLFXz z-LPwb8(BF&L^kh&|FdW25J<(8hqW3Xhk&w*g<1MgGu0Htuw&?&v1%MOUZgu6yK7+r z`mH7;bK~ioF>6=V+_|5;^l0@@EM1bRM{h-Ml(?f4S9T+KsT|G+L4iUx)6=b_FZhC8 zsWhFIj&Iz&IvLRPh!=Mi&1rQ?*E>Rm;Q8W3vVK|%kfLrl9SI?Xel5LadC#XXzt6?l zO2f1G^lb|V@mr?NqhG(os#O+nC2Q}28X!j9nl*p6-#a@4lLkl2>SbjA2Q24S{)mc) z7PhVP?F^+Kqz83T3Q~bAt_R8r&yI5-93)NF?yuea$=M0D7e9-h{*y{^@z@5ygn}#Vkk7IKNM91p2_M_R0STZLB80S`=BL z1^`WYS$@Jf$~WEj?-Iu;JWf~La7*{pXVV$s4uMy`E`y%VI^c%a?~TikPf;thl?hZY z3(IL$wtCNmzSVjoBFP5NyHgym)kl6+%Kf4RrxYV9J{e`%b`^u#wIWjdq7_-qM3YWaUewmQ608OU+7^V@^;{`Bolwu}6^|kS30RIe7Pn?{+36L+7#P zE?bL{tB401xTFBbYouhX356U*}Mt}w81(SUcRDmV2LNu zBiSIZ;fnD(^W13WATCM2&k*n1(U{_pv=k5CkjDSwre-}#H8DH8B|O00hI=ROsx^j0 zMfaC2)({4#Kfe$J~D=;I+ z;{~-dgj?7BcDZnlutQSPivgMAGNZXWw!w93*nPf>YXI_{flOIP$?JC{ItF=hGb`=y z!put1`TLSs6~f-JHw{gz{&Y(NdoWixb*2J!TS#24Z58HtPE8|mFyDm_KXB(D|x zEb=R`c3-06<$Y~7GLeVSgX>9!dn~I`X%EEv);0s(KFZL-z z1MmS;VcJhWxZ4n#Y`(o2-M`#FBtH3I!NvbF-T1Yws|^HjV{6@wMrrEUB#2(`Y^(G$eb@jmlC zHghQPzrHX0VbN;-W!NKuR5iY2kazOSV1n(#;OO)A{-&zB+GYIZ+j@U|aBs|wx(hu| zZFVLZ+jN>GefzEY#OD(v7iDcL3+nZ;%`*&pi5!ZT5JBu-ex4DA)NkKfx+i>4{a1zP zI{4e*Npc@i^Y)EU>5+~F&++*$q*u=b<-p-zleyVHJ}IMFkZAmtEukJY2j_T1*Yz3T& z*scmzDMk5A=ce8+z{skj$d7 z6|ggzi`~95zmpypddrJ-KCIQ&cGv92(Fb;<17988+<;U2S9Es+_Tp^zZ04vISvI-v zex3*$$=HV#{|6FyuTcTC)4$ou<1-(AUwQ;!ZV!1QSF)F3fZ61AA)rj9w3-aGjWgNn@nGGs^aP2UP2J ze?Ocpw(GFZtNNfMyaiWI($^M_Ii&qA2q3FuXrSqIn~J6qY*Ph+PN?zj7FAwUTI=I; z=*pbezrf2=kXqXYw$tLh{dJJB+2GCZQ!6F?Yt>tV;QQp{=*~_+b-MGzc96&7W`97~ zG13{bKt$9u``1PTYrPM=7XZ*cY}O{HLZw2Cd?z)H(C>3UIakt{yM2?VO5lAOo@;nF^CE-cD73#tyZsy`)T zQNqvS>aj2(32tedGYLF(;?qkO)&qmgHVo>kL@hrmT7w*qyt~=vQWA^R%UfvyE)Ud1 zx|Jy%rNp4M6UYsU-#w-m-D_b8FYnpo-$BmI4T6{Rm^s}(lll64E>K4F7*j2M9#DPI zuD5XMeQ%O2wcnTbz*q zf&KiBcV;RYyc>7>7P04pcM8wr8q|7q48b;qg@uob3RZ{TAz`0MV-kvQ*2Vk`Pfg^M zyPqF?a7K~DeCLyB1Ob2kgFC_8L;$7xh4vNi&KrZ#UV&TkZ)Vq1NwgQes z>X7?rqajlk>7H%g^an^r<=P%D8a~ zBqA!@oS_SBTupph!!UNB9X?--6KjN6U+PL?{6qx?^Vvl^llpxTwf@LjtWrY$y}%Aq z#+liAn4r{pa{SGpTR_4V-t-T>puc;!a_i6c z?6y>ZMr{tyEl=t|q3@bz@H0bt^^D%<{*+3N3%)I93wFHgWq$<1{kr+yHhzqs;FHF* zy>b`j)0XGp3jofoQLzq~LysMI*N2{yVn-)uQ|_za*w#odqQ}6G{3InPYtVr_JO_S@ zMBcAPKVCi7YLVko%TANKkK$cH5Ax}Nc;h}w4+H&o(ISc+Qpx)Zxw*NGLK@@CQdC^3 z+Bg5a4v^#Jd{*(bZnun7xOp~lf~vStygpF~raff~8xwGJRLsdX2Br~Fkq zCnqP*)D?F#BTri=Jzw`&_ba;s6pya8HpgiaF5f8EH!jZ~Exg!oIf*Z5tQd_ilBk(64PE zOi#ld+RNr#PwZ*5_=Gc9SqDJNtYDJ#4PamcIwNy2`N8-=>NLDV#=lJ;M7WWj8D$)# zFC>-0h)4FuG+S9dEa!$JAS=Zd-dEE-vM*%9)nM@B!B)t^t!B@^!>$eG%0e+fOH{u< zU7JzE-7?(orYAd>w$>&ELc%FlcxzSF*q#v*( zfZv+P7&N|*{Iod5iWj)*k-+je<(spXYFOoK%Z1+V8aTW}h$D|9tel4-YJso#QGmsc z;FJDTHl=EU|GcnM;N+}~o*})rp=mWw|DcESHALS@3NY9qp?CBHq|^g3|j@BMwj=a19-1QM@4?_R>v#ivobi>ufLY} zE+NeA%aEZL0lFCa_4f}XIc{)@f2TuoSJvs1B`%IlwnYWzhArB zmQV+O*qC<(&F` zK>f;UUWqdqwRCO!Px-_mveuD z@tfLFg#XWZXJ^g(BVpg@kaUO__Q*gUc^c&`A6OfW+$4GkZ8Li@jylJyw!T?kIrH^iu5HbHWpV6h!grT z^Rw(W5xlIDFs>pN9a$A7E-kx9?s3-f%lg8Zj0M34tNlj-;F@kwKt5vet_2;~TaG7KLqJGArwSKc$o12#TN@bGU23(@qgZ@g4F2is>DN=-$Mcsq( z`P{d36F~YPkbb;1C>|7V52lXa)83~GcgqVH6v5xA`9vCbeha_T23(p(vb`F6yakjF zqYyN$XR|Vh%$`iqhN{92QhOIiU}$ie7((W8mSQ@BOBd$a7aFo9l$wF95nOt;DNQ`Oj@Ry!|xOW8TP4}$L?uJLCWT;=caTKg&Bx=pA#}i z^0<+f8%%@se&I6l(JAr(#}X$&DH>yiboV}mBj2Oh>3cG?(TpS;or)0i)1@M@bU5HG z+)eZD7>#`OJzMF&wvZf0uuDdgBgDyXaWF~8cJKZuM!+e+p!6W_@WC1z0kewk*ZO}x z76jPqw+=%Kxo_p3>DZmjL@zcGXT2pEH!w~&)@9(kVQK(!8JW|mYXYF__~wP|sr8N) zj)z8kSyZ(x!48mft8Yv<3MNRtNv7+9d_4S0Cd|$+OvWIt%$vX0$qg7EwT_f-N8cfj|TNS5)vnOf1*bv!JqFS#eH>8vbx2HWbxjZ zy380L401ZdyFvOHiPp(#wuLTDoIqkKDynbxoE4+}LC%lcLEhJG>HiWs(|FoXj8m6z zSF=2ZqaoSNMLe4D5vD3(euHdr&Nk%-r^k{-Y8m{gYGWd!c!CdywYXn6v?-+jw$nVV zwA+r{s79nB{kbi9)s|ZXuvJnX%Rk7Ja`LJl;Atofs{7H|M0^=_c6M}f#GQ1~TBY zlgxe`MJt}EUP#$VmXfHTnP3e9^@+)R6es!?>h4z6Tog}!Gw)^`dQ=U*XuBbl4Wi^j z7N`t5iL<|xOLyly=eSU>_UNIMeK^QTXqfi=`ZqhL8)lNUcx<WO{B( zu6U^yNpMixji3S9{y)z>8??2LDobGa;9V|&=j;9Z%Zu75sIGP_E1)$IWSpR9+!@V0 zpBZ4soLaETM7x+`3#wenhl5K_RG4AXIMU%9tvkDM2^IYQL%{_fWqVrWh)%g(u*%ll z5S6R zdQg0+z?-mjQ|hdw6;`4ErK=SXOG!$HbbR6N8O@UijpTGkin$Q@);furM*P)?D+gzh zH3T2K9Y5$N|7n@ySY^K;VEW1Q*$XO=nx>ZK?y}LyJIJEZ3tU^VQN$OE1)+*yLcdLE zihV`OyxQ|7qkcSMn8!~{yBm1ySw+_II500W4m3i)&&9cCVZi4@0Fq^T^X}<492gAz zAKX|wQUlFqOBmj^uD3gS8XJjofHf&jgy4R@w?(z_SwC)4tcJgGAlLA;D0sy9{$!&f zT|AWP{O7XaK1h-;4L>2Xg~%;XQ0AQ=&Y@3#@)>-MlIUQ0-;@eh;^g@pm#t!uBGPo! zfR~84%6_P=V~~RW!bK;{9aP-NhTV$Q}Cni5nRK%Z@h*Z!SFTKhX!dm$un(Gebf;?L_eb1oGYG5h~XK zZRNS}uo!P^pOY~c@1sbZX6KoS#AP`Q(8!HQGNs|H&WG3=drHK^b5Z>{&HNFHb2B?b z-D2E$fpf2hdyDBja|QF2kjCL0=wBMP6R*9nHMRyQXhid}<)r)z+YY0Fnn8tBz^i=x zkXSuX?B`6-J*MD`dm)1)q#<>EZKJEiuFC&{*#oG$<5|su?;Zll)Yc}1`Et>0&)t87 z*QX`wQ?!CW3Jqkk_uD(9qbV}43w?>~_j~lB{C8gQO{@QM0W8yR9dh;EiYLw@vg&yv z84Mp?7;ETfJe>C`ySN`1LNZ3E+RO$5DFFzKH1Wwo`2GldM4_7pR=mtT|HG2EDW1Dp zoMzv?c3bY$wLQ9U#1#d&U;aNPv>{-vLfo$_|EDtY ziC%%KL+ttZn;*{WJd%7NwFvPw?AX7ySfT|2sP|dX5UT9={0A4Owb6cIhmAuJH6J ze#INtKDo}H(v{rS@ zuENMhNI&DAWy;6rc%s@TBKFCLjwEK-iAI2dXjAR+{BLIl4>mjpb%0|qc)9jf$Dp#_ zB9T#j%FPciFSIZUo?azJ#c)PBfUYROoUaH@yjcEHKTej?o%61^pWAkPb<^ou(?zP% zp#HlH<@=0#ng+V8E5bji#%E_uO-;9|{#s`8^uiZCaxXI{Xe|Nq!YM#1JpAOe43eOM zrO^U>iMpc#nbcF_61B?VuHwoE6rN{~UP#CfPQc)?Wy})%BievLY+_Fo_gyj$9VVJ6 zKL%KDqYm-U0uzT5&Fg@3OR|yv3rGiTwoQ0jJjs`V(D_SSoH zO0Z@VUA*v-r=kfiT9$C*89<35{PBERNJ*T)2<2i*kPe=m#BHquDplKC>1gUq5T59a z+c@sNtItd_tZ{eSE;FS|hDkCN)c5+~fO=V~AfE@?dA2i0}m?eFQ%*T!T$LBTu3c?Y1 zpYdo%rYp2R_0u+Ocb2slpkiJyY55nxZeMvzKa~Yo{kWmF@jGem$OFYaRfVaF?duwNI<~Me)qs3^1Givo=melyrufW@ z60yhOR~Aosvg8#4rW9l~00xHiaL<0R^$p!%R3ly96U#EcuTLX7b}AO8X9@2VG-E1Y=sNr6MlQT06Bv2fVx=->!2D2JHck2ddLpBBb^ffgBN>x4SQVIhOwHze|14^V_DvqEshkN zP=~n;Pa#h3214a>gb_8>Ub3i}1xom)l&*Vd?>)>jybcI6o_v-pQ+BK}DBT_2SFAP* zM+l-Hc60UbA(0y{ehaB}buKJQlK1aaIBvo;Jin5+EW;32xAT+7BQVOhLuVhK6gJD8XCIZS7)QN{L#S(J152BlICf! z^OKX^Y@d^CvMVB)sLK4X9M zsHq2a>I}N#WF5|FXMKK!AC=ZgE)! z{OlU>&6dK-+$qI5D_VZWRi;7nseFk#f9`3q81o|SQ)Kj38?*3 z{C=6*DKbJyUa_~VgZ>lXO7jm)?=c&zE!=Qo;le#hUpkQxH#WKe|4k?Gbcfn7AeWL&=r;F}G{r^eJ--RnrbnXe zE&?qw*T9xMO%LC09;-Tx(pgQIlRKV>MTC3F0&qx{9I(oBkUiok?sO>9W)sXEPe!Z* zT2wz;V8n*H)O)*l^V3Q}_lu@uokiP0`)K1&jCijNttds$tiHML<-XSy9owS#^5RS; zbo+M_W@ruT{ zhyXv-m&c2VLKntEM0fJFx3%#T2Yw2a8zA4|i$5I!4t~05ikoNHMIM>}Y>t-)vASXI z7Cb!t)oCsqcGmxosPB%a`hEXDwnRo&R5oQMd#h|AJ-oj%{+>+#^xU&q~f-S>4rpV#wwU6*Cqf~rXwUsJLT9c6?dGBVym z+HWT@w4C>uP@0yVR8ICc5m$aAmNB`3lu!`o{X0UgO(37M1Io^FOtOXPVc09*paUcI z53MPKaY61^O*uGE+Nbc8W&{Z9s%?7Tri*Ah0thknM%0%t!@{dYf=w>Y>5)5 zTqoOZYuHVW!1*w|8W(pQb;&#ZNH)t&_Ph4sEN;QR@L=sD(m-iphWGE^$LZfpO4eP$ zIG2D48}ce&e+e~eFNGmWOVW zKQ&L~V6`k4tZlCox*Inz5c$$C;B1GeS*=05E@Dp3)5Ivtnc8<7zm{X#Bu1kNNE)=T z8DUW`O3bKOAbP=`s=Ji3=0OMf9ed+fQbA?249i427ger-Cs>zrr?DVT=Ii%_f-`?A z2~FyZxN)^fCmy);TltB^DQ4H+iuV1azxK!h_Lpe5v(85&f(hTG2zK(gbL_W++aT4B z92=wapuSjC%Nd~8_4A=51*K#0b)JZr}e{ni-(%W)@!|L98FWLVP>iqM0>JSI5 z;3xf3SHOJXhRT9r=9sLFnhr%I)Yd+rJkTSG(hKMz;LYc_(lF*@t-bq7qMBRb zB1M1IFYaog6)c~tsi?QiegqkSf7@@B2;bqOShH>hB}bGX{Fmng0h^dlAwcs_P*v@~ zpbdl9ZZwea=vwX_)vFZ#*=ui)CmmM2e0#R}$<3jBx&rv?7gCJiedCHSem z%EpxmireGq?VwV}L`S~y3NIKq>(i(0nz=>K*BvUWde86nffCr$M#gjLgzu$yGlMs9 zqCuGmcFmX@{25{jOVgRsHqn z=ajD54%g}i!V&F_WI(O7N|qdTcR6yEuxbHBUKyA-0o?ueg^I%x#TcfCC1`8yiVrF& zStEZU!TGXASu$CX$@+;?A3w4ZZ4$%zXiWTqx_AATUiIDL!~N0@V8Ny9}V>lhHY5`rYvm&Ix8B$r)b zN9J5eqgx!cR9vvU!ros`b2v^@{n*n`mzR>^U%ms^^xFP zluV++Ph3EtFoZr|lCIcY(o8R+c2NN4d1kB?0zUe>r}0FSUMA*=fD7YNF%m_7D<~(9 z;IC%LYE1cSU-;hPyRE~a^L|hX*Djx4djLuL!EHfXXzOo09wU5J!?%j+Jk1H_Tksjf zy9+MmVkSckz2b*RcYLcDLCf?a)Lr$0^+tE7@s#3e)$$=_$m1$dLE=GP!b7$#>t|1$ zVw)cxe>oVVH-Ll#W;4K~Cyxb1W?<%eFgX_&9Uc8fG)$SQ3Z5x?tL0Ye3JRW~r2G1> z*uI)pBB(U))KirxrE5j`K4f)}Bzi{|!9pvocy$7Yn&~x`nJm8e3I}0Kf16 z!%k=?p}GadTMK$Z3yQOyON}AX^q(=ibhZI+8;EOrc=@|{k5Av;l-H)QF=B86r)zyL zFa~9F3|bG+=K~o7;lyq7NEfDsxW#*=9-n98o_<{@8;!q*hSz z>^~uedRQD_o0CMXxPS=m^ zyP7xAO7;3%0YwQ>%0P32EAk7y;y)6D2!1D)&++CzqVA-rm?OeS)xZCv2!>_pW|4|e z#z#Jinqu!^W?)v3+k6%RQcYdU_@HHi7pP=1jS`PT05@YZeMm zqJN_074pP0hsJozm~O7!z{D+@0j<9jCSygWXbeVy%o)u4S5v{(0>y%&P7u>XL@ye|QT*DSg`wRb)O*X;vH_MM~63;6zNE3Y~Tj%MO8h6@tr!8JxC zGvKb>F*Qz3PPi&>p9H5W1mdT^?RWonvp|uA`Nr+npj4W}W#WyOz^g3|Vv8JRY(B-O zx&aJHy9Quz`5S^iWm>KoMXrH9d*&%Bl)=b}2?F zP(nclQ=wuyZK+n)7^}vYp5U+utt`v+NEJCuQyivsOI)tdnBvDbVrU|)w)~N(|4V8+y}~6jJt36>gL{|y zLrCmD!5mO|ooe`X{yh{U@g*nRQ{&~DLP!-)Mz=7;}QY(Sx)s~g?@fk+%4ZYB?=c))R zqh^IOgmqmI2&B4j|EIpLM`Lk0{xVvGJK-m?Iz@iGSpQu$qE2N4M^shgeMJ_%`_euy z^H-KMi0ZJfNdp=_R@v^EXBcuD-AD+aZJfS*j_w*$oK4xgk-kXVdBm%ySiq~!bxYi? zqz@?$Q;NNkh-BU*FBcgOL`D}gz8j3A!z-QNDLglFIw+y?hun)?n5)ch`$%zks90f`@VNjhak8RaP?|58sGR=; z*c_~T!hzc%o04QE;OJd28}T1NS$`9FkSB^D`zr=|df#Qr@yu|!RmyF^y9hseWBYR# zOp=+Isc%yVXMGjcB8Q&W^hziZP~yJ{rJ2V=KFV|RPq!;q(_Fc4NUjlhLin7eCZW(;TS({`z^bZ6Hh!q zqBkBGzF1;3pW3mx&N_I*S2X-2Jd}8u;d$Jk%(5>Q)sIoPK)Lei!-_HRv%5~RLm>QW zpVtr6To!;@Zm@6B8&#$^|-{DlUF7DFLcv1 ztJ!6XUVqz*gyT)fXTlFafW_{k%Kn7h{La4mK6Mc62$ig9)qgMjCxq*k?mJy%=F zklR#U;da7fvWpZ{6lEeMLO$C5Jb!ZR?VXujN_vLt_owyE$dEeQ5yZ(~Y=?>Vngwen zm_Aw)oy_wK+=avSm`Olw;%oR~L+{{u-_$@P;9?^YvD)mn{ks=mwb)xPWbG&&_;5?T zz9#*4$n0BVc_Q`_@xUEXf^8m?-r{dWoz}DFk;u~>yTFJJlg~0=S8za%ar>}jp`Q1yrWRn#7Ss{`wKbumVvO5Tk zuOyl}NkYB|*stg|KhX|c$*Q_I;gZYNByW*fKl;zqbtit1Cz5~Bzc6jI5i?sQOepD= zf=woR<>L?@YP+){muRpA)D`WtpS%2@jpfK~CQvPy;_wY~iW*LYxT5{?qZ_q}q-6xU zu#dWDWHeUJ_CL7raIu`3dpGpXo&1;G-{|WcG1wlJ7lBzp1!y!UQaduW!9=zJlsqR-^kPc;8-Io*I+pA?=-&r3azAihi(0!*#liqp!?}RD`Q{TzI zysw4x`t$G0N*ShCpHy8h-spqA-^3{9nmtOCG!M)u9o(wxC92v+j+m4oDy99@? zfQ;@fEj)~wQZ-MWRZ&!&I=VbEDPHiz+13?te4lTjZr%6W&!5}BPqFmt7CX~I9zw^& zz<94=8L<!rchg@x^EPY-+&?GjcvU90VZHEgD_AF8&}frtt?3ihS%4)$j=CGM zvyJ!kuW`oOq&mB{>xVC1(ewPpicWQ9h-Zt94@e;Oj3PsgX5_}Jt>&(&AAt5_U{Rkb zd14%=a}Wa=bXGdxPfBk)E;~`Ntjma7{R_692KApR0+MX*OzJPApnOiM8Y$=pxd0i{QvlujZCJJA{^8(_ z!aDZhSe~OgNHxKeuifYiTD0J2~@PJs(zNHuw zuJN*pXNJ-Nx41y!Tv4#awTr6d7Z?4l5eQw@*^&D+dnbBHJ~v0I67Hm-sy^JzGkxa| zy3j$Ax8HJo5fIuajVg#tRmpcEBRmAA72_N6|9f>8W2vwH-Zrd=hM?-n+nz?z`jj?M zU*?cGzR4awqH1qt`H%KlTep%&!Hv>aQKrGT6JgrWjh43q5fSS~pR=qJo^vv;nwWqa z1Z``w6B?=h4~?1hIeGZ`(SB1ZK?z1|P2CjJ{pjYMN{isJQZT+2!ak z8+13yQHhUbrm{3Wd|nEAu-7^Wk1@{o;z|n$xLS^rJ3R@lnipc-fI7CPHbQm5Nyix* z52^;c!GzSaOzoi?q^*xuCOG%?+Fe?IX zdtNF{B^b>LLRI#uh19~89v~7l_(JGezr!R|y?-yQH}zxtyW`*2amUWLEX*Bg;e-*A zfk>a*4=d*{?a>RM`7eTJw%>dC2W^{z&ZinHuH}?bS`uHA;Q??)B6rA_m|I@tLMdsJ zUMxuw#0BSV&c7FkAocg3un#?spzbH`)VBuD4~IZ!ap~ibklnqT#|!FwviOG(S}x7Z z+jc$Eo?<YPts4{EJ*JVD}`*UAMyYt$qO3M_{ z`ab2pefRBK`if;`5*qocEb}FY~=zBsE4{k}f;))7_&f0K^9Nyo$*`zT(kv2>3 zD#SoTH!hT71bSqP#T;McM))~S>c?@YK2F=@M}8mIU$X3MS*HBAQS(~9Fqoj5hsc;= zB^fWKJ{=9aW;Y;6pGP13`14X=aR+#ZXei^)dion3@xl_T2+^9?MGol*2irm8&Q{8$$U@arKD&i8%S=T?Q4<#+#K0T~<7m>#tSn z$zwfm;Rf~v9EnC$z!3vucX9C&fA_n4Ayl7_3s=Jh8CF4tc4b9oEiYQzQ{m17+wb`I zY5})vJndk2Z!0|ZHfVYxcae^A9*vYOrZOUcfxe6B@J-=GsSsbH7dB^R))y8otJQYi zxzUUgR;5?k{9)?`0fRPy$3^MG+D4-j3&tp`p{{OO2()pNK(R;Fm^v&dZ(Uqt+|$<} z+g5o$Ut7|c+H8>9*->t2_KH^C_l$!({y;h5Vt%l@sIs!u*=U9XJeb_X+xz%|!+E`38kgWuhF%Xj5Ro?W$!IOU`>Ivik5Qwf} zVuTBaqR}ujQ{_~8ZP-&BBc~S3Ei17EN5Po6BEpbkoG8nR7PTBYJ{ku>6>rbWd2wvT z5Cf=Z-Sv*V(jwD>8w`U`Y8SL!U}*8W;_0DJ?1AA`+pF&avF8)olr+^toaq{#+}(Lb z{HbL=Om|okg#EZnfJ2=Zq0Od%xbbTqGTc1)bHal!Bk8RBcNco}U6Xn_z_ZM_2geSd zt(qnm<`EiJ?3lDqw@)wYhI%J3MO#2cCw0rpwF+VgUXio--1946+^#6q$bh=g^_)Y=^*%%C;@P_F>!3 zZA3PIUZpw~A6s*4qaLt;&)f7CcJv?62A#`YS5wZu_|U?$IP13|g#X*D9T2Q)4$~Q_QyXVIuc;oR4xw0WAn7baXs( z_w&8arq>@=IixA{+yc{hi>173%n6NBP1&ap#}9F&wt6})kY%zx(?kmJ95O9GGIWrYAwr+goR-oDI>jTi6N4W$j2dV{ z@(f`r5B1~B<7%m2$n$G}tKiKI?+0<3rv6B&9ng4d>`Gm43f#E+ka18EokZ|Dhf01! zoW%^sM6ZZdU0u)#)xJXq;U5ui!n+@Sh1;&Wz5{n|Uc}B^jdWxDnWGzmNT_}JyF8oD zlS0(t?xm@#y?a0FWB+?){S_C3zCl-UOjqa}*`Pm6;ojG(^Ju!^N%VSJqP0vqJj0RZ z7cU=4B>S5nE}4Fu&bDq9vpa!{z#k~k;s}hIFHVpZkqX|Y4FtQw9pAOwX>7kom%kbZ zH*Q@lEJ|PXZ8vMS{Rf)A&t8>s_}!E{Z;-<#cJJVJ{`B5ezq&kz=U|b`SJ2~KCbE$h z3D@fT>3{dm8XOyBb0tk4&E`;#!%QLHFjAnvKjLL9YH~P>XW7jBUGiqG^FY&P4MU*0 z5-8VP_q6vBhd)zP{nvSdl&=F0)hDQLbGwj}YhEZ&;*iPi*$0U!HtK*LiFRaQhv0Ln$v< z>u%Rf!t;9n#I`<=z74dB@HQ;0`0^RU&j?8u^$z8?17~%7l{@Wny;`pJ^MI?jIA8pR zo;|)sX$H!|g76~~9JNKmkIm9zjDb1=YEV!;6tKfqBV?Y|A> zxk{%$Yom1CRBb|L;foI~PQ(sqeWlM1EgXI}a_CJLcQ9^t)KQd=VjtCmgS+S0BwID&7YjR4ej&N?FCoj?{x7gOUioXLY`h$-8y zy^xUWaVb6DpPhvqM&5gOcD*cvB_mlkG$0bY;HMghZk^!7nzpzm-(H>Bn(|vu%&fg+u zlBG{x;F4g}pY*LqrdBgl^MDi-ur~#CbX0MC7Au%GZ5$>ms{Oghs%y*_&&MiEoYRY3 z*>nj$h#Oev$L=R%@1!t@v>){nFtd;n-5#d}!c1|dDXiK(tlj$p`;WUsm_2`7;s`OA zHa(mqHxGV&*!yPxG+-+m`Z$%MNA5p1ozKDZP=D%j;0pRu#T9s2|j$p#=nqz&6MvGab| z$R7q5EutRxU-~KSrI_+`oQ(aF$v4fhk!EiyTQE9{G|*T&EM;*^C)rK0%|s^b&mFKF zBlXp4&SkMl61Z(CmTJJR!%nSVp#0;74D|_ z#me@w90SlB>F)yqvFS9ySZ3g5Dn0Ed#zFeS?>KTR#g1s_Nak}7zAI!9hX|_{*$Fw7 zD{pcQRAou44=FJ;RY7NMjgBzjP=lZQBXZ|QO;;}s3%&Qh$So=C^aCG{4vblh+MTOz zj{6${?7M%?y=;}7FpblCe_S(rkHL!KDKQR({5j2=vT?eH?~ghRpv@UOTkpN&-e*I# zL&5R14OK!-3|sfXbmQgLG~hPR0FPwIptX;mTq+#})ZXlD|6fZ8$`88T{ucxzo5iRdI^N%e|V-O;74(WbSma22jf!ev5w4Q15&b*55<^8 z`i54b<7tBH`%|nyu`GnVopE^L__@d-QWcK)%#%Lt<(9;)2ekzG>@<}$z{iC}l5dwP z=xI|E7$1bMnUo>CW#&EHJaoXbq8hqY(c~@l1DzD939rw`z+iRYX=9Rm_>PVlPcRnOVU~8Su>}ug zsL|&_Z(1?$JnMyhG~f78(?*v;=yNKH-YUN=ZFi8cOfec|Gte6{`~OSjpu10|KWn-= z!_0DG6Gm%US(|xC>PpIcbq0eS%!>@iPpRd9BUn~;6db#xip{DPZ~idt5PEt1fn61} z`JNNICyzo|$}7eoGWp4WTxx0IM5qKmh645F3RNE?%|d!X$Sqi8!X6^i}ST3D^plsU=L*L8t}N3F_GH6B^N1)5!7f- zpTU=>I(@a%eW;d$_6!6g3`yzFX*@K>rHjqi8DJ8|$7Rj~Ps*nJ3R@te`)C8u;}*l< zl5`uRbdE%4W#+Zz^6fwuYn{Q~Q26MdC?BV0i`Q#qv7sl|_aot!rWh4%f9}4ahzJOW z`Vq48yp}(OB{om1%=)m5aiB6}qJ4Obv~C4x6~k{}Ox{75w0a-tf$#pR(QMtdY*HgO zpk~iCUZr%+y58T+%yXymiljs{>n()>fh9AsV0KnkvW)}Zvp8t)&UNC9aumur9_`RX z`pQTL#ovY@|E_4Hlj>HswO9YWr*anl%6Gj?j4b1q&dQ3#c=RnXbdH%;vMmS$mz9-0 zs*sbBlJfJy&&_Ix%aL}lI^Vn?eu3jWv0s-Lk0;+tPnj0Zb#)Rq!q3k?CVWSBr(t?_ zmMM9S47dc)-%XA2f#O==@eIwZVWnC|6Z2R_slM(DB%KgrzJXus@0xcLQ!@ zJu9*p_u!f8_9xG+%*YprGZ9`0Z-frO=Ty1ar2I^SjebeQM0|k*9w>WoK0RJ1`}RUx z_x}DvIy@JFpw%_P%*CtaKJrW8`Zk%LMV7w3{=)|Kx~?zbwToocgXJVmD)DEhdKB{b z8g1$Bs4%0n!3r1*BCyf)(ecWujTR-D0lxc+?tG%TkV!_Miaeci$(zF)aHA&MDSg~{zWs|JQU+`f5D+kmmfb|D;7+^QOug<23 zR_D0$w`N@9|Gxc&QJ{Ub3%LhfLLXOLaPOtN_cSC&7&^{JUOu3PKyt@_p*^*5JJ>9B zeKspRY=q~X8uX!=cd)j0p8nNkdm9#!R4MRH0z~W>t5Mq%_T3h0Mr{v{xqJV9_P1eb zZn%wj`;GZ64x>A+iaVkO;qV4ckl^0v zWoY7QO+zJFyMvQm)_B2Lb!H4#H&>v{M*R4o*^>W@bE@gvB7#aznLQ6!S*h3+VwZPM z%3EK6BfpMMAoQ8%%S0?=;DVeQb))u~tNFE=x3V)`2b04zO>fU2b{-2XT4gMF=zoiYD%GDBnvdlBhn*M zJ%L@YOAkiY$$~QwTj=GAcwg{t8*b|Ayz-cf&>`K2Z8>YVH9am0yN}rnJ;$1+AK_T|~yT5(}C%R7o@i66-bNQIbZcowk7R&B4BcZ!v}ukZSr*?q&n z=dTDpDw;ud6R(-a8ABo^OTXyhkWf%6*hmIVV0TEjad6Fy^Csu?HM0h4SbdZ29MX+f zdx$|(6%{7lElp_{okndzM@uKbWWWG89_qXtV<>ru)-B4dd`%l|7>l8Qo>)!fMx1rg zY2iPbY=kD-%={^JU^G43S33yG)C{sS^n=n>sbRIu0=^{DEuv008g92kzkL$SsRT3R z2BC!h8B^tq(xVeygO)RxHiQ3oYhBU8k<*RPI^HvBn30l64Dxfc1 z{$>p;K_E+rj_+%3L>D=m?8JUu73GH?2{j!Vh!Ni`$RGLch&Y5Kg3tq?PNtGYvFuC)ToNbzO)hx}8n~V74sS2j| z_oWBpfBxv|YM06EGy3pC#3p-n*vJV&s*MM-=4X=KVH~^c@Sfh=Av0R-DHY*VrNXf! zRZZ|&lyqVX;DI{s3G=m)k580xlQIWJC*iW z$n?5-BhljjgcPOYIh zS=@S7_&?grWqwM1ZY*~^jr>jLv0oz?y$klu228dQ!ZoyCA25xSr8Pu89deg$VrEuA zt$X^(%!A|Z2krvE5d)-;evFyp4bk|loSbJBG-KGyisn+B5et8WqS()zoVO<9gj z@Ojk~kJ!eEjy||`L?q$w3KRrV*d3hElTFZayr)z4)Uh#MUQcI+sI>w&Or~s&I71pl z2gi5^%WIap`}=Q%2oF`;bWh@R&fpuqb8mb65lLTG6ec!m%P+T3*C_-VmS96h&D@DY z^$DvFZ5g^MxJE5DI_<5E<^u_iRC6^Gmn2|8>YD9~*jm(xi;4cBo!~9?sU@IHb+Y<; zJrjbj_ysl5KVnrZZv!W|F%mWTXUW(r#M`!&RLvsp8m?^cjW)`NVR=UOj3zT`T5Qy|liljtdX=s8!&;+H2Rz z_+|_9nMGEl9GMh2oXy3X_?mqLrx_YBWW9@?v*WD8#raMEW-WTKR|KyRguH=a@5^4C z?2m*i`UL`6OhJIV-A!IQ@->$my_SeTAiJ4CRz^^wGwYLp`7>m=0qWjp$+8h!#-KOS`)zq)XL>cQ?bGf9?w^ zN%#Bso&~qF52@^0SAWh5#J~u_gjGcV$t0s-D7lzM5}?%8#q-&d$3Q6}A9bViS6)g= zNO)b{zQwxImT-6UXGFzlUbYx?{n?$s<@}w#RQB{=4nKb=d=THrJVdtiG`j#5x-K=; zF3r_0p%}~*4@w@Pt@1n}T_J>i`RjYp?G~!RDus@LD!Ji0=Y?;Gg&I_rQ^t*V^s>Ge z`0%dtT^~E`A}EkBct30NKZ!2`LV6RA0VcgLGoL}N=vE#4xv42-#fWY=B59(aqH({n zMa^1Z)?DUAgH!$9Cynu;l67wOgj0&AG4Rp$aHD4s<aaH+f;xjlN%q+P(dL02m zG#b4OwhJ~lY0)EFG74=R2@t!1&D5sp9rBXf&b-iu=Z1 zEMJu>QE3!Z6^#nm_qrt?(&*6AE2_QZDN6QJLTGRi@`nXEEgY+)F@zF(h4Z!cIf$|b znLAjlpk^L*ppFA<{-dAoJg@9x)Dw9}fDU};Uq{y%{>&-~AD9J2U0cf9l5}NikT)Jx z*~!*x<5A0=P_V|>`o3$Z(eM&1cXaTsz1eAOfO2gKUX1Rgw~BdD;z-BT_Wdlge2Os@ zC46YF$J=!AZ1FJxC_M2Q2r`)DvF($l8W}+!J4){qBRKh-Gx3ri&HW#-ST?{yi>KTU z<-T11uNU-}H~#hntd-tx9EyIu4M?f~0k0^n_LH|D+@y6+66O&z ztFitJcC|?~y;a1gL+FG>-1NH?*%6+hRctEUhS%HOO^2P$sR96xDbHpacQ; zOOB{oUTE_Nazr=&V@yZT#<=TblZKmPVh=|o3^~KD72WS6Ht0^N9V_c2h|9)msc;5< z1N5WN*L!JJ&-bIV>`UpO0%Du{PIqi@e>9PEAWgOpz1DYWHf9{Zp4%@N5x-qx0?_(1*LOGS?d{K zJrf7-frrWZjN9@h^&&l3@ROBtnGsdKTKH~p_N!HoEayZO~mK}0o`dg+w513i=Lg4gw;`;iyia~qqIpIxdO!@men1d!z?rY1MYW`E- zFs5x=f6n-61#cQFYOoo>o1InSmRkUcysD;z<7aE61bkZ<@H$?Me#I&eUbqLSkmS4HJ;iaJi>r<)s2)!qT*u2ar{2T_X!hT5k7G}nrW#cY zEq$(oRz1!8bgo)@BMwX2Dfcob1n(faC@e1>WjI_+mD(%e2oufeZgs0l9KLEfEO&gi zZy}9svb~Zc-!R}(*X3O(ro0hYl?;M^&wF57H*+>+(VbTgxHtorE1hbZn&fy#Gki2Z zJn?>qhh*)TY=|7&I1O%Hq&YP}ep{%3UdxJWu)A%@AEvjTi(&gCCN!24@Bzs1_D5UQ z20Fqmp&;K=e*}k^dEQYxmub6z_$Ml7ZK(A@KZ3OwrMgmfZ9sN~#S1b03XLEqC62tsNvfoi`arM)B_)G&rnH*<0@1RDa;*tYjkQJ)ch!&5BSbV1 zllli0@(pl!ZCV*-=G50Y|8wun=K7B+V1S<}EegXRBr)VcK2%V=|5)W-@n}vj4>Y6| zZP#LRD@1F7W$Q1>XGIt<_=Ce(fy+Q6hVq3Ibfb-2Ry6_6Z8hO0$WOPW0tUmj47ovn zj?FLTfnDXlY9wgWHaU&T){=cXQ_lIUS4jgQ`Q(eoSP82@a(EW&J$=!LU%qAqY_S%u z-a7|t6PZac5DB z?JCy!V02tQ`p%Yk#(j;PQaELPREco|%2SR>F6-DlBA28D_YM8>@bItAP5YBp&lX_8 zod2hR9~uYDrt-K{oMD>LVNutIM_ulr+5Dwd`IEIoMoNeDA^}{I=U!YkV6_kS`YA!s zS$%LAH5i<rDLbCu`wYxujoA$>CMYq5B5U%_PLL z$kaP8Rdr=g_nair{$ARRv1uYnuB?_ZqXX+=T5$Sh`>3pO$HUa1?{u$X=fR#0fCiQ7 zf4mJ?FnDafUAHV;Q&ME4oT8mk6-$Iq6&eV_MFL0Z6VbvJBXnOnxU6$6 zO_WaZoDXzf+yMgVcHLvUD(mtEc`@aXtM51mJa$Sy%Rh^Ee7+%BFL)zX`?fHBO|S25 z3NB;3K!w8jgTtajqep}q5b~T|M8MfPFo5Tx&LYW-{C_5%GmNC96f3sfi1Y%iMn_}y6d zhPbrG4i0`W4NvCmYXsn2E=@^nT+h!gpt{_x*0jG<@#)yleMmn(<^j$v$twqh5kOKn96RvRPZ}7xKa!)3xJMx zbIQ{?i`eT}?Gk?brN`%SuD;OS-(rf?*6DOv}@TBF2&TEUs!uhaxS;A>Z3Uw zrX6y696!>~?N7pQ*g=UunJ|{1p`;~IKCiUH+&*!$JSs!0{eQJQ8ffU+=93P6%e!vq zJ!iI+v7Ckb9Z`8KD;@C%EJ9w9GuLt)x9=fR(?F)6lMx;7AI>CPGT!<~>2fD$aAA8v z0J|qpA-6iamRC_`{^!`y4@anuMHr3=G;xB)sIvR&%id%uaU^Exd6~Dna6Z}8SOG^z z^pxa}-t2DRIRIoc^Q*I}TV)50z&;b9%Y8wp@2o++>G(y0^D}vp$|l%QT-; z`0A;MlyuN)4ddE&P@pdromLD9km>X3DeWRcf)770Sd~Z`f9T z0R}UCCb#u^A>lfln-?MYMVUOeoCnCRlM43GXL|ghr?Cq2gW~Afh-7Pdp5=iYWG-sTp7<|+kX zGF|4LFn#c7vPJ}@e2T$Cil=(9xRjK{c{i36f9u$lTQzZ?br*{RD_iO1PyLS(GQf699 z(|vIGtn^|9McaM7E_nxaoglRC!X+;lt=xZUK*A|9J)pDi=s!hhXEc%tp3w)6D>$R*H-;g^_I7RD$0mIHG!JZ#$2gCBk8yoglo7^6%+Il!}q}lCGe+xD{=fc=6_?tJOd;|TYrQqnt za8_KBIIqkYs~E5em#Q%eHZQC(E9>@0@E!eAV!?Mm0>>LQW}o)JGT6;pfR+dMlh+ym zdAZVeAk6vtYcg5!q&gNb8`aR68-$PbmayQjCN9s62I-2yboFgs@I?Wbqnn6G(2>!E z!1Ou1c5Z$?OTUgHl>C##kc}jOS=o=<=@^QI8 za0>5xEg)$@3e<2o3$o)Xr2}Y&A5Zc01G8DrCpetqDXF&ATSwg~WGa3BafO20WWyF& ztFE8&e{sVf$^6zL$z|9MxF@o90_+U0FEGEF=x8IT zSDi!%0**s32-3+A0VmFsml~H8iIxo(p+F*_JjaR4XA|`Kjh_hW4+`U;O@mC#xbk3y z0l)iCooDsm0u{#1vT9TpNyh}o3smJz@KR;YA2iK8K zh0xBwz1iEjPe#NP6zbdB#V=Vk5=846p6Nl;iyRo)kWI2m8g-NYOqS0di@E;R7V(}r z-E{V@r(14ygfGuTO4P-QE_+J5vk9`Yy7BA4BfgEOQ9dlBr59AfH_CqcBHWmn0)z{q z`N1q?Es6(v0ucq}66b;L>V$bE(cXU~!T?5aCFVqp$V@t<&C zL;z6TvgdBr{Vou0eo^L7oiKFPD`ER=>DQ}Ov&KZu{2sk7aW*Brv)n=d#l~3p688LJ zf219|B}cEn4h1BTe;8;>EzP9kwnz^JPKl#L)t>gP_(lhWS`1FbO%}MLOH|r$(8WQ{ zQFI^=Et~`#TW2fjYF9d>lOg{hbz-I<+8bf5Vo4o;TE9sJZ|^NtuVAph^-xfG#sIPD zFuzoCKHsNL^8#vB2A36u+glyKp#+O4g*k4bOLHMQD4EbGV$GaPne1SRJ3E`dTOQ?6 z+6Uf7H$q3s_Q&fIyUEEn;78DnP-Lwddj%Q}O+S^!9TV1oq+p%$wz`12=X3e99KnP1 zY>4{7btInf=l&Yr@cKu<{iwPZ;XiPEc8bSK)lJ8R+kvF9jZCoL(ZOX`Xk|``<^T{& zkBJ>CZpRlndzM31wJTt^87M&>l*H^ck(94h9LL(T)IeLa@H6sT)$(NW1huWN_U1p7 zg7pZPW^GO;7E!A)N2z882d zR@v_4WM$oP3YhP)r@;V3XMa9%(tl=to@a32{BmU!a18vf4rX>JP@>GXp_E3j{~j(s zx-OiE{Ed@I(x`H8-`=i+hjHUR#d+zA5blF=X~sf;x~t(cha9Ny>9LGuv7=82LHMx~ zAZFV;JTQED*6JuYd6lRn+pp7Ds!(fqTt%|?VJsLven3~T|;#Ct-gFIUZE z`4wKqs6s`Xm~MEukIeyd_zfignCTw%(sZ~jynCP zQre7MMP74Tg{BD)?;Flu14K-+C$*Ph@FN0PM*^4+=XP z#6REngoSLsw^`s=qbjTHfX5X|mZ~$FKl@%kRJUKe;8XGx0c3CHI}Q3=0VMP1+3))%k&B{vtK#}H)?>9{f!|_$s4lls>V%+t!Xl8GL;#UUoEE= z)VFZw^PZ4(8MpWnQ8NhWd4PLOSHsso9p6V1D+E$xh$qU6yc1{8u>6JWG>HT>7`-xg zvL7ghwAF*9Yda34cx-rQXHgEGU8K0z5We`;^k@jX_{}S-ZZAMD#)~U4=i-3tT#Ber zpl^BCQyQgaNeqmh0t@aCs@ymeWv49ZN!+9F1o)$rOF}cRMxAOS&l_#YqXkAQ);BZ; zr(=>E9Gy@v%}?ep=&c^qUM`+R7l`wWkcc^Ayo}B3q30{(0-?KhD|d1Ql?Ymo2TRoR zaqUxtMjLqWl#Y&$zAZ&LpE|4#1-N=QIb^UtEU&qLIm6zUPbGM^7D`AEbedmvwJ&!C zh~w<-!FG1V{{H9P+-)>S@YE_`lnlO-y!5euG%(I#L@}EiYD%Vlfk$(yA7mw5*b4#zU++m?|n~YRmQ6EpurNjk?F*g~l zIKAetg~vK&ZogzGs(Yl!7RTRC!F=+9oh^b|HC`dbF5l6tdE$NgJwXZ)99bpBi2(y` zONhbb=aMteqtE_m2anMzGCgn!rM6;9I!*}O*|gGeDdF&$d<^B{iLe%3gKXd9hFDI} zBg-+~3LpvbK-ivITTmYi!NB45lkYmSaGFNSu4Jz@Jj&5nf1O~rV9(&W=e9rdNLK=n znZuL!saQ2;e=E9FY$fChtF9XJ=&^ycw~A8op`piS;85~t7H!s$r)|g4BEhxK>oix& zt3aS{Uti|=)HYs@s4UhH2qJm4wxW#EkK(qCTdTjqCofI17nQYd&X2NAW7N4>LzGG) zBUN9+4{WY{3A%{bXqEI}VvBgM+}(d=I=MKz%KP~PwJP5ZJ&mv7^631Jy5BRW<8im{ zn`Y)@ebbUHk)`Kil7F7gP6w-?^i9T#AVKjn7J7sfzU$>1Vumz0uP;l5Q=~VLhtnrc<=l9o&U}`yK}y~ zvu9^!cV|Xurf}uKQ>NGLpI|~*m1^`AG$7Yf#fld?<-snzb%PiV4nB5pjn#eF zgZfa`+Q|0hF>Lkq#Q&0Jjpr)9(#;N*3|ad#!_w0r(I$zpfwTcAju8XZ#^5W>y-qdm zjwJ6~ozQ;`4v?WP4FjIyQyqkhpQwg?AFk$X>2(ws)tEBhtu=ePs+TD2Y}r1?Hy%gTq&BRA1(GJj9hDkIEhP!M_Ov zLf^(_|NoJk`5aeiBQXp3{^ic)&hONghk9+)IbZhi`OyXgzF4#t6xgu=tlMzKskSmL-un&9~wW(%s zAr8(IE)1%z656HPX>@gYmGA^#%X*iN9>5QYRm*&?RHhvF$Vc82+wb|~p!WYqo%6;X zogX^=CcxFuP%jPsz|6@+*R<mOkb&^m^@1vH(^DVVTQY~OB>aLH1GL7F>y4hHy7 zI^=Kx2#kt)X`WbcnDl0)l=l)plnARp0k7Gidk;4{R{-Q?7SYNPR%atB0qj zfxB|p#I_U@%(#_V;Azbe|)Ew=qjR$9?6M@nD{6O z^K+rbg7ex}mv(K?kJZ!UjoE>HCrUm}2D??Uz$ikNMwQyNPfpHpx}SQ|)8pa`zhiP% znIp*}B);XcG1xLivd8$s>6$>t#VnH865efC8&=|e>ji>KHi_)(^(p=MMp{c{9~0#=2m!Eg7G>Q_Wq#9a#8r( zy&*dt%-&0cX)#FvYSNnwd-r|xCpz`%=-l_E8N2I=r9*;7ng6^Cz~&Q_nFvdKh5zX z9#gU2xC!XI%QGIJL^mF-Qe_ipKLfXydvE+AEkn~j1+QRGovm3YFs{#BtZ#>iV<|2u zlt@7pm~~3WL)7uoHQc7$N@|Q(KdmdbaPIop!`bL8p59BmdqHyVSf63}WVfLX3wTtr zLU-yF@A68wHgy02aokwrDv>yxFd$S@`_aCjTPg3Hev3OS2XA_v(lS&==T`&c5S;~J z;0FyQeNgs-^jO~kS4BTkIak3jr_H8g>+o1w4fXUZCRqK&&28bA`xasxe!P6&8Ewb{ zluXm##P3118BLPdvNA}SUX6!Iw`?xH zrZv8mfLl;yN5_(d0+I zr~-fDM<&xYeW@xHDmO7Q`OnNW$`lQgji3GSDV@Dxh(M2cZ5fl#VE%$VfqlYY!SdPW zb1Dk9u+3-pQ^wTtD=Nk(U#_52kMfwK^M9mE-iZu1y`_|Il5a0$Yn)mugce4pI0OQK#$kGzi&2(_{;r6ew=)A%0+@+7MoJ!m|Zy}N?8w}ohu@;HbMdfC?_ zx61K;SC#8{Njyg zrxZbRQwxh>gaFv?u6kz()Vn5tyC>s_DP|8!`x=!$TaBgeOx82b_Sy2C;>wm`O=WM> z$Fc9h#8`gzQhDLX1#+ET(sQxXah(}m1{mKqJ1 zKb(jv2`isppg9NX98hRGp1Oc7n|&17Ep}Z6uJ1>q%gEQsU8oBsWH)=*SrBaOmW+%W zEl{g`YEX6|s+0*`sGZsXkUD9*%D*#8wYF%`n#+efR-y`AtZjD>vUupGLRHd9qlvSB z6D;e<$jllM5s<4ZDk(QUU?N*)TBbiQ@{@@zTwM8n7I(3pP3&#&cX6H=m{82{M?b$j z{yQIV^aK1-l)b%GgujOPaM{H(pjP;{#JBKzvzAP6<+_#0gB3yII*;?EcC?#c;iDvy zq{lz#WU>iO+JdPIS?s!|K)7K#`e$snDn!QmdlbL8F@VQ&bkX}a?iLST1E;w`}FQyo3!Qce)HfAY;eWV+0g!l6eCrW!U}zlvr3C#gC3d zkkRA{c470de&?~v<5FMULZvjmb#__F01YpEHYIvfOM%FX$gdM>%Nn zmfRB0o_jpj%~7A4G^F%NG&-LYJNRV$X%T=MctV-{)I?b>bS z-UtS(=Ly+f*5W!GIIc3kkS|FO6t~ZOx8DYh_Jm}*(oS(#de#W4z>E!{6o)mW_93;y zO2QXfek3GWPnT6Tl>ytAqTU;mLOW}{(*$I=^p)beEn?Bc549U-bt`>n8N3tWC}=Js z8tkz&udQ&PhJguhz5bFME0MDcW&#>ZdhY%aw9dF`nDy*U(1o*xcuZcO`8u>Q@|w$k zb=EJtvYbkfHVHn(YsgBIQ(C@OxJv!75=*0du6C`JOpKmy`ll*8>XT zWlJJ2e@-5?aiB4H#rvOQo<6>2185rzZ)g+!gF69F`%6);>wNq!9IoVz>44rBS5E#ZJV@OideXi?)oh(nU@z3&U1)1sJBKfDhgNMl z_j{#uUgTH5ug=~5x;Wo>D1;f~-Y>-?096DcAgBihz{=pjLWu!(KkC`9u0Hm+=tO&j z{gQl(O=SKQ$$Ww!c_+pu1q|_TPM+LIdhF71y??tq%lfV>3pVGv88X|nB zrW4f@8F?Z%g&;34XAWnUOJPC;H8%~;*!X3TRDi~9wLCvrX`aj?1RRI{I@!1KI+Ari zsmLpNmfuJwr)aN=ST+|3XB9fJBFS3gn{o&>?uW6Fcoy{E|c&9e)^$rROR3zbqgmYXCP|g`mPCj3Fgq zl+g)tm?ea;zc$-qu|HkivLtYdUw*(sGfVF7fsJKY8m-BV)GlwwZ6oLAj*KBfhIF&J z^&n70gDc#7D9ysdx=QCDTz%Vav8$fJWJR2e55E(i@FG#>GSb$jSoGR5SH(4WBE%_O z7=?_rz*fUF9p%_2LFd}q5yA%YX*T7&o;mVxMc zQn80YaoxtlzkCUF*d?bOrHQ75xOAKJnb1+aX))O^-|Xv`iWKc_9D){0E_A!DE@S$` z+597HDry^RYnp1n3#+;9GW7ZJ-6#&26*Wk&25-~$s1_o?3dx2Gg4%7wZ}W7gY`>BZ zgfA-cEr&E#52b{Zj{uR1E{tQd+-i45nstnVDi1utE5}>arzg!{12j3lv3)asVs`l) zR?S%4BX>T|)0G);#wK%!-HCgH9!FeafnI^?2j48-@k`0>GObQ9P4ZhpIsI1VpaJ@z4$iZk}oMr6|Gavz(<=z=wGhqY%F`g8XqeW z&KbprH=J;D_bREzHp-5XL@hEn4QEXI7VrjYk0+uZy$H4QODXyy&?K|j8v7uy{B%F^ zBj-`!VaY1{BAFi1P|M?qFPRx!+77x(_l^>fi*kiM+dlY;(%^$k=x>T>)XZ+?v) z|9k!sPlLQ}#c>YgCrneyex;n`0BMGMl^8Cyp@{0HC2iI}0#8pX$<3 z%+_$jVTYvA8=EX_EzOLGEBesf7BtxcZ#ppbfgOLpC0O&znW)H zY6Fg^S{HXPx3cAS+H0^sTYj9hDtt0I{t^5f8eQ;gsKsGr&*^KtYlAQzW<>op zY2{U`a@ZLY)2aLd>P|De_pEm*9^M?rR^6Ls!K^9cDzJarmOPyx*_ zx?)+}eRlO#%HuMIJ~&tEd7GE(3yk4c=nf(jzpk?bbwTl9HM(Sq;Zm7hV_5v{1SRxk zqn!ycn7;0q*%lqOC7UG{BSWrrq^#5rrP8Y#$7>A?q90pyLdk>maP7Kx(`!9D%2t;r zDrBP$lQv_5n%9opyUn(nt&l#u2OXmB58Z?MaXe*@-xwQUCr~gK%JjqmXYz z`Qu??X+sH7HT(2rh`2s}G9s!#TrTJK^(^0Qh=S0U#jpCxk`qlSTDA8Ouj zP@H{jVX`F*RZxT&sxi+VppUy@DZj4#qlwcobM=={Gs2T12bn!mj_~y84`0Yar2Z z@!BEcdn=GhYQ=TVXB`<%S zTA2-~MoGd(TObIhKlBxgiNvwDsYyerKoU`hc6BpLQ+kW|A~5~EI`HA%DdaSe?^kw# zJ{{8fw=(XX(^E4aT5$wftq7&^Yk}#k1vtHu%;Cm_O~2nGenc$pa1!fByq_i@D%2#s z+6x9B>iLbH93wf2Zox-{sae-_;rK_X4zKe4CGXtWJqYYj?GudoA1b z4FkD~>bellv;LKPyFHCR(1HA(pLB=(R`h`Pyi8v9%ol4hvpkqag8#fFH-DX!<`_}; zIaZssB~NYFwVA9M|HMrgg z>)3()R=-NH_}2L8pE<@%sGTTnpe{(aRH;*1Cevf#aWRY0*X4v6$&5;Su+cG>8bhzY zT868ylyB<}48EJxZJGryhoL6_G>3X{t@+*iYj6QJ-cRIo2EW&dj!K`-Y0nu{BJK0- z5PDDMa!z~~+66^NQ;+rbk;Gs7e~2xo?zB0R;OT(X3aTI;=DTNH1WeVu)Ffo4yWd!~ zuLB>?k61QsD6)P|jEQRUpNk0H!MFTKP`L5AYWaY2&=mJpMbYnk00X46ubs4-1o1e9 zfDJAG5E&6qhb)Zh`Se0V)+4G6oqUG_W>;E&2Dyo?RcPIHxm4J?cXEUIOqZW(%Y-`o zo7T4-iV_gqM@0#^E+N4{1QPH0RhXCegQ%!kkgbQ$pG^>1l@nkBT zkzfv_RFVEXM%KcZbQ;3Jl)50$L$zb@^PEoT8jJC<+h$Af;kTC4eD~woel&__qlr7(}n~QD}zo*<&*XI|kqpWu#Lmn&=n2 zRZiUZ0v7K-kb;2^66#JT`aXxLJYeU1x0y?DJqwMsPfF@zS&x@1b+ivY*B7&sg(@#{ zu;|5pR!r&Pq7VfDvMcPpge_a|-7S;ReE)tq{rn-ogY&-vm$q_Q#)A}9^54hrZc+?c zN2C+((%A#YXvR&S?n_u!9OJ!)g3 zA)%DuI$B&5fS_ULCv#@OPoW0V%;iEmL?f|naNG-pRzyfDl z`$WpiB z;Sn%@01;kjb182|h)$PKn0{6eFm?TmiFJn&E2xG8C&JE^v0{dgPE6p`FkPIWPWpnEO{*({BK~;^(oRQQ(P-Wd2h^Z$9 z9n3ldGo=hFn>dD#Eq($M3YXfn_Ab&p4JU|)U6g_!C5v~459KF|h0TA|CHSxC~Wer9XBK(|mu6C08{Jt%4F)aJSpxrlxymAz!xqP5N4oK5Tsl#Wk}l`gekebGT2DW5jv_l#zD$|}y!mU9&qc`K=t`8BmVU_)J}o;vpMh`@iGm295nQuk gW)b~OVb#CHi`RlHybQT+p7(~Dk`|;)(dza81N!exKmY&$ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png new file mode 100644 index 0000000000000000000000000000000000000000..920d913d98c17b5ce0535e30c6c98e8c88499cc2 GIT binary patch literal 23635 zcmYiO1yt1E_XP|OAc%B#cXy|vba#gcNFzwMbVxTyGa?K_m$cF)(hW*Vmz30V`TqXz z`#iIjBCPSwx%cj~&pz=XT0>196O9ZF0)b#ED!kHyKoChF5QG&}MDP>6&dvAW%d>Y1 zhTtn9-s2yHvoK;p2!sZr`09m@x7q%(k3YFruJrxvN9Vz0M)7pc{1ejcc-Nfb!=w^c z&Yv=@so{8Ys_CYcj0euFsa&hb9n$IFYoB5+LjC7eErcl+2^y6@2x(;3+f6Vz?Jh;G z_e3YmrDG4a2qxPE27Q#EO0Y6+v^Gv&9h0YO<((KSz-a{{8!RNC+atH@D+UfkI${U)oI>wlpKRVio6|F_#;$AG>cF@s>(=VZ>sf zud$Ee*Hf90$+v2&e>w{}D68t5-A8u?hbEqwRb39$&_gQpTIKK`OtCTC6I!3y&i}L& z${`Go*1EQU9L{?t)UqJ-yWYLLgS3dXN|+@W{COwR(}~^P-QC`Pb_q**N6STl!LIxa z@*K`V^8|u}6`^aNrUchA%jA{|)ie|s@|}snW=G$oFvWss;fb_RY_Z!wR*b6Xs2cye z7{2$8JFg(@+A1h!u)Gc5jG5iL8;&>bA?HHzg|uz7LVi_7?q?{gL=Q? zXg}!+DM5uOB`InoCO&he{gIfli^OG$f`Y=v#tw-($AkDf-9C3#ejwU8X@>?4A4oUf zHH>vIr2~W0s9_kAB)b73_dUGkyo(+7?*k?o)sw(U-*5bM8eUZRlID=E#>JMjY6-HObR=~uK zN=9HO)o@z)d#4_L!~!4Fy4h{QCokA$?dv(ojpN&VdbTg&W;I5|(;wSyK8R3YomhB# zd*7z{d=D3~#!V`up~a7pD>8{PPDH7+6E*NZ{x#db`=p(){o?6C?cVW>Z@VnP-L)^UBc;*RVPot+E{5-G-X64C=npJDKG-G7XC zEd?Yp4ct?RR}1Lot!}GnI%`%3+71XJ)bD=0-J5^4u&^j$Ha0N?g)}RmJ|9mmD*R2G zzxwpo$TdGFxskik@)a>BN#|G!=_`Kq{%{#L`dG5IUuL+v(-@i&rlundUSw=ETsCgrEkm|bj$L-JM z9zy19Hb1Sx#=|#Jt|wj2O_%4FaHE=`j-Hj-)kqB6dA!92nQt0K_r5B`(1BC~YXsVL z>o?GjrlQ&FU~NM*0Sf!(yQfXV+OI0r@imATZPAx-@U8K}DZ`EbHL)n;dpoqReV8k* z`z4X*4NH3Q_6rQY*SzBT_ewKmuw<6e&ghf6R;wP3$T>I5LG8)W!)-Cyvn&|_yg1o6 zXNIiLkY8#&Rb--xk-D4FRaJEkYXzl$){RlT}By~ z#(KrPdNY1Pyq(kQm=qDpUNtJIltiF8Nu;RwlURpnG;7E6OJ2u8{jJXaQ2HMHkL1Na z-dSPOm{S4YgSx6gZHBbZaFstaisjpK>aLnKMsO4jeQn~{-c+vymp@VMt{xm3>MySSR5lSB zUUIolj$ZQ6z^Cu=GG&~57AM~pU0ZL<13Onvg6Vhk?*m3}eo|21!`jk+9fmZJP*$aV z2?}_azBErOm5p(MCH`~lAz(acQ)I)zpzys*tR-mnyjy74o9$Uo$K+hE94#&?x{5(L zTdkC3<>Mq^V9-4igej^L zmAjrB^+XE(P%ZySYQloU34O_yCmqqdr{loyM~3ODJLRIk%0Jxb;uvOPU!D?a*O(r{B zuz*5Oeu`x>>R{p`C*f`g4b8j6xMh3vrDl>pKKGLFO9_LA+=&{3EJN8>bZYE_24x)e zX+;xjTGrzwCEWOBI$D$AWDPdKAz>d>hq#d)8HiZB77m#JaCJ8b%C)J z*}To?GX2PZYbZd!XHtHDu@X5~>#5(LZ$I1B1GVibkd6~v4i>KOE>%i@hOWuwvS3`QRYrw05c#YT_d6a@5_f1)JLF@L1%2M}917{k7*h_{O~z97d(4ITKXnV6WB8HsB$(FK1e;`l?^ILO6FLGYs)3yjRQ*6=cV8rSFb zXH|zWfwP%P**K%R7cXRNY*)ydIc#EUZM9-Pmqfh8T>GG-o#nQ0E#Z>Ttg%%$ZELf2 zfUi|N!|}Ly&K^qT;NWFrvbNQ8OXb;bYoUP8miol8>fU(8lpgJw1SC_+UH9l>8uIDx zl^ zYmMbE`SEVc-)bJ{!IIyRw@b1*?(G9@C*8a*JZ2p!$;9$=@B_8UW_KFm2${Fm(y^!pgVrck* zM?TS>;a>XUnqa1j{~h_Ma?tF}Pv(xB6_zVM%iqU%m7MRo2W-hdLV+9*BvD>i#A%OEVVJhN&<^y&P|=f^m;r`jNNuk>ao`x*)R#2Rsd=>trgn5B zbqCVxXqEZ2T+0|pGZh&KK1M$(68Q3AihLN|wfsTvdW&iZw8N|oBVH3Q7O|qgy{4_h znpRK{DQcz(yP^zt#lb|0eS|UVa%1Zw-ySGe#IA5Y5fTx?zWboB(^Z2;B zO}^h&Ku=e<{r=xxlESO1*{1sXrDoUSl9E@j>5hv92Z=FaBBDx@ueHU+FN?<==c<4I z882>Ht=wlDehtFQ=$8AFj3ox+w6{a8H~Zr$x!Ks*SXq7c z;7t&duWpP4Xw%cviqvHV1zqbWujp_gg&I-YKDlb!?qW}$KK02XM(_2kwiWRG`$x0p z-AMrr?M}uDO69d-SUHzHSHgxJ@(h(=N7M0}Sq!A*Z{O&0H^-Eko)i`0P$M4$7+-$k zW;f3Y8Tm96So{!C%fkQBTb^z_YTgP9C6suP3$dDbe$Qb~Jy&v*!hOs5w93;&7dCa? zaL%lrkMaI>#OoQj+1t@3H;U59ofa2&^A`VTYeSTeG^qXR6vR&o3o8p@b$kCB_At7q zIN&DjzSmhP{W=&l@3`-`GAfu7tmmK8bgZbelvH5socqR;JK&$)-1+$UXu*hsYis#j z;g&COp1epLB7O$cD>Gl=2lg6vzoOrzIiXmtD1)s?)@mNVlwWqXjR&n~L4$@~UfC{o zE~hlLjT_il)vvzqxQz-R4^~|3X&;i*k(|#wE%{0m>3yD$t+xVB*oSX5+kWaU30KZcp@UWe;1W)F)!;UrlpvC}fqT=q{WPI-qm^bxhAhq+ayV$rWitpe0H`PEqFS#PB+;zHWS=x8h>M7^=b!oQDYz@3@oNT>0y7mh9@PJpRnE> zJO-b(uq}8ikY>q&4kxQI(1B(j`;bJx!icEhmO}}prNBb6Ah9{$orV}08xt#b`fB0d zN77rRKkC}g75F8y8~B2K>GDe$5*UzN(_AmHBZ4X-PXePcBPfB7SHXVy4E+zqTanhS z)^=`5%hikIqwfGotKjIBIyb7sgJ{#1&NbQ{!eJghdkoT&y@C|7qN1j6(naD!gTEEN zfN%_xVaoX=_FR$RbfVF4b8}N2|yyfv?!1x-blB=HEgp>F$$S9%Uu zRR|W64jxr*>@${0#>X`fQg#9?gm-?+(D;ehmpo%<(`nPd&$p?`wTYu&egFM#bRv7D z!wjxxY;GKM@qNCgDG^uR{`~wL047&D$PD&+<-F3X!CVX<^$HR--*fh*vZB1A0#AIg z*I6{;H3mxPydzd5NSC{73@Qo>fA__aL!nT!Dq*77`2$bb^uoddo5%XKzf_tM8W?#<+Z65))Wwh2%qmJ9l;k%z6DB+Nohz ze%E)=J&a`F2sXnl-$u8Esh|^Y{qW3#S60{UI zovT$}-ikc^^aG*Pn*;TG!w-j3SfR$Bk+1w~yklqZQlrrOno*XUe~&Ln*vl7Oh;Xz> z>^n0Y8XmE@nW@D^cISbCv)l1vd8odkcV4IWNm1Lz1XTG{J8AJi&HwB0CZ0B%J_ti! z1zjeUYSq>XYTdK)5hk--igqH!+Fz6kgGD1g$iZJTACf5&=WVO!Q_Y%XzuCI&1QeXB zM<;y!QM%VtD?&R0?TsuPP84j(4=c$NxgB5ac>iL_JfO5?v#dNrtD+!Lg=cfr(>Sorb8HQU-Ju5ZJdP{#GUwjoZ#tnAAC+i*1Jc6i(aC3Rjuyb*ezgU|vL=tPAyl zDROXJ^|RAcj6U~!^}Hu{);VuM+IVKgMb`Yel`&dGLceDIMy%r(gZPs6%6sx7k&%m) zKJh>TNz`8{<>?O}DX&Y)k%PUD^K0nWl%>k-uhn+mp9&kkyI{OfU~nsRdd(!zQ&h9g z98XM4C|ueLDR z+XXVT4$Mo(R{0aXXtSGr2Yipd5ep-~4#rhm0Te`px_Ohjdb!?m=fBH;_Kx_svxbL< zNFxkeeGkg`@r71hDTrg`?wp&T1vCU$!f-n=j|+mav)+rfiR1|q>b?D4_k?EJp6ncF zDZl%rQ|sZB#{Dx1>S#H4qg)+2wOuL_vM*(ouMN|;uU9%&aL1zB2e_7tr)`m?23w(& z(1F`x8rrkBQu6NvDeN=-tqBH?;v^wLPbnb_(`Ip9_d)SDk(M1~#qFH$ipLEanX23v z$V7Pjl}y}~m#PC^Ed6Q4MGJS-Gd5LS&U*j$2`Y%bMsba>Qdm{zSb?y~S5Mg*;*_xM z>%=i)Qc~O^&BlV~!?nz6xf`T~Hg<7(Fv*~uwisPbn7QZXu4t2=MzN-#(3EMLdrOBi zbS=R5lO*yrGE&C}4HlhLbF1OH*X{v+dE4E;s|RgQ|FuQ4uQ)UqA-tzznEKK{1EAT4 zN8UWdo;r<)T>OoN$^c$=Xpza1Mvz3o_ZM-F!rk3g@+EJ6(zw~NN9=SGUhYACm3Es` z@+R5#3lV}XpN^u6HKT1o*R5q}qw=WgsHvpsT56L5gC$>fDmN13l_-~l#K>`5_G<`+ zmj{X|*NQDmHK9qfI|x|sO`6viuCsSr__t9=3fBM4TiEs-y+?Y(`9Ts%GVq&u7twRf zKfE|3QN5PRr~N{-TXdh~@Q(;IHOh3@Je|oKzi2uXf(qod%@nyZ<$8L0@|c`jM#JoE zwthBmpi;4!v}}D8rimomWzL`Ll9ub#`2aL$Q-g=q^7ny#2?ChR-TO20ykv1uMriNF zRoC16RpzSjf!0>Wyd>OQx$aX5^y;-;t#K0cSBNj-ypY+-5gjwp(I^2$CB=(IzVbM|Izot5%Gt)~zZ4##Z1gZh&SGvJ0>~GeSab~J z9ZFQ=BDOMkS(+MV*{B^42_{x#sP+7d*@9XAMpfTDR`t?ZyLz(Nc{<Z!UCjDl?$_3JVr3f|Za7hana;JQxOqA>Rr}7__`Uwo^qNCy}fTe&hLQR+XW* zp$jC$Qi8g${glyjke7Ev-x#SEeffg=Tvs>E+xPC@xod{}yrYnHlFGMe#5(H;{5B`$ zbe%6A4S8#5vDm@l1NtOv1efn9m=D}j-Ny~%*XxZAUTHJIT4Bojj1Uh(8*x`N&G-H^Xx?Rv%MR}xIcig2yaaQ{iHXQAFlVX2Jvai5FI-NM!l z(w!V_|9VS)=z3QO4<`OD^^ho6Y^Y_GAV((#*Mn09yp+X3fP|P-|J1M*Amg-&9kj9} z>9ZA3GNt7h-pV?&9MA0EGi>lr6Ce;d0LXa_0s%6QPrAFiyN{Hp0FxjoKDV&&SXe1i6DlM#RUS9i|NDgW7C9o(c$i4q+ zGE`Kr^syexU83f1N4x`N5)>v@>9J&9{evEZx>G2H2kF<>*6SRTvzfAh&OHdEN5Mt(Nv+^CiV(;^jWRNH*xUiioOe6F11Qy77x)^Hx(E?$a@ zQ4vKyB4Ss$j!LbwPjIYU@ATBPtSnZnENR%wjzSh{LUCn-JUBvkpA?2@0L^L^IdX8Tq8=( zO52Eujdo7p{9PZu^3lyq192*MCUStosnD0NpYvK=6=8b)N2FwK*qDqDwE)SMy6d+; zeKs5B4LbwdNs4Bx%=PQ-nHpcl*pOCQU4W~=;%i{eSLThrL7#zF>*$ak%p$2l{3;(# zm>f)lvAOv(mbL2JrVN7XQ4||<_DE?JH7%?vQnNXp4LYfFw7Y~u5xZgom?0F@j(&kx zRwPL-rhbLXt6q}7+HgraIxUugmG};vb*0Pv)}z6R6`=alZ2Y+iRT!~aYoycrX)@X^kE8L>|!@)^r6G&e{8XDi-Rj}Owp)n zGGr=9{r48oS1Y2&9Q^~YHvaW_q!-GVc8purOcCq;F84-e=OA2dx%dt~|Ix5E1vy-! zLMH2eKH9G_Az>V769bhsv}S7-nmBG|V zpCL5rch(mEs4_|hh4ys?4ee-UbJg^ZK4I|;KH=`%5kTE@2{hB~i?Y&l*4Lo!@+3Lxnv#Ih~ z?)B*3O-O6!Ym|g{{>WeXJ7M3Ts;X+=;Om%VY5}rHj$yOTz-5~{xOwOO)yaB|!H9E{ zzOJqz2a(<4t2ntjyUEY-@$nx%d>9%Uy1l)fELB%_N!GMEhB2duhlC|wEuAx`uXv@D zuLZjvzg$^p#Lo+fiboEibuP2$dokUtG9RyyeT<_Z08u0a?jfY0N8;G$mbK-Rarcex8rrzj26j%D;SRe)n4jM6|B6 zwcN+pSn%s-;Y&zFWMph??Ah5_WMm}xTRl(0=jNa(wh5tn-ceFga?R{DMZch+pkfAU z7VoYja~6xMc$`mlhUjAXuAj92eBL%|)Ssd6a#TNe1lm77ln;5WOrA#$Z0_#b$M$}& ztx$q4)Z3*P!Lgno0(&qqF(t*j^b&ZT-qx*Hlx_1>ZDCOAGCq@00X23y>g4LRL_#2vGb?vyDfqzKM*b2nJ z!bUJaDR4%)g>i61qTj4$i?9*}n^TA{ygmCD!us=pO>!F({bEx_nL;I~SkS#ha9^KX z>7>v3t}XYJz|o{+ z`iMOgTdf>S@BiN{0EFo7@P1gId(V4$cNzxlo|v3OvUqpgm(J;h5{kru9*=I)@)v7t zPlooup{kweA(f)^S>$vu+E1jKcbRc=P&Hi0?{@~JIhJ0&AY<3p_c~Y*+(ef7oDdSW zkxlAlO@4a%QLb37xDz$#jn&ep7scbYe1?##yTF=~FJBa(T8iuLATSt79-5~pL0hi3 zau8mv#J|Hjj95nrCLt!T$I#;;)Ih?JL!|#nLxEw;L6kD6V{D9mjM0r0B8T)S1E=h9 zu_ArUdX?ClBD?K-yjTfx2y{Y%$8ESE7~RLUldk~A%F4=GTa9;NV-)CGq>Od1UdSkX z>b0M?#~jjno>Gc^jfnD+3Make>P%u4luwtJCGS^USG?Eb6d1lwyB_4*J}toBMV8~i zB83uJe;|ZBk0YTL_c`4d7*G({6(spNH>aUx`LwGR5t4?Mq=2D;@Jm$fR(=>lf|<1$^UG0`$uky*c;R=#$9^auQoQu0S0L3f@GM(eVs=0Uqt ztgSN>dUO6B`;H7It3xbK<@4d6UMj zZ`Fj<6^>5q+_J+|I$1_Kah!4WmfBwrfBZRSKq*ztc-1=z93;AC|LfDwsyUz^B|`B| zLs@Lq#a@w_7|OEm#eOJw9Cw~5I6e}5^x zmUty392<;UTU!I9@`2Q>v%v&r>s6Ui#`gZmlLS!f=TR{=&HXD1sG@9gN62yR-SMv% zWr>M)iuYp?i5!;p!lNB^%SIYJnlTU!yD7Qin!5Kr+vGPd05&S%Z_Vbi}qA74Km>!0Gy+YIt~;MN^0$3Y4fR&OWW`W_|IzZ>%H7p$tI zd~(NI%JcX4!H5X^yvSAQKbJQ}nh>$h)rX5k7bFYa@}tpM6zY^?aU z`xYbkmX8zx8bXv@F)_Cp#a%T7C;HXG;vymCzQowm&=+M#k%^?4$L3hH^R~&N2PwnD zW3#q@A!PJSpF* zVf7mqPuY{iRVXpu*I$jHJb9t;G4dUl&xj-pCyR^NYD$?00TyCWW3cb(r>>r`Hkj!t zlmq|r%ALpL5xvmGv@?-WT>&CRQ9%L8bNvis zxSD639&E<`+5iJ0zIO=x@^r>{t;jNLzqX;K4J$!LRy>^CaR-(6Zx%l-crY+Ac`;J*^Q&g}KqMI6T=VGw z>{mJ&jkyP@H*yLLlp3xL>|EVGdyIC!-_2R@0ESFcg6hFYBS2J^%2$VK8N&4%j3}`p zdr6m#;2^Vl7ShG@aq*yW@qnJ59&j*N`~2U`%naPP3Gqu+mHAgUs1g+KNnv$04rI9Y za>ehcD)1b3bJ(g*W^Jr1C^q*Dl9->*O_izg=1iif<%|1m$A`=56&?26&r!%{HQ%ze z<+edx#g_^)C8NXG%XZj?3TU5@-OhpMt1X0AuhkjCr*|Ly|!2LxvTt0 zF;GrAU((=c2=J1|y$S7i6j}rn)?fr*J(Bi5F7QX8qeYJmVYnp4hyZ0o1CFh;YY_M| zIE~Zu^H*nQ^|iFL%*`J_`Lc#%nCE01iW2&I^0TVt;&`p~Fqc`|A9pc!HZ~nLa5TGr z{_v2+AtNJ;DOd?Qz^Sv)>BGxJ#w){D@t}E!gu8LU*LRBzcb>#X%&-Fftem0O#c%?QCi@9gVdz8 zVYZo`&n4RVgbd`vK7|90LhMQ7A0n6 zcx?x2_IIXMX`bwx!*8l0bd=WoaIrgz-K!^1JUA(?LB39OVHRForZs)IP)Tiqx8ymlp- zqT^i6y7VNf*-ajyFhu3GCPc{nqQA9ub61T?a{*aS5w8wqe%!dW6jxYZpl`O0p58zI z4t+Bp~670Ma4Z-_bS>laB67hJ8-rKkAI8%5@h8rinnhPV?>%6MNv9hVhQ>_NtA zhjp<`XjPOMs+0NQJqWVmUTP9TBp9);6VsZfcn8r47-B=(pe#73Z9r&Dl&vK(pvpKn zz~&Zd@%UffV~zhY$baSKbqU1O*F^K)R(CR&+kSj69Uy=QKZqvb8bMRiKOq)b&!?P8NV6@gpzFw8$3c@WooShSI zvw(BmO+j#S(+Wfx&uIY1dJS_nfmUocIG8t08^R!vt-1|!f*t~DWVf}obq1GdvbiqK zY>vINGZo3Z1@xTeYGyJd?&lCoi6Y)V9~&24I!#Ted8DN~>+5y)5$zlu37-50wR-(Z z6T=qwG9{={t0#QgUef=H2Xd0XEU$V73l(1)ZPGTmF+}RQJI{b9?ny9DQnNt0ZlzN!pYxZ5Qx}lZ%VA z$8PE=87+Douuhf^*C(Zg1{F|d%=ByEJMI{V|n zR8d4bp<7SbQqqp#w6uFt0#gQ9I)Mon(AF9Qz3t5}tp0m%#T z@ceT7`gn4(JF?Mxwz#z#pu&+2rJ|*iC43sJ6Rnseko87M@h!b&y$PksX>~OzV&I$I z1u~Y&kaMzDJ-Jik+e@=a-;niE_88~>gP|hL)1SV(-RgstDxs@K;Pn&$y?l=mNrke#=iDB!!Og?ob6)#cKgC-{wxv5xZxo`qg{`3Jw1G$ zMYQkoQ8Bv?l@>T1LoswBkDj`4k@}GPv_~JEs+Hb>b76kD>~=+Q3#f{$;q?;=k$2Ax zvkNYh%yzD1{>Y4dV8|t%Y-rr-hFq8jsF{ge{~d|$Iixfu=mNEZ3=aHg_6_FRdB?A~ zVf@v$50P&L(ePxn1nd4GY*Q~b;H2>m?NEK(rTMH#0E zCg?go9b@b}&zZgTtoQSCIE~@H@%0jRd|C~2%0HEoiNXN;cWotaY-$njnY%LU?l(52 zlqMBnOMgS;x>i-(prR08{FyU(+2&_jZfYi-U#@&Aaj>b=jc3CF{(2Zra+Ey-L+RDt z?UfYIf??5eiWa}VWlXh(Cs;5Adpb9{$UJOu5PDUHI!FX;ZruU3IWf=Oa`#^9CClH% zCvL{2n89Vs1k%*`0{GLi8y8{;`_)Y8Lnwah7%GI zXE7yql0mYNv2fAro3l6*7k5XZJB$d6c`+v)O4_fHAz?URiic|PAN4vH5~Sl}K1(br zEf{(k@Xvn17?C(4FNi182g>}A4!65|W?0@+$$!rj5kMKygll#R`{eJ1jdINibO=nJ z5^$!noUx{vOAb;HFodbtAe_CyJsjkPPrE8Sf?!_tq@c-Tf#S$@K$+)c&O}sp6uc!g zvEt(hvL8YnH1 zXUogfW)_{%BSF11NNKac*cgt?Km}-VaHP+z=hg>_7c&If$kbATTYk@S78;j05BgAH zIDG72KR7Zr;SmqX9O)OlnrjTnVs)Vi^zo3qQITIG)H-rtuq!dqgnx7DBzl1VjnFl( zXi%;>uS-&*qr9pyLoD=h2xB90i}|p+iKPlx1_C?|(IT>)(Jn>-V8gF^jmUaO$3}F* z3zrMZ#c9t2UiWB&wo~=8e6u5YOfRvqet)Z3o<#uFS_Oj^&17HQH<9huRcBGPsfn^6 z6}PG(WY_=OF$c5#rM2II1u;f|B=n7yw3qi(;|h!~CrPVN2|+HrD4qVzO;GzXn;?m# zL4%$RDn6o&@Q~YGQmkFR@oy9{c1KuyFrQ=N@93-XFa7V#H2IJ=t5S_Scx2UYzE>J5 z4q#|dg9>uW6fG+4S?K?r-y{+3dTOT@mPN)^x@YW^@4$f)0Jw+< z8MpEKzlb6y>l0UF8vRJ{lCF0Vb;GQYE|3k>l&4-BMGf& z1gJF7_+YnLzW2C3Wxx_CSzpFnJfZr{zv3-x6~D$jMWEC&FHUP12h4eHf(FGL6WD+9 zbNA5Jx1H>H?)>=S!SZyYOVQQ0D>luEtE8s@Acuqoyq-^KML&S039iE~NO6dj=3l#r z?sPQvU$>mP@oCQnntjs!5C7dk&omeIBx--O=on^WO_cb`xIF^^2}?8tv+P#R!0QHm zz$V^%xVy8&4y--z{P##bwK{Ie_A9vR4J_kQ z_`9Ij6L-$Mv1FlFGQ2K*?a^&6ax*pD9$T?V{OkG33XOnwNQc(5E^t^O3z7>PH_K{m zvn>P?ewg|5xc+i0Zi00fiDpo5QKtkEM%RtYk-&2+1YpY&FI;v38tB66or!YMf3;NE z7%;(b!Q|ipYkgC7hMJ6=z;gb}RksDri|F&ps+yl$q9f=AD154aMUS*ad8u3WDwRZn zuBAMuAavre;g9#v`^iEb;N_6AIqCZw;0*DpCmnU=<0Y|H8eMrgDvZ z`}FdQv}B)kH`T@q#=++T_OVu9NF`JyR@FOhuNe4Oj6L+5jr-$%s*3$}s5%?i54B28 zc)`<(;Ai#N8Qf=DZLTVUF;8xU7WRugZHVVVOC%eqV|tU>Qk*QiORr-OYVEkz#VzGJesCKl#I&H z=wyPX6ms8p3jbWo+7kagQxF2fs-iL6KRrR8&tsAgU6v7dEb8MdG*V)8U5^C6NXs0_R%x* z`n@_0U&G&%)Y=#+h|K>FJ$%ZVnn|^`RKTH|x>x8b!D9eI2tLHV$-ZN;Isvp_6Ves_ zzp?25ja^Jff7Gm7%-L*vy=6Yff}bbj5_x_?&cXz4UHD%!=Zv!}rjH~~ zOiy$w;-k*+dpQ)X(R*20_15SZGQdbPhrMNt3IQR&+c;BemxVpGiEb86}gnO77QHMLePlBQYFG;A%5i*(joGcwGq62>+w65?U_6F588DGp9TSe5E-;z zZwI-K!sKNFM^r3P2h~5EP%^N(pW`RG1sd5? z*fHPsF#sZhb(MA&`0c&AJt0~)ET=%^gtw@mX5k4sCG{#N(Yaavc0_R<^3jS8(&=0)>#m;f z^*TxuBBSAn7_V{<7}#0Umz{#@O*@dIEb-Z*{Ug2>MElaM3*}8T?G~oHeRym|J`vi*GCplHI{{MJ>S*$4sm8qTj_%m%@?3wmDzCn zk78~ZhK{}obOQyY?Ff}shzIO9AGtWlDn$3`c#vyV-n5o5aiPM>F}IQVq^&6N>-TKB zp(wnU4yRmyFXYpXq&e%AX$I*4+HbB$IT!-QxOJJ_p$f^LbwWyX8UF`;UylbJ zW@*(Wc~gOLowJhb7pRIr{SNxZP(}3wOvz3-@1kLe^fYMoc#!vo-kHh=c^|#lgtL}T zeeAYd`86K~G&mL2m|I{-$wfyLo z(YLIwh4A`J|5P4YQScm(Rg*xah79^09v}bz|9y$gqV@}P4BOx-jpP^Quqmt1o@12ZwX zJf9Sw9qjg}ydBIEyrM?SlmMR5n_)Pj00iO$0nCG~T8)TZLbp!0f5)#Lf-tswk$lJk z(8pAh<&qWqtf8&|U8I1)t%QwBIejcfbaw3oYy{#^4LaY zxkgRZ_2L%uB*9yaCeTJ-*>WKdYJoeC{mNzN1gflhHxZa(e(V~zZo zApui4>3%P{k?nXFkF#Fz@iBHFN>@ngch()J7%6fYA|!A@q>r6KLjmr`ESctK&r2B_ zAo;C|K72s19;YY{@FY(EOKEu@bpGFv2hs5Hw}!HKStf>IKr#QLrDWA)tW>4gj|XKtk0_@Jl=L!8HFDp?~B!3%R5-BNoCi1Mr)-sB`-siyDBLCSpm0~AsL8gY`rBq zZpHCe=ruUWi(tyHX!7s?x`0A!_Xw-$k|CEs%_GLCct*T{?0Zuk{QohC;!2o-zo`+OGC$^-;FV5&ewLdXuYPmz1lt-EJUYT za>!ZAAX{sk9WUIkqI-;{R*80!svz(&!=I|`@Yb`(Zgq{Iq~QWLzv3PwTT+X+e->s% z113Ej)6%PM6JVp$KRvU)ZsW$aYas)I=tO=GJhyqme4is|z$ zt%dU3#CZT|!;d{15K!D%wLXdiWttvN#gbEGS~$*2g-1t^{c#v^06<_l8%08^CHyQ7 zg~_S~T=iOQ_ew3O2(@{cuE^6hI%}rm{P(ye`{;7p34n&(PN4d1&yDPN%Nmwgg^R}= z#Huo%iB(S!Py*|UBI=`hCmmQnVTr|acR6Tmw|yxy{ff*zr(Wi#6z*?p0nzNpSUC@##xY&kRcf3SliSXfh&p0IQU4$3q@ZBaG7tji&k+gq z!?Z|+mf=Bq`iSv&tibOIAU}Bgy#UwbC(j^P%@5RlX`Szdq?-@d*JD0!gswLoS3HDw z{uv%po=hD=NeZ*V0yiZ%rB8id@cDQ>Zd=HC&fs3@da|RGx}BoRD+(Ry!C}4=@d}pL zne1t&x?JvqLGZXcO@ zN?T3ti*~R7Tk*P%-SEOqz5(Pmb5#_$4kdxK`RuD^LhvsLj~2ha-%e4NGIV4^fe1qk zIxKwt4VHptG3bblqeJfQ?#!=;^qX^+I*c!M&Coo#_$jI+Ry=+9vwt|Vcl9_2fQmoA}&UMZ` zeA%&V%-Sh0mY1%SVQTnlfbNlx`$|D%^M5M?CIb_1C1RzS&4o58PxozrNj; ze)v17Ue$$ml6TL1(|MX!1xZxO>%w1qVYTP{%V1ji)`~gs^fV*?g23*tbZ1-Vo~`vX zCAZ6U7xlw$1Rvw9IRyHSGzHh}xoWuqx<`J?xiSd)w^NFbjxXDIh*IEVo#EYbAfErU z8aT$R&yyeYxbL4e9t&Mp*k3@Yd|c0Xn?OMK)-ZLI*+2R+{NJqesoA zxYg`4TJ1;1l?C>g-mni%oM4P~2zxIUPY&UgiMh3%iUhlum|kzy2yZ*9D$4NTJO&nm zIHMFEihE|~^U$FQ0v+GJzJSpYlPXZ7q5!^YXlJDSrZ@da!Eq`(YWKU@xkW39MA@IC zBVz0x)|fC38Q>|}I{Kxri4#kjr?JVf9#U%EE$j9HAIAWDF0E6B3}heR7UIE?M9*L-j&!nF+JpaO4QZ#GGR*NbrCd&CW-yj&=JB^Bb( zf@#9QIdKJJJ_DL@qqfA9exmUJD3Bggcn=4t{seXY#-DI16MmN~;wob(fL{L6P2&OP^@^ZxVZ&t$W^Gds_- z^O>EQGuUcJLm!`N-{aaWpQ?Bu^$!@UAmaWr>lxKFKsQOWZ2)EDsKeK%@Oeb=;gIM+DutlaYCrGYyE;Jz!k zWW`;241ib(JZyOO8r-GtbTtH5grWi!o(o-|!5Y6inBSYR1KAd>ed9t4XXuR=+?<{* zug3D8b~2HE8ShdIoHqetM=4JMI@kwdD^`iGnFw*7bzF{XHH*!a;0jXJY+dof;%Xfc zTUS0kL~Mtj=UW=(bs)i3OVE5xy_QYWe`jlI0 zIv=*f*N)_jbBa35rc%!*AAP^`VgiXScP2vBX>rGJ23c4d9n%q#PyS?VcKm2_H<)addIdxCZu^ycKam3T z>lsU+cg=z!1#nOFRfj1=$q7xB%=(`j{ER&*KZ>}`-$CzI6cn{Qf11y*ao#!aS`?nF zMis&1!Cn)TfaU|SKBG(19UbX!oM=}L(gRF@_e3Jf9%z=40&~l`*~2c))|Rg5%dgfi zS>>m&sXGlGi7PJnm=p-AXcakawFDp4A5R0pK+gGUF~4SlrNz-j@a|v$Y#$xZZZcH} z-WLt0biX{|g&sJ*8nA_?WUysezCqfT1*z3+gft4_SUktjha4V1aI0abN?UJ{rZM>A zTr!4zj-aLE|2M{S6RUtdDdSNEUEVj!)(3mq>raSn&I0gQGTd9TUVEu6zX=X1u5(GOhkM+|U(C?&HSM_bf0~;e_&`!z__JUubqpOKT=c2>fhM1M;6q$glRWu7sIQs1Jtzcs>@H;Nx}=}%MoHlYwhZ*b@blC;*`3bB3H9Td&e$bUKgJ5-Y8Ui)mC z*skp9jUw7EMj$Gj`TmpBu7nDOGjH5i$QrTR`HBj=l*Jq|&DB{$t7{H}{!NDQuE;9+N3-?<2wKg%IzlC1$oyl(?-A4GT&TlwO^UN_KN~RCvn~I2U z8|iz5<1pRJn{G zkRjYHn8FC8W6K*z8nSw$2-hD{U+_)y>S0Bd-Xx2m&#A`@ahe}Uh_ao*l#=a%ID})e z@uw^6rPoWKYf?PtT#3!5m4m=T?)eNS@hZGgrN}EgS$<*m2d|>+&pJ2Y4p)rlVXSn) zT&%t;*u&TF-_bSvOov{Ewr$feCKR(Gv<5RduJC89&x9h7mU5Tqfr0+lTGY0%Nu%PB zpU)#uFID)c(~J%vg->a2u?|CArDvszV+$&Cc!Ad%Q^FJ2ATXp8e| zU!%0%2DDvGjy?|=B{yu1hZK$kXr{rbU8v>>udYmgR6Qb8zGM?sOVP7Kz4p<+-qW-q#)6N_$`8z$4E*)2Jn=ih{RO)-pP<_?+Z3J zP8F8w$2UoLK$LvPCN(bcjq{6-jzmochF&VW>FLv0^SZtmr^+9kVfA&WKwJ;XO`6gI z67hQge&-;~P~=ck_^NGG_iXa7k%?pf1OJ_|Rao8Z=co2sjWxV3y+3rzvhM z>7Zj-O}zP~U#$=)Ww=wgUwk!FD|HODJ}<~)!=SGnil1umF?oPP`=AHdd*p6#hb({To%<*~cVnUN`kK=X*`RCx`$3;F;=qZOWDkko*5`XGRz&|gn zCn&#$9~dA5f^YeTCqbgrAE|IP@ptxrDBI``6jgK|PK&f_>brNNzn-bpyTgyt+a>yD zr33dorxC4x$8!CfsLwe+lP0!|^ltNjZKS>AGR{UsMMVlzr%DS5g6hLS z$01K#IXI)4;7Pci^%P%-!xLr+BE{baeR>5@TH@uZNXXhJg7rQmA8*Zk*Ff?DyaIhA zAUby7)-|P#i70T&yG9+sF=H5!&%kfZQ2LhtX=~8=xbM=$0qS8s4a$SAP?(8ZWp$vY zmR3apamrLx`(q#b5QD0jpw9;aD%tviCF&t00nxQHfJD$Pgt~U47Cx9;2zne+X^9WG z>7Vg|T(=v(x6=y|PkD!Rq^`21Zy`Zny_sZbDI_nXZ}%&QiOZ##`#dJZxH+|G~jx0m6WTg ze?ZR>>Irg!W|(V0XXetS2oxqBx?dYAE*L>IH0XLljC@4d>3=*BMwsk^>9V93DA+$?R5YfMIkBj|~XI_)Oj?3}SANB}tzx$qodME`(#No*u0o;zq{XCVD zK@`_?dbe7?Z{R`7tGl-ZIaJ}-48JTgLcwWP;A z@x8>Y{7V_;9NHSNJF0I{HUCh+mm@Vb)u9*y!8b0M6?`l*H8O0s>)PC0^QBmc;@9{R z3pqAp<4EHjSuE+Fqs{!h!xMzPb(4cp-h>wnTbnm+XDE2OZM~CP`zvl`jmF$E2en9Qyb-G8m$^J4U|g|D+HUSJ>51Bpb-E32V+v0Jof%#B z#EEk~NkHeSacGvF-!vEMXazex?E@Ws*7Bai5k`d2V@(mw5`sB9Y#bKYZ!E`-Q0&oH z{r!W-SR;Ky^Ui%d?FiizHehw?7h&MFUT<~kDjrx zD#B`$X505Gv8gyQHFUvpZ1QfN5`Py&YdYJ(u^q?-eF~=wyr4lT8+_QNcfdzniI2&f z90{FCMy$6KD)(MwP9AhU;23{l4XHSdn8!-4EVPomkYa+ zo_eE@&J5G*SEU_#Ry&>Sh+#0P(qt%j;CLWk&LpJ>ikCn4`4Ul>7&g1#X z+R2py6=`Xy<4U$6UCX=n^;(R`~E}iDaQ2$F<-+UE_xgZN#w*2}^PwwSpM`Xia#@b(Uwt=e zMc(|STe+SmyOW2t!-qX!ZNyLDVR{MR>t`L}of;Y%o;yxBZPCv)StUk^JOo8juXNF- zJMk0?a|GOsU07Oryt#OD$-ifFEjrircY~H`*m~m)t)-us zh&)BL)-s?|%`J!TY^XSXjV#>`&87u7fwiFMhuw`9uYy?8-A?+ZZvmWCQu%G=7TD@g z%Ykk8X{i8Fv4OrY@(z`9B{Z|URK_(OBUNTj_kmN(T|o6{Vl8EsMM%hq>z4PluS(5z zo3`Ap`a1_l%040U7W_*+*Rug~Uky=+)3KeXRqa7CP8L(xXeVJ{{iP~mR0C*PtTs%& z7Cz8|SN=lTT7KTRCa|;T7+Y+x<^x%XcegAp>#&?P;d?qg_XfxKPC{@F?1RBo5Wj8= z*prW4_Z#m#eOd%-C}pgTCws5Ic?dES1i)2rB49oRcf%>eGGIT?9+pEh(L0M7q$;FW zBHIAN$?Ot-n`a|YMcG;VX&9bZ8b9#JvETD}oC{5Ctr1g}U2jgJg%2MX>f34=uZOf0 z5^sHZDZKp2ud3TayguRe>z>kqL}RTa{#vWmNl4=Awu$4`HjC0L8EAvRufyVq{SpQ^ zbU8)L?#F)I<)ardA1_YqD_l%|zkj3$b;`|j8aR9)zvJflAbVHa*luYGy}Q@@+u{)S zT+EDtcYh7%X9ijLzR>z2iXxF;XGZNQSI_PzwRI+uZ+(_3;?F8d5K@CeXvI2|3x3zFpK5mVR!8 z{o3>OTR*4y;qYw^{MoL}BVoZ|lhHkwA0_>gGgpBNpcrUjGH1fc#mU+G{K4`M%=7&v z)Y4vN&Ydg@&-w-R5RlLV>uGfM-6tUh-6|}Y=09u!K-96gdd+6B)k(?p!`VMv#Xj=$ z=P#(mK`khO0$|QB<>kn)h1JzQz0=GMPB9Qm`k6~AZrZxyGBSQ?(xr7N_~>2~BO$yc6@>4F;>OV))8c{O@GU595c_;c@&F9Ujw-e*5XbfTyYFc9KqWZY?ommaaskTL_%dc}fj*VWrccOb|Qc(fXX0MLiDoGcDGMN?C>ytC0kn z@4CFzg7R{5ZCV(W*YT#Ndq|HH4PUz;9L_@Q^~Yob9>KRFf9gyxpxCdU<&Sdm+pdZ+ zZ}N{$L=w5-oAoNc;M~r!49;8;>+|FN!?aQRG4Di}nS*Ac&%P7E*!}S+0`(Qi>vBS_ zle$_bUSSNL%*>y?*zVzyJWP zOwo@J@=MazU7vDS%SXm^G3ITb5>|(WZZHe$I12T0DO+o8rIl9Q;Cywfihdw?J<%3EzFL%Sju-IK`^dlIg?*%g%m7IMo0b}^6@@SdF!PH)dSK7cG}IL;c`aNqdQd>VLXL$HdPx2;r0 z{g0VeQwK7rveaw+&L0hEj@9`fkOEV&gfw_^sd#@-aj`trU2Hn4%1OmOiAPfSD{I%=C zx*5^q&q|ub2BQ70?50ZDqE<69cdZ=%XqPM87a-ajbJYqrOjLvg+cVo|Z%8OO)Y$oG z8)+8CLO3%nQhLsgvH|b_G-GI|X}4fPUOoE|kZO!}pe;E&5^=IXK>)~z zGuT-6C0i|z?hx(OOER+0(*CT#{{m>eps2?#G5Kgo`c)k7NKR3lU75m-6e!p_=qSLD ziki+!w1^TEF6TlI$_Ir0qZYX>T|K=VkwB_+HP!zojRxia5b(dhl50hbPrJKIG~ZV9 zlK2POkr%(_E#$Tr1>E?T5z9T<-r30!slT8R8P|!Vn{oLU1^jO&KguXAExlt23gFiP zfplqEK;bO^%&Kv2Rv^OBd&Thyg(N?|=OjHr)7u znc1>5g@<|)h&7?|j2B?kf6?~WK>odoMAQ?#{}co0cUVo$F8E(N0anpc`cI))dr{S6 zLqoG}Agjp#e|!IT^MALIBzd`R!Q3hs2^iwP7sa&wW#1Wt|JG54&6K!8ZEdZRUbx-` kVGKl2JNe9i3U&lufz@BQ)`kX(fI*`=6-QAZ)y1Tnu3F+?cll9DcIf&cJ+>%VI$uEV)I zX3sqHOl+f6m1W)_6Cwiu@J3EnQXK%G@c{s89T6IQqTRde3jRQHlGOu$;$Xi1fw~IA z!vO$tKu%Ij)9b_Wny;Ior9aQZM$eDDN7>@XpB=ihBkAVjEyq9We~V($aJ8#J$IX4C z2om>R&ETdyD#af0UgAH|=PYEMhTok|PL~#iL11f=L+O8KoWtvEI$ZD9Y92?eKswqn zWyRUrZD}+~meADPER&JMNjPB@kUvQ2nEuc8 zR`aMGbkN1cMOT*~z($}H?j8QHKX`HD%WBm5#WBuxa}vg*)BoGa4pQ$jCgc*%|0Kf0e2o&CJ3K z69bTd%(luHEu4JHfBgtoL&I@0306c@&CTdYwg&7=lE%=$&GE`WLu?VmM!<6O?Xif{ z!C2|GBWZ^Davy=khel~b7QA+RGO~PsI;q7SONvnA!~*ZAch23<|8{)4%>?DO+4bU-fs6BCVB9kYb2>!@8Eyl{PND<#!qocX4Gw^ z*GcRXw5Xce%;xmwO~;86nO)VYI)XJ@gVa!SQPLlqK;Iuo8fI$v)K(Zr%^JT6iRYWA zlSWFP9v33P-Sc$cKg!zIv`BSpE48g@(JB8i;7}!Jq8Y2laF0-m z1y|~Se|5ww##z)wCgMZ&kxW4q8AMWvIGG&83!+uv#niT3(ZM;8OJo|o^|_Lk9zsFc zcuo;fqkiYI%MJuBi6a`CVk)yZK!7tvQ*s;g~C;J&R0iDAmw0}EvT0lxlO8=Z=N-$GH z6g3_I{9~SiwdJnP#oYVFCu_Vvob3l)EBPWCxZNY2ZZ4(frqfO%XNoWVQleSE^5vmS zvtO*{J9waBiBK#N?;Ful7t*&c+AQjT#cPqEF!^x~j+7IFR@*ZR%9!N_$0=c;0CHIS zuV??DQ#Ph=PX>-k(@!oIg;^wS!%s7Akkxo; z^zUlhgYfVif$Ybp=H95={clOEj$07R&- z7OoVcB_=$}O0%B(&zBKv?SU_!Pj~4#`1mRv_0QCoNkB1}50E11$1gk&GN*m~eYkg1 zg+&Ju1A=DB{5DpWP=J<6BEZ-|1i=CYu)FWSb$xl}3moS#s}s<-WRpsN<4bMDHv%kG z<@w>nNsbyaPF;Bz%hL*9VuiG!q4yBm>^ zHcir0D`cay(rwVqO)6A$k_v9T0C$rze4}0?*-eeY-TjS|DkD9c?6ka82!_8#1Xgv` z@7CBv`;!hAgWCRncRe{_U*l+MIPlCXV@WqD-MW!mIt?CGN%lhQYLXj1Y!zrXfPhIY z8%Z`&iu>lrt0kqa+}jMNIWEZ6;!l8*ZacXw&(o&;zlY}AO-KobZTIAau>tSaUg zn>Fk_qqO`R;shB1)`q8Jy|o{FQHdaeaf`b-7x_p2t=}uZv4B-fqW<#2$x`xRYswssS_q~H#Jss?{Y+>X$(I^p&3+o0 z;wC?jNskb4iIrKKX)5R=`7Q^iIO+H!LXfI=IJXq&G}$v)s?nCJ?{ayLfVVa@Bsa3E zv(&8)(LT6?RaN}XA&POYXSWcAb^qav5l#5+&*|Dz{u2{Ul;RwpzzGb zzC*E`?0JN5lXm!da}qazdlHX>li47z4v0h(f?}RZ__r03nG1r@%n%ZcwH&9VY=r?Y=niNpU<-hJn3sAjEKO%-ll5f~~>r{&5E{Req zT1(~mgJ)>Y&;PxU(p(X>3w&*HqeS{{Q3&N?pSG5^`>oqP-&Ga2R`@rH#!=!-RId&p z?HKn)Usqnt7CrkDyw$U=?aBVa{-SS1u6UF6sGaQ=uAIa)Fxrm2?&_HLp=iQ_UXM2s zai!%d`SeUoO!V~LXWh3zL3K4FVO$4SXUyg0C3LVT6D~}U6(_@Z!;BR%DJdxl3C*_7 zj8$q81VER%n6K1W=BSVY4{k@{6u`qR)TgoT>^C=cp`;x;*7l{wY!BGx2e5H)7c`d) z+x$$t+<1qR=GNvW*zJ_uC+=hRy@SgkHabtWzdjp^p~p%Wd-ko)EQ`%?!hsW5u8R~y z#w>344E$St9BiEST!f1ndU6u zBFQj}F#rJMt1i=F6F2Y`KE0?S`FC>VF!oRToBE4)QfkuDmckp4j<+eEjoCHYF$*Ui zyuZYCxe&{^rJ`nPwG~l9t$E z8FjTrNCUdkT%jxkGplN6ae1Ng2}0K$r^+iy8u6`AmJ_-$Lz$j!fsdTVFQmVK9C524 zpQG=m?28+N9OoNilw@l5A6@y8^}0Xo^6m#m?6_0>8?dDomX=^deSLk?e^gIdulMqX zX+s1FS_GD^Dl{>Ne=Y8M#NlAVLSf^R5WxZ2Wy}^a+_Kbq(3u@50C!GY!X+`!?T^ps zI9_>Z@S)q=+x<~n#GO&wWx@{-09h0Yeefr=7$zd@D?PNpAF|>E%?kKg|1pvrajEuw z&h_zeC=uoi!&t$$KF}ZB8wHy0F8AIOy=3Im2&_IC1%PCUJd>GsBadB87#Vn$dx2kq zuU@d>&at(%xw^V+o{AbY6`azsuVT;n!59B|C0l=y%@Z{-O+Pd=)S-3NqHz}o`^>&; z%4VFVQu5g-y|Amx^lZI*hsL9G&7oBT+nhV+#6w`%8C-cXwLQoPEE=_RbX1g;<&!lv zHB)nPRyQ_O@>D*2YhY@J2XZE)31ebnh=_<5SgoJ39_vU8OGZ+mYLQxfzci(48kd;X z=gMrHM~KtrbZ^h)FJFe9$q;%VC@4^1f{x?2qc=RAg1W?J__%)t<2a*rHYp(iAt5O= zAeTH+(pm(;V==0LRR2_Oq#2W8{m>3U3>h_}q>z-nufWF|y^%;5)=*bh*U`a?8Dx1c zxKBi6YK0gnQ3O%IoQ_Q@BVgB;n&Tv>!IY|R`tMU$H+6KKC*PSXJB;fzR z3Gn7l>N2(XKYCoN_<>gYMcelMdlDdQU<(8ysJ?@_avC}PjiWZunH}nHeR=$xgOnUo zg1G!!SX;lN|L9Gg4}!;OK}gDO`379juin5(zyJKVhrBuyHuC!(?&`M_=OgFmBW&&3 z*t-@RN+)YpoIVF*G%n2JE|1|ivQ}j(g1oOEM8J=e@_W$7&7G*?XlP_}PNzk1l_@X; z=6b^Jhp7(?X-wlwmKn##fBsAhQ~wJH{5S3|yuq+Qs)WVc6t2Bgg$u9E+$kB!A~n+T z{pb5QvojMgcq_pZ*S1dz{RI_7+>_HX(uSPv_*gh&*0PTcWm~Q*U^&TQ;HvB49$1=g ze*b$g=3&ttHWapoU-(=3$*2w=DH;+QmlV9b!khB--~*Rl{lnms6<2vxAN?lw;u*8O zSPP$Lq#J5=Y;%7!dypV#>e`flf8{gU!=F2)-CPWe$lY6I%VB|7kOsxLJI>_tC?t=C zs^cnSq#EK=LvYkN`kFOCMb9$UVFfk~#rnU{L4n*96$kf_u*Sc;1IA~+>G)l1DLX!@ zK+DNbtzLydDjHs@R>!Fx&}ZRWSeQteh?#(_8pf6!&7M1Fx#8b(1C88(W6SlMP}ovg z!naN!Ure6uJ%k&LxLct(tUm!gpeoTqL;pcRMF9jiCb!q^12`tN8voTZLGMPd%6#5NkFT3eLXN!eio?I}atyn?E=;&6z|WJL z+-m{PvtLR!VIauO#+CB%@d+Gx9vT%>Ac|8Hlak=07tQp2mmG+PS9dFEt7tQk8Hhg- zaB+2k0NKgyD&tn znnah7g6=KXjc9Xr4}s5LXn31XM-^Qpi8P;j|+i zh4IkB&CTh8jk8{#r>YkC)O4ot8Dlm<&XO>3PC#Z(hxK!YdAp598po1%^LADF zxQ3qE!B^)7YW*fuIhc4GiXPF*WTXVct(vyKa;tAvEwC}an@E0W?Beo zX@~3@Gp4ec_ikL-Iy1ZYf2PU%rGhK5`?x&OlVi63emE{(=#8(#^#-NEx@kTBJ#hjZ zGPH=W@+iB48o(A%&HDRl6xTJ6<4k{;D{mhz_^jQ#xoXz`U&fx7P}D9Bs<;-G^EF(F?DZd?5wp)fy4kJv=l)r(prdcc1G=b}!FX z16Oxf9tKb-IwdySzO`iZpQ4|(x0ZAo+-lQ*tk>mEwS%xQ(4vJF7PR28?;C3xn|`xm zn{H5qnJ(!_h0Fl;PT!5$GF!=?@pdh%2H#--Az~+;~QHc0}xdRvK2gK5+V{N zm!QQ5H1w2@n2IzAQfjm*ay28>5^D2bM1+@}RBc~l5KXFmeb$1nU(o>uhB8_TAK!ga zNf-Xyhq7hj_%QBbP_xWJs5g#i+8Y-3%YSHxZ&!3Y)O^Rw~%k;K$z@{05&U)SXO7!e9dygDy`QXt$Fq^he z+9wwos&5-Zc|C|O&zP2$=K0GR0f2=L=2_3wbIx%CpB!HAs`%S*jE4-m)E0ePT;Q7i zsq1%2ynQ9*ak8>7<7_n55Qstqb56N-h*Wq5BnG(@ zUpKTwHo6G5DA<_yk4xK+&w8JbuvM}8qjZ^u*kb3lV1WpekqpjLvT{gO$yc+<&vTft zCRTQz42L~8_lVDs;Uu2?pB}VR#eY(XSx@Ze=;JlXH?2_}Z9LnH1fBo>GNaG^|n z->;8oV@fMZe${$s2Xlpm2*->ntFaN_vk@`F!xP76iA;XadXRaPP`9#CRfJaUlQ%fA z5CFcSqRf4C<0zkH5T*S&YP?rOFJ9r_R-r~l-7$!#0k`iTU{574go+tvvGu_}&8X9% zgV649B+r4`X(qToJSs#K1_E#nsJbeR!yp#PR#i5JhqFXd6?6*W5@VSsDW*@ezyDy! z60r}7t&j*|er9ruF0#r_r?*eI@H*vwCO||alKEbdcX)5e!Gs*!iEH*wQ(YO zi6sFsY!GoM6cAzC`p1zf%wnLBIqdJ4i)(TIqhaB)pvxcCJdQxaKr#wW6nG?Yjj&l^=;(N( z!7+Sj;qQ?%WMpn2sInCgkpAE!=T9sCsgGQ2+2L~8av`l}s9FbwpFgM!s?V4cx^HLC zX4aw0hf7}#3i$RhVWJD40*pt|k*3&B&V#{WJqnUX!kGH81UF- z@{z?BRYXTeM?^$qXA_<*Yg;sW-=40m`1DB^J0C69bb6drRa9i28GZ;$2N_vub5atR zNKvmWZ5j!0tUv^GEgpWx9!%*qE|+P$7#6riPgpQAGv}TGX=Yozr;`F_KgP#7axCKq zs_N=I`E$FwyBnC!R$CLy!=qnwbMwH!z}ngx@LEP$dhhA(;qmbF+|bZ4GouDTn3;wAAKa)h zp@7i-uhw&Apg6P3Rs~j`)I{(BEBs3|cMnfO^N;@i{yI83fq^1GZ2a3_o*Pd|BZx|& zq`k-7RfsHLsMk+QGpu`CDv7yJv z0jR)8h-iS-C_8YeTtxmgJ53)qW*4-&bw-`q*tocZGm0iAUYQUOF^4if ztejUHL8($pedx4(3FKP8?@k~i{CT{GZ_&^-zp^&qBY1cP=EJxhe#zGI#jm!zmixq@ zOR2rr($dr8YaCY1dkY1qf(#MaZ(BHH91cJo$ey_Q{Q38RrDCCV^p`GmHy!{8LJQ}O zr&1|^jG5LeDk}cT2iXa>)X8e=*|%_%4(yp)d}*u7udgc#TG;x!>WZw=BS9Jf+jl?$ z05Upgfb2WxidCXT!QS%n@}?%Ym*=No(SnMKit1_wS1e$2rP&rVn&I>Fugi9Oyr;RI z>n3{X(8y+h^@9$t3rXnY zBzY2&i>=@un>q29bOlCzNZ9aWK$Cp*FN3-#?!`ZV38FDfJB3UmqC4S zxjXLAno|U6U9Abo1rLXZFwS$`d;em4ctQFR7E{RK$-MQ_3=>`*f<_9ayS2;X7W9(t##f7S>*ie1=$l;TDLMR|t z`1R+Hv3VAJ0TebMhb^oJeGJ_fvJO1BH093K#@CU#tM{*dcK5k$U@`=a|n525CyhWlytH5 zGGvhY9c{!t8_E|rrk#JTa>*d90V55;`(o%pMUrBPaKYw!%IW4VctBA!bbaQ?l}51| z6ACWM1lvWRp`YNn;M7%DEf_IEO3p&3!Sp;i07MR`X==`IY}7rPDe{-k>FMhJTwbmW za9Or%DJr6rQiDf8z`L8Hk7i(DX<0o9AxA|;rS^mgqY@F}@wCC)@8mjaNY7pF5f0tfjZdLL0{-BrIDR*+zg_oL*@#yC1|kd4 z2O5!#j11lfjt+5bsn^0GHa2gra>B4g2sJCK<7$ijhq{cS3eaG$!1OBg{TsgyZcP&t zimWmZUSduqnPN2%3BfcE=mbw#XBe5vw?@V}ra566pRfH(iQI|}w5yd|1KkPYXn}%? z@brN%g5v1%$f(KJU^RZlu0@vGlsjj5Xh`-6HDwfg5Dg;!|GfY)gMPyKOyl9<;nKxP zs9#_}M+qhbIF%yB3ys+j0p;?PeecF)V&riA2+$;oAZpm5{p15|V2I2#ekrKp;pY0e z-?W|~T3ju4K(#o_M^E>0nrLXyxJJy7%h=KUGy#Xn}VFbv+M<$NQ8`7HqN&Arlt9 zk0-5ENr+jAD`DE4IE{ZiwLN6hV5-6HG#pO&XGaOiJ|5%<7qZC7 z%tVBRrlFzPa{6h;{=Ua=*@|;-e_sO|4v5jd)1|@E((>cAdjn5LOIyNhAl>Q^_sLX_ za2|u6l@&}XgX9AS=-t@(`LiMrUfdQTl$sGSM07|!R+?(q`F10)*Js?K(fYOw2OB$a zCBz2hzSPUbMcp1La=?sx@W5?vZ!g(1g(kR+f@gTLzE36u`;!IL`Hb9RdU+4qg!_i4 z(QXu0Y7x*EuaH6O>*Mki03_;in>F(N3wT0N|1$=jL#-jjl0_pQ5w6~~A|8h50UEdj zE1BqTTj!l;J=MbV{?zo*v+L{176QVwa=^KoUOWW(yXl)`SU^or8+OZC4m#*9P`9+Y zyi6}C5qr!*7zDk1>LhO(TNqp>iZK9O!ABKALdYwMc{r6)YNw7ZOJ$de6C8LwVoMMK zFVAC$qa)o?EQA3LZsXzCe$QQ;Jh*ODpLB$yXxekk0p(kb0Cj4q9~DbeWg^vOk9hYI8yqxHCW2N7j9S3sNX8&EU4P>hR`}pDQ05NBetCV9BbC^7Yuav^3D==J>HN z5!4&Axpr5;seH+oi-X732HK#56 z{<+h&fg@DkS-zi(hNb29{gqJuo#fV^KTo|+_GiN)r+@EHMO1BMzCApum-?=6!{ec-E# zGVWV6G`pXwGpn7Q-MMZW5UF?4#Rj$Sw{_FYtU0Dut+LgzEqM+1Zec{1mm7OKZr8C8 z(6n!E;E!(#lQF+8$A$pF#^ZN7(!eKo88+U$90mA^2X6Z!5UWkB2m##)HH100XlZE& zJUj)|0ohq6lPw}N!ShP87v1jalfMl_~q6P1mVF(nb4BN z8*V6?;OMD|s*TK{3X=h-yu>u2q3_~jG8MU&>QW5&F$cOX5CXrR94{}+ej8PT{#zQ zoVd7zl#5d3&RliuP--OjP`z}b$A@)BhG>^x2wfilUTrlK%gk;tbaU$J@+;ox$5txz8WA}bWpaw?i{-HZz#_5_BsviZI8YYD?Tcw5)42!{uv_d zaba3Mcb~U90me~m>9RXX3K=2r14$1)aH1x9`pMW*%l;34n>#wb&dFH|50eF+G=KJ% z|5p|YmHzbOSRw}NZy}ohr!OhOes^D=N#%9GJou>OJ9xkj8bdsD!Xjp{=slmduI?WQ z(=iF@dZW3*eMA;anYP>#4BDN!_f-AIl_62RW!d-duZbM3hhKVZpMDkpvahS^4qj*n!BvnH6NRyP)DyH~=;#+;Z795)Gzr zXQ>Bwa+LmgL}rrKchX{y{B}8@^Wo~=+E%U?s(=%$txsdiD8ztC(BQy3gaT{eQ)(K0 zO$|l{3J{G(5~B5ojQZ&fhCUWPHR8l3n2Pkh*4moOkLTvhbX;>0y!w&-&&Nv41y(ZuB4|Z#6mbQ3gD!f zUO@)p({T|*H^cFWrv!`b=Y6YpP+6iVJ?c=0lf2ve#pMVq8w0 z1`_KYq|$e<`8nvCnhOo817j;Q$&IGOHO7z&**?+}lRp2yW|0k1= z49Xw;-f6zi4ZQoh5`wM|_LqwL#FyuDbMb7)B8nq@#tvIBQen!!aM5IZdoN;eE$9|N3w@9X*V_j%cBhKEWuU0qog>4v&XXXycQu>)Hr zVWqG=3vf-E8dzQzQlP7zHgvjY71tPXkZdSlJG|h{3-IX){e>Z}4-O6WV}0&zBTrK~ zuW}V5qs;jxR;rql6-uF0k+{J-I0|gEP*{qfdyTL@m{p9|RgZayySh>$#OVr=9;cFX zf^tap;MUPP$kEnlDx^qi&<6t&H(jh)RYLH*msyfd5jQKf5huW5%sXKp36SE0C{n}0 zSWVtaN;||mR2BEX*Di4Mcss(UKfj(p`}{(wqrQ1e?TG%JgNq4{f2uS1ID19oeT}0& z7pPZjBWWJ|l2#6&k~4M9z!us?(5Qo1C8wsQ?`Mv57^XIk!`Nb0P#{+MU;q6J)}H4y z&1>+CV5N}S*A^q-HGDfOyZvj*q~)Wd9~{=_TP-57!4&6fGu$*2cqH(EhU=C7ZlsM; z)t@@%^0`V!@ho6p7Cjq=!Q=*|kXUFebI?AxU*W5E8TF|W387efr!rv@{ zu?<@|xH*k0FHm_FpNO61icnNsDpivg@}B~ZdAOE+Iz?sF@bw)-2FiQx-ig1ix8c2C z^!M$R6->cKFz+1ZN^O;k*oBYSF0r$6SYLHg=8@tv(fy-xNkM9oNsrS7eeAVSP>7uV zH{)$m?eik`dk6yHKDmBC?!uz8h?@!7hYlj9r4Ew{}>`T)05K; z-xb<^%8`|Xrmq6Yb@qau+|OVBB-3u5d#6V~2+dptPgLu$f-PMN6hWX{M5`XIx8T-c$(~q-Tut@qDUnP;nt646PFvHj}K(J$dCpE)ko;8mrB5ehlhw6|9-sbN< z3~}4nq$Kvtsh7-uJGOFX_U)w>&jO!PbSJLXIEsU&mGM#(oAHH9&FqWV2maJ%fxnTrCD&LhYhYu4gAIL$ zIjRx5-_RJuk8tEL{24(zJmkJIi!O6NzF$7-Q;JHiO8@J-#(;f)A|$FHh{WSO7h_s7;3c=#!s z`5-+7~C``x5P`o^ZH?Uah(mBEgQM(vElC zy45`$E528IUwjcu|9cyf4X?M@N*j85x0*#%v!RpmlDtWQ64Kny;qfO>SBRriZvI$L z&Vszj0X**?Eti#c4U`JLvI6a@p>)$Lhdvc>oFpX8b1AY3!>c=5br`P-GtFOrOn}%x z$+$Ajw%_tys+F;7@Av}t18QOnj<%B+Bo|aXPAw$`17s=Y%}nEH^3(}XH!Ku>GljD# zvw^uMbP#(Q6Qk+JSA9Qe7k&Mzx)H_>n=UJ6T~%E!v%%T>H$OPj(G@A0hn>C1QTzaG zfhp8WHpq8gjv1SOLxWf<0?MHulXbF;t8Q7<{y^- zJuAVQynH%SCpNw~m`i{)XDw_efY@ve_81zhHh89gnLRWMn|%X1BjfS)QyEaD6!#|& z47L;buO76+ra29p!)H;H<_aJWi-TT0f1FA6|9oA&pVT*M6A%aAi4w#rJOYZ_N;GA&yASLg6Mk}`#IYIQdS9;7KKIzgHr z*;__MwRxm4QU?YY@(LjIuMRr$X`=9oo6?7 zdc;D$_lJkGJQS%nAQccttU&~EM8>zO`dTT=PA*&veT)}e0G0KvJ+(7~!2i5y3<&sE z5nSF_YghJNGFDHo{uU6ma=^{bk>KL;QWg+b2pPZX)pI-MZZY#dyQG>QnH5^`&5VtQ=y z&^7foh6Ub6!T`|0dgalDv0yE+AyvP^8A^_?#(x*b5MACCTxKJ)FTA+HZpNpn*gKzi zu*eNQ+di0tmQxKuN=gO0l8oPYr;35x+nn2|ed<;!{}kfB;P-@6Jxu75ABt!BW;pU! z^uiperzB41q%{$`xDPl$9Aa{bWA^xo(T1`UgKtmy{g^)xc*3~E_0n8N{9C#B0h1Hz zUs^4Oab7AV2W1-(hB*$nJMX3ow*B&ZzxyOZ*Jt{RIEAWBOf~FRF8^vp+||Q}UOtP~ zhv=RK9r6NpIG~DwK-*hVOZ~Rp0O&i+T3Hr0s-qNUKp%4f*AQcM+vhrsYh}OtVUIV{ z!EWuu${H#&ng)S)&ycdqNCW9|FAhnr@cA3L}e0fxQH&@rTvb-8_zm20D76yVN(3aA;lF?#CAU zk76m|J!rkgJpsQ14)$_NWvsftf$axn)EAnJ3!ke~Fu;2lvZ{oIn7px)tyje54NC<1 zXn0-bd4qut81mgjF={vVC>tz2CiUB_r{SVZ22MX@im3k5^c z&>Axa107f?D+g^xTRwe##gmg(qd@2H+S{pj1GwS*%zr+y_ zz^R#qKopA;pJT7WMu4{A{pz!s6kYdr}-`liDTs_K#5=XFp#|rg*<6-toI%{&E zAfUq;ha`Kth#STZ4ITpZL146fcAz(64g4$U%O|8|uPBY{4&%7A>I#`L{+?f^=(()p zee4lFl0%WFX8Yn-{Lf#Y`mj+<8xw1mc=ANh( zz%kL>-ZZ6lOE)V=Rb2{Lma>K|zET}I%w?5$ba^nQ{O=1O zs@zZt$O3(<^O`=#x=n>9!PyY{0_{&?kjB@ggKKoPw>QI*J8;uuZkQ3$a}J5jE_iK= zZI$gqh}+4XU2a4N8k>6VDgvqEgT0HIa9a{yG=LcC->_wmq^f7T;S}S;&U1si4j`W z`n;ApR6Pmbnw#TD_)Bah!7=Gp)ygjYW?+owd1#GO&Z2veHWkiw9?HD)qR?l-3s7VD zAS>%ZqDX}YYr3IdT?RMkG6?AVx61gO?d@kG zBJNv=YfYjh&jm44vtAFE%HEt=ygRSaZH%4CcUwrD00EqW)&6tl%IZ=TRfuXC`2FSh zW9jc;EVt|w4{KhM##AeXNP`Dbo@!Hq$Rwt(k?@6X5gTowr_!;LL}W$+f5Qs~aiD>d zhb`s}Y)$hN{s;zX3!&UDHPrGiQhO`Jg?Ul+1REL1YRTz7ZXs+I7DTV@+etw1;v#t0 z2H3Q+uJ`bGWyqA9_br{Q3-a9SmW`t11+O6>c+2Mq^eXOGl!pUcOi3ZC5n$*_5cS!n z^l8wjvr%%@Xoh(pP9+J1mA6v@`ubsedt6hPOjHT%V1JZ6-nUr=T$=#^B!sJg2zLsILVC*_Zy_nR?v$hTcBtbvb+)oEwt3w6- z%ZlV^GvIol)tz)}RbAw3*@p6G6h9&XU&rrp$v@HwB>s7;@%}M^H2@Y6uHOc2SJS9> z;V!MgbHx2Qq4)3a8zL2)_2|GUFOi8d-H0{*rF;6!M_Icm%(7T{Gu%d&-Ok zEC0_`sf2n{DD+&58=CQz8Cmom3k2i?LdT@g_D~5s+*RY5TE`lz$~S4>cD5Dw3i2O_M@uEpU4otF5mnUqn5yZ zd>{y>4@wld=%0px!Iw&$Y<>4!)EYiV>(KqTOUx4_sTE^m^8Q$35YXkN;0tnWt3_$R zkY9d3+Edt=U8gKhMvwT&oJ9Abyp@|{>FYGExI)m!2FMA%PWg@fm&!Df>+g}Ud{JSW zEF`#xXx0ua4wDYZ`lR`2)i7q%pqk*AD%F?)%#QrH9ndjs^D1N+OdiT{xy>ahNI=-cFm|Mla|4zf>D$*F#+T=>IR=9rs*Z;5tw zN^5=eDrJU|V zLjD8+0DkxD{|msXKSin1MJn<-xPZPzQMj!w6~a+6lbRz<8{yske!dQh{gyChYA&c) zdl%f^3Pwx|Efvi*O(|Gr-F3AB;tY>fXkhSlC;{@L>0e*`q4nO_eR$>3;M%FYbGjNy ztA{s~^Zj!IFL-`2dp7kz^}w>(avrbFtX<)1?SO%~wC81F`{GasA-Is9zG&8Ffe_V2 z5Y4iJeY56B6MG;>7mvfj7jddv^YA=Rd~G)8eK1buhc*wA>k@@VwxRnR>O0IHOj4{gySi)nx`AFn(cw^{?{x2cduX+P$vk!__TEDaEwlRV*+-7j8$M%n zU3)&@QKhbfLXrOc%10OYz$8(0Wk}foV9dLyj_S@46G6Y?`GV4L-Lbpq`7vFj)U5aG zMLtxY&NEKX;1%uHv+{V3Kw=-WMGpVn9#56tYI}+@U+%_FX$bA(b>9y~CUPGwjg_`u zjxx6nRccIZ3rUcGmy91R zgu|^b$U$0mG6M-Omd|J(Z1?WpzjQsK7*)UoObMIhx{C zlXAuq(=awvYyu8O;u~S^~I|ZL9sJM z(0F^hY6Nn;5h{7a;C^HPoBnCsNpvQaIHzM=wokw8gDeEu$z%JTOy>3(t>p~%liJPR zS!Ur?SxRv+Pb<(jIs*+OaP0y_<^3rguFZ)LTyQ$=G+mI0n0zVwRty-oU4C>Pm$6*O zCBGcGMO_M1e(Y$D`_H#FDa#t<;Qe0}R~`>#^z|Q%GASCOkZq7Hp&=wYQI-)QOURyG z%93Rm``9B%)<{{R$)2@j8QGWY8L~|FeV>{4(XaRY{NDeb`ONb<=icu*_uO-ybHBH6 zO*pzK4b0y2STWx&DgGQZOH|XnkbMaNzm=t-NETx3;29L@CNrYc7S1iIB0?Z=QQBOH z8OC%52vpFsw8}SE)|8v(4`exLHVO^zxo4HULXz};zIgtEkc7NtEtHGoEng(Q4F)9l&0~9P+e@ zDZ7XWCV+>DHN8f5=Q1^r>f~~Ny)xaXsMc53YCg5VL+18z#*X@)hkc_6lawk);NxA! z_X7EK>%Ym5t2bD^4>=Vx4Q!oW##t*l?11@VXSV5b5n?LGKxlP28heNoPVegLzkbk2 zGPn^N@_p;J`q9&R^MuxeSZ^7VhHQ5)?4pv&f~bAHdB`8RlGOCEv8JTAUt2L(`KX%W zTdUfi%C$2f)-yLc6*Ty2DQ3{Y({Os!tJ;04<~hzs7OGA*U@Hb}7wJ^ymRmoVDV?R& zj@8O-yLoAC9E3~_N>TYrl6dF|reCP1uHy9;tbs%o!}vCz-37fp_2vk3{TQ#xC7Ry> zrs7>#%&Y7G4wpa4du^NKY@b5c-}b&m$$ng$BW+4&f7A@kOOdY23*{Y~$dukNw2vAh zia(zIMW*vH2MN@n*H3{F%4ck+fmV#2jM>e}eK$vo&i3D{okBg(&aR2b0fK6t^*>qS zt(os83#XHZALu)Qo5gmkg+C$Q;-~!9R7{Q?sdnDTV&KN2So1}fsqq}AvyWJOld&hc zY~{hvqbujS0Liv^sEo$Fv9a`W#JFHMh7+P9z}UILi0(~`yh=3MR6SK;s4Siuk|o3A z>T8Cg0)S2hKj}@10AeYa*}RC;yoW<_EO-Up1`o7dX##8Hg1nDiP&!8udZrzb!}>2o-;i$4+G4GH-Cz$?nNVg)jVwkd-=W`0=u=s#JpJqlD!2VLJLum)<=EpqKOpBX|+WdolSna}NkQ1%k|Ua-#J*6U*stonI6= z&*;ILBjyt1}vV%6X1i*QUh=3`mj}!Vvlw_=av!wcmApY4sEgiY?kl1$ZvS*CZrnyeqEv zX81{>s6CJ;HuDXv3hIi&Ep*}ljr4!A0YTWcgiaTZ@tT3zqba2Ya+2qa z4B%Nj<4d)(09fwVm|i`iZ^kkMYNK1eE%R1Af&3{09mHMHX~wd`Jg&d#x*hm=muvKg z1CzH=7qa2<^Go@aACk$m2lnK8V10c=XOkc`%ek&bA4Hw+^_l$68t-x2`Bf_UD2zXg zsO7HZSY@JSstN*&uRDkA=G%N<-{^1@cj{1=0aP zsggQE3t34|?b&n-3gqV^owDk9HATRVZrVwajARo6n!XlC0E)Y>7o-Nv-p~SOc=$>= z*YTDV*|r(QR2HIeBNVCIe;xq4Q{3LsLj#2kX0-+K@}V5#n1<#4sS@o*M)|g@vYAJ0K=u`@T zMeNyL9wS1c@Zfe^eVWu6d)k0Qc8>ungqsrL+o}S6z~aYsbyVSlGk3;?y&JD@g^m(7 z*tXl5p1(ChSzr4h5E!GIc0$)dJ2^$W{<;VTn5kdH)9M~s-j`8cNbj4IIaCy%d3o|M zcfUgTsV}fDOSf7sfA$-8DfGs0f;I_6`4K8{!XPMUNkuKl%6nvGfPo99~k$^+Gv zjOmJxWfe7-uXwSuja$l6vKW6BqoH^awi>ZIyc^H>el8luFEYF9cN7>)uJ-eKhUg@0 zZ>;Xs_H2oMm9wBDF2(){%Q|fP={K09iay$n(#ZFEyp8B-9~CiZmEV*am5KglYDAqC zAok@^)js9Q%F01*MRP?BvtZD$yA!P|tjnfz%Uf5$8ydjcVa|ljl#K9G<=q~I@HBoN+MnTezVV+Qg*Pm}@s3+<=}AiZSQ6L5oT;Q7892OEV<^EbRP z$<#LUMlHuha5z4`Q&Ft*O9Bxv{_N{V1)62D$6`nAU={-mR%GQ>Stv7EE%a$Eq9Lg< z+GRvU{+Zv12-EwQXYkY$W9U~8MnA8vG>|ORIrg7Wl zt^S^Br~c`o6KTyIthmI@1(MSa@YfS|dmBGWA~|7L5G)YH){(t3}sIvXR`dR5iVKI@z;B5q$j)%L`{&AcoQN*lz@Wlqy40ubnS z(u1^w$}*u2XJHs@;FWWIsnxs`KXeMB&8Xu*A-&{6l>=4(I2? zMsf(m$jHe4{QdyO-ezFl9hqNvu)OH|u+h?Oogneb^vas?A8H;R9!F>zmj?bC6Lsyv=a6EC>2qlB+8{jXM^IeWat?v3_S;&0w`H`yyTJ#pg zojy_dE3JN78HI~Q42f@M^E1@F3)=uuZjI~+gb@@DHwZA8Uj3AAk6hn>@C;$iVvM-= z@?7S9om9yiOTEDrB*pF58T6}~I0E9u-LN=LV)lJ0`a0JiYYaPn zzYuDwHXj~2m=0HtO^^B8T0YHpSEF3x*1(^^6`W1W*!rG6@isCb?YVhi@pJ!`;DagB z0)||T{45B&Q^|+GB2D$!GXvIFwkww4^!u^c6qbTvvLYRah1~k4r1sjXyw`Pyxc$Yw z!Dx+gnY1sD5tdxcNXM5Z@udd`D(a+1r6aVntA2jMtbUZJkNP*S5D}4=rcmn zXsZF!IQi-qD_h@yx*6>s=gFos^!0qSUBi`Kqz41>_F<=waYg<)u`t}bbG1TJ zzaIW1uGRE(zQ5mXG*<*haBwy4!ts)szxdD$_O>eVQ)WMp6mWAWNw1yZm=Vi;ey7gq z%xl&gFR}HvOStPIBk$WFrDE6#Q3fo3QpFGBh>Vnt0n*Rr?63G<#g>(MTH+~12*LfW zOwhaOC^9pdB(mEv^IO4%MrT_cchLUly*aC#*rtwKi>&C#5~(EXs5a2GR3O=xS9azl zRc^)`o1~Qs+21qv$Ynu#&t|?uD|q2>klN@7RivO{s7B|kl=u1mq^Kz%*Ye(ZC58|SQf1kPFM7}oT(qb)rX*v7rG_%}~$~V6Qt||#lxyyT>yQ_}r zvd=q{!_?Up+B=Los=tH;Bi@#pTruGfOrM4ROb;Hm*yfAtk!ki@IXQ!cN0@dsVC+ zD~r^G5OKRp7ndv8DeBNGjlEhv>#|Yr==nJs+)E&P)Io#3FvyRh{|HgRsN5CIX>Dwzy9wkXvD~gGGIKM>%-s;i?*VPms%!4<@o*&UzYi{07aEFZk}W+c}P>!ADTw ziajcFmKxRXWph)g`f_kM4Fmpd4T|J8$bhGSK;8RpZSNXfpH#c3XaO2Y!_?H2w6l31 z|7OT-gpRq;hGRKG3dY;iviL!&J4SJGVt@OHThP4 zmX5BF&jHOvarw{k^8LRNxT&R_$GjjVNKZYXiD_mTMP06z0K^FhuXOSRgP<#JJp2?b zkGDHM{KnL&cc97YQ>!MT9rm)T@SUEKK}#yj%FA|;Ypr_~)Z7jp_$TdPjoX~nfl@9F zK;6;NakDg*6jsSI0JG$PN_-DhB`nOY@XvWwq$Xtr9UX1enE-X+T)}~u1m=aRnP%Zk zKT^%aQX0$JT`SfkFN%5(Ct3md%(l><)$riJw8rtvBbRlH)cX7SxEYIhgD!fgQA&S) zJaFZxRpexEZW8?WP#x{HrEwu%qOmwdHxD2DCxnx=ghrxdyNeX&fooNUwwF2ux>eUI~hPjQX48OZyb%ExLu=& z8BRhWTxw&9)~I(+v_MYNi_`qEEE=r}hgCo(35P4xKs7{(Qu@his|Y`VM9U7^M-8ze z$)M;2+S6m=U^&APx_$}`5s+v1R-p2|HA*La9qY7IoY52%0ftY&J(PGQ?8oO+u33MwZD6&njy8D+v;;%*b5czjTT9`qjfH~>V;Vc?%n>z`H z_UC}WV+hnN&#J$`FflgKa=c!B?XdVco2re$`xGQ;5DR$4e*4lpXh_DUdl{ z0SP$I+k3~-Gh2tlps0m;lkEWBSv$lap_-7rub1*J1t5fQQB1r=uQv8F z{bHw^<2!~=oq+IY+-Dti8t=}rs! zY5s|_PQ)aNLVJVl?0=i`-+0_%l_I`|;C*x^X!(C)g5E}{!X2Tkp!>ng8>yeFCIGHV zamt{&zhiB=XwLyXfn4CTfXi%-%s*Hz7?&Kmr9_D5i2OI){~uv@T2R@~_V!25XBX28d^W8I{BOI|G!26y^dQ$*GABdp65>HAMT!2dqOl91qLT}K&R|? j%s_SW_g|bqWJ#QYV-D8ZD#c*`3jpq@>8O?{TcZC5g_%M@ literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png new file mode 100644 index 0000000000000000000000000000000000000000..3bc4465d74b0d454f377dd080dece7c24a88a283 GIT binary patch literal 28315 zcmaG|byOQqw5GIFplFfeZbgeb1%kV~ySKQfXmNKh?h>qcvEuH~AjKs(!Qm~xciz8m zPtGCPWM^k*?%eO*?|ws=l7b{EG66CI0s^YE6i5XD0Z|J9;l=V>MBq&7fU^Q-qG6ZRmh?{T;5}5{g#^S%BdeLH+c2NYZIkK z<>SMMR3ov6lIa)o=mWhlu;{;I3-#6Cw&j)~2SW1N0X&^j+6D`@TXsj}tVF(n2(5+H<63NSAmy2ui%-Kp(LS>z(_t z#%g7F47-{G7AtsrtF39Cu7C&n&PEq|3xmOy5bZoIzuerNeR%7qqjcS)sf?{5*x_-S z_b8-AnlnDXvNHBaf&9eu^=9nl!Yby|Rl-9||Fv)%A}~x!;|o97Fb5%eYhw7#zZ72g z#2^`vVbI0e&;9^zAm3}m932xgJ~EQJ&b~CVU}bl81my)MY>%{M0vFeKR;ER4Y-|J> z|FaRwaRk0gwB0PG8)~qfALva>`2dVFS>TQd{1cuAKeWE57co$n>#WrcrUQGlc%CBO z8l@2h(2`sai0gV7O}K2a%TNKBkMErC-@o6i$buM~=+l^ty{!lY&Ieo>w%wXu4)bo# zkS>u$Poq(U6UXcwPZ-6#KsYzbV7Em7(BI#GK#6v~We9!$=!8XADg3I2#xrjh=kM$$ z!M8p1Gzn`IBFf)8sZP25L0vL&rTawV_ zUxuSuQi>L$_6lJ&Jjgg%)EMTcV(ce!Va&k~PPzPRg2zb;yTevPd&{B2Mi?blTs-^_G`Gd^DFYe!;tg0|In^%~N zelRQ?02xt86+qW zlxExUl(62BlStg!9N~dhyPs^6wJL{As#_N~F9r$+u4Wu@Yb$;t45}GSiVdJ1;Ki;A z7O%5GTSGnO#RD$g;|;S*!(0YnR?O@ zT^WHfJ_nd?^OP4-i-b0M#d=Gfzc>}0U87ii%nK~#o)jsXW;+L0cDxvFGiI_-;FpA- z43b}qyscT}{gLS+1&&Q-&;J@~Q!G5=`>C}H;w)HN>gy0aKk3(0KK{`qpJG0gp??}R zf;gsfr|!||!fD(Co#|@k;=dzN5G`up2ni|>#VSGe_5~R?C4R1NWFT9Uwi{%|OuBS* z;F4-O-GybWlMybzNT;10`;zwM0sd{xNJd)Py6yQe$&X;$B=gAMh{q}i&+9{kQM4Yv zlwtQoZA16@IS_lhi@x(muESE z)w^j_bDpQS`EJp z*#RFal@ZtSeFiobrwS*Fk9xB5M13bbcBBJNOB}@i0bxv;8|fxTj4uQaMqWa?A9uzaX#WO`*SvMAd}$>kAbZ@;pnaf#iFT` z+ksx2M_e_8j+Mhq{xkbg8s07vR9^`Zm^d@LF>TKdo7lM}OD+D;O=!WPtN{%ZM(l0c zfF6_&biv$yK;$&_hC!CmMXaai2YOw{1b#Ys4}Y-e3&4dgPv@VC(H;+;KN5TP$z$r7;P+kD# z&Y^i6FD+$H`+EDomH8%%TT$Le1MznH%^6}$nRc|F{gf>(I`Iu8=lg%lRUm>o4O{LCrv-;(?B(iDxGUoE)LO?VIL-}Nk40H5m zJ9O9LV!Ql}!K}a_HkI_5SG)h0@1ZukIj8_mTx2H8RmS)IoNqOCII^I^DxHwjO)|}< z_q2&kFi)eUz?^*d$rN{L|6z(PC6b37faRKUOFT?io<7K|n~{nF4p?)u23GAavI-ql zZPyhf1ScB;15WGtg@wNh3vKoFyO&3Af8fD^D-|JrY!*IWkK}s$68d7kl#@9* zBW8SOxf3khTB%Pn?obmlRY{Q}z(N0*p{&k{6_yImk^ct3LWX}&x@qX#!otYo{Fc*? z9+Y|kES;yD$J_i8x4w8mlj|vOm`H*%UzS3#D*tzbC*ce> zQ4G;VqnPX#W8YaBrrSUwQZfjOZ3&_TXkVzIzO*YICnMM=&1jur*PzX#mSL$-xMfnW zs)6vkycUl*24X5+4rR$%>fl>_B9&5{nole**Ru4e6;TPAES(gWwU&be@c@tF65O`a z-t=?|LlU}b*isT#9?Rlyy7g;EpG9vlJo0kuzQau>VQ;D8u#HviS6aZDQeLaFb^w7uFZcz1!ZNc z$K0s_vxf49@Y1gCM!`HT{oqiPH!KrfNvvbF5)|VFYv~RWju1|qo5uaBppK3=YOeHH z?=Y2l+TfmwLS|8k|IGEq>8te~o5^iC+&C2bs&Bdc=n&C(mdxcA*bB zy}{(<;20fSQA*_X`}@A^-Y~PQtgf!E*DdcRM-!I-f<~|t>%6xx6$!Qov9JSM=vun? zmiR4juJkqS7i~4*CT+WL@nuDUsD_D|Q>Gp8{+-fc*3SLw)_CyaLJRn+`g=QP3xe+# zwOo-#p#S33!^v8jnj#xq)&c^>Nrj@K%#CzL-O6h?yBYEEGU?&fOS*U`Sa8j+$bdE< zaE@=QX-f3X2bgu0_vppc^-bsp7GY?uP?6#D{)((mBr$(X7*r=2pSZa0>j8IR6zXu& zk8JYV)G=SpSvsbyOg4=AVUp3#ajLXVwMEt6L{odSr^;$zsM2oeWU5e>Iz@LrrjK0N zSs**IKi}E;JWh&=NMj@+Ac*WQRm}};BIEPygeggdNqnfQ;~wa(O^M>})o{>cwExCZ zL@)$B`T*^L_T1)g4R`;Cpr2PlbVliW>{|Z$PcI(2a1A@XQD(`}`+Kry_G&$(bOM}= zaDW#hX<9pTc&JAO`4|SWrMq$Yx}!*N^oHt6KGZid7r4;Mff zW#iRG>BVSTJ+h+|nH{cO*Z{wyk){y+bWt24!9`P?sq*Pt3oj>Up)TU?>9rPkV%GQA zCdN`#fxen(sKDshxg7{Qp-D%jf3*RK{H>$Hz+wI|EU4Z&=+wi+m|U6czTU&t_a$X) z7oR9XiCBxv`cOx--_BU87V?mjWCo|RNLOb4DweE>n=T)@=eV~fi6pR&c9sLGOHZZ( z0O-x;b++*F$xPP7*KkRg(i%}hF58b^6?S^Ky;D^+CCmm!G^j;+tI>m%9oF!g!3Jo$ ze&eTw?TY!@jY{lbTClC#?MIe-z;nczlVbwjH}Nw{gbsg6nXLbBCR~4u0bw+e63y!i zWP}mNBdcw(#=Ixq1C`j&Z6Ed}mgXu)cN{4Z2|n`6%PZ@RubZ0#>DpF*pF;xumR^Ue ziwhzlACJq2B=bh{Tr^MCRAm45BflpI|Ziq;kc1wI$LcFPitUgKjIL{wWZ7+SG6FK) zthCffOEFDNO?Sq!OvQS#v$HP^>+%{yzViVfUh-zCRD=>|z(iU_*B_fIukVq_TP`It zK+d0WMqeDlvBb6qL@u(!-RY@Fj1^n~HCRs-b;f1yawXJ_Z6>zjfm;b3NQ+3M1ovo$ z4D)l$SgapGTQyg$rC{5nmK<*xlxYr& z|A0BkWgA1qneq);eoAk?2@3!jcfe0m?CJR#~!2uUPcOJvTAEhy3A1 zpoBv7F1os0E zJldzHi%FMn_+wBa1B&bo-PkeUs_w3iY4f11?vB}H*w6VPf>L7MSRq9CSA^GXI>gYh zyzRIT+oNAF!MiviEqjD*=qlR$W)B|jeFGbwO!_|GZmqpi{@a?_o8MCu&E?JJJKj~w zVbR@#1JkBCRrJ4K7cD0^f8u(7JAc4?i=dRR5rAQIUh-(Y8j@MQH&#F5hIPKwiGkVf zO!y%Asb_(L78awIjQPIUcMHgwo`W~2#W7@bDWO^m`8kYTD5$r5xyW0II=N3(!c_t} zF!JHL;GQl!dEyJ(tv8K&H@R?{+Sr~OX$xzpzQ5LuS-qLcvdk9f*@oTTvgefCLoNZd zm7TBd9Ct`TvPCiJ{0wjEp#k0eHP-f9c#c`imknE7N;`H?Fo9&gQ8nCY02rThgX8h+ zLY87S(qE*jlASaj((I+GzAZmV(3PPAACl-v>ghcWvrJnJR$RA7@U!JwD$P8IZXYPk z57X25`1>rz1SACxxyVuGUjPx4Ee}aV77;%AbF1&@&liXCmEAK#P5MoJLOt{56+xZz zqsM;{d>1V$V#svm#R#Rk7uRHEQJzI@zv4hYp4WwGc? zcMENNWSr^fu455gJ`+KS`LWK>qjq90NJ47p^~4##c2l+H0KSF|4WBYb6$A?_f;W*g`FhSVYn*NF7H=(;5cQWs#D5jW2O!2k5t?2oY z!gfc}*zaF3rg`NYRCZ^-7C3itEFKosA^!0iJeBF;ua@y}`3e{$&n<@VvrN;U;^hf; zqRGzDm}!~p(TPtuG-fw)x`fA=g1{`f@c`4(nWk|C8y0xnwP$!p=sU~4!isYqNMq@# zr@tO?&pC~{wYtpI?l3FEcywzMOCrwX=Sz7YG!oXY?aHw?GWxDR+`)`e&|UqoRJ|92 z&&saa?|OO51pph^d1XhJpXAnb{wk? z@@!Ig2dilDl>@+FOS))iy=!DufpE4Zj}G%vXkNFQjE9gV*5*g|rO0)U@V(f>=Mv_| zjk|43EurZ*>~~RvgDE|P-yu6Ff|3F)A?a9E-O9HS?8&iBymX#k4wR;)oTdAM0u-Sy-t#5TPPJ=fKwv;6Sw z=gN%0z*VnJ%m-zPA(;yw&znE5vNHbQbX@4tpQTW% z2mHYfby$Z(AorW&$4O|5<`|j>+}S$D7Q8T8;RP5Q=Z~yTT%o8Bp&fBjHOpX&Izd*! z_S;7sWBJ8|&@&t<{q}Z-CVsZoM9vD=qf3!tnfH+~F&{8n^RmZx2;01pI_EvBuY{q_ z=-`66)+e~WfvL}ZWq;+dw&BeZ1Bk=J`6SL!P!t3Zk8Ohg_Se*P`sJvqArKa(9^7Hi z{1oY@v8O9ySV~OirN?{|dv*T#Qgz!OFa?FzcI$YJdzzn7`hyk71#n@F!gZ(ptij_h z5yW^^lCEQh&u-9wH$x+GO>xF`6#J_HE`OshKjwpeYHFn z)Q6DCeW-?!V}U9Us#P51`_ic@Z1ZY=`)Te_b@p=7%KiIrw%(>Yjz+V2@L{hlz>lh_ zyxI@Y)=g#lyB78zfy;}c{l-p-jJ{Oy;?8`+ z@F;XmI5Q8Xevf=pQ~l+-b^+xTVns(~XY1c*GK|Z|KlfBE|9%+xe9&O5vj}L+%4Cd@g9OLC3sI#>rK4V8?vZDaT!)PQoZd~_*uN_$kB;%YM2@n}L>omh@Fl{> zD--8))vzF4b>Hy37N}S=F5KL^w)uvTogK6(UuhY;tl6;^2KgZkkxy zXWD$dos7wA{=T33?|}H;!5bSJ2M48LswCOo*C;8SMvJC51$!U-luqgYktho=R0&kY zSBTARc5FsbaxbKu1sy)HtR$~86&|YzFob)9`ie1>mogmuzRe!Xdslbmd`^;ab#ud- zgu|94B_%K2ZLfVg-jI0w-Z>A;qYGzXDW@B{JMMhi&Tx#5j#f}mcpcbf#9HEMa0&2@ zxtSigB&j*v*}-MYzD9m4m1W+b(~9jnHd1Bm#f_*=Buv31sl#RuN)bmv2H#c2vf#Y!azonX=LjiSicuoL$f!HeR*44^Qh> zh)IAK>;zzHP3az=;iIa*V-A)M8n%4%sByOa5#@)irNcWRnXYS>##4Yq_Ta1KOD03_?k%afu`2EH~V zB){=AyQcS1y50#9?!DHv>W@oENa*S5S$aWHo`MyZN9Wjf`WiFLvJWoos3?%61Wn6U zq%e=esRCl{ZM=*{^!Q`RiDc=*&-8aMbe2SZG7h)B8Y2C@pOeC@&o;Qm zLJJ^gBI&qjQ<+eb)W>&?y~0-qpXbVP^W+iq%GSq)tM)7RIx19<>J zn8p<)g*`)5m0Y@`l6pmWvREB3x<0~)Ih2e7A|)^+b4dV8`oZ^-b5G5;wHD8%9pr!7 zyQj}&^&cZ8|7La87oA2IS6wYsYYXJ z%2c-plWMESe*gYrXqdx=D6WhxuDtA~EB5RjwEHa9wUswfSe^bPY19Ua#*mp^4S%&8 ze1+M5yI+34wz+Ahs+!Pef~i>znczyQphYPjQ-CgcM?jec-ZJnDX-f?Y2Q;!~utzR_ z`Fb!{c{qG}da7yY>+0f?IEvj^U;iE*z1mL#^$P~#mp*_fYx~k-kuP5x*qwx%@kavM z^cl#?CH(AoO4@CmoSa--)c866cKCXKN(#SM2erbPy}ub4*KX97v*^txixEEkQhv&n zfuL!-!h{b)u6&M;H&51k+Hi-KjH~pTyN~`I9N2zS3I)c>W^F@&QhQ)ybU-Nv9eJKe zi0v?`Qlp%i=eX@$0a)1GBCu}?y7V~WwE*W+T55gkJuQHu-o$qvg&!!^gG&FyVp;*0 z?JTHmYmX`Y2L>kU`}agVU%wFgx8PuQ8O5R_J6Bb6v%5qgen}!a^@!vSJ~KbN;S=Cp zL222xwW&?I{QLVig6_*~7Nq9q+z#go)Jq^kTuj_PetGt0^RQ=T((Q*vGg11eb8io` zeb=j&mrKX1JLkkgKB>pNtU^NB)sz>&QayaVtXdyp1bT}wt2*=A?$4DzLmA)DLDiDu z_fa$pJaK0eF)<;8{o`YI@L_h6MFZy_AM+_xmLJ;}d!#;P4=Shh4zu>ekXxUQhr6qt zieQV4K+(_RMYcu3z!;VN)3vKkd!CYQ+?6&yooiz`IK)eczXTSio!~H61B>Fa$K7U3 zNG~8N%gEW0C@mC^U22MI`#Zi%Cf<=$E%rAX-e$~_{*d1_ zfFOVZwY8Thv*%{Qa9Z4GL#!`dJUQtBG2GdvgrKA9>gaf_9$zj$EHQ3Qnq)iCIbQ~s zAHFu^Tv%Nah6p=vVOW?wz0F{mAz`clT70HGqKtjmr`YZ74<**oRN$=o{8q-q!wkDG z`ve$hSL8oQPid}R?{7E?R)IlrRHgFqY{DMYCv!^2HzRHiFJHbymlOU9ggE6Sk{nJ> z>Ks*J?kjULcXSd!gk${PL86Q)7MBE@pp66xZ1%6JwW^^}CC;Ah#;W*zQ;fsvO4~#G z*i}6`-GqD@wY0syetQ7f$f$XhyrJ77-7n|R|I-2xhM&Q<>{9GBugq?BcqvyKHSAH5 zKLdnIl#6Km!mpFqRj|zD6|>WQH}-veCog^{Nna3Sr}N>$l^ZN?i{Ugm*ez+jD#hJA zrV0`24`gFExCAmP%VSyYp6%@lmK!r_(G6banEWIg=(MAj&e}lF#*$6yYC@JIl?jj#R3{9QxDBIb20Cop%!^K9FJ5gX~ugUU0rHv$f8{ssM`Z$YM=42c_x3f8{TK1bGILNA;!TVujpc^C=4R5 z_6W6daQH+JWo3|WSFakV=ps;Sfz0Lu`TF>~?Mj-ZJmrj60a`7kjBSsh5;cNN@%F`U zJr7m64#rLN0q$*GXJVvfRePZFBY4~)tBr0-dPEZQBRFT&V#6JWFbIVG{&mW{S}3vb z(&tq?qnBOU)_e~bmrwAHxiNUy(LvqR#Yqawa?=texG5JL<}{&z`Z&eksg_GomY>Ba zCy*5TDE@EW@b6iKu0T}wpD>9>h9R`>^pF4BjgYye@Ad<~J8Y54@_iH==8R&I)?;*a zCC$@tggqbkvilM-fh=Q<<)|BFLNOs-C5>iKTH|rmk+v?#{$}os8ot z7XwHREeeR?TO-}wNK=SR>=n#>+}yNp1E_`r`q*g0NqMrC`ZrAl-cpy29>8X+LMJTN z8#P;*g}(U{H+d5Qh5^)Pu8UPG-lm;nDNq~r@WWnPpIL4m3*2Op`W^i^UOBH~hPn9n zPaj2J9qkG)gO~Z6>{XlOT@*1UD>&|&tNp4rlA*+p@D&;vsvA2VZga-wG6 zT;@|RlIB1WlZ8#c8~bXiu_-?+ zu))3@M5Q=@ih>HfbXOLqPTh(5!7X*?urcqao_6=A2k7%m3IpBat>Pz|CkEa$xHUo; z<%AQDJPIjYy~BNZCk4A8tcDorK1y^KmzR5h2qyIpy*TgY)rUzSc@9d{HvOHIm2T2% zceQg%XL_YDaMs!K;FdB>J$%+^zr3`x6dI~;OuAeR6TUo(6FBekcIn~2lJPb z=jR?ikW6|)Cq}H$-Mk%IOYk|ho349sH&6hwyUc!;n3!oOvH`HzobO!U);9juQ*?#l z2zKUnKs%SJu;GESYT1T%XZ@ zY3!C4SN0r0jQe{A*^#dYr2uKD*g^eaJRTc4*uugBe!Qv(0!qzsQbD2HjLH6m)D+>1 zcBb$oHVdIYl0kBG*dru(Wo7$rtzjjuMe;2xTo7<-D0WU>`;zi`#3=7@LG8w8*Bmd~ zgYsAnWO6`3efY z$*db;zj@HrD_DV#*n--pzT~*n8oqEqOIF7a8|=f(YH1khK#X*Z*Y0(>-%kp*t6Nl4 zhczt{BuJyg#aVZo1jag<8#Cf=Bm|G0hJ@4>o%&-^qzkiFk9KF8Pw9evA}+srjeGMy zR^?yzS5^u;K;eYTOHXa>H+>dxNdX3(9~JpeibaSw0Qa`oSRWPor@tS?&`Jm!841xp zEe#)@VQpnKAsi4Is`n1B)q-5H3m9a`GSW~p5LUu?ExY&W0PwQ;-YBn@63oKIT~|MR z6!CNRfX<_HH^Z?*8uU|%4jcL5&URkMzOhPa_ir*&%Z>#D`P(qyG#7W%K7r-6+4>>j zMw~q+uE(PGt_IZFF&zer_xQ9<@U2$TE9U~};vqU%JGz=c06tcmCA=u@i7UI=HXPu7H*f29`3}SJ{+c061W7ANu(Cn~EO2ZQyH+UJ9ETJ((ydF)6rKi!m*d zgPT9Jq_lKzn-pr+>ZMXeHkmA)Hb>fIL5pf$Nnl24qz_LaBZ%7fV}~6#)(whMIBDwx ziEZ4B^5}H?|MCi*Zj_%bjEprEvCzx8wKb;Vgye%fy$+loyu*P9 z??fqNXcFRQhB|$AvPi81jjgT2s@(?AuB6D#3n5}?na_#&^|%vY+gN$ z{vyz0gj*CYcCh<`u)P>S{PdP-DeFw^MFiOY*yIqDOaV68oLeC}^2C-2;CmO6j#^*7 zfU0LI@DqK2_yDv4-JZz>u-bqF$k+Wk!ESCEVE511=3~d>jEQo53BE`i%@?UwuOZPwV&ST z>XwgyeBz_7VOO$B>MI~{Q8EoVvy;#7 z+r>fn1VG~uZt$bOl`A>7x1LqEEA~fB#4j*jfKdNt>`wO8%_f}GQgf@Yg5j!hfDQBV zO<-{KoG$UwH*!pUpa_8)zrdWEO-Uj&GUSP)=f~2zF1(q;$B)BLVoEOsit)Yr3|9eI zNK;c@W_vnm`@@+24Zw5qyRY;;UR(-J%wK(<&%pmmxK5;_?feg@^lk|61@(3adWz05 zt?UGL1BEEt7)P?_)j(y>lxS((fk@BLd$YamWU%yDPkAn#b-p5_l&J35TWt=$J~5`S z;ZF#29!dzVZ`*j^X(O}i4!p| z3dq##HZs1rf6*i^+{&33(5#XKlAuaHa_PldchPtnv$RmOn+LmlZdTSWAZv=_O*410 zSZAeyY>09_yQNT$BDZ!bJBs$m$va-Id!Qgda=%9A{oR3!gGj?;1_w7R=;FuwwT&47 z35Mv!2}fEm$uUpAl}Z1X7L^zaprGG82%wzfNad%nSdyAa=rL26EGIj>wV!`q>A?GQ zR(qE~yTLfaMReb{stG2iYY5J95gpV1SM{>{h7$IXq)P!$NxwXWph`syFTK=p*xp_bw+!16ECHTV4- zAZb+2=S;aIxZ^Vhx)NM1NcjZ0fNo1DOI#I3N(+ z!0Tnjd7jjluo<#p(K(IVv076^Ow7@dkqM_+4$F6mg6-TybF0eYEzDR@Gjhxu^qZSo zQP$Ki>ydL{I8*{&iCY`X#2+#6RzbJ43(-O3ACGl%JRm{c>R>YG-QwWxdrs>V7uuw zAg?sFw+Gdigthxn3a^+X)K%8oXvJHn;GS@L@~y8Vk#-GyjivV-NkMm9S#&l%7JGW! z@iORqfIqpQ8*Zewy9JoK8hMJ{x&G(Oak4FGB_%?4Wn@t>A2QPL^%bo> zRh9Z(f8Gr2vD7ZF8%AFUo_z1$Ij=Af8gFFb?kURG5_*BqK)#rs{WNPel7TFUrN~)G zyulDbgi9JFc_dxtPBqIP9}#$JdmMo|_%L_68*_Z@;|z|S>h8RmPMJb{xJU`o^y`{C z>6o>~K_3}^8a!TPSb ztdwJFvSkt*{jRp5-Ph#qa&dca4i1NxlW-EDS!>9g98jU7qn`&7KG#7T$nTBv_Ly1^ ziW~n7b8Ss}Y>aDEWido+XOTX??43nh$e9f43_PeVd%ZOrd&v9su6!8R9efKA}(^XpCOj7Mi6wxJ_>}AuZ<(yY&Z6A0An?|v4r!;gt z*c!L$r*D4Fa+zYPQ1xn|*q9>)igbKv;-b1967A540pc)7yQlX-!yLeJA2tN?is#3{ z;p(V7BmYduu-WPh6f*(<_u82FRkxsg&$2wkU0yh0>T25V{Gu0rAn4rwcnq#+p9fTh zW>@x!5-)POI657gR%iz_|@r^8I2FsTLTzx^dx&emB< zsVOnju8=@xYa1wCj#6!c#CooG;H}&?H_h24Ony=#)}NkPr1wih@zbWGNMDZ2XKmd` zl1sZiJWWC77_(!1USO$fDfy#2&UV^Zdx~7|&C62gEnC*#H5L3)vplSX9oyoG`+W1u z4h0~0j*341gj5KPMTp37DTR!o9cmm zmDV5jT}C=UPEMOhEV&H?Pi&MwC)An$kt!Ymy4C2{-Pl8zw zO2U7kjy1#RL(9^A8T8aTdc10&Bj_MYu3b$E<>7I~qHmV{=qAmZ#u(27*DHnP&qZ~o zedm?sX&@=fAebRUI01t~blE*~lsnzsKr#DX*45fDK*bD2r}sePuAp!)K(K{>aJ3xy zOg~Sg6~bD}aC#^^4q0B*>|!Fb93Dx}V&hf)Dqn>%de!z#c*{`x*E$28)4eGo0_)HE ztnHZ6GyF-ejEz7Bm|U@*wNCUW+b>o&wloyt${ni@5^g-F3 z?4&&GV__I$qKjp^u|R|fxqKt9EX2B5@Q>(yA2$*D&-tbf1<<(96+YZtS-XS~+hQkA z!5`a9_MPxyTZLc=&XX6<&X8z=U3=EX>Ia1H@0ig3WRfn%GwuE2#= z_1gAoV4w@714#Utg^!rpKPnt%N2@a8;6)jRb~JfF!R~N-VZSF7$W6q0aBMeXqn>_Z zFFxQ3A=i(hM4zgYT16Qb&#z88)rB>TpA^SLH3(f;M22?w*d85vi0#bMjH`t+<>9HV z|Gj)Y-cZ!oJc22c;4!*%k{u;^7&5?1x4G~)!|iBdtwffeKDADj#!Y|=fS0exSjw!) z`G$$c^aCdfq(a(OW^cZK`u*IE%rEDPlCy$?yRgBNz_5@jd(m_sAwx?`%c*p)tt!%B z9g4~2c;MA&9YIZ_XH(a9M+h&h9Q?t|bcESAZ?<%{rHznmY+uIr$qY5Cur!sNB`pkesH$a+3 z;hER-bnqduA(8d#L9!c?pmnk+#L;7zR(GT(v4#TdiGZN~VKp5B#oFw|(S1~?U#;nF zNvQuDms3NXNH2cd5%^#%K6CQe8)IOd=E{XNN#6O?E_OQp$O^xRh{JmlXmL>t2z~T% zl)VC-tv+u39enx}I-i0PiJSf;GxLq|Jgxaet>V%Vv{xbaXsaxx_O)if8z`MJ-d)Sk z{9d4ojX`O^Yhd}_Fke)Nl!>uDOY%H{m%iXs(iRRbNifVU`GMSIu@`#OhsQr@vF2-B;cX(NnFwP zZLQ~?-K5@64IOH#D7^cOEF2pOli|Iey(XJw%DdjWF|^>$6jLz3G)K7%9}=Bo%Rfk@ zCr7&ayC7RWKT}7NW*0pjy|Tkrez@xQ&)&_{)HY%E`tBt{Nx;BL5VZ{48ik2P9wh`< zg&88ROEh2E#nSsPi-F-Ec(PRf=6%bY7gwJ03Cz!A=@Lvh33oU zyB1DA-T}oDpi)>X3}^_!XMbWK^9q|pXlzS^-IK)<*7+$|OK7A*6~f8EFie93IW`7e zHdXxz{NHwov?kX6f1m1Y`qO$n>MuZt^AiXs7P?1YSMs zMNb@;`_Z4GCmP^$%**eEE-3Ft=GC!E`0l>3 z1F8}x()x*%(9jv*vOuD#chW)(Z(3eHiaoAuJPT#_f;I)WfSoD8IhW*m@1J{Cx)v^Y ziNHoFNy&2qWS-?8St;&BhpzfoW86fW*WCBrzAQxfrZ5(V&Cm&r+=~%>&&ZqF1J~Iq zpxShRK1-HRk;9~ouZSGM$KGSDWIQz9S8$1RM46U2J@@?!h(0c;B5paY zvC+`wZS{{WcqbMKN!G)uWu75w|C8NcFZ1$qXAso?OS+j%aTcXUqtWL*1<4}?u6FBM zP;h-z(5u3EgMu1^`6~VA?EuRrArG<>(K+4i#$i-I{xyxugHM(hmq6K`$c^I3UD~3! zl>#R|8f*6=H+*%b9$AH%;yfS?f>(2#ijW(!DSvzlG5mELY#EaC)A{y|TGR=D=Q;na z>6Qj5FS3$uINy#I`x}=Rq^@Rk_O=X&TV7pO-hWQ|?T3Ef z(t23`7**YQdOJ72_3j1*e2wHLaN0>_@aq_fBA#~hO~=#kH?6{NuR_j)wT%G@&|(xb z7!OlBgq_lQ_~!2ioAcGs`;Es=@;vavKh44>Leq$dTS*M%xf{c?!A%B3@8D2iw+okF zgR-|K=R4nFZ#0n?E#Yl9_JPi-um9fgO zotzVRSt)aFlF#HonODPrWfRVmkLJ!g?XGIh_|}@Ye!+gDUYQ$^Unzp&g_gQPR@$DK zpSyhb&ke6>Fp0f)7J%y1-tm~@MX56GN}o_|WLb-;60EGbTW!?0Cqu8+QinQo7u%J> z;VrvK%^{~%7!<_N{mRDn$yv_h6Asvq`&U?Oz@8_zgvvRY< zy9o$%+tv#KTB3hX?xphBgQ#oDg83WSn)9mGj;ndF*l@M#8flndSoo)pw(`K|H0c36)@Ko$ld5v!B25^5>|#Aao_(@s%v$qH3vk>J96H%ixZ7b4|;` z-qN*Gt>t;Y>Kj5wMsb25@3wXK@#gr-y)_nzzVf+(Oohe*T|*2?@A$nC4$Q)^nbvsS z4w&9jN+_I$cw;V=g+5w~5Ulfvt_5_*gbd>?53pr1G_(XJN2th8;S`&H<-wwh_}SfM z%$e_lBaqzi$yU_Ocn>jT#SSF}EJB`Ckaur#ceK5d&DWO|+hDv&SN!-NKd#Xah(?=d zxb4@LG+Chk!L>zDVh`v71QWnvMulZB7e{n8m z(!5!;V8a&N%-tE&&n0whgZjCpj-jEr(Fay5b#gtHQ-hh>#jm0}u=^XdB#2#B1BFGxd&shZ+G;b{_IDBqUQKrS0|d zY#Dy5EdsVmoI3K{-L?w=!ro?Jmy&W%2Pd%IJeOwcuT${)Y+bNn=qQ-iCI?b6BhE?T zPOSp3=dr-SGRtUS6e2M6VT9L(Zdi!P7KmIAZQchleoz*p%5o|UqqEPysRrQ*6FRoU z4k}Y13ldo}9Hgn4dOb4O*hx-#R*r}a_-Vl|KC=8c+xpIT!~9|(ejM0w{0Ex@@|BfT zD51X-U*E%4_2h4}^On4bC_wbVJ_*oKQCtc0Ej@KxcN)JV9nkCK7R&9E+^B`oH~Ly_ z9tF8-SlxKPS#G==31m{>gvM)q{MH;=BCTb@`-!UL5~=n=mtp zPlyf920LCEZPhSY3TKhE!DQ}%YZrR zBTt0|l~33^2l?p}D9Q{@w`BPx1Qx&X8WSOl+dy^1!==K}kO z`O2S+0!%56kcpr~Rpiy<42|NobmzPS<;Ef!gzx)=goLIjhi=C!m05g{e*1?V-v~|1 zDbbcw$biPQLV|TIi6%KR3<({FU8HZ8#4sx+9YzHSrH7A&5;OPWdlgmT>5iqrrUoB_$5nx;w*(Qhn4hhLr$F!@% zEr*QE479c_w8pfz)Y(PrP;O&BWwmm=H;s%R23?cb8z zWLgh%7?8x^$fWNNpm}dhJI!V?j?DL^CpgJ?ZrN6!0K0=uc@+2o{99-T_<8eV%+cq6 zm$0PqKXtu%Jd|JjH$1JhiLBYlZc@r_kUjerBBLxL`p6B(t@B8|1X0GL2=X}=p`F!5<5tVD6fVpD$9&T3Yqxy8=AI;R2 zB?wGG78#~6{(-8Ecq_;>NnT^qPYN$Ye>KErKBQZaH4NlS^b@>Pc*_&fu`SEeD7gdh zjY-gK@lVK{rda#p31ImNupaCjm^6#NLfiF;Zb}U$!QnsK)$tPz?L97e6P@q1_h1is#w2B zhV!E&%e)!eO=}CEN^sVnq6T|>Mx*qDeV8mWTq7&a4NTDs1#Rg&GoAj}44>L76rrL{zyF-hplkk^a^vp!mIO)Mwx58wj zRW`HzHRuPj6zc=y7p-94Xp`ZWJ;=O|wLw#<_9iJ4G{U@)GFangw0}_Uuuy4eSrHS< z`=|M+Srnh~^Ystq3t&3YR$0#}NcZY^E+rUTWFt>*WX6J;G>}$u7Zvn(C>B`-S18 z<7+Z7!;O_3CzpxYBg&^Qo99i2X7XG@&wR_QSJXNO#;|$j@DAyzYlW^c#mqzow@0~= zbA$sWfU-a0624*dN0Q@S)w|mkd%T$q25+>dH;FX1*RIQ*xu{9U$p5A!@3D>I$Oah< z_EGGW@8@gtRs|yeUrH6Q%zsNmdhuQihAe6<+j>UV=++evGQ8xTXtJ*Q_MJin_lO>Cqc$E26oUbT++z&yZaswJ6Y9Zj!A4hE?!x3dFpFh(6-x)N^KL1nKD z8N`6z-d;yslgf1;1)F`dMB&Aq2W){_;Dd%}#rU%-rmzKp{8>;l3d?_5KTNwwyNLF| zxOn};5uKE>mkh29OQtGnOJ&R1LfvLB_F78<3+3u%lgaHPYAdUPlv(sea75a zX&`D1T_$_f)CWIqqd~|$9gb9uN7{ImzBm!!J-v>SfzABlK1lFkGaPD3f|Q2oc7?H{ zg4_R%|2%873m&6=sF!~ZdfJ_s8H&RUts-3gL#Wice$x zY@<(}8U2@hJ}^_Co?A$~*V)44LG4wrhxB61)?#Ikb3L7Q47tGdu+0}b_@oR*yD_0* zh~ET8$}A3denR9+$J{j({mw;VyaXu^vcNr6>k<7cMo7l^QcJXKte8}_+8-c`UV-U^ zsmDK)sMR~X<7ZmJgN@A%f=;3`()vLLp~DGa*Zwf0rwiKPO2mId{S<8dFm(T}M>!qD zP{Wt^`ZdpCMqeMemn3wru-VleUHY3vuW?ME`x_P?cb!qS?{TCEw7+z3;Nn#>ajaWB zG`0g|5u`?fpp|h?aRyVWmHU18r{Kre|7!r+)6?uuw#0nNBy6}S6C{=7DzAf?CME1& z+jC9r|2TkT+t{zUI@n%jn3+OBEKYnG)U(4P?%ZMKdL|N;+{kDr0L}PXp%O74{!}cg zyR&NOz5%-2rg9!o@7!Yr9jeo1ZN3&GW*@J21dc+W0M-L-Cc6hx0>paNdOVNIQ|KLN z&^#rQTG$gA<8Kv;YJGSAC48>^M(^ zpDXpY)J@*%>cx?Uac5*!I(J$`0f9bS_-*LrzTMQDmg??jGDI!{HT0Hysuy2Z_vt_j zv{tVwd0^L!>#(w5;4obgssXm1Yx+TZim#J=mJOhnVG+RbNcs|05Opd>=Yjzh5gO{P zgJt*j-7E+@%J0zk5H6y5eh-&fj~0VW4lFd324x;-D~c-lo3rsD>6RKOV+Pi@T^mnZ z61B%GJIp5VI(CMR2{K%|a>FK(y~ZraFrkI3LsZZhD5?0LJsZerY|7$>f4IFnlqdm> z!e79`REXh2w+RdKDKb86*|M1D|NZ*uW81H`MZ71IQ2y24`l~YN4$#dVnN7vYLj+7= z|CDJ+qq?~~kWeic*bTamhVw0;6|Yl3FCyqMG;mEUewsPY82L3bWHxmHcplh~;_taL z;FnEDJ_BlKwaUV9QuRl#sLd`Qi-ul;H-gC+u^@GjRj*I(Y6R{&cGG5|Sx6m>1J*^S zrS!Y|;dN5x1ABT0+W$`J9(1o1cm6`HcQ_ygsV__hx7Q+0OA_SOy zwY`S$#Jdam??cwpw$*uiR#M|xp!K{{WoNALBQ_V9AU8mgbA$J8;Tj+n8A9d}5YRJI z?tguW?AB9N0$q|QWJEx_+Tkf`U|(TBcmZ1ukZ}*Pzi>TaJLul`#)ke|PIn5)rau6o zn~S)Iyb?E2LdX}q49P=HHuXC{Be4gce|`b?)-@g*AK!c-VEMHl z_EVG3LT~%Ob8~HW_X3HbQ66B!(m^uk6vL$!n4kOJ(*&x{{XblQ##jBXm9f7)v`JMB z&C>sk5=^&7b12<%jC2E3lKu~4*bfd+rNI_-GP(a$1 zUSi|F*IV9h7Pt$L8mRN)S+Mola`qGerzPW9AAXGnv%_tP*2}Amop|w|UyH?~CeKse zhV)Z66SyT$D?H}w(DuEXkUqzE%{%^>cwq{;QNCB5#KC~Kc5P!P{_xBLRR?-VuxToO zW*lA{8u;()e>=d-7RZZ2_7{o}c%(@+cnqv4oqyKoac7Gfp%_(7MY zSQ46E&Oc@nr$nJ>`^k@Fv|bzf`AInTpRl~pJ5S1d&r@_0S~$fBdPI3>ChjEuVy9P5 zVq#4jWJB5@cv>By@uEKR`P{vx`PHVKxd(Gd5UQCQ-XC2rC+eS z>!U|QT=nLRwY9TT%Nxw(%hfONMl{#fO326@E;TGqHiB1w8xa*HBqX%(xakg{a&r0s zQ1EY4-k;A)F9}c_@rFd@vK|ea|Hgo= z2&f~KmXcD)_!h+?t)%DCFwt$T57_i}Ba}GDkjYPNYyf#&JfQjuV)yX!no3SxURb?( zewLZy4S|Gim|*i;ITa}M{uB^Hb|NStt{GpvdGn@SioY1mf~_4#rZ+{gc&XR8Y}Rf>cr*R_B6oE+|k3D)S&xA__JmsN&F?`JnPNZ*m0nwl!bE_8K~2MRet zMjJ*o@axx;r%&^WTWO;@6WW#Yh8D_3&&ul>CanEyEbUVO+WD?KyWJ96$_eMkreTE( z3LB#Q>@txXFJF+X2hvsu*V^F7o%j-5{x*?rn7^l=f_wbZA>Fnf1 zRJr%oR>$W(l4ZPSCLdts9UqdPHJJagp>UfvTz2Q1yga3Oz%J^DVdNf|zmb2D43Db8jXFTLDIEpL0CTp_Eho$($r zjQ97l|4!`4KkYm<52=Q+v0S<9ZgplSC9rmE-74NHWs^y^B0ZJhhCu2otD7bkFtc=Y zot?alEL-PWzfVjwl}iu6EC!umBfZQNox@SZN|-MFUW;mU?ZkXednjYM^uGh)j`e7w zvR*L;gZb5~8QlJT))_axsDXV>n(d27EX{#~ztziV~LAiN!frb;G%VitL}$WoUq-IcbD9bWYpgPR_&t2NvFXJ%%At2${EU$ogUW6{)3A4p z$QL*~UYvO3!rVE^yOM|9`#C7{;S9G)Y%t?DMfHf+#}Y^^EG$>DT;1I{b3XLXsq?#WI*rfPW=6kl@)Aw2h8OZ( zs58X{t)<1p}^1zx$p{&XNTL z)tBt5UOpd;#m4J*yq~d7&YtfS(g_iK!`@i*%!~2ti$J6arjIA@P z_Fv)+CDN(d{!=bSTDHB66A)jiNBr>E_Mvt4ntya?2qliVV)tMUhf zaC%=@MNx^A$Fx;O!&R6R7Ot^WBJw(f($KKo&2OpVjbJP)DPCWFUMdP@f^%BDLKZyz z1i|Ve_G(cQHUBZm4kN`SryOk)q`^ zzG_B5o4wp6Yk+Vy2irSIj+4(-nLE?wMx&5_g1Q(glUyzRVS^oqcn8_>fCPPPi31@) zK|sC(H@W0+QTk=zTi89-R~EJ=m|{3TckHh)tYdN+4MUDtz^#Yz_S$^&iqC^J+r##mI`-tPI@mD2!;FO&Bczu%|1_Oeq z%g$Pfje%pcuDS_ES;;4@#@OTsnnhV}-RT`ypU42BKaR_em5PdOSHt=&m4DE6?1~<+ zhTrT|m^cj*a%h#SWQ`_qi%m^UJdBC>9HK;@e8ckiB_8}8PIqJ?y^U@0{-G?DvfiJ4 zu#2Y(LD5g_& zBjgC@VjYUnW#-a)m>E#&9Js%=7~RvdJuP)d?cH+o{*qVAK8shnI{y_tq+x=vLKt5d z7z>1+MPW%&S_U}}(om+POl+ua`NQ71XI8!Y`nRLXe1%;#7+(QE z-KHiP{+Y>1bB42O?<8=a`BUhX_ivP;PGn_?UX&{=(@e-1j2Yp5)QA<}6u?)oywvjP ze4LV5_O{9M$muKxm0j^}&|}#YZI({4*C8|t>PP}pxZo2!Bnf(^4oHFmxkf<+c6Qyz z1Y>A;-D*cr)l_2b=H7;U6oT|i2#Sv%P`lxldJJF?jnq% zIF=9#6T__4os}7lrNSSkEh$dSA&c&1byLmW+rdg)Ie+4FHdl3`0Do>NpE_>$)Ceb} z;}4Q^8_mDroI2ew_#Dc%3b<8-(>T+sC(@G=6ym2#)mpa>bA>#Z=Kw#!&rfb2%uBsM zJ^rdU^XuvP`T6N-i*>3I2uSdtSw3(Fy{yx&JA0d?6mb`K_-c$fwPT-gz3Wo%c?$g2 zx%5@A+!SwuTkko5m0sTW^Y*_RMLzz9{eWCw{hLqAW@|fKCLdZXt@r7mbRUoJp9O0TFi=S~8uy4o?2L2pj6$hvBEnAT>#{mJd zl!!mJh{3;(Ypa_oOh@pRY^(sVzPlaoBXhRP{Gm0g;u#;4$t+T`GZQIX zenn~OAp2IKImu%%;L1N3h{fvh>xVYMx+Ua9iCi?+&3RRn*JQmllE%+?@WtcrKi?8Z z)*ENsM-d77xPH-)MF`?ky>8XU{%`ZSUzcfeZU@8CIj5TG(#To8!H;#j%{E#e8LirG zXQTfzS}}KCk5swJimyuV`&kj*Wt#fe^c`eUwWCiCnSNs0_YM_KXTOGwZjB}trCd?&A@l?m>%D53Hm6?D zZfP>K=@Pg$_G>b$czw4lnBdwbCvCRQxo5cj}^UD1j2t67M+zmVPHh2Xb;kTOk!hZkx^MzsX4|D$lLVRv4*^zj)d7s1? zMPw)EiMvp|ubmUG(xTQ=+H$m~=`aFe10Hx1p)`eL%4B~1K54@gPA5+(a=aiTe(<$V zQoB0WWc}-`sY9QE%J>^06HNQ!d?tnQPStG{a@YiS*T~lR^CzoZ;&QUTn%|M)ew1)-i37d@)CkBicqh))3+Ygz zm}5Ysb=~5!MMWGMty7h~8bT(!p1ZEh=nR+~YUc|%tG({BY-`(RJpHPuhBJR+%7VFiQYabA-wbt6q>?M|Y~dvn>v0w>1ngt3jH)lwhVv&_{?5 zRlv2Uwu?B~gCv<=QR&S$vH5Gnj>;p*laOJ98()pm`-^`oWv5 z`KR-?yHbj6M+%cz272rH8W}s@581cpU5o0pYUclActpPQki0GWMJftba$SflQdn7! znN?0I#{mYT;D`PrfOU-_gDCNNIwtfxoR$kgXwal-mY$yZDPwC6IwjX;G+5t85O?~> zb5Jh0;G0lL;bmwz<71wj3mlCO8I3~k-1@ZZLqavXoAdir(z~0H!U)*tWyLXEq;T5= zbUxv_mG@~4YQ2Eu^M>ed$9<|~Pz8H5Q2eIM=`ZQbi>2?TE|Z*`oVT>vr>AEp*3ZtP zwqK0~ZuM#m+JxjF>6@3MPmR9}1HQq*%AW7)gk5p^eMwWc-XG3o(>A5sf|-b@V?9ix z*zsw61sC4FMYjlfVDQU85d_H-In}c(4%+FwoN2cV)OK5u!+XK<^)2Ze`+x^%eN;N_ z^|YqCxkQ&&OrRV!WHuX;W!0iS&)OIoCYq?e*Dz70qCyo8%~n?SQ~)i!PVqDJlh@M^ zZDJW9D_l|^jF;ve7mox8#^UmF;O$E~Iy&LO!R}%ynmj4}Un`uX0bNqbRPpI`M2n{U zg>(u5APYjpqHIYG!txu#l}}C8@#{j9=RC?EO62A7CXOd~=whTUPxT=qsFs)o+MNUt) z!$+O=7bk_%Erk{7I`M(~HCrr|vh$}sA#`xUkbuUZ6v!#sJn3iJQ#0jGcTPUPWRN+W zwD}%h`RGJgZN8MqELcPccktzuc=Cnx%l`43`7%SoV!x@@KQi7;zYhELSi|77nBEuu zF2dr`_w+6_GA+T%1VfoABc9t-LFoy#xTG3kawvnOc_W4Odv0I8B^xU4FzUAzfDj&H zpjIxI9KYi0;jw{Zab&^h!0ve^pmzU_R!+N00QTiUJ0#)r^a?PM&2wZH-()k&7F8WP zkTl9^bH@jBa=dZfmgPG~qjxPdlXJt{GYKSr*H%tH{gdSbsSZ+HYmiF~gP*Z1f8Rf6 zN}93XT^K67>Ri617XemEGKyMxz*XYk_P!f)r<>pMq>StlrROr|N*1DOHYYnXXyV(wd%i79E+gOQ!wYhmHI`&pBJSRmKwPbIY_ zj}mg`d~w8$w%aTI#hXuV|Ee!;nqB7oZEiG<^KD8aN(Av;Rv@^A=3@n}%GVkgZ=I|F z$U)FZS|5u?bk~VKX~cS;G!6b+b=j?M%;Pv?HYxugTIE*d3@4M0ze576h<=C z9*LxS1#*JVqg~{k?~FL7^+~(LFUwbh?vZo6@^I{|fTL1d+}UtvAYtatsd9Y8KO;fW znK9?1K+gYVX0}Hc3W@O9y#3A7?0$o0lvFdyZmUtwE6_iTd~68gOjL+R6~y<1w-xCq z3G`(0t>Kw9A7XNZdHUsC@5?ODOvI=7=+%}8-lx3IDux(j#6kPu6FKpBlu(8jIGn~g zt-LEP&wclhk{Lfxz0>i>r}-g#=MhJUa4uX!(faZQ{>WX|-)(up1?p^MmljTyQ0ElY zmz;|Qezsa)K+Aw1^)45OYI(jXa9PpWgix&?W>tY4ce1sK!6kC6@l2RtMA>Sb#-VI3 zPJ};v?V|D0=jazL{=kW3@@1OqkY8)7xQTa-tSz||%swJv8+2pEpZ|VwF#lI%v`fT= zpeJ{d;+0!VzoU^3si=7ygOfDHOfeBLt>fSn!5`-S>5+?Zf-b;ZQkkqG*pM-=HUM3S zPnvX8rSp?_B16?e;o+0RRB_$b>%$Px|FNM0KG!!Wn*KTYVcbAtqfv} ziT(ThqN(iw*(x{ z=I;rpVP#|UO*5uZe#eD# zBACu8r{xytV`{&^8v&=R%Vdz?NrWH}W+|02W0G6#$;^BCGaMhU55n3_M0A5Nl2GlG z60A$kk<+_=&{w}Re4m4i6=a~*!-j@-#p?+1jun5aUO(Bn2`wFM?Y7%AK~d2<&zs6h zNV78kWk@9z@O6YShW6acc=y{3jozz4p>X{3-L)B4iAMi@Pd%Cs)^^Ej@p@@1-7b_0 zKhP8A$4?@r6L$P8z!F*3nE@kM0r#Jpdl8WtdjA2+gl5Kl7rQIr$OcWTbNNGnYMGZl z9rvU>YepZXlEtM)K|uk>hY=r=3o}NBQ2vx2)5J*1$P{Dk0YxDi+1x#2m7MDXC>x(O z^KcT-+uPeLP%dO>xZ9kbJ3sNLhE?|Y57MTPPbP=o#gi0IM5}tZr50VtbMdn-xyAUF zdmR7+=BE*olCk=LdHEuT-xOP<3I^rYsH~@?R5+yW(6@=gpg!0$-PK6J3iq!g`aj>+ ze3xB90^Aaa=NtJG*KoanSge#)*00uwY4VIT9%gn|?VXa|#^=`7(tur!scqi43)@ex zQT4B9Z?39=lv{HU{7p#JZmrX}pSQta(LBAAO`ph3r*R(6Vl?Ghr7HTfQ*5jt6Djgx z`WMm&vL8TdEaq|s=Ame42$0k$;;3cpoFrS!7h&Lw%nSg&loS6O;cx=oIhkNkCVe+L z-IDjCh${|~s9^SdEH-~(dUDde?u%60L`CS|)?hMlr0Bq4QlD^(txwn^-^!#DeYXE`UATgLaFrS6}uN>^|;7g1)q{g;n&90MuwtE{XN))?fu1T)Ht1M zdd!`V{WphZK?@rNA0EI!qxM783jFQFKxXeMZRw77W?p88$CbH{5=_%)QcN96;K26B zyUV5@&-u0>5C|p7+GpSsHI>x;Qy(jzH%-Rz>Szx-x$z9>~^ z_K=bBai-`_L>J+~8wK*EEyuOe0><$v+_H#Ue*7B3ijQ~sgl zZJ+dHINn=PloK$U0kLxZ=)i~MJ|+$T4Gp0L=4Ij_%R`5`Go=Pc>RWU5hyjI>)UZ$J z3NxYV;l}~HGsk<|$NR@o=CsPO{q*UJQ(YAiq(%S-85zENeGQSwP7W~6^gI3G6e-c-O!m@Iib_r9%ODW* zyH;9+w%f3ll97`7Zo0g%=hm8?*7BW>Y`cYeXCwjmGZ&ZA64HR}#_#rUUY#_}JOfA0^}AJ) z78k(iVM-f);!}R>ed0@zI2K&Y6>q05^IfS^n^N$+339(83KFLC1QiTruXj;!le*N`@Q{c1) zK5|IQ=^1!H`37kr6YTrKYPWS0UrSb0wGIDiYkFXA2dK9h$XlWz+V#koeh8&cn3*MXAlSr_!$cw zqSmfy4Fn`7{9H)|YOVP-Mq{NO>*t!!u z+G*FFcq#BtV652HFRZk#wA%ZvtZ*&S(waq+W+&#wEam z6!^oSJ*#>3v=v3tOKwTAP({CRx3{^8FUS@xUd6ZeusZgAEuyTp77I!U4XRRSq8Jt~ zfE3P%M@U!_4N8dKS`rREfb^FsGCbM)`z2u|rO927r+|L?8}`WZPz4NQ9WyIPBLBYW@BBsLn`WarofTvMA{|O5VJFJAxyD!(E=CoTb zAg0B5_HFYjkd35};#b+-b|ROo*MU-${c{LmMDqzQ0CO}vqA6=Is_g>4OszBgV-q_vM0T_{c+nfcXn63@96Gc??u8Q zn4Fw!Wo0$bB>Yt0KHx&q?kn;96!W+<@DiF2@xE>{cy5X?q#;?oVo5HJ>D$!4vgZ_1 zljC)p@9Wgf`bk3f`0R{?n3xf4?LyPFtRW*Kv#3zT&cVd+zRdLcRfk4?euDi}qj`me zg}J%V2dNorXM*mhgwh&Ulfv(79rg3b$SMvoG>uU^rNHnt@#>5Fsm_Bh>wnv1X^@pz z^h-mYGb*V~OJwkfs85zeps;OPc4n zt26oU_N6QY?fFa07owEoAiO%ILlWx;N7$PDqXo|fPm6d)dwoypni0G~5JT&}{Hg!d zshNIwBOvDY7kc-CV1JAajKfT^EDNq$8LJ!kBS$*kXo4g=rx8iPbl9etHTANlQ(LEF)-io~LNwL2p0CbdAB@9?H<`rQQrR(8&{(bNcYRgM~ICt#(GMW zlds*y;Y=oJo-y9&F}s&-BwN8;=q(qg3jA>q&(TE(N!VWw@nj@S`O86}w0V1+rFlaf zbJrOIuRRbf9LcKf1mn{dvjMN0UZdAv9c3n-J*sa%7nZz`1Fqx~|1octigjLWnS8?F zAX{R~c%;+--OBtD1c=_Ho0uCm%p|E2(aSUKv+Nb%COmC@jsLqQsw`t0nY$!!pPR8; zIgkFD{=P&M7v|PiGDd__M8Mog8TgJAxPWLzbAQ6g6^m~djhr_lnbREg)wzAq5*kg5 zMB1z@t#N}xMj7+z@%>WTsjxTIXY!hn!1*=p@@+!2 zSFV2KT(@No4!o3X{Dfw7#Lq>r3x<^RA+jh7oG~I3d99i>{k3$eACe$$)>3>&1dS{a zfa5PF!=FJ=)KCl}D;2kbGogyj`sLZJivvgeQ8k{pwc{bEWq!ynl`VdXrZT`fe7?gN+1RbC%Bl(Vuj&12an+mg@b>mDvfJsOE!D1;CXI^! z1aCOess}g>1Vr1fp3@1YVUME}+U6Da=BGc@untUFDT$lDUc*dd`~>`K7WMAZd`V%U z`|p}Ed`L;EH_jF zz7&T=xkp&)!(MMEf+55aSOzVm8lyX_or%6Nrwg#P#;V$l#dD*V@Ct%K=ao`{h3UUn%Y&Ez6wvSMX4vBVHCTh{4pCbO|g=B5VX;ky(Sv3xe zuAWCFQ$^brtgB)tm1MHg^q$?Ft+n~>W>Q9=e4L2Q9iAGsYm*T^Y!<-aN?sMTMuC@HG}6Xr@HTHo*fzE>(?|Rp zhqXrX>^Dp?kZTYx{LV)dGBSG9LH5o(IT~EVPdLZ7(oHQ+US5-1nnZB2sa&adWHMjv zGigSlGC9=+y>8BTyKKCdxaxV*9VMeNU)MHdqGWvJ6(7upYMA>%L`xUfJ*Vp!X)sEK|}8jsA%9~ykeI%b50IkI*B`ebDW}ZK=&V7*TNK|ht|$0 z3NVo0ho8=5#6*A&?1*Y3zzd6@HHY|4B%tP4F#K0a3=c(aBvdNpn-(wwsocz}vP=|Y zNf>!HQ5Y7r?^W+Nl$8Bu~Cvn9dM@?whgL}CGL1jVT3L2!zgNf-!FAAH|Fh_~+^xbF=tjHTY#%1di$VX1VKJ>B`d zq;IGPWxS1F4RpAGgFu`<=3UG|7~kPvK7OB-ewdu@T;2%LNG%V80dfUJB<#DzG$yJT zG5#DWxiE7tFIKcfNnSEVC{n4(54wvXz-rOMQ#eO&o=uWo9Xk+H?AD z5RuJFS6d^6I~d+)%ZMQN4-uoZO2eY=?p)h0~VtdvMp1b$^%R4>FL(qTh50m)MVOG?ZRMx(=A z++0ZqhNxJu@B39rlwNxWJ5t3MwaxJpV6^@P5(O< z`y<4_9-8h@iH3Q#^kMzq9qm$LBAn8N1p=h+mu1!Ch9Y z2U!ypkAIPJUVK8vqR~6W45joGehVvx7ZwGqE1{aM?>yo_$PRQ!QeY#-)*%IV^6(K|;!S{u0 zU(6_7Y5o2*kuAYCV}J?47_8PZwNXG!M1%+v_`_c?L7~v%y~bcc3^tzKR%XYK5I0s< zes$pHWOah}XR5MLpV{o12G>u@o1%2^>oJ`jI&a9|tP*bMHcy3Y>e;hCxeV1ZAh!nH z4_*9NfvhIhcM<+ANs3mhMOQj2t*8Ufel^e|mLX3?MiEaWmTpTcku~8!5siz7hYa&M zu;W}Q#Mvr_S1ufhwgBn0w#Uf0*lth}t`Xt!<+YmJe5Pqnw21nWJvFcvRuOR-zPYVH zD8YhVfD#s>;%%z)GY;aHG(K2KxT~PC$MKt*Z?RjVi|A$+1@;qX<2XdGb7@5ZA|fIs zgQX1EO}1WINWnx{n`gFh4qT=$%dxZ#es8amfm-gt|AJ~DD>MzwmqOG)w2IsIMgDVT z1`g6Z61ZW#R8&TT!!*c=&edVONdN z!Qd~hEkB^e`nkCiOQ+85_8EsMRZs_WX=%xrBplfb26dKLg+%3>Q$l-Btv_wS-*i&A zPwIpM~?@ zEdCEIq2~-rknmKr%gWwSi^qk^K>=yVE?j~G555pu51F#xsPM;wKj+j&ht@Q@q~uhy z#6@L|RavuEwJb{(wTsXlabCaGZzpEegvKCHt*N&js(2~BC;%UT;|`xA6Q%xB0HVsP z8B>E=LStBSVFxsl^|3nu{oqedse?oaA`~-BbIs$fxt1N?RY{$ex$A}$2UrLC>FG(8 zHu2G&;TTgR>{<9;7|UJb)WY6gJpwzq_`>(*+d<_w;eL(rB`zb&uXnOPIgeSZ{;tKy z(l+eiuRa|4OMgJspl4dS3HoMSE&Ty+81s@OjyBOaBSBN^eg}Nx03=t4IpEB37fngh zY{^VTpnRVES+Ag6h4+JFO=1R5g;MyKmj@=bLPLJ(gn{Acq}sc%K%+7%T}-07$bhPt z^cb^S|Cdts_R+bg8xFU4kx}}{Jm53_CcSA`X)^Nw1z!#shmiIuQ2a9=MZKbLhCK$?c-Z$5gQju!+4OnevMj4oOpJnmP4tAVumU- z9s$?tmeWFJVSr`mU0lO$BTxeP3tJiAPl>_j3Q=~*UR2SR985^V+2=Z92T0? zv9$NWZ{-(EYoT&sT{_VE5CV6;$KNr-VF|^vKl*o(Z5IT%y1Fu|GZ>726Ur&pRLM%N zlieL1j;M*6KRvapizoAskB?vY;+(atiU#fYQ}fLFS5?=nGX2$~FJS%7w#;gDa* z%$q&_S4@yYCbG9aD$DWLlM*@t>xL~iu1c{yRz-F7J*P$xRG=d=*0gwGz(@pFb?@5M zH5ebq>J$-L2rz++E6W6?-gGv80DUkhu$JVni5z~Lm6BSVMelx=LY_wZ8Qu9x=A4L7 z)!06>hA#Ix+IPK^M6~TP_$vd5R3zBSmZzko#Do@ZeY59B4F_0LQELXMQb)Xp88J!4 zi)_CFS*(~MCX``%Bb%u-1fd}#=9Hc!+fWqdACwyq=2`#ThB2Ku{=6lNPHtnJ*6Kt}bWER2pTM($dny%1LqZ$+WoXqaMP3 zFXOm4oz^HQAxt!ExSdAkt@g7ehw~e@ALBh#wb|Ngmp9Co8GeWXvBrr@r&L@|kvDl*lXpyhYATjNTpaS=v|JCzZ4|KTd@!ti?2ZPX6Uv z`exmh{(N%`IpvVQGuqa2U@!6c3H9ypd)?K5{s^;!_#XGITR)rHk2a_;+PB%4!&B*r zAu4Yw<`&JB1Yd)EQ=WHJ@}m$R1VkTZSrrTPzw;>NnBWCyh+@mXaf^BUelQTfox&gm zIgmHf(#N=!{na$R47^|eeExgM(Hq1St|B!gu?_N135U?fY*D%_e4PqR6Hd;x$YmRV ze5E?)@;iK(g16kvJxxFoWQCKc8Vg&QWvugYoSCkbJTtfT4|A7b!w++9Yj#XDt`F>) zB5Xl1%x~9=vaN=kH_w95*C}jkd(*n(;M{lPDsYlcYn7gnHOyh_L>KbBjpruaZKYrm zbRM89G{cyRewX!8oXEM;iv#+yl_dv_?7lDl-H)CC~J`ZXX+51DEg{LudJ<>E7M z1QJv--b4l@6w0kFPKJdExfe^A-q{(Z+Q!5&Q6^)V7pf{b)ADK8*Zz_3*CM zVF(eWc#GT*bG&U0+8}~wWajOM!8w45ss8X6iqEt_vocY=sQ&1NkiNn;M0}F&iqbf~ zy2==mwRYBbOgJ=+9y)!k=o{Q|P0s|xzF~;#(?i>!cCm_1Hcoufp5>L0mtK7pQHS@WH+{Z7DGvsij? zXn&Y{zidK4m7VO-aTFaXo(0Ij>Qd4kwcMyTs|!HG@8$Xtf?^cx9221~&BGz* zT>rIX^;3)+Fuwz}0Sh)TXum~!`}#gpQ6**}xg(|U%34>tp#=sg7HI35bEaVY?%v+c zp^%E|N4_(t)F>)0K5=X6Fqm&}H0CBmfeBoDIdy-4Aj~DS%8%GB4*1ht6B%^_!fO6& zG`cc32n}GM8ncPAc`5d-4^a}t3l)YUVq#$Wp$UuY=|W|}$BBq=5<%jKK7Qgc9D&yh zZELG@96!hQy(JnrkWFpv+QG5SOQ4`fm$~3m6UOH<{@cX)MJsmvw}XsV8eF8)#oD7z zFygSBoA{>^iNSn-Na8Vhp;B^BJ~KU?II^3bo__ZI%v&Oy@V9t2NK|pT%5;c4f=@|Z-Mm)o#;b)w3KoSBO-wQQ z_jS>_Q=%0Dp0l!0kP@OqeZ;@J96w_0*-^UCXy?;qp1c4Kj{hKZdLb9ymBX20!Pkoj zE>2E?x92N39JsK)Z#dldUd@GWKp_=;V)$m)CZDfutZ}umh+3{yc{pB1-D+EbEej71udAygdD)j(d*0f? zo3cJ)@8fbRs`-v!UB-L!8$QJS8$tKRQ<&yp6dnojZ_3pteS)tQ1KqcIszQ|3vn8JA z9k6}Il^AcAOewzC*)W>ED&=pzb+(&pFDoL*sA>e3gpBmkL?J%=JT8#C}=uM_w zyU28JraJ@u1LJgLT@8k{6_1q7*BV#G4X~Z^nXT`a?@W>E$jHd|@86GROW#eJmz(?k z#NMx|wUxMidV2c){vH_oMSaVO?aIo^V$g4#byQbmM^ovMqBO`wt^Ut&9FrzB2S-Q7 zBMk}LCS-wX8Kl2TDk+hqa;n%TED{tZqzN=Js~)p^~3qIWM5cU z#~q&?1*eP2UsP;|!0qtt*1CJDcK%ahzci?w|F9 zow))Ru(jz|GsG;Zd3>Zly5Upr(FCr`@741HK%=F+?t?zk_A}~sWdMN1=(q1QPY_S` zh9*eZ8Tns9l98Ou>wcQLV&~4A20CqhIt9=%^NjCxSy=)6QtIk+h06J(sXSAYlS=yf zaup=QE`0nnm}n$voh(ufoD56g|tHpX^C%CQ350Oa>z#E!3CuE)>K?Xfe6wR0aw zr~cuG|A?8l$fpi*aU_@>h%cX_W)Cd8x9UYdt--!_9N4fWS%E-A0{RIa*}R`h5m>{P zPaWU_94T&R}rFZMF zfI3g@s=WQ0191=gk*SRyghpC{?_cCsJh_&~)eoaW8Z@t&8b*3a)qL>c@rF=R(Qfqf zLVme0P+n7mHDrPespli?`q84bB63!(2AKrO+vtbcy ztQ;IRoNdQ0=|JTax;aM_jx0bzVOigG@lhz!Tu*qOeE+R{b<*DQyT0{0-4EnlWWSex zZMU6Yesu_3hZ#_WSRiWIRM3nf3PB|yu$I|0vVset(6jAHPCUI82p##av*{%A^Ygl* z9Om&kagjiy8G?SV&kvQAl>`d0D7gq)5!#587#d=Rzj5=A< z20y3;*ZB0u>Pujf1b2N5?IA?zJE>ngbsPI<$16wW%>Bn$zdrk%VLu3?lCWnby6UT_zk)Gu+@i~G{AVgTA9I$wqYf`LSW z5&Z-iunre|l%?20zxELU{KLB4fZ~$3-LBS7nj&1gbR=s(E(ay!tP54({`!xtYom@= z%c>107YB#!OG?z8@9h{ks`h>|!Hf5`7Qf@Jg$2TZ>DFyHp8UH8s>~!G3wbU@z%Qf+ znO&xrzmKp3nW|j3i*t+FendOYz5oGeS{k4P4Nm)zQ9o3lPDUrq;Bwr`0>QHfFHFf7 z=mH#iptw*!V>G8`|91~ZQ$H+|vUBSzgO@VG$-%MX!aG;0ZC<@nApwA&I;!AG7M-Tu z!ZLB{pQ1)r^SC~2m)}&uNuEOG6rMyVqS=uLjEz@42!BI?SaAO+$jwyQByMbk$NrtxrBl<~b1uic8`(kAAYDG_YSq*fM4^b<_T-~zENuF_S z-~2rTj{O4J3G*yow(G}f?FiP+fEOuTOLSBEZ&|ldv;E3H4vV5ABrAHQ2A2 z^?siGe_8;6oB7W1X%}*D4?HF1E~;ZZ(hp@0CD?X#RV;mkYu^c&f=@%KLIT-waoYa75UoPel;>?+J~-%D zCp~RKrBkB-f6EW-3%qsv^JjgTr+W*O<^NG5)9cu#%y!|j8V^gwu{JYPJU&X26dTgP zrY~H-re=A0a?-%=SKpT3`8CNe7M9m!54rEi(K3et2ZU$kZeAmngd&?@(d~}@F9Bz8 zK3^Q{_w_&+^|C4&bc<&;Tt_2#j|Y+N1+3a9f#h+V~k4NsB%n$Og=Slk)nv zfYq2J0;Eb83)U>qI5ix?Rh0f7^T z)8>Au+I)q9p|j4`<96YoLujb99>_>qpD%|9IBnp-!XkqBPTYh}`8L|d*7urSwJBv} zl91VTPf^^?yTe?q7hw`4->YjPct*@`!H#OxB41B>SP}F|vxNF|K&XrkvoUIQh zE_zZ>;? z{Wt3t`X$@CGvB)=AWFY%;N>zgkW5>#|APT3M53 zA7jiG?py4Oa>PdEZP*C|fp%|jFP&Umc;XgU+r!9e3qZ1ZYYr+zGjI*gFEo?NnD3Mh zm-dxHdc(jlJ8Y4GgX*sYG`z>J`aGGoiy@AhVAg@00o>AK{zF79hXod11-_bLz`>Azm4xvy&K>Jp&@ zGwJ@j2I>>Q*u~4|su8MD)zy4&J_~ww%@lK%&qYh#Ps$;lVsfuYMd2M`QTju8vZN9#hMdUme-+Z8)2E2EW(aAJOZ zI4BT1JG-o`Z1Z_1BF@pF-9NWdLEPuX>alcQSA=%;w#ONOD36MY8W3dph~0rpQ)jxnS zDI;!q`LJKrV&*0%FM)apyIpRhf}9u?7imv9q9f+g|_%QO+v_yHbY5}GZ=lvJX>z67sqVdcdKrviQxq#WkMD< zHY#Pkqf0^OAH!xDURQj}{zGP6^I{A02Ts_~U`5s3_0c#cgXTUa-zBC@4A)eAy8;ik zTFc4F6?(<1y)`_@@cVuwlaNFc{c-R|)J?a!zwXYXMdUXW>d$b9Hb`H6MZ;Px^IT2Z z&Z0#Kg_l1=&kr-jtCf{M4iAG54`X5bt4h4gQ2c&#_P9oT5kv`1C^{znJcC1^)z$*xLk6h|Li!|5Ub=Y>8*A{CfpdYha-!6mboX;^PenIE3m__U z2`4}z6Pjn|MbNyJRnTX~B^@%Zdd^x{Hm#M16JB(|4ehD2v_bNhh|frs!jl6Zq|y&z z$5>A77dU%87SpMn3-JU(vEIx4OdZ`~t9=8!9DoU6VPRolV5q99f{KcY=7RwJm&<Id{5(a)65{FS&6_F9_~?K<<(F{=CETIug%9S*4uuXylZ`GTOl(owv@L zp^Qd)ZFO=o})siNMT@ojqpAR&neVxo){*Mc0< z|8~UifSCXiA|AzS(&jZdj!t3e#PUW#O3yPNG(VhG7pM}=F%+b#PmOG}cpx(D_5%cv zleJ@UMFIF0++v)W+~)ZO$)qZo*WkjqSId0C+6_%MY3bz;MWlduD9fOLRhSDV5I_K7 zNK+XQgJO*RW220Tz|kd|JcUt8If#))b=Y}vsf52>#Fh3id7RP2;_G6hCO@TpG@T=W zNs%)N^lV9({%Yap=T|5PVFnh?1`eV>YyeQ^_o)X9*Le`OI1f5a8o$=(qq*fc_NrFR)Ain4Ohn zdTlsc^w!>uL?ik6m8wk;hk?(Ixnj#Xs(uRw5~EH>CB`v= zzWVc<)<2nyDwFr2Dv&qL0^Ho(8j6aU zb4Lu=GDRHQTKo2wIHHI=vY2!kCBrh9kZBN9_A^XsY%j`MU#WfoDE1QQY*IES99c0r$K}IgGq?aVzK+gq`b5T09dnt$GvT>@+#6OGJ{f*rDta7{?Rm zO1@;-tI)w_+?mhqM@MYmy>gLw-j$`K5;%zncb<*+!o*j@J%^6Ui8BJM^K1l2Fske~ z@!EF4ir~*Vn&wO!RZh>%Ia_Nym{5k&VK3w4bsFUl(^PpOonorS_zl0!ym;#F#Ka{L zrnCN|^EO%f$*_&IKxI?3Z{h9zlqZ*>LCS>lqRvuz=!vQn8$Dl|o~&sFe+>S#^08fa=X=yyyJ-lrvrn($Ta zCUJa56HZq^ef5}A4tE;1gdTL(^wgG&(aJB+YtDhqB zfF!1!=O_a`4m&6{GdNtJJ4TZI&);Z79LAd3+RSBHviH+tg)RAkXZVl|mSOu;Zs}x4 zRU*pELC@{mZ&ul&xg#Kn>a;Xm6mD-8{;R2Ix$(X7sbsDc1SC*JhES^KJkzYK;P-gG zY>-JA>9}mLu2sOG+lOTeUWAxzmL*G}GBLebMv<45-KP8b&18IfcGgMXB8f&mqYYb} zm;A?Q`@BRi0{VxMklZ1szQ-?&W&hyXPpd*9z2}eku5Ao!Mh#X>A=!_`6?(bxt@8-4#m=?uS_bjx?{x=vv(?wzKNR z|9zZ~CO!Q2c^=zhltQkFRZ1t}5%qmkrM5l4x^5WXlnHBQDr-r3xqG_1yl$crgLjVa zuuagvpb(4?a^T{>K(u>1eux?&KW5*}1OLwoj2@icrZM$tHtEmpv4`k-qQ9cd37-gi z6O*pwEVwh=?eCLUYMf<92(-8{?8Z{Xz~^GCsjBYef}=+J<80MIB?Qe|WoNd%S5e?P z|5QNeRwXTzPBfU$!}6Jdo=I8qJzd9HFwh`EV1Xw@gVJ`SjEu>~z62GD6LQ?eCV87I z{PS{!I3YE6aA3wos+zo9uKk9l)An|U0h&c#ow%*M`C*LFu_jxDs)g&Z#crxj)aBT9 z9vt+*;ym8@KO?F1!J9qOuhDpfz>LqE;63<9JO9h~weKJp1anxP zt*x!W5br(Dy~C7)ULClTZY> z3dLbN!L#Gbfe0%@R>Sx~MS2e65tJgch#^4;AJ!)(fVfn_Hl~g^)Pwn-Vw9FINrX*F z&m~HV-kBYo!f87RfvVq7aX5?@)`c5DszDzg6a=G)Nl7zuiDHRILbAs)`S|FSi#Hr(JJ1qb3By286qU$DYGOoMPo-Ar+FS zwKH`Dvcc~EO;U>)Ph=Oy=Gk91oynRA`lzt3uKesa=5v%2Zc{_kiXD~jpcwWQmM{p| zDK^g>Y(<;#GcMJ+IV2CJa5(jyIiXxI#%ks3t={l;v)U;w>EcI4NHt%zNCw+afIztpB1X{3yl6e2S$jP)gO?d^QIDE zG%N%ML4j@-Yz$t}vt&&ID!uHsKjxF2ulm;&7AF08MGuPsI;jr<%9^T?9bopEyBDs~N@$vSb=h|a@SAA+n3n}(x zWkp`Kt$HGF+@65s4eZ#IV#C=tJsk_gnxzwbEo!N`{5(6%a|ThDSoM*;f&h>eQLXxE z;|G6FAy5jcJ@GjTXn$qCc(SubSmQA-5@;Lwr6g+kG-;LT=C49-8q^~uAtB+)n?@SK z+u}QI#A91a8!;eyDohQ>7?H1;gqS@o9N6J+ek09*>3iJl^FVJVL5@g3q&xK^2y>uv@cw)zLeKOSwSBiMrMOKUx!q?XRSl61-tc!y zrxFbr(5ND5noml2?g4VS_i1|JnpN2Ih82xEQ9b!k(Pv}kT^|vS5U}pn#7`Wtkb2Ds zKp4>LY?MUWGW48R4FN3d)1Rg0R0DCC^h^l!%5lD~V5E-(lYks9TN7TIV(iCj$9g!0 zk7DE`_E43DKzpNUDJ`&|SpYdO8^Mq0+q&>5L2&lD$yP_T7bxLAhXF*Ez{Z#@B@nl= zTkG>a`wD{MbCj(j$$`U_GhxTu1(}1tp=?flO(~R^oQzLQyxQPM?w^^N2@uZ)D&_VW z=`d(4_)lh{ih;{SWX4ujd^0#f!eseV@PDhSl%jJ&)(~E?$X}@hnI@F6&#@?Y2SX`= zD4Fc$C?pk4A;pRx#+w$d5bK1c!_`n`R%IrN>xfH8=hql5ShQJ>HFGlqx%%Uyp{Q?K z^JM}Z8;>ycB4Vt8OYDD^BO!wLpkuJujH^lnJ%+;%Xs92q_QJ%CsWGkC@J}upi2F^G znf1v;c^UqQei|I;97>(J0)6+lMHY}(G->*9`hFLkFSGwmn}?? z8o*FajBUdcv)zr)elceahAUcT-q2W6kr9%RnDg&RGxJKn3%UkDrkE;N*fNO{z~g28R+g4G{o&dH zMeEsZ${j_InTvNaSKJq8NepO*TQ+lrRd;lMZqnJddSd^rq@2inaiOF10%Mj*b$mUZ zCqZ*n@3@MB5>hyz{yqF2itwIh4nl^(*x-Mki=|<+Vey*DlEDt$=}^~q)ob(RLHDG= z4(;0-JpUWQ!z~;{p<7;3qDB?fYs3Ooj{v zA0U4I{5d%2@dq=Y^1|jUxCTG>OYW7p$9_3EIkCxZYxBEJ{{!^k(5Oa6JiYj)cd|VP zZA>c!JprnCWLMLgIX=_899gpeR^s<(bL_w0I1Hw!=}el!Z5EtXte^ori;4QqtcW`` zIoZhUmmKAy4d-yzN7l`Y22zzPk_e(FvAwB{WQ(n1;liY0qclYrcwYlEzSZSn&e&Fm zh=pMUhUVy;WKom6b6M3mMiTpOL*?H`reaJ!z$t%Ujgu;2+bK`1Uk<)?ZBJo{Me`okid~|{SsFY45cG&4BOt>%5$olrKrJ)LNj@^|Zrc@v%)5Tt(a|KIE?e5Pw-Z!&6^i(C(8)2T#%hLEz}bx3 zZoQScJfO2CDa+1%YA~*N`7|#XKY~=H+K)43Ym;kCSI-q5aLuUG{2LHx2y*$H-5c8) z>lO!91+?UG-V0BvqkkCx_nGP*keoZsf2%el9|Yt1Xdu%&08T2G1AI&t3U=C+O_DFX z2DdbMIVaH!$I{@#-IuC8l|(&#ZfiSRDrZmi7lwv_3RE8KQlUm91iI{Q?QhAXRN|rr zb(izwfBi4o{*hYx!>;Vl?z1U+NSZyj0a{O!5Z~vMO5uPMV@GeaB#S67axwu7#PmXZ z{dJ(M?O9++t>`a8o-+WDz1h8en?rl*bCc35bXT`OD_fm7$u7K52nxbx-C+7i%`S~5 z>KU`>FE``P;PrHZ9hwWAAQKY`WhEe~G+y8;Yzh%)#+4;t-lm}i0jY;&H-%^TpCU_8 zAdWq?s>8}UQ7zN7#GGg^F<$z=zO}be#Jx4A$4hfYR6h%kdyy^xF9PnW9L7>-MNp)aRXNROYMXLa@J_(8U-LDJR_*Zv5562;hR(H{c#iq)9cjGbtyHDC^ zw5o>yIK*jKEjO=5s7-baPv_U5blXp6E=h={PN?01eLUhK-TxPyMO|e%L8o3u{|_zC zo?H|SN>T3^^Cu%fGb;s;)h}%=(7;7-ah)BW@YexEPNX^h;IVU~n^d%VH1kwuEE{Qv zo|F{|RD}nn9S}p8fS{K`Bb#zQu)i|1^v6s<7nXDq&(e)Oq8yjR7XQU_WNd+S2wHVh zB>AQY_Xy_9fFQPabaRs!Z=-B{fPq_^e&sd~MCrUC7)B--#f znD0QA(eH|plhY50*lwI$XDli8bV>$^WydTj?hqiirBcC^LDJnMpqt`7IUI9$MYB zEUCA-Ye|0^QQb*O zgqmM@ug^s1D@_I&CW5S-DXL0QRxN0@dyYfbzOi3agK@xD`tI&*)0rC=M`KEIY+RHA-(&YZ!&dJ2|MHq#m^op65y+v~ zLVgc41h6qUsIccIR9kJ#5OMxfZeHZfcBPciDvtK0^o#znL{N|wEtbh42dk6mtPq<8 zoQaml4`W8=h+hl3fGMqVTSWb5TkxIO+566oAlb*4A{h20*^R7(88(2((a^_@)83@} zP&9Z52>$u5e~1iz6xYHMHCxJGQKrK372siI&z_QIAhgBTy{`QaPSQv|#)J|OnkR%S zcr0^NF7WAhw63xtwI!%C>I_UR+NWkS%wCdUS&Aeo;lCdy5$y8oJ_helF&Jc<1AD>i5H!s;kp6etO4B=;eS8>U*e6rSn9@ZMJ~H9>j`A z^I&_@)m|pEpO00fXZLP<2^M$~g%QCf?^_&em&{5M4U|L0?K;qNqFQ%7TofQ_$v+6I zO0K!F2T5AtsZ?o>E&T-$D@XXgWvk{FclV?xQ@)>4%TC5}-?j{nU4iwBn%cT5-6k*Z zC?3-w^`H`jx+GxfUq(V_sPI2zfR9-VLE5*+Jp-#Baw1(ne8RnR}b_t1Zp zjD|AEC$0D-tfx7_!5+(L8dRpOjm=?c~R;*tJ(bL5RC5ctjP-sGyw!p+u z=09_!wqKrrGC9Uz5G-Sjz`qHL;xQN*c77KeC=U z2*gCHC}whs1G~T^z|8O8}{FUY{gZNtl#QpE~izRV>zM9cnR9V z7i&u~#ZpL#H?9*u8OYu$itxuFFPDN|64FpWBR~92#zR>=yA7c>LB|^nYkwgPq7;c@ zxS+G@p^SCzR>{DAN~+B+sBz|A3U}W3b+pz&9lF_d*j2GfJm!N1fKBBd&Am4RsYc%Y z)LvG4M|emF31o!R(>2*?vH}?(sI5K|C;g({p)HsTOT0#v6U`I8x2?s9R1fMJ9|AQ; z*Dw+n%l3N@n|+1lCTS%Lw=@%+`jms|N;ftX5puL4$QOI@kRNbTyul-!b-_zr|kBNJ> zZX%31FqVg9spm1EA^|qGj(S+R;8u0?);Aw#f6MB%R_wI7+MWI0rY;aZaJaRD$b< zPpfNnt_L^S{z56e&MejW_R>x9-j1y-Um*+g0z;g3*WD-X-=!iB{)MX@K709#Qd{Jn zXeX}{iZFsfNsdo-gLjhNL}~ANlF|JvtElR)p2<({tX-pji+{><3VX!?@sn+Hm+<<~ zQKxoO=<_G{RRDC+8^baA=+#N_OrZPB7e!*6H!VrD>koBZ>%RHU#w5^6<()|N=x>gc zarNpQ420|~F&gFAUumv?&h~7=6tlRzFOj%#dLiY2%5E} zD)qv7^QynZPLYXBXrl*}3ksy9$G)bBkloRLxP-oise|amB`6n=Oz^3;b-g2|GapeO zuhVQb`~oyIP}I0HXkV8$j{KbJrOAYPDZ^4aPOGF6oiI@=$_%dNdnUh^{fb2*X>(hg z9=YE!CDM9FM@OezCu4p z7>6s4g<9cWC7PZ-ZCHK#EzZcpfD@0Wv!K1by}8*Cv_~Hu9d&mr(Ek}N&ij51p6jF| zf8*_So|>}RqU&Wf=Y{V|OS_A%sn7oQ^1gi=QRE6~tgEot5Avm^=)K8Qrp&%fWtG9y z^Qw0+N+~T~nkWh#M-~Pu2GZE7oEO?a&>RG;jzP`e0wXBwIB8coyvarJ0rff`52OPh z1-K-;vEG9UPcJOw(}=-}ii+4q9c8#sH*r>m?)g1Dif6-Shy!iE(h7T#V`ueRF;7=j zCqrPO?y{E-@#VER3rdtvh=eb_&@o)P1^3;TlN*Q2R{FujFuC>)Dv{pt;gwkj_~qzh zrmfWXs_C0472jh)&tBvGSHqPqdX|VDy?@%V?<9Ef51Ov0A~!P5d*%L>jZKooA7|cf zucd8G{2HJ+QcKY}?Q+f*Sv@SMIi@ZKOpy$t4@A|=sYbaKb}~KX#@BD?Cky`60^23S(}POf@hWlPjb~|Ix=ideB6g0`4pcUR(V@4 zh%F;h#rJw#kl@|Z+_{eku2ZQ3wt}axhyHkR8c8#6fm-i`DkM@t-`Q;5qPqf=;mjz` z`PC2_!t43R2;JPEjF|D7j<_c?Pe2*W^upP!Ud~Mu(7kx_ZDJzb%L-4m>&HPjHT7QR zp{D@F94^F$N5J;E$tm7oMCyp#Q`WyI5yZg@V;nQvj9W@Vf(@Mf+V@_}(#0GP$Ei?x zXuE!5&N90g`z5V~UrNNxT-z6@!=LXyuM!vealGx#f)2V$x;|Iqz`ylMHaHu1*S z8~x84v}$r7*j8eq`;GNS5=!0456&*awPmjKF7lwr;Zp|*?iZ?9#dxK;m`yX)SrXaW zxLy^-3^A}pi2{#>_6TcFVhVA-T`c~iGK`QN?@I`KndYo=TXo&jOJB4jQ0EVQ>* zaS>c8Udr2=RF7y>s>NnRIZ}wFy5fpL^%9gcjRzcphPekkd*>sm?nX*ascmjV-g>l| z>w4m;IWhs0FSUp!E!=_4Hzj^-19&QB!TyS32Q{6OPv~16BpQYo*Q;qDEzA6m`KgVi z=>2@4Za-t`uBJ2@>^go~q?-1G$0m8S0m^+&CRpqQ>I%e)1x z5_^F`7*Fll65?XXE}hlHeJzgK18kX~?5(e_1PWEh`+&)Y%T&<$L0t;|QQ(mB`=&zt zsZ!T7=}KCGjq8N9(0lnbS}`oImG*A7i_6`2ACYw=UzUm(kDLTqEq6&qjx;4RWRMIN zx~rgNk@C5=M;#M|eLgq!ug$o@6?+psjV_a$x?exZ-w)3X=`J_|d-t6hetF(}0X^%qlEjEpcC1oufYIG!i-iLc!fsVhup2%m@EMw22TJD>uin|4@CYlb)DU_O7A&KayZd`^){D=C`MhYcr4<R3GwBsAF46cydqZzfPn>eapF2)%MWArA6$pqV6$wX=&&(=bzuR3kCDH2X_y z&-Uat1T1a2Amn+XowU1V;OdT->4XRi>|zL|q~@$aAGk+K|0ioNPXVWdwU{&h3O#MB4?e*&4-@kJS z-^6K>__$Lai#GaYXRk9_pt-GfUc7Qq9?8-LSi+ zm&GH8X9v7Sq2gN%@kV4Rhf#5Kg@v&ix_Z6h-o9S)-_Zei-r z`;o!=S^=3_bVIiOc~z1Ty13W#fbMDxfpS~1ijEddZ4@V$ovFa)3D3A3A9fjX;>&Eg;ITB@xyn-Zy5@Xr0E zL~ZYC;T2*Yh=fiXMQARQrT&n;Lk^8G%-Qe5wp4;B#Zv?BwEE!6jAacqJxlC%Fs0$p z=mNn*Gd_PA6-+`}U zv0K2>t~qk+)a6Y~4_UF~Ccdk92O8N`sbuQ#;c-Zn*cxu3m_loVB9)CN);(X>xQhTT1u5s&e^n3!jxg0Ju)g+X&yrI zE6X@4geivm={vha+Y%N8o9^mtXR6)BLOh8rC514=(B+B{HU3=$%8>jhB#fJx!~JYu zU+PUpDSG1rL+Fd ztSaJL8rc<%aK_NtXm-mhM}9j6ZEwX4Fhy`|hiVd_m!+j3m(J1IfJKcSaKhJF^`br= z-(PE&3-h_q9@iCboXghPbW|Ca)-@wsnSx#hhuVkoku2SF?obHx}* z{|&#(>rbXh-Ccd40zzIMV!j4>{A~4d(J$|^JS(`R-HYmfypY{_KPmca2M)oHw1weo zi9VV7W@@+mPy9-SEpC}KE}~t!-x~91g+Uc$q>-_X(l(E5#?qI3XmE@qP>jBe~n6 z>DY=_oE9p#+%#Xn)j^op*LXKszk;@#;2NYN$?*{i=3WOao~t0iWrlnXpKJ28={u9B z90>TSlbuEdruoVBu*j%w&l;KRc z!S!yd=*`d#SW5$4SZXL3modh(!t~JN*V^8JQpL9z1?2DshUBpHFwS_R7B4bLadwdz+M)C%3vj4h8imF3AKF#^YDq`#vYHS>;G@ zAV$}y{X~e{$-@P}Ce~}bzLiohQ( zEr0M{zs38a*l36m>^6i0-C;j^^InjaqX8lI)DJ!0J?X=Y7TaO6JR=K70_*KWmD>tP z!2==7#CS5xx`xUjKG4HqKQm8e?Bd45p9?Gm4aKPixm1&fg|Cf%n66VH0Td>E&@?|X z*R!CVJ&rwAh>1k0w{TR?7&7+bUO1gDA>jsg^j7u&Num_hSD9ygjawC20gGW614t16oOd2M8_!N-9XMs!K&3qG+htA~QsZ|N!?JMTOk3MD! zVOei;tMm1fGSSwAiS5AizTst-80Yr0_S#A&9_6-YI#xAAT;Lcyy*_EEI0@8t(>kVO z_xWc=y5S(5F=IPIX`p3<2)m)EUpy-N%gYgh4mZK+RH1owV-EA5z-m8EpW>wvEMVZCjkMlYbDw?s1mkw8l%ND{4;LN;VP`5As~(rWwZW?Ej4W6rOJ0RhPSBG!lj7 z*qTqD^c_*v=CH>(*RgNckk&$Gco#e2N0aVKB1H8c^7vv|@IdME|HyDJ#eAUU)78e< zV|la+lUDoRh+u6&I+K^`Orq(Chghomk)`7Z0h}o`OFds;I5xh?Ji$XT>W&vA{{4<%FcD~ zBdO2OtA%JD*jc`TUyK(Fmo~0#6jbE6Yfb-%k779gb&b^XvY|QWL{}Ot`-iN6j<>eD zcVJ6u==j_HJR>peHu+9p_^0o*pB@#QC_YFt=|%k=OZxhqEaTDY8DK;c?6OL~?6=sD ziZsi4Rj^zQG5Du(s@ zz^<3lU6sCMsWIFDDyJ3JXoVV*vBj$avKypH#cS!x0uQfbpk zuwTJZH5OBE&}uETa{q8=_0Ro^>+Ay%h!NXMfm$~;Qn2>VC4>*sG*?}Vzw3(I)HryY zV2Q{2a5_+3LZaB4+E=kTXhtN^O3QGS?S$psaB2L&O{}`OI-y|wp-H|Nc*m6r%;?jn z?a!$jjOF;r8V6<`{CbRU8sPc6cVSE5<^Uex1eY6Wa4#aG1f<N4Ptf(uNhP!yAh-gIR9q*!vAIW|Cc6sG>YA~@!9f-!K_#s${}Y@ z04&eO!-7?*AQU<8yZLZ4Hmno-v@bOlR!V#WXk zb8@nG{~SP)Oo2u=>lqLsjUWk$5?jT`$4A;B?Xs-&o98HGGmw4aFGf9}3{s%LYyq>q zkS7(y5V3f?5Ci~EO7rh1V}*lSeQRs$r%xxz`RA6PQ_#VI8#Wr)UTHTyKhI#nld#09 zq)@01Dy>4Kwa2V$Gg+faLIlQbg$p7yA70%Dx$izbO+}! z4NGf9!%xmsCJw!t9}2fhWxlMRkxN0YV=#eK5prLtl3!Ts>locjq!SygQ3<5QeO0k( zmvuMMF}qM~BXaRKTGhwp&xj(Uy!ye-22}mg zKIjA8c@g+s3Yw!p${AB(-ze%g%pmn%NAu2JksVj3a~c7U5NuQ!#wz8Mzw6#-rLsSNQOJ@R()?RHk zCHGkhW~St)kk9ih&t{4x#BSB`Y=Ux0+U#um0b06*pv$wKgm*J4Q&Ur4RD}t>`~UDk zq+wJMt`?hkiFfg$-`N|MrxA3+$u=TPphA8a@)*^T8c?JMgst5V}oJ?Se4b#A(m^wn);q4*N;ueE7Wj4ck znaK6J=?Xg)AE$418Ja*pWCca1YJL()Z`6f6DWRvEdkCTSiXQ)E13 zwJ*r!;c?-ZMV;amJ-pF6)nbdR-+z1H^FU^*nIiHUr|A_exq1E&M{^M1Xi#y+C7AEJ zaq5NHX09S!>4duP9Gm(i+*2SeLD8v&-H@H&fc%)S6@Ko%L-iZ;TI#NP77{wp$)u*$ z#YJwP`b;v@#fDSXiJz+1_!DT)_22&uW2rInzT1P@|GeMw#mr@^p8IY9%?RaK_kcd8 zKG+%SGl&$S>k|jR6qjjuGR2FGg)Dbdr zECWslO_*n!UdauX z23T0MwVP>;&H3>6QG6}0pu;P#*E}Tj(@IcWVHre5F!OPjhjbO_;@ZK|UO`g~E@IzNKzJcRmu&+HYE2 z8TFOGU;!@EUBC+V{SDi~35YbLlB^seZ=eu=#q)6e(UMrgx#g&^Vqv1=Oc&~Apku8< zq-3XdbU_!;h0-urwByVjq~=URRFnXcHo|Dogr(bI+Jq=H6L9Z(vi{S11!x}91&K}=|$wLDFEkMqVN z%=#ry<@Hf2)vvP@yeOO-_AV_~#@ePLRx=HoO-=A+eIy5pL>6tsT)k_z};j@a^P>o9CgAZmP2s@U8X#E;GSe>1FR0{~TIa+(#Mv5mf?Nt zT77?7Tp0nFaKaK3L5!gs>+5s2yKzw!@CYs=tXQ;%xyZ2A2#;mKBqVf9u)^C|Zpl(m zfT&Q+_PDIotbl`sWmI^jg9wc%9b+l5uC<$KK-$GsizSeE8YKIa?YddA)ty&KUz^KB(b*bj!yM?bDdO`ov=TcJUPR9_j25K=*n}SjUF7gUtWN| z5WbWkn?z4b65NG=7bbx!lRL*K^>$5>#1eGlW|eV!o=g_lqU@CraS zrRGN>t_YD$sbk-0R9Ie{tYR7Q`wX+V$V}ShN*4k52#dNyOuVw;!z@>=(&n$O@5JmZ z&`sAP0Mk@YVImL}6*Za=A-WIy&L8t#cwpa1JWKO>EO0x5v$9m!^|Lmb#$Spivql&E z14sj~JgoHre)gapEE}px;cr#i+(>jN%zD+kIbu#P0-NV_$cpBiniKBfzIsP1XtlH) zFDexJ2)F~mSxFZKA$m#g0VKmztxdBOCc}!Fw8+jN;d4PtvT1BVRaC1RMmyvUuyFQd z0ms-{QZ>&Uqx8C-Wa6D5=D$VdOt@1Sz@1M)wWvV#EPB@%Za-{8s zeqo(W)Zr$sSCd)k23VKtD3YYSUI$h=zlHO|^-pII*9j!$b;nw=LVlx7+!hWwi z18FBqU_8McZYDl&NvDHT`Rt3EpE@N?gzMRn<4G`_Dqdj;i>-6$Td~PNN4K@TO0@qXnT)CQ*qP0|MV+=ni0Hm&@zTPgaCF@T4I8a< zG-NO_jl16ghVub2eLj4vN_4s69gu4epB9gnl&!{0CR5h%)fuh!8Lmc}yEfj9j1!pf zOlAc=3^Dh+^{n8($bCnz-*C7-6LC#C;3hMfJgKY;+S7Q~t9k6f^A)qiL_wO@k3FC# z%bqLLCl%*!cm}XipOBeLc^8hsYAgr&hEzYfB9^|Gd$$I>2PV22SH#MUdTq$$IUfLv ztSO<%@ynHF>k@w+Q^2aE@g!P_!mFT8!z7~UWePDFaeDhhDK#Uq(p_qc9CyUs@IANh zuoDZjYgdEP94TqT`eVNBLnWSzWE$=nuztfzBR8Z%zP{N8tzg81*f)X-kd1duw^5r>A#^m@tgElLwh|Q)r zflop4@T|CMlSb4+t#%we-=BxD|Y0(1y;!P$&wUi2~;J` zwfcGA4f{%lKCu81wpUZd43-Mq2{u+b1E+j;}gn)F;gk7w7i zH&wYaS;W*;xq-}kr4fa~lL1%O6kKAzd_ zI)idh^70t57Zw$`xA;KtjU~y>_IB$f=1eJx2=6+xT%x<1&T5Icu8w84|KH_G!r^_o z9_l-h9zVQM95FxnlJ~GcCDp}ntc$M3$7j;QQQ^+J+%GNhyz;NlmYC|_%6ZMs-5)v0 zB|1vQUw9m_aAOm{9qJwi@18X{4tSDvG3ATNDi#KO zFMT1-vP&^cSxH9B-@OM-&o^!9&=YZjqp!#dg%tGKn)vAh-SLn>p#-~Q{LSMyd&r47 z6q_qkcl*&b}`+;E!Qp4&%Wc6@GXszhd?do`FK{y&N|l2X|GJ!fYll{2Qlni$U~CI>1W* zxm;5Pr9MaK^E`IO9#;^q)4Y$4mM-y;4lMKk+Z|6E85wDpMe$moJB&$oVyytXspB!T zB7O>c=aFu)BrL=3uu;)Rk4$NOYJu8UB}uiEriqYY%^(Tu6C}ijicf1ClR2NK6-B^% z1*F8cHAm~*)^*s=ix$t<3*c&32?D*voK6Td-(km}iP*dnfWM5I_!BnpCY0Lr7Q#YB*vn zDIE}Rc41`d1|~4R2cx!4ZJtXJyQUXJ!^BdjRnx+X7`_Yb%<|B?_>heOPaa=!o#W?e zR(l0Tt*y)hHC&;Ia;)i28EFVBDLmdAKzbZ@t?A+Qm3p-hZoWR zCc^%et+-pQ4r4Z%rbn?#cb11tejV!MRqD@i-p*a1x~?psV@>WIOqRX%NK` zC#x_hSgv32XE`ig^Y|?SfX&s~3@<->zlz{fqkMN(DmbkgTaPq3BU8AgK@o0UgipAx!=5?5iEKg0tMf33YIyozP~(9K&_ zCllzlBuQ)L7~Umo#ijOBG|af0iZ1K1%)D}p0?6-st*8?-hmpu?kCoEjO0;3@_fL)H zuB_#G%D8TByb@#$2_Dl(36>}8BTJcB!F+#YnT5(l-G$f~m zikIpwV1T$9AD@T%6eex7*7il0$VOR@-s@?GA0Ho^KE`*C#A;eoyR0XOJxhQ*B}@~q zPzW6c*s~@rK5)Z^C5aVah45BWdnd8F(gmGuH+C+%Kp8GEefQWw9AfG3#}V5WuP-b{ z+#s8vW(s0uNa_eU2`-2-KpD>3hQ;$$9t;EE#BB-(N|rEN(d-B~I4^+ity8*!$Xi8# zfYRQ-r+Q>pqa)yTGmhPQd8>0y=>iSa)rrUwiy2)>O@$iAnHnB>b+3lTP$m*tIr!RH zAfi|^LkepvrX%fux^Q`tsX}Ej=cJ3?))I+V&4K-mK#l?>o`qyn`fe-S!T(J--aSx^ zMx3A{yy-M(udH$NpCSu{C&n&IKg*z@h*qJ~lYZuRj<*E8eq-vyc`NhO0BX~>aD<;I zl=M@A0}URjmA*AI0p&(NM(8@EjINV^532l2ZbJBOM-5M>@RFDgnN>I2?Fjf<)02R? z^?MpgtTh}zL|_C@a`Dov)|=2|Al&-wgEQo98_$3staj?<-9qcy#ILSNtN;}zMq&wL zlV&BJAhZ1xTM1fvaSfYSOsm5fPi`2 zP|e~%cv|NGfq!P0Tow|QwQ;s&UFdrLrF8M~d!^{m$icjd_MRY!^GgTlr&-M;AWPD$ zej_SS_GI!g1^mc=m=C81c3~uLjo&xoM_W(?rBq)P()9AO-Nh3NI7cMPdAUBmEaB!ROC#ur{Sx9E>{);^$XktjMv%B_q&>z@L@s}`Lv7*! zfVMSPaObCJ+AW*du1r@Hh`la=rfMZHDX43;RBSd?Y$EdT;cwX2$t!00_A%3bp0LV_ z)y|8eX0BS#iWO%@h#4EW_wS`J)%|W^ zilJS^RFdTa$%glH_Bn2qzV4s{-i_JqA)gM$RU?8#Ry#$f)?6zUZ4kyN5nu1?T3{Bi^3t zqobQ@IbxDlPb>xdYIqU~_-`T5@>FbgzT;ma|I>(k3&*Y2LbsldJJ}$3!rk!v%vgbQ5wb`!uA{>|VAp8_w}E-S({=jcrC{Ra@9 z&`+a|7}-7EhwgevM8Ivcx~YI2#GA%XbYBUz$!1xYL;74%$Q(HexEMrQ?51~*S6I53 z2!LlU{yJHV=&APDBvI|3o!L*Cjv?GwKl=1}lBI_al_KftEI-kNXCa4%_93`JCe5nP zNo7>n(>PtGmr4^GD^K72rF=hJ@K02fJ6e3WCJtzYY7*H7LT3Mk7fEvJ0LI{F6R*XO zU1FNskB0Yuxtm>iWIM(cr)S&}OIaO}i?7KAsD zrlae^G`Ec>=z9`9;f*u5L(IIrbw`DV_p!1qU4Y$BF}6<-1O@cd>Sr8Bg{=yC7(4mn zmL`t_5TL8W&dJG%CSqjUtCpwMQIe>$(Ru!S4|AbVD6kYA;X;o!&>i4ZZs>(3gwO*w z<8%S!=IK?OXKfK+{>Bv0(b4gDznt0e0!~|>kArBooN%tH_-ajCT){J>ft9tLx=6Px zT~GC9lMKl+qOG+x0Dv9rCG*=%Kgjpr1CEeR_97A1hZ(|^`SwzjaTg#gqa_<0i6fs* zOG7B0mhKz zSq&T#*9>doWdL=9)=WtFo{CT?%6cuJAXh_@lB=*{6GQ#ZtseE?tzK;DP4 zA3Yuh{(4QB+mAj%@z=yMx9w)3Ua{)YRU9hEZ%omY?8f^d;o zd=wV_6l)L61DyD|-D3e)JjjMMl;K73Xx>DFmIzvKDjBhgraw7cA1%&t@6Om-RvE2( zCMSU+wZinx|0u8@tQp*I0oVYGE>yTOR1vaKwt`ciT=!3Yn$bk8JhU@YH^DsmhdJAo zx;W76Aku(*C|Y#!0T&$xolcluPDowyja%B2#zuquSgxdZ7zv0GWT_T|q?i~TpsblA zGyXUF9A{E1^#Hz2M|nr{o_yl0T6`2RFaS4+eIp}N4ZU=|3?#vgtHw5~Tyh*PAx!G+ z+Dv$f74g@%mc_0?%78)CA%6KYlo+!rb(xQUHVo9*#ozLwa^Q01dV{s_3}g)5_496iJ>h86N?82 zteYDR%UZg(aR{dyB@b zm||8+E89*%CNhi!Y>~4wz)2?}CZ_L+Uit^l=gPigRWc|~L!nlfgo%Jf*~d^A8hTya zRbj%DWjX*87e&{D02v|RQnzDHH$f_vlCPtKp0ESp(wkHsgLLJ<9gQuSTM$oo0N_h} z`G;8U;0r#ZKLFd8!u(qT@S1czAmp37B&JT*XW_SE2YYanxr1LACN#Xi=rZZl2=s|p zGZ4-J|Nblj(~n(H`GW-fCjEN|MDE~l!ZhgOa6;~2698yl94{W)?3P5G3s^sUWb zDL3DA5ov5S<3S(}yD3bp1%d6RjyMpAo?qXm%Rf`> z40EH^$CitDSj+2u<_9@ku4zn9DfQ%4yu+IRDkn3BkkJFSW@~HwygKj|YR<$1orjlO zDnKqhxZc}D{$q195Pl%K?ZR~rQWgeo2G+{9-vSAfQqdu%Q(=^-asR=*hqkZcFrh4X z1>^2Yle`F5W<2BH<(lViRuMN%M@6t(cklNAUF3~JkfFC6Us%`EAqFqMetG>5-Hlrv UzBJ(876?R1URAC_)-2@z0Q_wY<^TWy literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp index cb29f9b3b42ea..6febd15ef8052 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp @@ -21,14 +21,18 @@ #include #include +#include #include +#include #include #include +#include #include #include #include +#include #include #include @@ -54,16 +58,15 @@ visualization_msgs::msg::Marker get_base_marker() } void add_polygons_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & polygons, const double z, const std::string & ns) + const visualization_msgs::msg::Marker & base_marker, const lanelet::BasicPolygons2d & polygons) { - auto debug_marker = get_base_marker(); - debug_marker.ns = ns; + auto debug_marker = base_marker; debug_marker.type = visualization_msgs::msg::Marker::LINE_LIST; for (const auto & f : polygons) { boost::geometry::for_each_segment(f, [&](const auto & s) { const auto & [p1, p2] = s; - debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), z + 0.5)); - debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), z + 0.5)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), 0.0)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), 0.0)); }); } debug_marker_array.markers.push_back(debug_marker); @@ -157,19 +160,37 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array( const auto z = ego_data.pose.position.z; visualization_msgs::msg::MarkerArray debug_marker_array; - // add_polygons_markers(debug_marker_array, ego_data.trajectory_footprints, z, "footprints"); + auto base_marker = get_base_marker(); + base_marker.pose.position.z = z + 0.5; + base_marker.ns = "footprints"; + base_marker.color = universe_utils::createMarkerColor(1.0, 1.0, 1.0, 1.0); + // TODO(Maxime): move the debug marker publishing AFTER the trajectory generation + // disabled to prevent performance issues when publishing the debug markers + // add_polygons_markers(debug_marker_array, base_marker, ego_data.trajectory_footprints); lanelet::BasicPolygons2d drivable_lane_polygons; for (const auto & poly : ego_data.drivable_lane_polygons) { drivable_lane_polygons.push_back(poly.outer); } - add_polygons_markers(debug_marker_array, drivable_lane_polygons, z, "ego_lane"); + base_marker.ns = "ego_lane"; + base_marker.color = universe_utils::createMarkerColor(0.0, 0.0, 1.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, drivable_lane_polygons); lanelet::BasicPolygons2d out_of_lane_areas; for (const auto & p : out_of_lane_data.outside_points) { out_of_lane_areas.push_back(p.outside_ring); } - add_polygons_markers(debug_marker_array, out_of_lane_areas, z, "out_of_lane_areas"); + base_marker.ns = "out_of_lane_areas"; + base_marker.color = universe_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, out_of_lane_areas); + for (const auto & [bbox, i] : out_of_lane_data.outside_areas_rtree) { + const auto & a = out_of_lane_data.outside_points[i]; + debug_marker_array.markers.back().points.push_back( + ego_data.trajectory_points[a.trajectory_index].pose.position); + const auto centroid = boost::geometry::return_centroid(a.outside_ring); + debug_marker_array.markers.back().points.push_back( + geometry_msgs::msg::Point().set__x(centroid.x()).set__y(centroid.y())); + } lanelet::BasicPolygons2d object_polygons; for (const auto & o : objects.objects) { @@ -184,7 +205,9 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array( } } } - add_polygons_markers(debug_marker_array, object_polygons, z, "objects"); + base_marker.ns = "objects"; + base_marker.color = universe_utils::createMarkerColor(0.0, 1.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, object_polygons); add_current_overlap_marker(debug_marker_array, ego_data.current_footprint, z); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index e51980d60dbba..c97e10cc8706e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -77,8 +77,6 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); pp.skip_if_already_overlapping = getOrDeclareParameter(node, ns_ + ".skip_if_already_overlapping"); - pp.ignore_lane_changeable_lanelets = - getOrDeclareParameter(node, ns_ + ".ignore_overlaps_over_lane_changeable_lanelets"); pp.max_arc_length = getOrDeclareParameter(node, ns_ + ".max_arc_length"); pp.time_threshold = getOrDeclareParameter(node, ns_ + ".threshold.time_threshold"); @@ -119,9 +117,6 @@ void OutOfLaneModule::update_parameters(const std::vector & p updateParam(parameters, ns_ + ".mode", pp.mode); updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); updateParam(parameters, ns_ + ".max_arc_length", pp.max_arc_length); - updateParam( - parameters, ns_ + ".ignore_overlaps_over_lane_changeable_lanelets", - pp.ignore_lane_changeable_lanelets); updateParam(parameters, ns_ + ".threshold.time_threshold", pp.time_threshold); updateParam(parameters, ns_ + ".ttc.threshold", pp.ttc_threshold); @@ -318,7 +313,7 @@ VelocityPlanningResult OutOfLaneModule::plan( if (should_use_previous_pose) { // if the trajectory changed the prev point is no longer on the trajectory so we project it const auto new_arc_length = motion_utils::calcSignedArcLength( - ego_trajectory_points, ego_data.first_trajectory_idx, previous_slowdown_pose_->position); + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); slowdown_pose = motion_utils::calcInterpolatedPose(ego_trajectory_points, new_arc_length); } if (slowdown_pose) { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 8067d9e8b3410..c3714c5609135 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -47,7 +47,6 @@ struct PlannerParam bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps // another lane double max_arc_length; // [m] maximum arc length along the trajectory to check for collision - bool ignore_lane_changeable_lanelets; // if true, ignore overlaps on lane changeable lanelets double time_threshold; // [s](mode="threshold") objects time threshold double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object From bb921b56e06717c936d0aaff597e0a2afef31f54 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 4 Sep 2024 11:43:11 +0900 Subject: [PATCH 129/151] fix(static_obstacle_avoidance): ignore objects which has already been decided to avoid (#8754) Signed-off-by: satoshi-ota --- .../src/debug.cpp | 1 + .../src/shift_line_generator.cpp | 12 +++++++++++- 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index a542107e890aa..9840743867e78 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -658,6 +658,7 @@ MarkerArray createDebugMarkerArray( addObjects(data.other_objects, ObjectInfo::DEVIATING_FROM_EGO_LANE); addObjects(data.other_objects, ObjectInfo::UNSTABLE_OBJECT); addObjects(data.other_objects, ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE); + addObjects(data.other_objects, ObjectInfo::INVALID_SHIFT_LINE); } // shift line pre-process diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 57a6e340bf853..e54a00b1cd2c7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -248,6 +248,11 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( return s.start_longitudinal > 0.0 && s.start_longitudinal < s.end_longitudinal; }; + const auto is_approved = [this](const auto & object) { + return (helper_->getShift(object.getPosition()) > 0.0 && isOnRight(object)) || + (helper_->getShift(object.getPosition()) < 0.0 && !isOnRight(object)); + }; + ObjectDataArray unavoidable_objects; // target objects are sorted by longitudinal distance. @@ -284,6 +289,11 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // calculate feasible shift length based on behavior policy const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length); if (!feasible_shift_profile.has_value()) { + if (is_approved(o)) { + // the avoidance path for this object has already approved + o.is_avoidable = true; + continue; + } if (o.avoid_required && is_forward_object(o) && is_on_path(o)) { break; } else { @@ -394,7 +404,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( outlines.emplace_back(al_avoid, std::nullopt); } else if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { outlines.emplace_back(al_avoid, al_return); - } else { + } else if (!is_approved(o)) { o.info = ObjectInfo::INVALID_SHIFT_LINE; continue; } From da8b050515427fb2bf92d3e292856b7e0a94a046 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 5 Sep 2024 08:40:01 +0900 Subject: [PATCH 130/151] fix(pid_longitudinal_controller): fix the same point error (#8758) (#1512) * fix same point Signed-off-by: Yuki Takagi --- .../src/pid_longitudinal_controller.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 20f8dfe642cc6..4acb73b1d1b60 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -488,6 +488,8 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // calculate the target motion for delay compensation constexpr double min_running_dist = 0.01; if (control_data.state_after_delay.running_distance > min_running_dist) { + control_data.interpolated_traj.points = + autoware::motion_utils::removeOverlapPoints(control_data.interpolated_traj.points); const auto target_pose = longitudinal_utils::findTrajectoryPoseAfterDistance( control_data.nearest_idx, control_data.state_after_delay.running_distance, control_data.interpolated_traj); From c0644c325374b25d3f7d3385f6cb549f52c34702 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 5 Sep 2024 09:40:07 +0900 Subject: [PATCH 131/151] feat(out_of_lane): redesign (#1509) Signed-off-by: Maxime CLEMENT Co-authored-by: Tiankui Xian <1041084556@qq.com> Co-authored-by: Shohei Sakai --- .../motion_utils/trajectory/trajectory.hpp | 9 + .../src/trajectory/trajectory.cpp | 23 ++ .../README.md | 191 ++++----- .../config/out_of_lane.param.yaml | 24 +- .../docs/ego_lane.png | Bin 0 -> 17530 bytes .../docs/footprints.png | Bin 0 -> 28711 bytes .../docs/object_paths.png | Bin 0 -> 26240 bytes ...footprints_other_lanes_overlaps_ranges.png | Bin 127593 -> 0 bytes .../docs/out_of_lane_areas.png | Bin 0 -> 19244 bytes .../docs/out_of_lane_slow.png | Bin 110077 -> 0 bytes .../docs/out_of_lane_stop.png | Bin 183400 -> 0 bytes .../docs/path_green_light.png | Bin 0 -> 23635 bytes .../docs/path_red_light.png | Bin 0 -> 22819 bytes .../docs/ttcs.png | Bin 0 -> 28315 bytes .../docs/ttcs_avoid.png | Bin 0 -> 31503 bytes .../src/calculate_slowdown_points.cpp | 131 ++++-- .../src/calculate_slowdown_points.hpp | 45 +- .../src/debug.cpp | 305 +++++++------- .../src/debug.hpp | 8 +- .../src/decisions.cpp | 389 ------------------ .../src/decisions.hpp | 116 ------ .../src/filter_predicted_objects.cpp | 46 +-- .../src/filter_predicted_objects.hpp | 4 +- .../src/footprint.cpp | 23 +- .../src/footprint.hpp | 12 +- .../src/lanelets_selection.cpp | 118 ++++-- .../src/lanelets_selection.hpp | 39 +- .../src/out_of_lane_collisions.cpp | 164 ++++++++ .../src/out_of_lane_collisions.hpp | 57 +++ .../src/out_of_lane_module.cpp | 322 ++++++++------- .../src/out_of_lane_module.hpp | 25 +- .../src/overlapping_range.cpp | 127 ------ .../src/overlapping_range.hpp | 63 --- .../src/types.hpp | 215 +++------- .../CMakeLists.txt | 17 +- .../collision_checker.hpp | 69 ++++ .../planner_data.hpp | 29 +- .../src/collision_checker.cpp | 70 ++++ .../test/test_collision_checker.cpp | 176 ++++++++ .../src/node.cpp | 47 ++- .../src/node.hpp | 3 + .../src/planner_manager.cpp | 51 ++- .../src/planner_manager.hpp | 11 + 43 files changed, 1412 insertions(+), 1517 deletions(-) create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/object_paths.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_areas.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_red_light.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs_avoid.png delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp create mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp index 126e66772920a..0ce42fbe1080f 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp @@ -2504,6 +2504,15 @@ extern template bool isTargetPointFront & trajectory, + const geometry_msgs::msg::Point & current_ego_point, const float min_velocity = 1.0f); + } // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__TRAJECTORY_HPP_ diff --git a/common/autoware_motion_utils/src/trajectory/trajectory.cpp b/common/autoware_motion_utils/src/trajectory/trajectory.cpp index ce26952c3d634..080d8ca8c7437 100644 --- a/common/autoware_motion_utils/src/trajectory/trajectory.cpp +++ b/common/autoware_motion_utils/src/trajectory/trajectory.cpp @@ -599,4 +599,27 @@ template bool isTargetPointFront & trajectory, + const geometry_msgs::msg::Point & current_ego_point, const float min_velocity) +{ + const auto nearest_segment_idx = findNearestSegmentIndex(trajectory, current_ego_point); + if (nearest_segment_idx + 1 == trajectory.size()) { + return; + } + for (auto & p : trajectory) { + p.time_from_start = rclcpp::Duration::from_seconds(0); + } + // TODO(Maxime): some points can have very low velocities which introduce huge time errors + // Temporary solution: use a minimum velocity + for (auto idx = nearest_segment_idx + 1; idx < trajectory.size(); ++idx) { + const auto & from = trajectory[idx - 1]; + const auto velocity = std::max(min_velocity, from.longitudinal_velocity_mps); + if (velocity != 0.0) { + auto & to = trajectory[idx]; + const auto t = universe_utils::calcDistance2d(from, to) / velocity; + to.time_from_start = rclcpp::Duration::from_seconds(t) + from.time_from_start; + } + } +} } // namespace autoware::motion_utils diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md index 99396eb0edf22..0b6aa697fcbef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md @@ -1,161 +1,138 @@ -## Out of Lane +# Out of Lane -### Role +## Role -`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects. +There are cases where the ego vehicle footprint goes out of the driving lane, +for example when taking a narrow turn with a large vehicle. +The `out_of_lane` module adds deceleration and stop points to the ego trajectory in order to prevent collisions from occurring in these out of lane cases. -### Activation Timing +## Activation -This module is activated if `launch_out_of_lane` is set to true. +This module is activated if the launch parameter `launch_out_of_lane_module` is set to true. -### Inner-workings / Algorithms +## Inner-workings / Algorithms -The algorithm is made of the following steps. +This module calculates if out of lane collisions occur and insert stop point before the collisions if necessary. -1. Calculate the ego path footprints (red). -2. Calculate the other lanes (magenta). -3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green). -4. For each overlapping range, decide if a stop or slow down action must be taken. -5. For each action, insert the corresponding stop or slow down point in the path. +The algorithm assumes the input ego trajectory contains accurate `time_from_start` +values in order to calculate accurate time to collisions with the predicted objects. -![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png) +Next we explain the inner-workings of the module in more details. -#### 1. Ego Path Footprints +### 1. Ego trajectory footprints -In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters. +In this first step, the ego footprint is projected at each trajectory point and its size is modified based on the `ego.extra_..._offset` parameters. -#### 2. Other lanes +The length of the trajectory used for generating the footprints is limited by the `max_arc_length` parameter. -In the second step, the set of lanes to consider for overlaps is generated. -This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets. -The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`. +![ego_footprints](./docs/footprints.png) -A lanelet is deemed non-relevant if it meets one of the following conditions. +### 2. Ego lanelets -- It is part of the lanelets followed by the ego path. -- It contains the rear point of the ego footprint. -- It follows one of the ego path lanelets. +In the second step, we calculate the lanelets followed by the ego trajectory. +We select all lanelets crossed by the trajectory linestring (sequence of trajectory points), as well as their preceding lanelets. -#### 3. Overlapping ranges +![ego_lane](./docs/ego_lane.png) -In the third step, overlaps between the ego path footprints and the other lanes are calculated. -For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`. -For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored. -Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored. -Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information: +In the debug visualization the combination of all ego lanelets is shown as a blue polygon. -- overlapped other lane $l$. -- start and end ego path indexes. -- start and end ego path arc lengths. -- start and end overlap points. +### 3. Out of lane areas -#### 4. Decisions +Next, for each trajectory point, we create the corresponding out of lane areas by subtracting the ego lanelets (from step 2) from the trajectory point footprint (from step 1). +Each area is associated with the lanelets overlapped by the area and with the corresponding ego trajectory point. -In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects. -The conditions for the decision depend on the value of the `mode` parameter. +![out_of_lane_areas](./docs/out_of_lane_areas.png) -Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path). -If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. -If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. +In the debug visualization, the out of lane area polygon is connected to the corresponding trajectory point by a line. + +### 4. Predicted objects filtering + +We filter objects and their predicted paths with the following conditions: - - - - - -
- - - -
+- ignore objects with a speed bellow the `minimum_velocity` parameter; +- ignore objects coming from behind the ego vehicle if parameter `ignore_behind_ego` is set to true; +- ignore predicted paths whose confidence value is bellow the `predicted_path_min_confidence` parameter; +- cut the points of predicted paths going beyond the stop line of a red traffic light if parameter `cut_predicted_paths_beyond_red_lights` is set to `true`. -##### Threshold +| `cut_predicted_paths_beyond_red_lights = false` | `cut_predicted_paths_beyond_red_lights = true` | +| :---------------------------------------------: | :--------------------------------------------: | +| ![](./docs/path_green_light.png) | ![](./docs/path_red_light.png) | -With the `mode` set to `"threshold"`, -a decision to stop or slow down before a range is made if -an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`. +In the debug visualization, the filtered predicted paths are shown in green and the stop lines of red traffic lights are shown in red. -##### TTC (time to collision) +### 5. Time to collisions -With the `mode` set to `"ttc"`, -estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated. -This is then used to calculate the time to collision over the period where ego crosses the overlap. -If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made. +For each out of lane area, we calculate the times when a dynamic object will overlap the area based on its filtered predicted paths. -##### Intervals +In the case where parameter `mode` is set to `threshold` and the calculated time is less than `threshold.time_threshold` parameter, then we decide to avoid the out of lane area. -With the `mode` set to `"intervals"`, -the estimated times when ego and the dynamic objects reach the start and end points of -the overlapping range are used to create time intervals. -These intervals can be made shorter or longer using the -`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters. -If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made. +In the case where parameter `mode` is set to `ttc`, +we calculate the time to collision by comparing the predicted time of the object with the `time_from_start` field contained in the trajectory point. +If the time to collision is bellow the `ttc.threshold` parameter value, we decide to avoid the out of lane area. -##### Time estimates +![ttcs](./docs/ttcs.png) -###### Ego +In the debug visualization, the ttc (in seconds) is displayed on top of its corresponding trajectory point. +The color of the text is red if the collision should be avoided and green otherwise. -To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path -at its current velocity or at half the velocity of the path points, whichever is higher. +### 6. Calculate the stop or slowdown point -###### Dynamic objects +First, the minimum stopping distance of the ego vehicle is calculated based on the jerk and deceleration constraints set by the velocity smoother parameters. -Two methods are used to estimate the time when a dynamic objects with reach some point. -If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. -Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. +We then search for the furthest pose along the trajectory where the ego footprint stays inside of the ego lane (calculate in step 2) and constraint the search to be between the minimum stopping distance and the 1st trajectory point with a collision to avoid (as determined in the previous step). +The search is done by moving backward along the trajectory with a distance step set by the `action.precision` parameter. -#### 5. Path update +We first do this search for a footprint expanded with the `ego.extra_..._offset`, `action.longitudinal_distance_buffer` and `action.lateral_distance_buffer` parameters. +If no valid pose is found, we search again while only considering the extra offsets but without considering the distance buffers. +If still no valid pose is found, we use the base ego footprint without any offset. +In case no pose is found, we fallback to using the pose before the detected collision without caring if it is out of lane or not. -Finally, for each decision to stop or slow down before an overlapping range, -a point is inserted in the path. -For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$, -a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$. -Such point with no overlap must exist since, by definition of the overlapping range, -we know that there is no overlap at $i-1$. +Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the trajectory point to avoid. +If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. +If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. -If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter), -it is skipped. +![avoid_collision](./docs/ttcs_avoid.png) -Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible. +### About stability of the stop/slowdown pose -### Module Parameters +As the input trajectory can change significantly between iterations, +it is expected that the decisions of this module will also change. +To make the decision more stable, a stop or slowdown pose is used for a minimum duration set by the `action.min_duration` parameter. +If during that time a new pose closer to the ego vehicle is generated, then it replaces the previous one. +Otherwise, the stop or slowdown pose will only be discarded after no out of lane collision is detection for the set duration. + +## Module Parameters | Parameter | Type | Description | | ----------------------------- | ------ | --------------------------------------------------------------------------------- | | `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc | | `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane | +| `max_arc_length` | double | [m] maximum trajectory arc length that is checked for out_of_lane collisions | | Parameter /threshold | Type | Description | | -------------------- | ------ | ---------------------------------------------------------------- | | `time_threshold` | double | [s] consider objects that will reach an overlap within this time | -| Parameter /intervals | Type | Description | -| --------------------- | ------ | ------------------------------------------------------- | -| `ego_time_buffer` | double | [s] extend the ego time interval by this buffer | -| `objects_time_buffer` | double | [s] extend the time intervals of objects by this buffer | - | Parameter /ttc | Type | Description | | -------------- | ------ | ------------------------------------------------------------------------------------------------------ | | `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | -| Parameter /objects | Type | Description | -| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | -| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | -| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | - -| Parameter /overlap | Type | Description | -| ------------------ | ------ | ---------------------------------------------------------------------------------------------------- | -| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | -| `extra_length` | double | [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) | - -| Parameter /action | Type | Description | -| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------- | -| `skip_if_over_max_decel` | bool | [-] if true, do not take an action that would cause more deceleration than the maximum allowed | -| `distance_buffer` | double | [m] buffer distance to try to keep between the ego footprint and lane | -| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | -| `slowdown.velocity` | double | [m] slow down velocity | -| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | +| Parameter /objects | Type | Description | +| --------------------------------------- | ------ | ------------------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | +| `cut_predicted_paths_beyond_red_lights` | bool | [-] if true, predicted paths are cut beyond the stop line of red traffic lights | +| `ignore_behind_ego` | bool | [-] if true, objects behind the ego vehicle are ignored | + +| Parameter /action | Type | Description | +| ------------------------------ | ------ | --------------------------------------------------------------------- | +| `precision` | double | [m] precision when inserting a stop pose in the trajectory | +| `longitudinal_distance_buffer` | double | [m] safety distance buffer to keep in front of the ego vehicle | +| `lateral_distance_buffer` | double | [m] safety distance buffer to keep on the side of the ego vehicle | +| `min_duration` | double | [s] minimum duration needed before a decision can be canceled | +| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | +| `slowdown.velocity` | double | [m] slow down velocity | +| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | | Parameter /ego | Type | Description | | -------------------- | ------ | ---------------------------------------------------- | diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml index a0cf69ee71027..5d36aa8d3f018 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -1,32 +1,22 @@ /**: ros__parameters: out_of_lane: # module to stop or slowdown before overlapping another lane with other objects - mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc" + mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc" skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane + max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions threshold: time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time - intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego - ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer - objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer ttc: threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap objects: minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored - use_predicted_paths: true # if true, use the predicted paths to estimate future positions. - # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. - distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights ignore_behind_ego: true # if true, objects behind the ego vehicle are ignored - overlap: - minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered - extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) - action: # action to insert in the trajectory if an object causes a conflict at an overlap - skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed precision: 0.1 # [m] precision when inserting a stop pose in the trajectory longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle @@ -38,8 +28,8 @@ distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap ego: - min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego - extra_front_offset: 0.0 # [m] extra front distance - extra_rear_offset: 0.0 # [m] extra rear distance - extra_right_offset: 0.0 # [m] extra right distance - extra_left_offset: 0.0 # [m] extra left distance + # extra footprint offsets to calculate out of lane collisions + extra_front_offset: 0.0 # [m] extra footprint front distance + extra_rear_offset: 0.0 # [m] extra footprint rear distance + extra_right_offset: 0.0 # [m] extra footprint right distance + extra_left_offset: 0.0 # [m] extra footprint left distance diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ego_lane.png new file mode 100644 index 0000000000000000000000000000000000000000..65cb73226465ae3de6c27b35562d35c57c5906b5 GIT binary patch literal 17530 zcmbt+cRZEh|MyWTp^y_2*($>jiv)`ZhCH&b_`CIsu_%ImkmZE};1`KvZ4+g`T z#Jd9ilKS1n1pK)9Nzk3I#)}d(@2BU>3%1CK>7_U#O+ELl0v+OTNZ=T{? z@hU3ivlg=zml|mQ&9?ol)S@{e_>6CC^fS-PuLN*16d~EGZ#OngtKQ=Hj0MF;hWrj8 z@|}`Jic3-~1--eKS8uei;pR9?!%YX z$G9VQ-WEiBBxj+aa`R|#`3!&m*K6-N_!0!p!J0K3hZ$S-T&?DstxX&*<*qh-rnA3BZ+!QBzXo5 zX41=ssYH@bhT82SoStpWw6F`R-b7b-7P6_A>vR>eVbJ7KK1)|9m}Kn&^exg0$M~5F z4;=l{ja%{dx0BZTxP&D9-U>fTB_}8EVh+HLj~`Y1*v^=3ru#hAu%q{4m1OPg_TI~v zFU>R~3Kq?CwH}76j+pGvlbSG(+PWV~6>L95*461O)F94Q3l2R#9)p)$K_9h>WiN>R z5^1fRYiiFIsp-tIH9dTQ_^9>E<7YI-qSqVRYXLYb@yC&okv+G^zQqKf5JKlyNcru>rIr`-=c$$^MVTDmKVX4}Jqgzx ze}1OP{<3n|?Y1a9D;R|gFV6zIZjxMHUXG38NK!J&C28=G%04hH*v28zF2!`Z+!Wt( zZeVeeskNS50Xt4B>($p49Ua}$((;Y0vgWO>c~b8U>JCRyYhp1~` zCZ9hk9PHuJHp2J(l%`hABW-y8a_q17Hl~{}Rhx+^;e2Uf%@>*-i@mCRCsdD8F~umi~FXrH`VYp^03KCge}b#6~&vZkAd0|_AQc!t(U?y zGyHkL`+l8s;~?(7|5lpo1%A_GwIHCL6v_KnoH(4uoM^e1v`y{+v*92cJV`pbS^6`85Qu#~Y zj^xzz8K$XebL(wsDMDZG&|Lp~w5RmFE;QUtjndJ&y1MNnpDI1ZT(c^Vy}zT}gfD9; z+va+c{13K%Biu4Y=pQC!Pk+H?S6r|j;s4-rjlKd?`DmfGibA0V{r#5zjv{{7_sJqx zU~G`-t6Y~vhFbqdq1rsR7l#vAWK!XLFTh;HX@w2VKI@TOehk?#`Vs!{@6{aG&R60d zTPD`aO&7lrr$nc}Pd3|{z4k6V54UDBoAEiXnFqsY8=aSWlh`qB`?VRN?}qprj4LB` z^T$q4PYaY&$jHg>%D!XlaWle3ys0juIbFUu#X+1WAdZ&m+s@ijl(bEMzH&}2^xXNQ zDyxnk(hfhXmm>(ly-6KP;zz)RTA9mRJ1;(oUDhqxY#FxG^g)WRN8 zCyJbtp5hM$!!@I${%uVs2&^K%5p!ZpO2t~CjTLX23Nv4`yVV@zaU&^FGLx=bBl>t zw>L+SOD^@<1X_@v!6g09-@heeUc=YU>%UptgRQ6uKL2h-(Eo?TU+-ZO^H!dHGhqie zVbHQ=o8!R#e(e0C5r^sH`l3g13Qt*={GUpb{c#qlD!%3aocV9tEufSGPr{x6u`7|6 z1zTxsf=y_tQ7*7Xqh}GG#{6meV@-!y_fGupN0ET7{5vY3I@0;;sg|~`wnPfwJ@eMh zhY|6a(!5pX(&R&ua$^jpUsWiSK9|w>?2XdwER2rkaB!R|ZvV46Otu4x>MCw=xVx%} z%_R|?&0sjKzxPx4<>uv<>NiZ76QkmtR)hxz24Xf(7LEfETFWP8YPPioZ{NP{sl)^J z93gbO#cgfYs^&se(yh>-e1Byq&qHu^(y`5ca{o)=py6qMj|Fd36)m3J(OrC_JQ(fp z=N+HqBfq(mJL=!+)(tC~TYUf8lWKf-qN1Oeoh5IjV%*GgeP=WhKb`NsIb&pKNTn*Y z`rOeMrZMatgadN`P3oJzV8^4;7 zFv-r@`*GJW)&WGf&7F7l7*G9xQ?Z&atCrC+ZNVJCts~B{v0ahZd!5q7am`Cgic92V z#_isO9lAc8b(a_nuUuU^yT=6F*{%%hxyM@yGp=8{%f`I8O=a(d--7V+Z+*Q5i@INE zlU{iA?FNmw&*3NZwC~&KZaVdE2Ulm^*^{nL*4@8Vn&NI_0i^Is+F9+Mm%uir1oH@E zzrNW<+c~4SyfSs)7~gsA^1?=(sNcRVVP$t9!HeC!z(_}LA{ezfsoRr<*STXav(o4SbvR6kVwPJtg(#PVDbDPy<>6K=aN z)T+-44+qxUP_fWh=h0O)R76W+Z*PCIl<w0NY;VlJ6~1_n?A z1G;-&`{elcQbLI4( z@F=DxMO_`8fs~MnH5H?qtZ|*!VXzko=roDKxq$)yi=CV{dD5J~sh}G~f`WpF*!zyn zPTLl0s8*`;`DY|oV43B{mFw&FY!S(Zh#AhO-zMvk6exf8>}&-mqmOIHvM7Qga_C)k zrx!jA9nPrvZ6isCPBu4<+s-RRE7&qsoKIF-f*1<@6?7Gq6#zY}GTupNKv zK^~3o_gKf-a|Hjo{z-bf;{NXH$WJRe6bP8dbuBHeEiKu7BHc#}ep_do7u+c)A|&_Z z>Qb7h)M7l8H`XwfmF4AG;v(qFm1<6D9xtU_tj(UUThbrT9GrXkonJ(7rB>v|h0WWK zZ6BRJ-Z#m>{|LtBl!-qdwazIg9y(|}z@%_poGca>v*Tkhm?K7w5&q5DHm>Y!b?BP| zgVlapJuH>UgrUC?jydvtZnCEMEbr){TWqZj8qF4QgL#TpzisOCQ!Sjx3N7Xd!FJ4v z$JbM+%;@C$hIjqE8{+CL)phhbGmZXI!#s|6{eRyOa%gtnCLHP!&P3(L-6425&~h^I z`77}F0j>JKhz`H~{j2sgTg24c`)nu=2^5%sfPKEfX6q1Z?#DgJMEVfu#`$NWTd#F1 zF@y}dm1;;??b6Z1TN#{2jr<)!A<){7=R9dpPl8(VY3o~BI0aS1_x5!CckUTm#zKPV zNMP~rB}z_d^WX04ix5*7boY+vc?;dqj(rlu$K23+KGWhozq;D3qkDm@vM(cC&@~%* zVKYJ0#SG?td)>P4?BqaogfTZ(@>oG!Xo*6dvF@85NG>}I$K%lwBpD`kQDOFtnk)Wt+t>YI(=VI$(a z&R=SkYFF9NSJlsWDcjv=9rSh!s_0o3o+Zm*exB!~Y?p2~`d6UprioYc#W|W?SI}|h z)CGG@rQyR3y02PmXBkr}F`PTA+d&5Q&Gq#xg0)BUkq3^`UM=d&!^5Qu8f>IO*~JF6 z;V<0lv5SgN#4&9LGtcJ{XIonr8%w$?L+@usO<9wa%rvFj+=o zWT64$RUk+E^2Nh|fBTuw*4!J9dDjDwKKq@ClGxkX?e2Bn6a1>r2l8wQlrfdF_{_Y? zeT6#=pcD|q-gTsYQgtA+xJ0Y*jMyI`EU!+H;=6vq$@9Q_)OL@)zz2%7+$SEa+k+eV z8{riGQ+b-7joQ%oO>louko4u@XnUMV6JL28;i@8YF2&JFCo0>t))JH`Z_<70eR_!1 zi&qN(OXUBX8rIX-L6yemwn@95>hFZb_?=NeHOA&y?7gl%A7Py`7R-B*h0S@g3P&o*E% zIkpB1Gq6D~U#<=1$shT&>T%pruhQ#V-T|Iweq?wVD6M15UUJ3S=?6>w#)`E@$%0KN zWuHqrnDLIK@j1nIJ1zYBr6ZY>!l;PZGpjn>pLA4P?LK>4R$lIV&@|iPx_ZYS)GSzR zHx0t~c=zvU>FJs0?#fV)wF(XhgfNn!7ViU(rEc`M#bQvQ6{+PgD|eLYR)(7Dm5#=z z^f#XzYy!uGmHts(hP*h&lIaE)dCVT?)i*ua8b%o4 zqYJT5E_{G8fMsqnF#t7s+p~#NYw(B@-+nT?q7n}{4_Kr7=7Y@*<<}9fJH3@g_-w~! z$d7As&dSUOm?GQ3LL!P-pwKfnx?j2qZkW|g z)jQanjcs~DBk40%Kn(9R|EQ@22d)rkhVvGxA$O-dcxsvgtVd^z!+}% zjogG1XO_X;^>0BpPR~^fZTz;r-B{0fwU6dU7wVHef6L}6U&4u27=R<*&Bps}f1tk> zunUzKB85Gf%pw*Z@3cb;^;?~n$jr+$Jn6FUrwii_W>QZ?u0F)CS`~!lYdKr1W2Zc^ zW~?(MVh*eCY?8^zbO;%gWsrVHFR{BnI_otW73flT=e}J%Uuy%ImhUZ|7+m0a6^g$l z2UV4qKbovN8s45M8r*vL%I`cr_oIwf`Npp`hKKprvjeB#cS9%`t_37gdWcXwMK~q2@EP@y|yy6qNa&pH}L`U56 zMD+uHRCE~?70A*?G~i}Y;P%H#=eVM-_Vz0zzDG+b^Q)R$RaH&yn<#%&o@GzfW2xFk zv2^FHAR@`R8&?&-9o}wfzWt}rGM^Y^xy7Uh+OLUVBmAC+_d>rtr|K4Q>e8R6`Qh|Y z%is>DvMs;yjh?NkHvb$NLvGxV`WG%PnqN%J%@>aMK%G=kUao3K1_|7)F(v46*>$;ld{ghQ)E7K55V>p8DdnFh#Rr&D+2I_iwp{GA{ua zvbB!}MO7s7&zZZyy)TVz%zN3Ii@BLq26#e))WV~3M_+b7;g4!ZF&w2D<>~FssaaWB zc7ho_7QIW(c|*dYq7iE2uO*y*&oOCkbtBHJJkrBBe;j!h-n^Wc`$T1=Z^^kpLve(E zh8}Lw@s(Yij-c&yTiGuq_a&yH>%=q0r03co9laNDu|0e;GC~eh??3qSeNq`&)EBe) z^!@?NDrc>6&&$`*F}BilY-Xm;{(1Aq8|6Bsl_y$1*92sTc+(84hnzAS8bJLH$3GqY zh4D{lHksR)Z5!My+Xapy23Nn<06Y+p%Z-9Bo#Mt@>Q}5ql*=TJ8Jk=o$3RKALZnA4 zYg-2A#V*3LXU^WSlAy*UCMM=#5#2cN>+9=WZKuu(n|;T}qR5ws zH)0i#>v!{bVCM*3M5`_c8*lGvr}UoWtSoBd_+<2w>Arlnbvo;<^{n45)jqvZ9u8$c z1n^-t-yG%Is;cOwZs!_T?!;(f+=6IVh9$-vF)zvtrXRuoBzQ;E8I(h>TT;J|l6KB2N9|bGnt%cB%$a*HJfLiUVt5WYG&Q z(N;dggNV30npVsuteq4g6gxt$YeDKt`uFc~Rz$W#;YCGcq?B?PIt32KiQ>DnC6 zU`=jl?mnS1B-inm3D@SZDSH?z`joQ$`^phOFKHh!e>fEGe{a?A%5eigL=PEQ_q>GY zrhig_Kww2hLo43xGeqKjxJ74F#wuP;wYYzP3{%Y_^geNP$bFp#u$`|_86VS*jSPK+ z1~v$8u#~fAQh}h9YMFp|oa*{clFjvVFNJJZ22NVPo$$S8rKZOzxvkcY{LAv zm^id``kF$IDb^$y2i%(qK9KoSW3lZ$AbkrM=P$S#Y#1B4w&46}_S5E=nAf*7-s##w zhG;S8?$*F7AaK;!DBZv__kC2cSxS|!S=g8P%hJnf8vU)R@;%6BzS^Y^)dl&Ylfgq9qgT^jSVM`&c z=$;w!JCQY~mdC$Q+Suf6AfiB8lL!SZ?p0B;5b{;>rT8F#HL#5cx4f-U#vktNGY1Ld zSHkqaY#3n|fSH4q|Sb7piP#6%t&=}B7EceBvx!@NXk!Fy2|ZyqU~P#*ssEr zmxbRpBX4Q`QR@n2(|RaDno-z`*9zZ1jJ}18YP^49y#|x;J3R#1U(fTs+s!l7c4V)S zyh9EFZQqYRX{@@D@04A80BioWkP^Fb&;O*Zs`*sQPL(yqyLZ#iNPG}=PA5iu>Ki71 z4J6IyAR%<2KVBpi@*Hn)yTELAVI1ybvFhd8;|@$uU%Q;tIjzP&mASwo9z-n1>>aLe zO^rQwY+<;G}Gs0Fn523(c|JQ#Y{7&!f>21H$&*cQ2ZTl z?L?N6<@(_HKe73n!j<8-r33g^ums3WWQo`52Cva9(TxAalA6C4o8RH!`S=C1B0@0} z@j>h1O(rcalo&Fv$-?q}1FZ z-jBUq#}#)0D!vf1jbG(c8IGL9L*&SR2+v_+wR+FZmI4hnhPv!rgW3clcXwo)jx0r@4fB&pzJ<4AdlCV^3hUFyb+3pyr2=78VtsKs#s1ZKpWU#pyqQ+i)9n2^kDb1kuqlru;dL&O;ilQcReno-tX_t9{_3cOtm)&R1y8JKD|<7Y;V2Jo^xxEWt*V zIi7rlG4sfEl^(dy;g)Ia8w>%*#~T5wc{T`+6a;;)?cRjVSv_Av*ee^h18nyu$xw|o zf_O0cIZ~NN zjrG7!v9bQ*V{k?w6_rZ9$aekFg^3@l&J$%ubhuq3K~SA&b5|{)SWA-Dj74pru)JKG zzR}xVQ=BJn9zHcTMxlWZwO9%#0F1Gst$sKgzHCK6v%MIJi#X{cQ5(#)z?bycdMqv> z47nvU?4RfB3?Y10v_k2rD%3>+Ox`kY(=S(AOs1BWRuSzyVC{RxjG)+`$w;6zX8Y!- zDy{`R>EP2#Si2s?=gp+moY$M-c)q)srth*jBjNW6l$2W{x$BVgnQko0OXW%GE%imq z#oaRJum122s*rPw(Bg2hkJ19?p0f;o<-h0K#tP{X>a#)R>%!1tzGOdj$QSmd{>FXH zeYrJkK6wJEaty}uG>{XF3ft_~DxDVbyk6Mxh4~o5uL>0*5G643GSY^z#9Z0Mg?w?) zV9L=++XYuADfc%e(5v7#faVs^t+0zwg%v?#{hMp5I33UNl^4f(B?_%MM$G*|q$jwVtzVtY0h&<%`FaOG8c6CYG+W}qtUsGzbm#W=M0*h#=a3B~z_jgg>zFZql^#F!R1Ih+q(GaPsmew;*oHS%STq`XcKK%&Ri{r{ zF@*4>IWG^GSJ}MyWNRh}^>7Qtfyc=R%`+EKkZH(d6Z~cYy_?-J@JwBW@4j1XgVz!S zueDMzobW%n0FP&rQ!qccMERh>gZP`n^YW1NX?LK#YIWnf!QfxL1nu zPp3M?buj(cxm)J*FD?~A>KTL)3wQ1Bd*zvSxtJd6(f)0-xkLtoEVVgG>FXY(1USk4 zaklD4n_Ph;dp)50LAxWRDX2{WBj7F_?D52&K&|zDi7^-%_T#UunkMK@8bKfW(x)F*Q*;hGDK+g|X41KO<(o7P-%G^gIh%*Xln9+cFpmzGTX3ee2?fCLL10`A| zH@Lcf3HqU@jgjQfi)er#Vc+e?%``I_wMjFqu0Wq(Tyzm2wmN?$*w#u^*)T)86Hum9 zu&QVFQhG$fR&Sa!)fns}jF!H-jL$0AAW8qZ)OTq7fR(bDp?>SOyBSuv&_Ko_!n>{l_ zw+Zp-(i_xYdDncDDQ&Nzq)?ZsSH=;z68epe@H3+&v*I{ z<)!carQ^ZLgnY~^ze0V%{^~J&O~`5Ttt6-!0-xY4;$mtlYZp=saR-FkG;9>@0&O7n zfiTMqn=OU@Zp>4NJo8m#$+-|XD=4tMdYYz^O=FV!>XJA!(8FEbj-vu`Hokgta8)wV zn5Dk*f^^_ItR-)R0D9m-d;3i=5EuB)IVGwKk0FWgyqi2b=lK?*HXT3QMSLJ$b7tE-!moa{3TE?u~#w|555pT>%1 zPk`HKJru}L)lVh}30(G6hx4GekD3>R(+j6teNUdx9_!SMbHMQ@Cnvd#n_mcK%&P_7 z1lbqNLsdP|eb!fqu%n@&p{uJ4fHoQ!w+C*`bKo8088L3;WMtxlBW~0D{T{caC_+n0 z2KxI2D5F^;9w7Y6Se2^u7ArrswOyPZ?Ia+GQA9xATM-p&{#!Tv=NdPrrly96HCl`> zCNQmqYsXVlhQ!xE4PHHi`-f z9c0X&GW&6=T!FNheY5qXqNJqDj7Q_=nU`;|9wYti!NLB%-6S(TilVK0)V8Zzrt`+_ z=jCMnV|Iet+Izk^VZ8TR{)nE`wRo(j`@Y%&fV5c5&SFo(VFUMT$OqEr0!#F_w3O{x zq-=GhroLBQ#)fa+=R_rHiKER+kU(KBMXV4Hmwi`JVq3E+Ht=DsA^!7gn(3_xg1lGDpUAv65Qi2!3*)$>nO;IZ4T7Vd;DD%%IgtFr%vUs71S;MZ0l
Md2#QV12}HbF|XtybrFNP3dYU(K$k3~uJp#q$w@>Bf8f?Hp&73eG#BD*R}dL= zJ;}Sx6I1q28LEoOQ8FKxWemLAvzTu;C>6B3FZu2N8(%`Fgn$3O^ta+=i(Pu5ezDe5 z@mq3`S7l>DJ4@!wPEKZUEtVujFe)Zn_Eh&hj4vqx4rD`O>nUklU@mL+G7pNd;|G6q zSgy|6u=IEd+miD=DPbseQ78@x!5#e$k1X`n<0A|Tv(V=pObKtH>?6&2g(F40MWg;O z$)G%$1Fa4pEv+rIKWGvsxqe$}tTaaK)|Icj&Q!~vyyE&T44V|y69<=Xb$nlPk%3=( z$aM2~LH%G`uKPgE@Y(`Y=q2`A@V2gnKAJrcr^gQrnDvUIiPS}^2xcr* zmaTb}>!2-ou_fWeHFDihAZ5E7YRa5oBS@JRB_$KZqdjtH7HZnJxG1FnxGlfj{;`_< z`u$<~q+IGP=PtptFDy<2=<-G{D?JJ{&v;d97OLOAc||23&!`yhs;UW>)lQoCDdtBS z=;;x2g$zjp-C;}Wu>k8Vv5_ieQgnvP`bZLxjMrriE+>%Za8V~DS&HLy^Y?djq?g!+ zR;;BDa9@~Afe03-QD{RM`oXqjnKzd;qVuD9w~)!532$l0)>^ly$)A_BWzSKe+bvOwReR7Xg7rV)42oeXvuVz%Nrk7WTU&EQ*Dllqh z6GX&W>Z`-)osEPVdg<{3r9TiOK>Gp9ua0rc=(qBT2s?b_A5JeP^Ca~HzAvb-9+$|P z%D`)VkZkak!@BK~60*oHVam0=#zGrx^lPWPEd!3 zKmn(74ES=25V$%;D8M1Q38lu^|8ZR9HgD&)t2HpCkTZn`n|^rq#d%4|M`?tAaEAk( zJCabz;Kx&W^mk8GO$Xx!!W2X}3Xw9QK$)&T8+l&Mh$|I`UZRW+J(T8tc)1fZZuevX zz}n8;_n7gRwYA5{~t&HlSwi6jjat$#d!MM_oKG5Bnf&So;@ax zAp!Y{#zVX-lXaH*uc=uGpHz<0=Yn{OuFho@eS~X2`BZY(7eV+$62mNV!I#j(SV4~( zYi|#<)R&i+cPT6`u_gX|nmiarO-+3lKLj*#7WcTJtXY9=aHpO28C*7=i7heky`}!I z-@oZd8Y*5+*11H5-6kSB`g_P4F>krubJer~7tuw5wyJ5YP>%m;C%C-4?9z}~Xw$kp z8MAOwPK%enAR@rcd1;7VEi>D`+S-8qx9l0SaK4?=Mi@AEc?HZ$3dJ6O}~Q_6NSq8Ql-ub4XFMnQmq z#zVjk#G^2e;5aEyw$yLktT!lUjX2B^AC6B;A#AYFsC$b%8E1{~nDfjQLULl(+_bd= zbs~BGe4wX-GWNdrh8y8yKMRd3Q_z;$+BFTCv$jd(WOeSZJ&=|Zq3h$QAa4EJsP&$p zeU>}#7!}1WR}c5q(hHZIJqLG0us6A-FLxXCMZKi7wFOj5F>6sgvg*048rs^d*AlR( zg=cup!ng_RfIVb0(c6pP_ITv8kEA~!tA>Px7;?J5diANLg&Kh?2W2E|UG9DjK1bVt zA-b`#0Z5`A99X&*;jwu{@!Hfq93u20PFpvrxt*V1tJcF1(~oOj%n84RDr37zOm~Tc zed8E!Ug+akU7r=;$Gg&M`66#$U!6XM{R+dW+0V) z_i6XR<%)~Rte;oQCq^c4v_3K2w%Zo=OO1N+I{?X`sKI;0uc|pZ;NBAO4zgmet^@UW z#-5$##jI2hQ*tJq-knd2(Wilj^NSsexLB#?<7^(XP`WnKkX_qh)on`?Ldb_1%Q2HW z68Ex$&d{pxsD}gAJlg_G8UnW?M}9>zI`F8Da7THyJjh96Wb;Hmp^yL~&DVmx~*pO4c`@?i=! z1CVtEWZzMD|EXd`I}=|cARy?W&6jEJdgSzue8F1G7tv1c9?FoOt)gr(6&em11=($Rasd%W}y=&xjEZfkKBoD`z@Az3$Z}k zXI0a0wX-vbh|Oiq8AMl?y#(5!#GJqe#|PBJ@RVQ@Dd75xcL29m42?z$InI;`*_&xl zgw`6^`$N|(H{pyXCFvb?57w|9UU4}Ybu*=sinVf`NG@YnBi-bsygV;k# zvd!GdSt7F3cM#0TUdELoZZqkxJ|7vpNSFQQ-nx^uSng|T0Tl1+056Qs#KB<$B%5C6 zry?Z2XXWl5v{>4ynVEBxQ0s3`;{uKFT-E^*$nWkF_W`H)X>y-OL zMGbhXQZEwt6qbrmbx2_v|7~obx}_+vNpD;;je)-#w-Y@7HOX@-`iDxb_OSX;U}1rq z@F;O;Q8fiF`x~QKe_NM=6YzQ;d+|hQ?YT*q=<5LUSYw@+YF(kAj@@^vL@rSv?jvas zOsxStWY=)~&kot5!kq{hE>ooVyJ=OVG(lh@(A-Y8MCoO!Me(fWA6{AYIH+CJpSgp` z>dt0V9Jfopz?&KHHe^Dvk|c9`tx)0yxSA*aOV)yS)!C2m9~>OyE$sP=??-gelR(9d zI3n!M^aoQ4rFgjRn|>=kyg;v(jT1kLP;oZCG?nHeLK3W7a0LBZ)8P15QI|R|#UA!_ zCd$v<{h(iH_NSY#jSX80df8c@etyzIEQXZk2lfnC%$dsC$?09pOQ~+BT-N!J_nRk9 zZLBmLKlzPx7C()yalQ=2vRB>Yybj#T>Zt9JOn!-NW{CL5!|6pMjB25g4p#Y!)YS@{A%TUJW7UaEGY)NL0}s+l5kY4PB)`i6$$d|O^c zYoa-{z1V=C{L!pt>N2Sud^(UDtW=S+j{j+UlwOGCK}fD^swY~kCU>65dc%=@6bn)- zjT>tt-A6^=4_P0uG@pR(O&8#KeXItC_NqBQD=fXA8ElxVQSAMM-x%FA3S?hBcfo=| z+>T*N7$fsN(T#qwr-v3d0(N_ss@wmDutoq1Ky|!%lqK&yzgG@Ubg71_gDfMgC5^7D z8o4BLP;$1Kgr?lJE!(KoDeWQ}n+x3_>>$3*5FW-g{o|Ie3F7(y1ZJ#ut;k%*mTAD5 z2HJ5%^$G4!SIW3jJ%90*1i%H4y|BeRiLB>`1|G8N!MxbO!!U+C-2|23(wsv-4Nr_i>cWihV&###T z5#sd1p6bkgE0+c;8evzX6h~3~1qim>^}^1}0`HRh(U6migM&Y#pPR5|+%A`X(QWc8 ze&^AVr+)I$l$NZz$8mO@70D%)d-d)$oXXR7?!}OFMn#|QTGPH1y8XY`gUfZ4lP&3o z`5#5(E~d-=$2;l*n@BM8AV#gL!>KpJ$f(Iff=Fc5L9B3RGSt(Xi&mjrj12%sI8Fkx zEMZoJTsQJqx5XVn0Ut|Zn=XhzsL9ls^O=P@?A{4kCp8w`klNW^LW8nJ@{UdVpHdPf z*}IiNBmkIr>;<@79o%-44*Zm-8v#)~=;}Yq%R#gzouZ-o@)E}PWJzcOqTbSJYj;un z_J9(Cb)d+kdh=nuW3TH*|ME-@&^?u+pGSx~-I2TH3o>V8Q;G;x85xT)!O0o2=VCn* zEgJ+iho=pulUO|EYEJR>N}N21Y%r{xO4<8%qn+C@C4UdB_11$+S&vm(!|%+wcoEbw!jm) z#Q~j_wgm{ZzV9w`n6clvcp_sLcjM+2FIU%mYAP+S$)wMVC#Ia3>?R5ZDlx6#vv28M z0s41B>1Jo5QbL<~B68P9wf!A7Itz+E_665h!Wf%hZAbkU%C0^|1QcRW9MvVh7PG*O@*rkzVr_Dd$i5oevhYYH{LVpH zw?!KEQo>yfuY1&EStD{;<1IZuJ)t|Dc`J_eoZnv1DGiYv#!@aK_yBAfuKZOv!UKPM z!NPwPceQcAdWkinokDpaTCsv7xC(&yk4uhP2Pqb^K-R7ppNL*+oDIV$f~|~EQ;E*~ z_>4O*Vfqs|L04HB^sZz3CNQ?ygB*mvBm#j1?C@Fx;%hrQJ55bZ_ZSlTEfd^XRYbe3 zrm~kCDozfu3qU@uuAi}|B9Qi$RDOKH!`_JGrq{_x($;KQ@joSdAD3_jHn{(dN$PSUi0c@LuL?l6D39tSTfkd`$C z9aRNvbM~Mnt?x3Ua7+wc zjU10!-|=Xvf}k+2!c5qqQQWy!x0v2WFyB&EQu1fVQ+0$woik%ZAUX_G#&2k;O5dFE zU4^MotBwS|UuwuMVTH?vn!aefjf^udZ(9*hQyUqLd_z03Vx zP5=DYJJBzadcrp#x< zoGAyrr}wNq4xo>;Ev`n^QL7Vcy_MYxk;Nsw2T#{X{LkzJ(G&@(`NiqEtkuJwOOjF7 zFGUc~D60+XBL3)Z5SycT!mDQf^v10@;q!T<^F{5Vpm2 z&H4^}^^=VTBV#th7LS06wM?b{I5=aCFg%FL__@>4yx=^tCvJqf$CDdIbU*tGGRoH)3eW3uj%qQ*#_wyf{bwk2oEg6?%GS~PELkA*!;m~|X; z3f;D9BXxIp4nQDFN~DPS*9$j~t{OHFEeE*MK!RwNmK>zuDf}352TO_l!U?j__Go60 zYuU+xiC=hRyY~*&;g&VywzYq~ANUt@;{|eqK-dhIgCM_EU>k7R?B$fhUz6oz2}?eb zvpgtazY=A#VK%n!4Hcy}6IfjJk-84r-4=(+Yc^O#I)qT?6s_b<* z>H=va=*>6?JEo_nb?ZxLh%s)yv+h*#+M`w@w*$W(_$VfaDVPz8p`*xWe1U_8(yZ3? zMsSjeM6o)t{|_*QLK}cUN)ZEWOmze99|RRCK=BUFRG2%iRzG7Uu1enY&PG{ zt_t5)6EL;1F%*D2wF76$OTi2&;K_B2#fooc$;NwdvttsEQV(boN)x+Nt_ zGNu$(HTv`qt!nO1P7dZEVv)B{(v4nwf1&eDbz<*=eR7d7ttBxF^w-Z5Z0g&NK+?_777UOQwcC1F&3Me?i zH4o0dzyVgQ^-xjWg7RML`I`gJZ5Tion+FnN91GApQFjDr%%j3Q=)Q|Z$74GAq>l_U z0Jve>u2ZUAd;3i1rGo>fzFGT_`AToMNLrEjpo@)H(> z0l8TCBX!^4-TTSfl^E3#Lj!}}e5rz4s3Q@=%rJ7RA z9-@Q}ojbnP>FOlcL#K$vAGTL%hJm)GWEvFccfcVC;3`suufl9xTwQ;@;3wGfH-Yccckbv%moQT zZEY=U1UNx^KNI&23;*KB-DLS>_qj}@uQqfwA_;seo3m2 z@)knrpszAwRntRp0vu6io6>P=A>fbvDqZ@$Lc2~)!vY$P8kLw1?q=VU{fh&P|DMHW z!LnzC+vnyli^8`ncfgUVpSHEY3Xw0qeERfNOdJS}jGX)kwB9Zm*}%*Jx-vb%n-*14 z67`}=YdB26;Jnq16}=7IIzSh@+HOR3td&qv=fmQx0Gt8jaXvkJHmwF0w))FTGDnED z_k}?NcfI52p?Hd&;PXn%kXOlZ0JOKA&ENZ7)(zuxz8sB{)lb2Ew8JuCl3WD z06}LE94=wY`AlT)p6g9{IlljnkpB+oYeL<@h+NPe1e9)#Vl4@A5Zo%(T0OARBcG)| z%z4gCO=WVRduV_11IPjUATKEBs-%;gwl@8QPs0;{)$gOC?}H>W$9I3c#(Hp`rF|?5 zuN^d908R(ax@_Op_$LK8-Yy;0`Lk9fCj2`$p`TN^4rqS3N8C{_&`^gn;RSNF9tO7IsqpgP zu?xR;Os5zk zZYkivOzPZjOVhVsAqOqyAkCmSM^EnkEJtSI*U31rRHh=o!tRdXR4#Bbp6}mJ+NifT zfgU^sJ|@-m5?h#q7hR{LCL-Oox4?nHtTgIr7r9mNz?aLO6N6(liJ-|(4F0ZN4^{?C z^_&iT1x%NS)J$Ijrh*GGFRutI|JOb1YjiZsfKkK<7=B>p7QaICRzg6Y$-kgcjS-E> T)*PUKflE>LsZ52mN#OqghXEdX literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/footprints.png new file mode 100644 index 0000000000000000000000000000000000000000..a04727eb5b718ffb3e7f6c0ae3807a0726a26596 GIT binary patch literal 28711 zcmb?@WkXbL7cK^hAYIZ(H%NDflytW=NOvpUT|;+@G)N0bch>+S4BbfAxq04m{=wNF zbY|GI?^=1SYfYHqCn;n^d_*`nIArOM;>vJv&o$xTo-H9f2cM+&I~jui-q?TCa)N`y z2CuO(p4Hp7tir*O!byvZsJiR#FWY?4S@2-K2}u-Jj+cNWn_eeH^M|t;^Kj)y@6kdB zM#5ORqNhHfp!{&bH$=-Z`e2!mh?jGN@vmDN5liC5?*R6fX>S~VVafY@!673;J<&`Z zF&p{|RDM^-q(uu@=#5zXo;MzJvoKj}-jugSsxpZ=Zoz4>S9qZKqVHntam|9f~ivK;{q z4qx|nB46s<6kGk?oFPS}_|r}VzBpadBrZp2PmhF;Qh?K$7@ANMTv@4}0o(}9ySKaG z@9T$6L|j5Im+v;{uGV{Db_gwohetljOdlN`X%H9=dA(B2((o1T zAA7zPU`LnqcXoX!g?Vq!(EQcw*SEK~*8%nqSb@t&a1W6ix5mC6P`?vGQiNwYkP{I| zC>XI@1h46*7*lu53p)pgiT6uos3Hh(jK58pM!_{UHrM^3Im>~=_3p}H$gM_@Z4AR7 z4NhC5Q#T_slQJ=E2^j^2SjacyJ6(q=oy&SJa@qQDZ6G)UcX7uFLRgngF{2I@FP5L~ z_3}@Le1}!Mm+#@e!lOvAp_e8NiZeY7ALj=%J}|sTcm{{a?Q>ISxXFYqY^7IfH^OVpi zj1aRo^Zv{JPq&%cgL7mG5H;#s~=&=6ZTJqX^?>C$Gv= zm>d7^tx8a@vbbUOf3MYZf3S!Cngm-7XO-XTP!fd%9T2O>e;S(6(m_+yJh`*86G+fN zcIdCqPgA#2h!9ILDyk1^ZpF2Ddc?VCRJVVjkrF{b0B1WP8yws;v_hwGc6OE(GJLq) za_{@t8SvWeV9{l7meHmbJgqp}*VEAO>mxXt`|B~k_PV+{A9{NvY%t`qL&?STrw^s7 zyY+MW>r0BPPxHuBUblC3b@lbt=k3X1tc(0_&>_OlBHLIhw%k$(aLtA+SKm;*?Tyxc zv_B8^@61^}GB7Zh(@^aN6LCFQgq?fd`wB5j7b*)qUXL}}!Sg*S;c~862nrGJ%{Nqj z90cbZZyS1g`Wqa^FJoB(FJ8R3zrQ~?IMA5MhllAy!5Df$MkY$0v)Q{>~(2Nw%F$7)|M1Z7$CY)p2!MV-w0z`lW6ln^W zmzgp@RaR68cwez3$?WXuj`K!nUqm?6%AdmrbascJ?#VWmcUQ`{w8O#uQqs^+(9js$ z-DQ2mLk!wI9#_}-CQOQkV6TsJyV=hovh@rj!#gAB?$NWq>+sOlC+^#7a`S(?m4l^C zh@nJ-wP-{+od_kloN20Ej!di^V{lejfu#A_*hizmIZH*qz3~?GDNTw-@skSaXyMyF zac6~`UtGA>BS|l3VJ^NoBg~aue8YC2`gdol7$%OLjioxbxJJ8xLd^eBr}*uv@2!nb zJ{{e`$V59QjCX9880e4lYgA$fyg(qd&b&TbqnUD4D&-_s*lLT_`t?ms*MB-+oKtr# z)S8?A9jDj$q1)lBr;ZII^xv$GowVKL+S*!ueZ96z_QG}g)WX8fiF?h$7Y;wsTuUrC zXF&tnz8X2I^a1xUPayxzEw{F-4T4QGX_Gtb=*ul`3bzh9`cebe1vzZ>kbl#qDnQ6) zEU5$>{_Z$?y4ctRg%S%g+`Gjr->MKj8BaZ`1j@XbnSZ^#MGS9)F3^?Cw|;nCuE-YR zn0O$`6i;0qE|ZfDt+%B4^BrAlm8%4Q6V@Odmk`e#Z$CT~mI|Rx(4rr;2jwc37{;U%$rNkwz)MJl zROWX}iRzjo%V#vbH$*I25$BfhWUP*x}VZ>w>7w7Ol(MokZV^Tu~XVIXvm6$7K{=liBuDrLG zetFm?720+nV*xGKMXZ55U3ebJR#~jPB^51Aowa)62c))@21EOp_GwAp zw&vE>pH=p^qnU1d@Be4@v9u8}l)St`OqFOb`=%-2wSuUO&u&|wFOAxgzW(>%iD4`g zGbI|01bd+Xi=fnm>VsBxXB5%Vj&!a^Cx;VTqRnh!wC8YGeN6BJG>9`;-_45UU&Cyu z>XAfgpY8GdZx{p=+WrEX@7-7?P`PI7Ii`-)j&25B1B1OIzekzYDCOr?PuABKTTWz= z4pHbd4)x5V(^FQY0Vv4DlAV*~Pp`|vOx;@lfU0U4;in_csWPlO8qdx3r|pj>5%T>b zEHq<{hzP|0PiH`(>DrBF^O}rsl!gI_=z9e#cWt8hv>nZ=|n-q)x5`wXjs zzIRs_Nk68&x$j1E$zH<-*4kl1CvQ7rprA@uSP5 z4R51$QLyBnFv1XE3SXlT{#oL(mD7o){jShxyUgpj(LZ`S%1-m-WE|AhlNXnKcK(TR zpm=$DcCE3jexgbsARyRG?ee?;Yis<1Lk8SmctcIiZwDH!t4>tkSUZY@0T|4bwHIr) zqjA;O%iTRS)b(gZPrDEDDrl4yPVq(DM{$GcuePgM9(xrAOiU{RuKVwpwKO&VV3~Mb z5+^PpuMH;Ad*|0hvmqk_2dFx;v9WP>V4JnZ>o{{G zqn*)AzTL85dc>6EIJzZjX;KUb%=chwIJ4A^t?^YY4w=jZ41d6e)v z-2B_A*fF-Hz<8|mP_9}F7sXRVfBQ-yTd<(i)BKjYuxO@AU(et{EI@V3MvE}9J(D|=H%$M~s; zP){$fu?(KG-k zJ5{U@BAR>tbh(_@U~HmA^zI4{PCvtzUv+o|;=G`q&(+k~-tnOrVIagE{_}?v9RzfO z4_E8(V`ma%aZl4H%nK7I!;iw4n4VUx)_NBv{&33tcsf9x&F{4Nw$Hw^_(usC{_5Vh zWAzdB@fh`{`M_a5RN_7D3p$xBp9-a?VDqacL$CQccP|w+_2Z`9!)6$D);q$d>uxfo zeIr&n?xTsfcZQuTVohl&tuLBmTu`;<{`FRNN_?W#@^?=V!e!+-xw_8g!W92jH8xg) zttK0UIeIg$%2BN!vl0*ig+RROfyZm1$1Q^gn1KxK!qSp8-Y;wp zZf^I#zu%C_6e=H9a<7Kc_9rJN2L}hI-I~1jN6Vr7{kdAf?`CQh%sI>bZ`jjorfxB7 ztQieVd3pK!;}D@l&3F|zCY4w%vs^6%K_Ip9aR~_tTVvT9=-@voCJ%#Z5e{ zs%WKO?EKJcNpm#G4e?uq6LxCxy>GrTXN6>BWx0-0D50U#MC--~(#72i68{EwAc9_x7AR2CiWrII*-zDI8{Ms*v*~timhX$(VW@cvp zB;YD!M&6OdH{}j|DA~}*W!7hR>W{|{Q5`0NxVkw)1s3(Ie6NQLMz_v@4JV81pP!%q z{re?4cD-!bCQ5++XqLc`%Io8$dAY@FCq{M4%d(>XQm9?E|5B*>rxXeu>j>M10uhxc`JMMPND|z|5WSQI8+1Y=q%-juR-wl*kwwKw7{5y&9^ZxQB zvNoH(9|Tb=HS^g+j!^4PEQ&k=F56>=^ZkX|%C?KN_U1T`E0R}m?6GHCV<5V72O)Oo z5B)Y?Ha4e&MGl{Q#-~FWZt*U+SjLzXcOuDWnHn1)Ac`Sy1Q5~zi4CSt5&q}6peV;3K6H^XCfk0kT& zb}LqRL_@M&Dsl#RDT74c`zS3Z_;n*QCdouaMtWb=X3uDR=}G0u_yhE1%ll?Z=w8JJ zyTyL(Ij*1FNL8iJfprZOlIEY`y^FyXpl0=XWMri6;bt!&Ai&#zE7z2&4ewj4OoKCI zWSp!F7bKlHyI~)c(*)p|w^Xd*TYSQS>W)O#P(b8-Pa+H`aD~}9}eXmU|tM2#B zh3H$jxVSDu{H{X0bwVe1sga5K1p3u+c-}3&0DmoX@6TFFo`3|pfJb2IAtw>1f4QRNSrDFp{ zb3yttQ|UXie$vlbrv`r-gtfV~bscH=M&N62Z|{}lnF|JO)W5VQN0?0YmR9Bo^-zi^ z!~5s;hUx@nnSPzXa9NG*GY+_ue!~fmPf5Nu!Eqh7^@@s2`A8#1dZn;f#;Ue@GutS5 z5~dJ)Px{)-EVuc$(Op1#xH^(5ndf>Gm+xspHcdKzSMF8YkxvX^w(87Z0SQK6VI3JkkCSA=jpk~+G|0NwXETe5@yjzZMJLi zrXotPu6%x9bJM4DP%d1R4XGYMjw)d{89J4;CvmRtSXA{#WlEhV6l=QwC;%f|l=hae zE5;aP_DV9>;lO39hU;NDWE|U!Qq=aZ&wi@mh3{vGkU$n_z>Y5(=*}a(alels=3Zi($AcD(h%Kdz*TJ0AHNGCVp4maYKKo z*u5-uE&RRbJ-$R{lN~7xp>DVXXzVn_H9JCA@~_u!39fK|$%$+fs78P}7$1+lqfLq$ zJar%OAZ4(|N^qT~ha^kZuvwY*a@Ez!w-z=*2yI5{Pk&gsWTnj}+r`P$L?v>n)zeO{ zA*%*NeaBZi;GK*0@hz$2ujTV8iTBQ{*j9G?^<9L~a?BbxZ<84=VLyhG-`LglVq+lT zj_A)f!a5G5XQ>$k9~sXS!iAh}@kPlEaDmj(1;N)S!gxlgb4;S@`@oM_Cu%s+5v2U$R z>Co1UAVF2#N!33p($D$sDw&eDFW?_Owp9TnCH_z||t<7q1B(5MA zmy|e2+ficR>e^^1%9&VPh`$Z5v&b{TsgjVS)NjsCB1%PnXyH56u7#gD)g?uzY`h#$ z)quE7q?wPjlngUOz9T1_CgivsecF+xYbjA}5Zsa6Z%eryLf@O7Hl!H%YK`K5mG&Gd z!6$nZ?|%9I@yu*9M*UpD>|w}lUhW~N1=`F1p@_&jqfrT!W|6btpO$?`6l@A2bT$&= zSSwp2|Jm9Q(mh3)hz{KpD|ORwQ=qiV-^W<>^+UR~nU2W`8%W!7cnxFEx(ucy;C-bSlkAny^bjxnTY{K*UmLd z@p79}1GcEBsAtA$3dQXSr$HaGKe<|3S;;ia5zDylK%1O4bDkF+#(U~4OS*=ol%w`Y ziBTPGOiw3zM_mguPiG?)+_A(jjf8Yy)Frtt*1ruhB}>!lk1>0Q7%w^LjhB3h$fZ@n z=?i>+>UFVi=;^&uh}?0b67O`*ZOLHdFaKq!J#{{Gc{#b`xt`OZ!7Wj>%}YlUlfVwS zsi`UNZfH?fQlXvfl*(Ctb$?d6fcl0ZeoWuBb%q>Oy&pUXQN({QF!ZS(z*TI15X!`_ zK807Y{>(J7%O=yk#&VR3|BaB^Y74);Q^SFb?7Z(KtZ=MwtmyndrYe&U=d?084yX=3s4GIazb8vwD-< z-90%=K6NqnsVn|cvE{EJKk-)I&sTg7b&$=X8u?n=rM*lIar+4V9 z5LcgP!aP4C6EfHT{pDoh8x=b5cYqcY{So^xw7Z~d!L+u{if$QH3Q6()y6J>gS8u#2 zy;`&WJi^Y2Cha{DN(ePIbuqY#iZ;|fPB5I9Woc>nk(DetHBspx)-p{KCnPqK5u)fk zc*jvyANgLk@Qcx=1VkPQvalR4T31TrIse<9P^6g_&J-DxIKa(!35grJ;QXwlnMInh z=&NU0BBmx=;*$d2`~L>`H5u32T<+ zmaM6PBxrqoeYaGcW5vXn@j0H|nE4K&Ot(8fQ$_uv@ud0*V+R2UnMYLSl(DjSoHnV2 zuEW$1q~#>Z;@tUtuTM>*yA4^~cc)7q9v*`Ewo@c+km~o*K~&Y9^cR5a1V3scH4GH3 zM}-b@U%G~rNj9EUhU2j?HF;a5q+1S;4ZUYpgCa<)3wi!MapxzFk<6d4P$hl@`q2%} zXw>86Z;v=x+(!zTC7ah^su?D_)jQ>3U29b^R9rG%5bN&0pYyJv1BuV)>VX020}TLy zwYs1DZE^zG6<^=llTb?pbsL?dzvO~oOkAIB)f*&iAWh!dAB^bY}lvBe7qg1}9oPqN9Yj+=K=@1W&SKCKJ#oZ1?GB0shf zF~5NfB*hTBpM$U+NkRYet>=s<`AyJB!ZYR1!o>26$s+}F6c}J7R+>}^(w}5{k(LRF zh>~8<5sSy4-d8k==POx0BPJrs%*cooCj(jsj$-k}De_Q25|%$$?j~xEJO3#8_H`K+ zzOTu-5wk%%bZW}!;qIE*dkqN)DG>pI^(^t&qUv>+k}t$(kso zV}e3kav>BdDyqB*8eAP+#j+1tiN`oDxxaIhLr>hj-Q6{xTY7uzj&wxeGNYiPme;Re zUH!a1rIa7ZIxbeo-n5jEzOEoG(BF9O?C5xUbG`>wr66!V4Rjs1{Wu83-(04a?jRc! zJdlbG%8?0HU{_ZPC4Jerk6%gm`;c9;kVh!fiHgU(LK5ZYC`ZYcO*B0^CpO=^j}&C` zp_`m!7-7fO&X2~F_)%rd8G9csEntYs3$0ZX6G}hsuIioc-R^H(4n_c|mf?3ACy}od z!VuZF-pcufJr?Nkzr}iMU97%o zQ3T~Q3<~CWUvIW_dy_tF!mjo*?7Mh8i3YV?auYp|Dpx*5ZzeDGr(>?}dSRf16k1Dn zl2A_Oi>K;HhC_@p8e}97kI3T({~+p@tN#$kijpimhUqC^Qs76)9HsZqnl@3iJq4Ff z;Xh?ws@joCoa&|lh_1kf0cTxXTMG>c#`nv~{088(F-iM$zWPv`4;&^9?(@2{4>XkTVy+|Hw{;ecah z%_vl*HkHi(?h}irEg@Z#^X+Bm2 zA!?NWYBnqnWsvS{`{-EF`)$1(chu0P%8;YtsXIv9xIW@1Y|hiZM>0k2UaRu({bXUM z%8n0nih?HY9v4+lJY7nMRQXIB#OyV{jUMY?O#%StDILOP(&cvAjJ&A_k@JAb>EE6R z$LH}W)&q17+^no*ZPEdqe?a0o%0~KbAL$i9^^*#sI- zDB296y$048HWdxJR zM9KZY<-uYku*(eUUOPE)IIm!-ja9gk|MY3lyh6>F(D#(}dOyGQY*Vm&==#G<9Cq=i zOuFktBbIr${rQlVmVnY}|MnlBDd3SVP+an>!$m9Ga|D0#&^<#4$*^C@8W{dZ_buIX z&ekHwHMXANoV_N>sebE@G@5Ws(hBLT=oHvE;|cYq`QXdlv_JOBAwHdd4!g zC^J9Rym^|_>IALf4>uUq5!hrTXSLjRoP75Pj z83Chqh@*FkUd=F%5=$~+KY5Ecn&nrbdi>_mpF@RCKUg?uXT+U-_v$zm;-L5r=uyCn zl)TMrWO&#Y)z-1~|nmJA;Y!~8*)31dNzA33roVe%Cqlm$UgolicahH%enbJC&d@@U$7`pS?DuU)i zR=Ya8P)H)7adPEi^mOT@n$gDBPVMIF#&B1EsbtecX18YCrw z9&XGsSfj`nt=VgOZbwE(gAisF24ikL_J3J0`)6QC=nOJO$mhC$3~Vhb3Chdot?Emf zzT^E}{Wxq$sD$tM9sXJlA()_&6#bLHCJi8ROZD$GJf5#MKE>H7Cn$KDV^qIs7mrD6 zdN-PCbocGiX*X;nV~K8=J-b<&d7(EqGXL}dLnwOLNKcK0wx{W!)&b`&8`bMe07!DI z)U~8DLkXL09hne=n$!iOcXlj^w}f@%i(Fr@Ok;+ak7n@rJ@Av{!wQNbZ~g@E&4q$; zqUT}L7O}v~2>>?@at-VK4PwRIxw^WVpMPh*rY@xXczk>mD0*AxRSKk9-KhWfsE+tG zBd^2Xmyd$6*$73!G>8P;2)QCnZ+SK|c+Y!z9s?nGUEd)YTEr(1*zI?YglM|%NxjLM z@%58!oiAZa!w04J&#UNfr%^blTBclv-=p-X0Pop_#C)7EC_OUfy~*Zi|G1;zH;A08 zjW);xtd7k7Nj!+I+Yi?4Q#I~4xz3P~2*le#t=+gUdf-(N9ea3|pigrh)<&`d$KyZ7 zFVlWXn&N2M4=tZjKv)L9K-9XMab`Poxw^J=SYu^k+fe=eV%SymwHY++{n}lZyj91z zozI@ml7=njGX6j@XRK9Sp5oFl6ID?6Qh%kYK^ZW_!(dO&_vT>uNKboq(t~UI;>RPX zAO9P%^F2#nz1#f#`!_(-uF`)&%!#pq#U_jU6XxhXkkY|VjCjxj!nLlh=jc2pM%Xv~ z{Usikv?UzA&0|7Jj}k`cA_&6juho-0bXl5s_L~=aDOU8NW~D6&BR+Is{#l9LaOc^k~HN6L*1)*VEGj6?7jTA5;=S zU48vzHEV17!C+W%QI0N$Vz+z|C_611?L(O6E-7gh(M4_cDcAIiHzHez}C ze#0_BWsRRWrFopEu;APDw+wl9FAQn<(%H;YDsG|rtGg|s#~xruD%Zga%2?aIfSO24~xlD>6^p;tPVf0E9MS~r@u1Syx$Cisq8ySb(XD!XFeK;(5K zxyoGUuXciUTlEc;UWX%e`5Tzh{VQ}nL#XH;$*rR0@sp-2(1omRsyNlki=aGeLiyXp zbPB_TkZhsrl=;0$gsHHH5-l3pX`!IS#-7vK*lDf~;^d0_U9-&jm|6!y}ds395$Jy218b1lblqlqC#@qFy?kIr|icJCG|g`d)V zTw%60qo6s@(X)-yl9D%9fz1+hmxl=U%dPT$eI7V00NHYE2*gUu>5gRqgcO zrBSKxa}7(G!Ste&mf2yjTJV{MQqp1yT{evkh>`($%$Y?p^YG9T(9+xyWVPZ_8p6VA zv|IJv%5+=t+^gt$x+HwgM?ulYUP&`V&kQY4T>P{aeXwgp1d2RFSMbm@Ol%IH5P#Ct zrpchrg1$WdO5>-u9LI(UO_uaZa+UllVMxmN`e-YKTuF{%fchjzUq67T7}W8>^@I?v zK3p_1>osFV^!z>fdE+T>g{n-8D0E&bb&!#a+;^fdGbUx;5}0hePs@H-zl0HyD?|jXA>1)Z9;W=G%DGgRc~!n2+nXsQpwc6F_#3`< zeCQGvZ5r=Sf0Bd<;>+w5F`RIv^a(82qsUn-TFRWnDjkCM4%qMCf%~=M-^HIl4wN(L zw_02V3!M$KF}Gj+jbLu4kyry6o=4IGFMeY-At^=}ILLHu96*4=M4t%eyw&y?C=~&w zC0@MM<7{)3;8P)SMPnYC$aeC=@FW_(bK`O?UtrQN)?W-Ub4e=GTa>wlRAhZdN&>PY z&TdRea@uF5rZ~;uSSgYhh^;v#;%l}5&SQam9Sk@~4H(-XCAMupaI7@X@&JYH7qtc>6(Bx0!oMowB8cMZbp^nGBurIYVu% zv~Oyq#$nzjvPwD`<=Vy!C@NU^a9Hjsl0R~a<)W>Qk0uP*mSpSAzf+~!LZR#$nN{ME z@ApHzE?RE6%xb>F?YPo{`RCS2Dsj0^+SBQo(Iws&(h>%uJjTM&mFWsGLjx1iZJ_qG zW3G=y(_h)ey7013Shuj326mpXg7uBAC9iP{3dd>XNmitU!Fj&gZ>sl}c}bC0Dg|lw zcbyRI0*K_Kk+=@i#^;c`;u{2Q$y3|(ihR*>{A+V@3XCTEwGP3v;r`k&K{1`P{{GnZ zn%4oh)n}Ab_@B;a)C-2>^rG@<2m{qNH@PRbhyC*Slzx!A2b68%nuXYL_#L94l2Jnd zEWqx#Xd1J;ZcjL<{R2f-(5D1`rX+%x-3q7dO|DszGdl;lc&bEhE6=WI5z}-#1{6vc z6=+6hf6j3GWr2YZC1fTtaXDGd>h{FqZs>~C75W#u=S~yT)uL1J(WVXYcR+j??@ABCTL4V`=h6T_g!4Wij@{k z01kuDb6Z>v)G4zO8P2D2XsN3=EF+;l-YMQ&j#JTR-}rIswb0eG>$6kXkRzj))=x~U z{1TXZm|<1SBcHwD@vm>4fS57-n8|&@Za^l}A*S`e8TLc(UcBI9c%)T_==F^IhYu3J zwk7UkQYDKE?GD0!Ny3X67Px>EjQKJAEm!o;V??bO=P$_jun$EeW&j5#xWx6+&#cxQ>{QWG*@qJ01InoTXj zB?(KK_0)%&!7JSHkM#73AE4tXS{RUy_dK2?Yah+Zlr%bEE%~EqXPkW~yxCp53?$fe zfKt4M=H}+6t~1O4$Lz>goMz&AM7_wQtQlJ(^SdL*h*J$uZLijQjBM*^b)MMSj}KFK_)dIlPbIqBg)zs`u!#zN3Ei<1RFt7WOzr7`Y)}d% zBqmPA<@oRc%@T9^zFC_fn#$p zCKPz2<;cD$?oQbNw2ivjyzw7|CX0WN`I54(5@*!*EEfD@g}z*WR!d07A+}IYmXeh3 zgriRZ8U84n8F7l`?X}SPDpCm9YI0w-_e()EP(hP*^W#yLB^%`2B~nu|7Gw+IuDf#^ z`F2yAeJ_`+xsuXgo~tD&6FGp#{m@Eb$l!PEfUqNL1HiAQCZ0vlDT*z38)dv03+c(l zf_B1%LJfV7pvOcts-b$mBZ06Gq z$Xj^p$_ixy^|fzFLU{&$-j6WwZJ<-=&LF=ON=yzN=26sQg|I7-3{GL+C0)aq{j@|s zPxt%@ubPl&{~@PV78jY=Qo<}QKwC0n;s^%_7%0XVh!47Gu1oe;mKFK_m&r%;EgRlf zi_)1JEaKu=42b2)iOI`a)`gz}&<2MNFTWu35T*qU*`&6Mu2KCO^k0GwyXll)On-?G zCxbrp8ucy#xVu(!gHM08`KBCC$%<@HltYmbGY)lXkqEYv;TO-!K|vvvbk57hoWCT? zblpm^wy{j_UKB;x!MU4Gb&JLkZYJ)#c#kxrI^kBP$00E=}%)XHf=QqpI#WMl%0R zQ+m@V#k4MRI=-81n6OQiqDMj1w{2n*cLvCuQvgWD&ik!x^Y5FpQ&SbixPZY}4hasf z6MqxZ-5RJ89tunj|NcMqMrn_i($CRRLOlE^229idE|fCdNp%TxCmQ71lWtF zj#-2V`K(~J<4R@Xv7Dl(6UfQQS**UcX}bQZ8+Af3ntphb|Ch4o_u2kf-ZnH8ZC}69X7B^<6+L);8Ymlk0P9VL{W@+}uzj zD&DBK??IOY2y?9GddTk)%FRJRN8smME%_CThd(Y44)Wq_2R>6U!!qK{s~lRt#cF;G z%PXT1;}RL2z1C`)pIV*Bsmo^Ymr&@hw=Zl6YyzsQKe*`P(_UjKF`=>x2pphA)v0Mn z_XG0Cf7njj?;}7$jN1I74j8EZFIIKJfDL^6+@rT61!E zB!e6ZB!j_GPiUvHj#F`|TO#bPYH=kxDvBrN79chJ{>K2A0m$Mmov&~Ui6q@h{Ho45 zhgCKyAadQVT()xw2r!b!gM=hT|0a(2Q4A2wSm#{(Vo2Ob0&NFH0C&p^MQoEq5UON8 zDy*TAQyvj2dV7IB@prjJ{2w61GGdj8TMu;$_yD!2`?5dlo1|k)Zt&S`VY`xugQ4*Q zDq6D80@SWsXyhumJ?MlRE{QY=4IR*OcHW9ctK~~qG*6oi+Yr#Ydoi{Rvs1!oDwzr@ zywxB&GOvb2>%aVk5&G63KWZK8d+Yd$QDD6BIJk4AOoGVz{mUl-IHl@CTP-MT+xgut ziT@i=@I4)du+_Bj&-Fy$X6CClBnDf%rEJQt}t680nY1}6JzdOa}60cAs>Xj3h8-^3D7I6T>!ZagJH{~Oa z5gj*4w~Xc$8CH$e(8v{Qta@z8`;;Qt`U8~bXhj080cYqr7Q1T*1}PT?duBj| z+T2{V=VqWrpJ5BVqqc#MS>97q7+_{%8k~7qzrudnYO#zRVW049MRit4MEo97eM~S$&BzqYCgP1FgBFxV4KiysIyRc^&si}4loX$=_XTw3EPoXZSy+dThj&eGCOSMV z^fefYN|lAVzJNhiZm?62PRJ!U)Rx4J89qC9Lxteu404wa=Fi_rvlB-?M_x70I(}SV zU&kAuA7!QeMPVrJ!6P70*=m`XWvy6`95CIps6NQ+^04>OvJj(U2TcQ=hEj0k__8jYU0-k3wDe!`}Z8Yyk(!FesgOSD8CKqjt|oI%Gcf+I6GYd^W{IERxz25 zfS1;o^oNnMsl-NJhNs)q2i+CxJ(?t$D*a4wRZ5m&L=*75$Q-6UV@dj3Y9fb1`%z|V zei5*OzK-&6PN%YaCG)Q1C@t=04PGWmeWW2`xPF`zrduj8P1fe{J#@-mM-HVSL`m1M z8y_X*r70s!oMs6)xnEUe8is6LtyM(JY3e>fHCnOjd{qT8iwaZWUJVv2y6@NnfV zjy%Ui34u-QXEl;m^e%g}(5#oAtLGI*raLMsw>ID!gG~~auxEE#(7#}k&ibxkU9km(FIpRJBx_z;*_-I>hJtL&Xrk+xf zq6jr=p`mxLU-4&PW>Qk+(Ok+6JTM>2nn}UK!Non7KrUfeO~qd{dVwH}Y&nB16}rG~ zC1rC#NJIp?P(GK-eQWsV+p+j>T)n^L%uROLiN5sEO!M18sk(%GLQ6A0lBm|eD#v?K zt-NRsXR+Pl8bTZ^FV`yKV2p;Ag%?~)(;c4M>2;X=d^Y*(s|``*kwST>z>w5RG zE2-$FiOT=VSw{;& zB#_Q!cdB(NA#$jImO`&2wjx(j|!->`)LA zF6aOP%+4fGK0o8YfzC9~&PdqUh>H^t)cI()+=Ms;{$SVbR_#8pkD$LuQGX-k9Deg& zdCA~S3X@*5^Ufqdpu+m)kfwh9`l_k{f~^>Vi_~FeUOv8b_TbA>u*UY&q)N1jC(bMC z>3OA}-s;CE{`Z-g9dNk7>*iIioB|rkNBuO=r$b}YKo>&R-jMy#0iO~6jR=AwYWV${ z^8N)3hPFgW!OrG%0~pZn(c8{vb-+OLfIVJUPsI~(RUPBA|Ku4+0Oud|?b{4~59L+c z7C<1+%8oR*kfp#tnd2wROVRfXvui!>LRy;J-cbHk1j;gxLmhV!?TP(sr7-*kOiWB$ zrZH6?Z%Qg2zU^bmiGP=uLyBm%YttrN-CrpW8iPC$zh*~tR6q6OM2o%U`%V`{xM#ZE z{DStOxuwN4mp3<3&t=;Yt&K;&>)T>VeI%gJ^SnaLnyq-VL#{H-^)0~O*SGyo+oxpQ%OlW4T{KjRxy) ze8~p=C)H0%VpMXY2fOk9pbHN?v=Bav=;y2B2v&Yn6qYYSz=0@P!K1A{uzLJ{O~kO ze1X=(=QF!Oo|03JLIb`{1n>#@=n$f!)MWpgUB@T8D8^cOk)xb0NyLfi3Nw6D{Ho); z!cH1dztw%BCY1g4RRE=Q=fc7QVj*en91R@%50D(3%pjg)BT9>ej1Ufr)UQp;dlm5- z>#{0DNXRfEP%y-Ce1afbOA$pcSv=)CiA)B4XM%iu zIv0X@PrX#^4WQR)y)UK%FrHn{beH65$bnreW&}B1^A0)rvJCkCwW1soiW-hue=vU8 zVyVctA|*JBS93q~YSZEQ2vM9yQsk%@BZQ)O^}FN|2Q|G~uqe{e{~1c-OOz-0gI3qC zRQBt=QK0)3kilEb#WiP(n>jiv0~)vgaIQAIGPv*Z)sxd=(*!n8d1tav zmPrbytU#&G5V844Cg0(Qx(=a%ji!M%Hc&u|S7&Euora2%i%-n(r8(T3=#=?(v-HdY zLkbL9ZvQSLnFcysX%3}wdO0IPFiGt8@5}Ypa~Jyyr4A)I%L%C@(GWK$i*ot zf=d0~RY_C=0Zv|WlQQ=+6=!XPT)jW2X2XZP56{hg-&E-;<$_&eHOVCNG-do!Rhjf; zUgDS*ejalkMA3tlzo)IF3DS%GyV16uBf|e1LTi8=M@F_2@PG2(hHV3?$0pGbM@{>+ zss~})lQJY!wc6|P6E|94I4f!+0)8PNW&D5#<>=$%D!t95D%px(r{Z?lPdzLH*g9Cr zvHoW7Ef!|!!j~z5W>4aFjz0ZKdVU5|0z1eGQJeEiTAk=I7{@h;bej62Ctx<;;9N&PLZC3yMSrV0lHrkm#DzZ)mZ`#b^=tHaodQlImgcRkUv?TdYjSDzn zP|ez#t1LHvDf>}`EG;c<5?3TDhwSCoWW_3%#Hg59**q1x;$>bcEVc37B0&r~i)& zFi-$PyZT7M%E?LPhr=IWL5&kpdhhTvg%*9`096$e^yX-XI;|>2rRlp$YsH$rbWCfw z!cN(JJ&OKZ7^%7?IzBl%nH)BQ3=Qr147xis@)L{o6Vhtx{$dQGfZnaTSOELf3#tH! z!g0|u$gr9mMji(!N1=MyCA4Lt9F=VFrvGiw2hfoLSPMR-U2E({|Al6|YEBVEv}4p* z^;sOQ=m_U8fK*oWci)@!dffB77h*a>`M*y%WY4{YV^CkosRO^(GlR7HL@wnKS?K@ zZL@k>@f(1;fJU?C-$2rLoyL52L1i;(#I_9SK+;-R4~zqcw(vV$*7dSp=a2y->?gB= z(bm%rJ2Frc$uG*0Sp`G16qDz`Qv22iKvPXP70e!cU>D38jz3SHBwwCghLcDJ&>uh( z>&ZbnSFuWI(7~P!WD7r+>VMB^DFI=cWdb|-AnS7oXtq9B_Np>OOG8De4+0`pRFmM! z`Qs5PMT$&S-Aya6GD6(Ap<6cqTxNmT%5jQFy7T1eW` zKrQ=IFr(wMaMJIL;ND;48PSKu!PN|}13KGPtvcl&N{2>Nga6x0dRA)f^@u|p4rdYi z*J0bBfGS-q^|0i3TdDnk9yeqkv?~U7Tm_PyE#&#Hq26i~VY&Hy zrM&XtXCR(bZo|`Vipt}*2!TAI?IyZJR=7V&^GsN;K`V)Z z4nk4@XwxMn`yVI-Do)AQeE@zm;aD$G>_(N(ae1=8#~*=Zi}>~VBr@Myr)!Mq`scG* z+X{pr(HkNMJo@q4H49{M^%s0DE?v>tsn*#H=GTm{P!E0X`EXOBRxit?nt ziJVQ5%Q^7!boGWFJIkQ+lr0<2Yqzxc)oUR`uA=e7T}(wCAop-&xQq$Opz{le?Cs!K zG)xnv1m!>RV5;mi;Tc!#4@IKG@>QgMI*;bM9Z4xkNzhzb<4a)6SN~Qh`6ETB1wclV zOS-rAc(4LG1%2WKhLYEUpMKTD{WqbyCRTgPa)5={=HAF!_m59;pz#wpLpb5uokQfC z=g&Y(`)HP)vyQ?1HW&cz)3ny?z8Rv6CBQ%o3aaQS%m1udmCxCn=W6_a+WPKzs{8QoQ+KzJlqeJuLS>V^Z<3J6 zxXIpIvUk~Anc0z@5e_=Wk*p9ZapHusj(tM*dakeg_dKuH^LieCoL+Rk>-v1I>v~`7 z{dKfdG#=gl?{4MJKm)wh_K-p{$Jl*tF0Sz$JT6edxXRGV^}u7wc%}#8yp1rUMtE)BlDq zy)VCD217>a9EP`q&Fnu^xVyRg>luGjKtvb+*t~G;!)&yanw_bszk6)M#!T6b)A#v~ z*Afu*G`*Y{J2dp?EF^ZlnEf2~7AA>=GTAd@$obdBm?xF*1TT0>|tL;%^VvI>yJW{kbFQJ^g(CZuP;mPmY>oZVV#a_rfLL>Y^!yk@FD{It_<# z+#a`tdsNyilV~gQOv%^9x)>i6oGvlM(KXHtwfieQ$~8^|EdE29SZj!l8kCy4Bqk}laUJU+uczTg;h>O3sIZ0KEkx&JN(=`w%| ziz+I4hSEVrOa;p|4vG8@R8yq(f5XDOeaOR`ncw#S0+MesE^%*ljs-UJLv^9)k{#vo z$|b3?7o2@a^Qhq3`eiCOcly1+z!vPstoiwQ7}ww}mz>WQ6c!F+C_g4%;Z{yfgQU?Z zQ#BLh{#jnDaG((zfkF%YpHEqTeu+wX#oQVS6dDbudE&0|rO=vsRMh8YfEI}s4P4}D zgbk>5#zN>4^&5i`y`baa(ItxG|0&j4_v`uNaGL^mDI9c?lf!*nW5dC?^%p%WD{C$J z)c^do_U%Jw*6D>y$T1%`F0!4{7sw#_@6?b#ZggzqyzS=MA;J|3GXdurghW>;Srx>hz^64mEQ&{Bak64-cAlAqMSh;|NlHX^ z3JP!&Q25%_yh5k&UG?}+FLw$;k>&O1nJE(z*eIT9dQJDh_!g|s)2t^Wnm049{azr4 zlrQRAYDr0npL8W}Xp|g4HP9MK$ui#RNh~X;Ag{W!wT(@LN+(D+zAKok?3lfPiu^vk zel-kn%0)!I?fEPO+)vzRVcGt_pMXVC5fMMsh4fFRvaTG12$aId(o2Z_&iXyViW)iw?=oo`Oq1AhBU|G?=?h4x)k1 zqd$sqUOz)he=?I>JB9r#dmTAGB7)B?*AfXpUSZ!cbdb&j0SGoJavJlAcebd>z~dai zs+RL=Qk*>t5Ir4P)TM8^|5W(&FcTIKFq?i4LH?NMs_Y!>>|VQ{gGNV3m&NOBE?!Hh zymowrC^12#Uwiq^=c2(k&=XdOMW4@}@^x^aXw{=e7IpG_0kc@ellSzJ!or1>PfKMh zA?CF0xMVsSBEYW7Klm8g6*D0>tS%$o_Z4aGXK8;bAyLqer;nhiI+FAJocyAVxg2aV z6iWu?4h#l;lfmQtpUKuYv}=k>Rbw!@yrDjT@ldZGi#m+hlTbgeJ1K;0pcfVbCI18T z9|WwdtFkk97`(1UczZZywqDEzs1!d3`ki~0raY;GwA!-n*?*(bAA#*^6bczb=UtxG zn<_OqFPvz=Q(yH=+61L$@8ctWId(ziR>$Tn_Yd-ciBaOfiw3mbMx{}Kr@(b%WiVl)Cf>z@T4v-EUfML zjX2bmm-kJrQczOPuJ5>s_XS?iP*PIjNnPJNaCCH>cT0D!tgPHSI1E00PG9=Wx4#gl zx)=JYYs%Ky+1LPK)`F&?F5-Bz@6z|Gii!$Y54iK*88|n4;_A4p68^2#HF0;C|Ud6<%z>($dv;>4*@T+ zQeL)%Z_bDS?yCL${n63OR4&wnZtk7WMycfpGN0p5rG=oErx9~gSC6)V0t+wEc-2avWM)S8QHJvyPtK7~ zO_f%;JyWX|HF}k}i~+&{BO~LRH)(FWt-GBKI0@0mzaQo-1j6NvA^CjZ^nevHO5)yY z7L77*(b|HVU0|~($1qRZdgjP)_ z^8?R-E&BK_S4aepkk}!iL%EZc6+12I4Zua?4(kg zTlQgtsu?*eJ=%MA*zB1g_zmC2u>%qd&&eRw+CeBdV2yCY!{QPLi@hqRH#d39xSSmv zK5_prRxbcPf=Fhhf>qDgaar~u@El$7UO2lVE$#MWaYNdmDUdKWzp}EDjQm`5SE=~@ z<0n>dad9yr>zS;HlarHrVBjO?$G=+FmK>^kabM8W-P|jS~4T!&6_t;jX?_DYoA}R zD*ch5sSZ2}@c)wHC*6WZx2HACuNDrAF!2MS{@cKvk&b*pZ zEk6eBGwVCCs&&0N69$HcdV1X!0+_y~(S_3bzAJBA(i8SlG;L`N|NR$+jy@9Bp}piy zr>y5z&#sT1(``Bm9xg72#w%L1h>*2F6P=x%ANfA=^xa!nSb$dJo5^XqIt*a{e;U#PqGQ$N8Gmp@>8a|y0kLYz%Hk+58p}Jx$7Drqi4uMS4x81 z?akEQ<%RKD%!~Vk>a462@m+(z)?u@2ier+fPG6&PcXux@!mW9$FSG{7s#?|j$UV~` z?|K!5E(UTKM|)NlY}x+otQ8;KAFq2k4?6YW&V8DVDsja1+WLA=H#Bh^*ssWz#~O9V z93c2S01$(O^~K;#jFpt6bGE!bE;>$81vJ@#^@hAKUL-KT_@&k@mHDR#U!CN?3v<8! z-VbOQAj%yD>m#`gYJCHPZ?yD4n1@?*bhh8}X>Qr_Z2{7{`v;rO>!m=nX4`F%G8iuY z&Xo|iOMuKpPtQGd^>b8G272=g3rhX*Kw zzxi11=psTQDJD>l2yJ13C2vN{4zzS2`vH4R+Sre!@mhN~H!VC}Db#*Y+&zmMJ`t6i z>O}0Gldo@v>XSMQhMx2k13RUAcg#O5Yd+1=#!AxaOxfLM?GSj#U3%=p9IR>_mzR$= zosWh`MlgSvJKg|=#`U&$S4)1_*xTDXJ9FegWyn2AQ8;5JMZK<};b!a`Fd09zdM}zb z;`UmK4!2gu$Fjx@9mngyw#YDEjX!Q=f8zOHiV5w8F7KX;g#A6RCox_{jM{@GnX_a$+hke48;1WGNJs0CoY9q=1OB*&9(hT|=F>oIZ zb)EMu1k#{b0-pR*a-he%I8g9|fusEaWVms?1h?2nZ3*-!>)!FW*L5ZGpnoS`DO%Qy z0NB36|C(v8Io6&mzM-u2_Uz93{|{@H9+zu4vI|i)}XZD z2fV#8B6Lf0b04il1T*N*d8eeNQiU9+^Dfm^Rec#6O763g@MAQB8y{0G&^*T^$qZ|> z0qlBzF0uIh{&^xkZh){Zpla0I`VX%KillPQOA@9)z;`TefbU-!sVRbuMp(BL7OsH~8tdM8%)266jHljh!1$xhMV*QjQmh+$jL9h%tAe-V`j)V48OJu);j zpR{)p;^j|uMaO9d_l2#O!nVw{|oo2tjBYAop zbT1o=g~y7E+gzG01SALZSRgyIu$VRG~ESP9U(rIa9PcX>qxB?ZODj+c|Gq7zS#Q>@Vmj{!uTIdcXUGEH^%@L;dWU`_o{T>%Dr;#VBh zg=cC0cuCq-U!d}2fQ>$2RkPz4;O?${#r}kL7&BK8ZZSDf4E1>qA{ieapZ$O%5DOHP ztD*Ixpx`>0{OI_{8>{SSuf&hvZhkoDKle}5Gs%9e|K7W@CYX+aqd)=S$ZU1bikB1Pt2XQBbC$l;XC;Xj67hljy< zEUfQnmV6sOJp2}X8oFUxfI2A0Z%z4>X}QUvD$2$%(wg`c(Yt=- zqkLl@+XL8d#x9Znh~x}_yM>=FCSTPtrcw&T+AhqUmi~Eed;f$?4jSxguT>4~3GLwL zNnVN9HK)mp>@oDb(|AALoB`a}*z&5E*Wu-y2_pRaRihY*$I*Gv^-a*`2-_L_ducO^R#KY8Q&z@~=)~WkVQt$X3 zetf~&+}sT5a|pOJyT9nXwB7MspH&-?eR6-eXR}F7I;X{DisT&2w7pC>iAu@0#TKur zt)sm_u+?&Z*{U&?^t#Jg@>RjAhm$K<$3~v5DCep{O0my5#re4 z!qN8CzxH-_zP#E+OoIN(c=N6L8jNJow+|oWc~bF!eE4FpgZS^$;2%lluzuIgAKC~=*G?7 z4t~z6c1RO1bNKG^lj^kJUXnnpN)amGvO81>nij_(_H}4zX4Pxu(^&J-QN1T`i=&|@ z)B8XIcITa6VuIz1NHdA581Z-#J-6F~d2?*hdhXh8IR9rS4;}_N9h`F$`$)t2HJ?$H zLoJxa!>%iZd!&j@B}E~Mrn`3!YkjG!0h`CB0^Cer4gxN94E@3+eLi`(*%VMT=)r4b zQ>zbFx?9&o03`9;$b3qWAId-3@5c9~B`IEoEKIR46L`Le;nOAe& ziu&qQpPHKbnzI3#3BXq@ZtM;ZZ{{4W$s8Sg3G8U0WJi?Xh6nSh$Osz6D#ykLoM^lw zl?h85oq2&~WCWf0j-Qd_r0CHdb@lZVUQ=fcaaUsRfIFS3R$#mTLn4k^=KKp&x^CJ;hA!~X=oZ;I zQA&crx7!y5EAlc3-U|7)4P_tIjin>M+x*3gvAcTRKvUd!Y;KJ4e7f>tGt*WjH=Iy=E2As;w@>B4dsch3d<4qm0j zhVoJ1C6)un_pMtdI9NKrL+=x;62wxg@kh-=cCjs}M94`!{nKM1;MWqD{+;U|1sKiO zFK4RPo9&4BkiT)K`HM|)X%C%wOfn$CW}}?+mn>b_VOE%@Gyy8;3^x59C zhF(SxdEYHT_y<>qFKTN`4Ls7tNO+6r-IxoZ|6(mUd3V*a|~Y5g?{y&45y!%C?Ul%)YJy=QLaNBt7`U= zHjCxdFIQPh`lo`nj*flnO?`c8Rl!<==z9h73U%g!W?@d5?BwTCjU=i``XF3~-kA>R zA^BY9fY+tPQwJspsrqxHRV(`5>h|TQF;xLA#w9_)-LFunbG67j0<=ExS+vJd)Uak% za{!^4Y-jKD(o(b7#|>~CicR=!J5_SkvcvgI0lblHW)S-54fWLz`KA@;V97FFWj?)i ztiyKZoY}PG}xBMildMjx-UH*-!sWW(sx! ziKG6Tq06yhHlR7+e>7;CcV;upbX6Rdy2``P>9webe#i)w#~9oXKsPsM?ej+=%#cFs zJ0r`>d=!f2H6s*3vN(6Ow%e+M$F;wE-!8+7NfWjlC^f9C!dwHqoN6FG4n%X^${C=I z?wG!<3eky&hfb!k>Yq^MV})1LXs2t0nNn!49>(DmUze7G8>_HQN2a2IJ~82->rO~U zM#kR*4|`{@gjhpueqlVl;tMwAWe+@GOxtO06GXJnJpeTTAORRoD+BZUl+rsE#AMyD zuqrg#?Je=$!irOo=C!;^?5^E@%_&2iV6dDL1P-ZFjqLq7GBQxs=IlXO<>IAx=YC${ z6Z?L9*Y9y5)6XT-n2|ch_)Sql#`=0dmDgL`7X|X{h~*^<5s^sFibCN{iiaVA!zY-B z6x1}d{q^xPzk?>~2{hzwZ*&v6&2sKn|6Pb+fEyby9DV-9lxPe;RY-SevzIfWm&MGv zCFF)iUd36Rv;VW_%XJi`uj@*Q5;9%&QjAwLBT7p%U0+nPxOCKr%JC1=v(H-|4p5+e zAF%Y-JT$}H&wu50zdtoVrJRB#w(rR4fE^NiHVu6$_Y;} zKWca<-7j>?NMsiq^oWV{os4(ycBKs3aVk< z`2|J{Hs1+u@IHvauS??GAq>MWdqAT@TkY*mj3Yj{l{sf1kRuhai$lZE&m0&1Vj+K2Ig4nsmzQ*TfG$9bTAa;LGrl|I1ysXsWk`VfSsAv zRFezGI+p2*a}NXpgnv^2PZciiLOMb^$GKl5y1=YNOMHz}aqas*e&W&|KZ0_Idth3u zt*wPF*Ww*}tKAHFX~@%5Now!>C)S~Pw>v2XoKcGn7z1I7*WiQc!@j(<1=4^)A@vwA zs&^vA3%XnkbrbTP>KkGH4SFZD;^=~{1nF_^kIIL)&+y5SejuRujtYg1H^4O? z{X85W&t7c65_NA4HQ6pStn6W@MEk4+DcT?&Ud3hGmi?%ERcc2UmR=ZnQLc?oe7UZ$ zlqFa&?bGq;z+6=VpHtxa&(;a-;iL1Xutc0)Z3H|s*hYe%t82{!F}}t1d7*7-sea1s z!&W&K1BtA-DbZ#lb!{4)JC}XZ0O7WpFHFyN8b2lbuu2B@&&6U~NX^V5-Fv`YY9P^4 zFJ=1Su#6xDYerx8T6?Z&9Vd2VE0{A1nC00s=(F5Pc>RiwMIDxVTJC*h9^VrNk(fM= znxq&y^P(HuliuU=o+(kJehDE8Q7pYtKZxhzB#KTXBE3d`64>-oEEQjz{U_B@ImNQe z1^kdQ$NebsOxM+(?bAx$;w(vQtFJikNvEn@Vh-&_RK1j+#n4xLO~Nw2LreQ&?cjZ7 zzd+#(%NS+VuUcvvH2>T1chDuW!70@S6&NmuwbCWh`Oex#6dB->Eq8?GZ}jU%F#CPY zqN2j=c|LfLhV&wHv*dtz!t@@NtG9x%dT`~1fVOx%V&gOUYe$gnJ_l7B+lNH?}Zqv_P^f;wrs)rt8F( z7!{$NZGI$t^;cuq#Zkig6C%f7Pj57Mt+G(@cjoa;XNH@y^;SFL6WC%M9%+ArNZx>l zLpW!kphL2%FzGex{mZZVMKSH26lLVbNGkaL#j>IzKfV3|}YirfSJq;Qt#o*ix2V8Hf zO=X75{ad2bHSvrL$!+-Xcaj8Smm2~a;VlDPmNgh=QXw__db}xJN-t~}8b#BX$PXg` zVADP4eosJ4w$uQ%guHE_QjDb@mKYrc1s{BvsaLkh z2?tYC(R+zpTf>j(6kinDVhs9S81zzFc4n`%@wI1dG*rAPy&3d?;k~Ef zRySt5J*k9Lk_Avr6id}Mp@D~BfOhTQJHQgW6WD-s#DJ%Zt`?u=C#_qeHA#H-pDMuP z--=4>yO*HFlL{52h`Sm|Ff6EhGa0N;RY7Qk1KuholHZu&SxgllMPi4%7-5nP>-96! zH(P{((ziLAxCfb`Q}Cb)T)+JX)`6aS5@))GD6?Jc9dkaqq}~~*l9$>EXIz~6U{?zj zN^q_h6>rdx$5h$X_Rvw+yk6yR9UB{CCcRgXP_dY&L2=a)?_pR!L5#L$`RWe&Vf%EQ za-Cr2j}`)Tjw069l@kr2`mYC(wmGebG}oi@)@y36Y4D_)$CQ+cGf>`Ei?$X81I4D? z*w`3T1uwrS*SV-jwQ7~lPNkP}QSk+W%*5kZSLS2e1P&D^TipRUx?+CV2$8ozBfC+^ zE!F5XV8b_V3Gi>Ck9*c5fU<_{-4`K8cmIPST_Y$Oj5+Ckvc3Q(%F~Q_Np+n?Il%!x zJ~kF>tgEeUFiztcO;DUN6m(H{33NsWK7O0jC;j7x!J|jf9Qvj=^Q~&cWMpKSY6}^=%C$U5_CV$}KJX;!`N^0nK(Q`Hd;*jE!7tZoPNZ~Ow2P{b zw%pU5roZ0lXC}!(5@hz3bA+RU_2%a2<9^024ei^cK~8}K=YqDsORGl9D}>6Qpw34< zzn{5|aDP`U_9tXE{mm;(u_FV{Nh zqVw+hDNE<1vXx8_TgH86rdkepJ$h8Lz7n_2gv!^9IMn0mXiv(HqV>xWCKtd;wW@J5 z0;#mLS7JN+GDJE$@9U*h8eru2+OS>*oa1UFrVL&Re~@u;w8EZ3NJ^sy#daCs@Ev{r1&iN@!{xnL%EyDH11-u2D@`YSZ<*(-gx7*}%`4}kwnh1Q?oIF6#aPeJ8f|RX( z`LKg9zZ^NLFMdoYt+PfNcWOFG@`<| z#faaRJ;8Hy6Ro!lF7&Vl8eJ!@-g;a3A9m^1S@PD|?Q=!|<47(Y;I zqV5)eofQ;ZC-6!i4Q$Eqg{8=Sx^7pG2kV--4){bbMVsqV<5kmrLbqpCUCGB%NDi5aqk zn%niGFi7D{$Mf;4tCX1r(V)IAL2(+^AE9-38f&OsvysXfxY90|u5&wjIY2!jALfi4 zgki+M5O-08zoX{00uAlAVWHRvXitC=5nWi@uLtC;IZ9(j&eql(QF)pr7U{Flx3GI~ zIB0xs(Dl_YC;QzK%ze^(OEr}+;LyA^K9vbk1`xah)E&b^60u^@$-%)U-73A1;0=*) z%8bQ%yL8A|w#R%~S*hUa&7(L=Rqiasp64LE2NN#KOG`hn{=N>sJ%K$Hp2YNY(0K{C z1Wb2q!b>5{S)i^3KYl>kxWC`D*Z|lXE&@pgd*2R6wQ!eyNBpq66h)g;{iB=7ANb02 z-aw%R3J`M}KHcI4zj-HR&tHIBh8CQ;&1Hn*hdpmV=4cPTw{NOY+$pZbrFd~^a4Sx*6nA%Tkz&P)dx7Ha4lV9d+zS+U3lij>^t*T7 zn|W{EUoVphOmedKI%_Zet+f*NK}i}Ng%||{0-?*wfK@@Dr`jOUlSSmGz&pwP&L4q4 zuN-6`&L9vz@IOAzlRCSWRS<|0BnuW-_b@nE_H`iL_NBjuj_G2)6~iQc_KDO1*@8Bd zSA3p;73J)=6V7i(h9jN2I`1um!(dp`hqUH*jJ;YtWs6HQ8k^--%niB?3lUxV^esv2 z8uMoq5P_DuDqlRBkU@d!Hlywj^|CTQ#3Vj}KGTAD$30RquizU`$VGOJEH7HGhJ8dg zzafoX41WYUwBLKL=nzv-(1Spqls38e0J>dpo>Kv@-2b0mYkzik2Q`(ACMG5hE3z7y zne{F`2Z31G-U^u|GUC z-#rh=B6#P2z1KYI6vjVsXXDxLO|))yoBg&&$<7@9T>-M$XtL1X?7USHtXFVh zc+lQ--yY4FxgVfJegd+o{7_3r?W&s6A1-QrtujR5Uyl_80(mDVCs!T{nwlEv(&gAb zuNOZxmzTRU4G8Vz>)i4V4P|iQFtK|I+EKT0HnUE7Cn&f`?x@Z5xR8Hc^G0Q2Nu9{m z?)Xhx>~3gN(Y##76OSjO5bq$suj#QyX;A%(bvdxGM;aWTDvMm zW<^C{8kS<3bc4+F9u{7^D%G_!>&_5XZ{F>Nl`L+fyK?$FWv-UH514utp!@NIK+z7a zM08bGG~lgFtl;=z6Dh%tedEyuLnB|x+!#-4&Ghwrf(5eP$?bxh!+sYqzq#K_#CoP) zmpwxf>-3F7v&8@z@98Q0cOS|$cFxKj!u7);{?H3X2e4(T z(w5U%!Q;3ywyQ>EVKbo&jyx*o0%FACV%#@xdgoT#WXRi`#u&z}f;2nAf%=|i+OKP?O z;5i%MOepctWj@s0ehV>ey3FIvng5$NPWAVLo);5)SrL~2;<4~&AP?QIi6DUTc_D|g z@AKI}xZP`5?jOUV7;4zB@F%itarV9SH!%se2E1As>kcfOyo%BEs#w$x?8p+I zX3R3u#&IMF-y4bHr~rq*Mj`T8NPI_ha9)j4x>9z~YVPKi$Sz!JNLnrVIrwv@^#!rL z5B>dUpfzSt?$6T8fbr(H&p^aQ)zJ^(r?MS9jMUb_WAw_TWhP2zb=I@x`YpU194cM! zgk1OV(lBb|O19uXRrX&1w}`AZI!_R*ekns+!(T5;xHQ^_t)(%Nm9E9E)kxaUi=m;x z>dq<8nSxi)Wl>bU>K9U?h}8^jc?PQ6bb24AW9g%Okh$TRCq?b~VwaA%fqo15+);tc z@tQcHukO$Eb8KL#St;&jy_;}kHBzQ;@sY%Wg zC;Ba$kgTH3#C()A5zWfFPT+0je1s+^Z1`6 zE^IZ2g9HvY8l14gVmWYXzO9|zUb9k*pt^A!$Em7g{iH*EmYX?Nta4SARPH;Tcon?O zsUo$^Lqgx??Og?-_uz<#h%I<43g9`+s+W4~E|8GiRwt3`2PQo7@oJ^2i;IP@Wv`bo z_0b|HUXMxeqW8I&s>SuG*|tevc-r|V`wF7LbhzKwBP?Tq}6xz|?L;JG&uDtRd$ zx<>H{!_i~yNWQ#!6uMuuv?qY$<)z3fpnCuySmS&bjtJKwg1XIf6a z<6wkv+a+y`Vf$JN68p=D-X-i*bekFZ^1(}S<=VbHnxJ*bSr@++tBdQ*q?xA+KH#o811zsQ zceHUT1xFdzohR0V@hTiIm>Wxjrehy(WDfSL_@F+MJ|V%4?z~V&iqxtKVn~E-2-D;5 zjn+xW1ut>r59RqjnKLBt))KXC!?z4+X`!JqZN^7ohet=IkIM@>t4n%Zm!Eh}bIUj* zk{U|lbn+-`9!cPs^q3K@hC<|g8WQUVAGS>c@-e121~!bLWV*8Dm5CH+58s2UV=TS; zEYSmEveG+6D%6IZSGm)pi5nVMz&vhA0aQOH0!=Z;n!7utobM zo*Pp$GqbI$dhmYU&aE2}Wo>D?rXs1MWR3m)gh!jR=b<=^h{1!*Y(vYz zlC@Ev>WEqlVc*qx%hswD4Y7XyMu%&9!FOl(LJ}haUe$^Y``IL_I_BS!U>mEd8XZ@1 z^&*(Kc7Zr5u1nX9USLZ$G02}bK_x!9X@ELy#NL(&+SBmPBL_9CV5CaT%6!(FAHVvD8^+?}sxTC=OLbz17d zCz>Ty?29#{OC!2)ZScfZzvjg_6X(s+!U7$tXxE(8?i^Q<$cv%9C3vTD`^oL;Y}gJ7 z^tM-ih~!UOrbo(Y!B3;#k#}XvnWV z!LY*OhXcKD;h()f^M(o+FH4jT3S31!_MG~jwQFU0CxjZnM`n9@hqUXV<>s5_()3c+ zs*ajJr#!JRuD*1&6$^m5dq?v^3kTQ!?oA_1^@s^@5BZg?t(+O&$~Mpu*5C^-UxS7j zv&j6>HV+|)CKk@bANQBg+q9&)i_zWl$*|n%#2*-QKMiSW#uq&8@G;y&x|Y>@9GuE1 zk+W@istMaNSlC9n@6p;;E>OLC{K)~!m9JrU>hWy^)9Jb?#lX(H?GB%KacLzp%~n=t zmPK8oZY!zA{7r@hO&n)pc)pZwt9x4*cK`J-I_Qt#Tu6o2y6KzZtG{ts9~lda-`i~w zaR|i#p7`#m@;UwXyeo?Je#V7hO-&8>2g6_rmpKqB3` z~oMJ^+k|;l4-^+!qp+mga`4kM^eA4q7ZrGEs{i zX%Ew62K>1<{IFsEaAIOYtw8Cpy`#NV^J(f7B{E4^mNu39lkY6~Lvjc0H8wMNCNE!p zQDiMp%3%6Rs1QjvBcMSt!E{8&I_)pQ#pS&FJ5S0juKF%5)oXvH4eIgsv5^2(qOeKl zk`?5U!uXnA|o{5m`<>O7#Xnq|p3jCP;SbYHl5Si*Xgl?Zi({fVL# zQ4qee^h;17#ePqMoGbZ}Y)$^!aSB^)#i8!V?|G$5$Zr zQgYnJ;>T`4CQ?$p`kE0Pb}Lyzr|xi1w(M7}Fs?*#L*Ly{q)pt$s zc7czpt-Lvw+e1Eto9PP4!&&JCx?8=sDa|~lc1&f1qa~{5^3%rKy7{8K8-<2?g}!wv z;dPJ2w|-5k*A%ZFBSX#8?_90VcA@t8{sDq&qm0IJizLaX5kl&ZjwT}#94}^PXD!Wd zckWcuG8)Og4JX1`O1H}N0nr#v;R16D2sGE$a&sAIGlMpnG@r9scp5FeF$F`|%-prSk$+xl$ zuy*s2?!S)@+WRth@rS(1P(s-YMvHiMt>b(9`bKOC@*l+1wEV86w1rk{-N+O7ZW}T| z3lAt|r1jF(A_c5T?A`BL_0Ug`m+p_JH`6XttNpG)pvx^LxS-tsc$2&viz{^g-TCCS_ULpZi%nVJ# z37_W>0B*C8*$?9vSDHKT)ZdL{q@RzsBEDYq$XV@5VD7WA9V==_C6(*u=2IHiM{w~p zjyH8Gkdm{dZ#&EJ`MchqJznU~Xy03hbt^Xan42B$8I*7?Rr*>VB7(y5yEQGsEH*!pN1a~j4ApIX*^fMq{SAAW5xxbZz{kb2m+ z@96C)-3qpuH=`Q5)@dVHWxhOYShYJ2;{s@&TYRA}$}g%6*1~;7ZPYNIv>oJ|XB#oJ z`sOgpR=KeBvp6uTJ*R*39jq!@1A}Rz0$BFIHQ)Gb)6jlo-E4}NzC=CKR%epzpVb4 zQWAi0WHA`~>B=g{s}sMBGWM^ZyWBbMY1fQX84+d1`pYl6nn0c~!ZObA9OHt8@D<(% z&fxuxw9BlQTQ8Zt+a#^-5Jvd!AF3HSLfals=;`Luiv^x1ABNH-_IDyloJC|Pk{2U499T)(dXgK9?3-K{HPC;T?2MrQLnu*R;l`O zPTj-Pvgi(nC-LpddkdZSYR+nqwlIZcL_KCbW*3^|5>J~J%FP|jmf0HX1B3JA)_5uJ zSB~#9o6w2nXGgrb8~ALu6)0K{_y`E1IvxbDM~e1by3H0lszwwE%+{Z@#x|vTv@*oB zU}I45pb>m5UBErwypeNbA2E(*eM3vV;(Oc2-ge>J0ToK-cZAo^^~iz!FGkq!ww1B5 z+pJr49j7fK622K>L(VVJFy^dJJ&P64YbqlJWw3)lA2&8z+_StdHJnRA^hLd4-pazJ zc5iMMqWx-*Bl)@s_G3%NO3P^*Dw1krv^|Vh%Qs5gVYl-I?dIog8sDcp&j%+G?0s)^ z!50bk{+nG;_y-?U=nYKEh|evWGLNoY8CV z=Ma*C@6oC3&oCtV;;>#IUQKx5G9X?hFPB?Uq`40|Eltk+JcQavYf7Fjj^1u{tHPBh_L?v27EiP~{*Lgx;(iPE(voFBGYgVIoar^| zk))^4Wq2P~T5zHE*!!@V?q9sAa~&Bx8{Ofz{wr)^mCTg&ar5z-eVxw}U}A80=dX@; zGT`LC2L+gMm|i|CyoQ} zPvN51PYyGU_7wDp$Estlvclvs=kHXvE&hh2u<2;Mudi|H_WY5w9EX-9xY~ASM1_0b+(IP&y-Q(&ge(Z{U)o;;7 zi_wU{Z;c+ReI5B?AtNCF4ayOr{ge=~{K#O{h{V3TK_c;Jsw`a`n{jjqX#^j+4Ueo5 zK>n1JDMZ@}lKm`co}Yt5T%wKPu$It$5X`r~Hk!_Vo?CGr8rkrsoX*1hvW>^dhKGf? zOguSdxHKKYcp0ui5bOgnd?8824kzu5?#axzEcIXXaW6w4!)Dh{#jlE_@{;fqjr2!5 z3c|u(g@yXM5eB<$ga1-o`M1x{PX>d5Y)glUZ~FDjVv~7nUlR+8qMf25paE`!+bu2LID&9W-kxkr_JrHRMO9z! zvz3J^tzHG}*DZL)6Bf-Zcp8M;>PkqA5n_vXEza9YYTw4518#^%Q=A}iQCvq{MW$sV z&NaQdaHIRat2BwEbl)#C$0>IL_F8Sbz?NX9E^vzX(c{!yxIGLot{;roU)mf67B5|w zerNd0PGyJMCpyAE1GQ?YGwZ4z@AlTf$+4FWBl zz#}a#u5+cq@eBkVlZ)0Oolz`9rousF6g*$;n;)G&XqY&>f=BMSiQ&Ww6wp1;PTa$nJKs~BubxOp?&NMnd&pnfXBQL{R8%M@ZmKio z74M<4x5g;YnL@UZcA6g|pm*zlb2ZS{$0y%rMZ^TcnZYVu9{fqpxHf!u4_(#iQdtQ5S?1!`lMjBA?+N}rREyMk(@Ys@p3i<>gfanU{-G@+QJcLdMu+hZec6feidjUz*7YSrYQRp?|sCu5Bk&%&^ z3G;Ym0f4ZdyqbU$!uM1+Lt;E8bB#+y8yc-EFIQC_4LtdsCttc69eR6v8%4@b-J8vb zy4h9j<9Y0^C43+7@TtJ>C#xo1SibN7uR=~n<}Rdt=7Ov0;gtV>2dPsmqd1Db2E@lmpZ+3P|mBaoN9RoK*`6brjv$t z%gsGUOn4|=U0vX*a7iizAoqFJ)2=$EFD*?qnlRWqF&fR=tYg(4Wz;;=Q!3GPvQs>E zPK{~k?BwJvd_0ML$Oj@(R$aM*-9K-ZeW|aYpg=0>2e4z(C3$*U!vHT|wP=QzZfT=f z9R#X#5+Kh~)1VgM7ZptzNIqVPWRDZAsjh~TbG6_4jcwyqC0s6bcR$yCX2A5K2>?E- z@UIZ*z@S^{jk8nSa`wa=7RH!1it6 zZ;@KTb>=gGcUt9oRrqJG**@Fr#%ORws46u4;6+XCu{uR zLO_VJJ&N4@ycU|iw7f=XDy5u%aU{(>a#N|Qts%`eC_VusS_*lFJ4T_<-`PveZ@E$+ zt*s14tGuwmWZN=L%t3z13~wKe+kTfIUw(h5hod3)fhsJ#)5sZ}5(cm&GAOc_@8e<( z+u!Ll=Q^#Kc%uDZrU`-6yxH+1-%oFRY%o)u_B+3zBMHQrrX08D(_fA)-!55LTm)uf z`ib0~e_*&+q3CFUpM2|9oYl!=00ZG=?y^H0QBh;*cvE1!a*Csp=GH;4l#4k;IE$sZ zzFyM~>)YEvv(ct^=kc)(D-2vNtj|u&|_>(KbeJv zg_PeZDAdc#>u9CTx_vPYu-W6!g-~<7ZGX}!@wp=NTW4&GDU6hl`9}4d`5#uF{EjIr zz5dfeagY+sGf$IW-<=Z^iXe8Wj&yNWH$|n?K07{<8HGa%88qU^f!CZWgEbMFuWz8o zy~_IW{ioVlG*uB*i}u{w>RoB|u+75govW29T4ex4ehJD8-achp**!S_`lzjDTPB#YW z>o{6V(@mO5{mZWUqzK}PhTc_bY6H}2Z(OaR#i9JVa0zvQGYZ>y!PCL?+uQ6rTh(EL z1q?PX89V+~u)2M9Uh5w&+PkbV?|7V2t95>}lKQrc)8}+6qLpn*sPDQ-DE;}r>< zGE|tjk53uHi&&%2EHvcr2OPr>RmS>NZ739aalcbtJ-jFCH$o@EC8@j@xJvpXgQ>E^ zA4-WuORebLST*roVh^Z2*l<0mFNyMj7~I-wYKvm*s?ua&=oJ2wuJfh=2@$ehs_iA^ zlrZ_QrX`>F!KTEv+8>t160~ZWg`U!@NT5!^}Oiw*00f=d9aZNAl0Z!^4Vx zE#(S~{lpL~9F=t|qa9In{;^xeyx{z3ASe8ZyJRDEo3UcB&Ak6@Kj-bW`vV5au=mZ_ z!!WF_xbG_aXn&vi4nkEY+T(8T>2jy?s0_z6%knzumX@0Gu)25HS=l(wHr)Jfi*j}< zPkjcz_kFCjA0w*FtCdp;rF;&m_(M|3Um8E>yvma#xdzzkH#zJpZQds{tRY>mB~?ry zA`X8(6&D|ECzY3%pNaflTQjsK@Vgy6-8EJN<9!YJVz9X4AU#RWYvytS;26~`ac^GC z?@%t9j)W4c&=5Dj#;F;H2`C;&(+)WaWNby2sp27S>pg7gYy5Wld+oEF%Bf3+Icl%4 z9SUgUABW@|29~>9I2>Q{)$^xKdZWHr-}DLGD0aM0x?y_bz@{ODnfjVX?95lvbsU;_ z<)tk7lZ>abduzZ6jWWI#B{R=W?g7W5Tb;4^(CXEUU(oz^)kl-Cip{|ST+~V@eNX(L zgr8VZs{NQNo{e%{fti`eWldJ>=3Cerd2}D-`o+^Hep*f9GT@Su5(!%!|4F-dm zL5CtB{gpWm5A3UiB>RQ{u&57R;eR1J=Mt%CtAUs2T?`M47UkgMlm^$}*5oc&?5vbW zyoUtF=wu_r@zeGR%h$xYPqt&evmVEVmn+YZFe)kUFh%dylDgIwDIPuip{w3qT^Kig z3HU)al3=0CgS~JY8=LFF{>?lA2@ki2V-aIXMl~GYJ)svpks3Y!fQPXF!~3o<_$vZ$ z%uJ7;Tw_$Iwt+E1(0}~QO-DF}z$qO(rtq`7^RX)!3`d12ffLQRP@8nvr1|`&BMhv7 z*{~^sJh`h*iM6-4a9K-2LekdO_UmJ1OUvThujA33`7A8Jo?b>MXC*IFRUQ7cJezq~ z%WUw}A&t11$({J0to^8xt3fENU07X%9 zWm=rBAbD}>X6J2;me`cx6Fi~&V`cxl3Xx11TAVQOoGNL@^;QJ<0;s_OC|4Zc(POXQ zir+q_-6>4fMW3FUSGLa@aOs~4`0WL{1ZBvYfzFUqf9Ap7-rnE8e^(jzg<3c|awN!M zPlS*0Rn9wLtAj&m##kEnx-4mi7 z#-8Yb!09!%xZ+ZF&lg+j>B{N8J}!@Qvtl93d@~_qIP@$jxSn6Hu4W)u$g?}AxZ z*iA%qEPTiVY^Yo*U*Bn8uZ3LgL_4obIu0%W>`8g2crjC^Ya%P|_o6T|5?yf;Q6X2( zFDbF!=4bd8p+J#lpqZ#xW2^vq{SdvTD&E-KJP1oa|9H#*#Bw^Hx?b9h!pp}AbXL+SHr`_7xZ;+#of&*avaiXbX z6eFV7(wLee4Nh>1Ri*o7JZx6xp`pREiz-W4M^kJQ@LV^Kfcv%DcU1Y?nT+0e0~yxk zRy+|L$_x60lo8d(jvHyQ0KkpJBrT0x=bJ_hE>arO+=qYf?tYB3tz0r^-3(uahFVx! z!hfS^Hka4%lY#M~`@&>2ruC)O*MQoK(9K`^&b7m##qx>@cDB*pjeD@m&NvmX3!x}k z!B96FiZXa1R4OT~!hwAjh;LhdvBx%gc*Y7h2^4&>58{d=aue?!sXBzby~|VNuC^3y zb+}%BcHHj$XPJH{?0$9bk-7~~1bZtQoxc)4)VueZ%NfFR7zRwfwVASu0pUwokb6)n z??-2C&Hkg?fiPUmF2jXg!cDodceQSqs`&U+abw%~d0GCR_qWg*L$0cZaUH_yA>M?R ze51ch{h!S-U%&5N6@fR*M(KH92uAac+MT3x<@5si6FHgx4|-SOA`+W;jYbev?r4#| zwLb8CHj5NbB$=Wzm%p}`e*5>7o<=`5TI3uXTiEx0cf1WNOKszA??Az@NAbTfmUSzk zio-3#tBS4lH42#`t5n5OKAa2Z5Bk{ZGx}z>5^~%vVEavD4G^tKMV8uF~h8u)-|ZmF{sFe`4^Rjyx(V z>YWZuO--#d*8FRzxuF^7`Nb#|#77+hVVc0<>I9E4>--RId%+-Mzh=e7q{~!L92; z9rN33F!-a=_b@w+zq=Ry{HZuh6o&Jq%5)h^x*K)I2&no=P3`FHbB^G-j!ION<^CkF z28|bAzqFxA1@b7|EB&-#6ASY*lURnT%C|X|r4vEIKOjI`!!?EppiDeW+jzWQ=0Lxn zLB~f78KrbaCIdaj+dKmi!)XXpouOTIsD3zhEN@Ois;M0KbkY%auiIfLLhJ>odQ}?) zaX_6md^7;WUPWTAsd*g>j`!Opv!>x93&Wa_!RL}F>E`PssQJ7ZiN8t{uN<>>otYzg zcZPXm2&|E$plK?99LHSlIo$?cV9?xzx2*sLMnkO5)Rs zkbc+$!Kw`|0xaBw)SS5Zcw^rJW=}*7+DhI7qj5jsxt2yRfF!y02+CwcNVqDoCPbBz zw!+Vr5&Z*oU)#<+CM5MEB-#_Zx~Wjxo&m>wC`L+b0=XWXdyNeMgqqYj8R(`SD%aPs zf^%JcydxQrktStv-L0~EisMS6wANEn+~lmKqJ9PK!l17K{M1pm-9T8S)#LMMg!Hi`3jkvik;7 zSnA_d>~E>gb&n_zVZ;4G3)%nHf~Z_Lx}$)sebRk1H~|%a(kv*1P{)*&mCZPljH*(A zYVJ(%9J9vFDI>2UDcz3@UvWiAD*0Hz46KnDW(qIe4ct6?9DAaMqT}vrI9PlG>xP=1 zcgRO}oOH%zU4w;EzUqFtzrLH+k8D=rSstk~LTte-G&aX;1K6_A9e-^d&Jo7C49<-g zcSf>CD*fkXo5SHwO4v0qm$B`BcdmSlGTxU_c6JMdgWg{5*BK*(vt7%}d*d+z+}sbH zs2l99KP6Q3de*A>>V6>vOOx%3gpEr~=qS06HZ65dcjr^6rnc1}+A&X^Ql918{Zt7Y z0ZG7-sQrVaDRXc!l`6YPRbybOoHgdFMfen*cYpE@BkrB{#y{L2ta$guVaz3o@;2G9sAsp74Ek zN!W7=N^V;*wPFUF+iEXB@xDakg&+Ee5>D#85K){G5bV_~s;*c{;nYl`?-;UQy(Q#R zU~Fvk&S&U&YciRHgCJ5kLk&+v>|K46<%0W&8(A=6;xt!1)vqMg%A5~+y;pnA6%Qvv zqJN=BMT6_g-Q}y@%a8QuV3&R9l85^>8II})@10tIOJ{@<2m`>Nh#135@{*^vvnn2j z5Mkq%#>}9c70;Kw2)wYtJM6l%lywO zXU_Fm$L`F)kK;bvoo0(Ky5iMGDjMqRDNCsIYtgh;9Y+?lU#S-zmdRITaHZ^06;)!M~tWGi7 z+cPVQvNAGU8>ikg=I4y3MoeR=#T*QZ_tNOv(*R%2sN%of#@kHK86R!82D^AVPPh$z zl}?;i+g(vPqQJ_#X!dcZHpl(4?7Ht9UZzS_Ze-Utjs3=YjQwNe_C59!`(dl zedLXZGNMhM9!F57t;VGDbCDS_8QEdWe4m{z`vIlFQ-|BT+V=$2j9mD`@e}Mj`FJKJ zbgwn>aAKWh_hR#c{z!;ohbRkp-CD5 zO0122%1Xqhp5%hi@r@i2&1dH$|?D1cEh_ie3hjQrxzj1OU3JC{4{m z$!Ktf+iG~U)Z`3&vpzK7{>|J>OTDMsIZJK+pCfo!&>P&ak}$xIE`$=KeVr#C;J!De z8vk_sa}!GI5}^5LT)1`xok@YbC=fTjpIqVklQ!+Fv5D#9;xct32&KFY%vfAy#S68F z-vP>OzB$stPq8!3JT2}l92{b%1Md2qY#!$JX)008c46({F9g6Wh<(Sf+LXXzz@;vKq1eiO}DeY$8gamApr_A&E5 zdZMd?wd3QA9gZv*+)eHf5gM8Umh=PHq$p+LNzT(B$fjOred4kxNwu@cn)1o7>q5zV?eRyg8DO2DQg# zSzR~K7v|n|IB)qrWhCw=TQ%7?b|rY{Yy1jRg3wbRb>%`_^xX@MG&D@@KkHAAz0uH! zCPX=aDf@_=!Zrd^e@xla^5W)hhgt}3ugqQb(r4Y!W+^gx?RhI_*%Ljs|O}O?4-W%Il@Ei7JmSag0DdN@nU;@xj^pLr7 z%4{M&e%3Ef(hNBS1-%a!c-CTUadB}=&l+8JzukyPClM0Pcc)CAzH3ng`;;8f$t*Q>U*_62f4*4Gli;Vjr^++ z;JgsVJvxT_G?+8RBunogS4~4h#2;)TnA9C9U-dc*NE~n{Oz64@)w%V7D>yzfg+}H| z9jGb@R#+l3t?pVP#)5P;9Kw3~%5hVtxL~##wG6eJ>9_qCNe-WCDngnbH1}3My zsxf8ACM5GVQMSjTlv_|nmLFj<9pBR=QakE|PbIQKSN!0I#1AWJt5@it59KK-DXLm# ze@I_qlW8}QUv^e|MPd4<-UdNfPBW%U_xB|S`Gd>c0FRCsP0>#oK!a!biElIZN2NFO z@c8<9-QHc?4R|Kz9{8_!$p=$+xWsqedTsjwj4C^}{-A>>E%?^W)r(PTbY}^^gKQlj|wX#hmdU z9E>suUt#GpY6!T-D0JK?Tf1)?l$y_2SXudPh9o3p`zkMk^AhjFu7y2FQJK)?{KcPUgs-#Spoj;sC%byad0eRCPH@R|5`t$r{`EB0;aPQ|>btybRjd7PHav4b zT3XvM&*M$C^qvus&E#7MH5*AwjZly-?Eb64yz<1FxCc*AvIq8$;GwjX6vNGr!m2U$ z&0E2S61qN-K^jG^rvX5lL8uJL1PXmag@>fz=Ep7pNg@OlfulrpE_0f_nqA=%BL35x zsHZB!nEr?FXF7*|r7E~MVFCj2C+L{bd1{V_q{mwBQnoq|`|m(bOr#OQ^iP{>$}%9? znm?Py1mc>7&-s>{iE>B!inInqB!XHY1Mhf#z1$`}$-`r_uKThkxi%(xlccB`}5L?f512T>*pQs`Zp&tUA-S$4cd)*9=EprdhP?D8lcozgYWpFdzckk$2FX>^L49U*Dpe zl6nGm_I6lWMb+Y&f1>;9JSBnz+>uo09Wrl>(P?i$1JAW2Z(sQC&EUz80EvUoeG7E; zamMdl9Q`v;7qRd>LfR%)!xI=%Fawr4TmCs_APPr#4Pd5&xHT#hL2sJH&*1$9G5y)u z+giXF^tQp*O{DdJ2{ju$>YxiF+QELW@5Dc8wZnLq2kNQuGqB34CYnhSM7+n>uCb+vZAzl!o1f z)1dxbV5%_^LFmrAO9N;Jf4yZYc3fj>rPOz6L`3bYUcWDAUOaj0l~}P5N(T#$q9D5J zclgc6&^vOMRai1yjjvS1Gi8J5zUIkvIa?j5 zmIez*lp)s0U~^;4&zKDb?7U!w^EmrXE6o)DQ@~Y)9vq($yF@+()xO;Jbsk*Sllp7s z>ubhIGaAZRC$_S%?u&4OzCdN|-!v==+ewbY=CIt|dU=9>e*1X$bdWYrBFgAUm11yu zxco7IG=OT;RM)_4noHKe3`Kn{@|N=GBx_anCLmNGtM@8K%?1P1L8-|4XcL~))Ky+3 z3JI9zfa7k-i=>$MhAB?|yN;4v+0FHmn*+Hiwfl8nFNP#Wl8@0w{4~8|;J?qsG(ymf zhn5z!_tKf7{>Huy>@A)uO$0npZCrl-nphIGG_zj+1j|27X)b4$o6lO-2=9wSG}fmb zTj01Vl~MkDT`%osQ~kF&6c)IN3j$56PE$FnscArCG~xmA8`RBTCIHwgZ4@?kpf#PX9{ahW<9Aj&0X*sZ@PEo%} zi7iQuUv5(ID*8gUentWVAyKTZu9wMaso71FJi?s*({B*(&99%*-byaMMC_E9D(F~S zcS|dbK+!(%ZaYr^LA_C`hwo|N&t+r~zaaP}@K zaOxl|HxuwdmUd_4h^2{^;sXtm-!0(yek1>PTi+Cp$keCjYDjI^Y}nME0M~rdwHp+- zf_1C(()fOxhEg{^K}cJjR&-cy@m`p|@q+TtB@hVo2AJ8fvD@=uLnA@GkhtF#-%B4H z`~{5fZjjX@cIVu=4KJ@q)^(Q?%Z!Z;HS*T(vY^pPU*FQK3`8*O34!+rx@aLOLGm z5bJ*W-GtZC_OQg%k}ceJ=J1!s4Q{{g--9`aOHp7V)ZTx>aTfTNj;m!P5g!KRP0!01h?c=>^P&p4KtpghSKo+{d z9JW*W*XIlF7oQHP!^nc(|g#VQG@R6?R~p8g(GhDr*ZzuMA=32;ZH-sf45$Pa!ae& zmU}CQ&L%s?%X3MG5NF*Yzr^r4L7kFd+|5y_EiLdKD7k87LTQKapC);id{hsgC*%r#%zF6%d!N zsp+J4$;bCZN2hsvLrr&*YX9Jv5%p6l3^2E-eqh9HIFok&#Or^u)qP9LOrE|UWXXw; z1CRjmKWRAq#SbXFW@St+2SRekkrRMjK?qW(lKTGPJD>&JRhOxn|L7#h!kK(GuGHhf zstqA=3vrH9Co)+-`evs9FbDL#-GjbNdaEK8paZm!ZVvyCWf-q-9jD)o#g;=t5K^yk zKfPxiVE^-QHZ1i_J@g5;Jx&{U=Dd^1bg6IfT}H!7nUU3P9^ZX(cmvgP7^{X=6EI`NB9dELWBVPMw{)B;)3*u_PcqeOhWB6VDR^LxiX#$WW-thKYyh{Z1L>+f0mL)D7D!C{_0C4 zjqV(m^l!m`Ugkf(=Kp+MNbD=H_Im!mWXCBSM-3Q0#MeOq-dl(%-`~o=4F$)4{%q*X zd{F<-tRsFxLu^yswSVb(8N%IspqgPM#&FMdugyb<4-;M(!xo)|_!H-6AW-Av^mLaU zFvqrkJ9s3h8+e}JEnn8|Kz8!ZpT}?h;PDt9^SbxkbIyI9bDrl6g@#;_ z{n3Mu>)DV&p0P%7GG*DFGri}cuN#*ALuo!dHFtQ|PWON?2a?$2ITcD%pL2tnA{*@m zUd%0ug-8yGz6rupZf-Z1o&dvU4_^zW|1b70HFScEtP`D*m;;XKht|t4i4IL&+hR`&EKck)K3YTQACzOyS?PR z2?XNg{~A6M-4nsb1}S@e)jFxNd~%!je;(rh{KWr$rXucx&NVyAo+$b;*8J5F*mI~l zklv$~nN7e{fkm^>h8+b2igN*i$N^S~i=HE8oerfW66yJ!2Tz_D;@-K- zr+3%`cEJ7nVqg860Sl>SATip5b<<8ZFcr?lt6K!qn5601v zP=xK>`KPx6(jr0Yt7x(v>JbKWE~Lp-MqACwYU|;MnO-i{T@52pOTYE>tN4q>Md!a} zPVy92!~7kzb%aMmoUw}Uay3Dr82=n+-MNE<62;$tJ$+4rP8|oG+xE%qF@MI`aY>kZM z*}UrE+@YQhIkQi8fQ^u-4hX|=I%QdA7!I7woNdW#t=yWL*`33O*avQCJH>i7}-mGM#(*#F?&=YO*e?%zbBh|dtV(i z^}10auV;z}vk9||^K@Ybu(ujXpVdesIcr6a_^z{ro}C@utLixCiOn*21r_080M>}Y z&#gJ3)EF>qTTfA$YV#@5(o%pXT>atsi=0;ArJofD1O0ycOg+c&N&>#7_Rpbj?Yn7w z1D-VZqah$$5HTvz8uD?v%61txbOC`gIvnYpG{}10!*veihLPRCJ+=K%U9fHc^+Pj3 zO}Gm)9$I7wS+E3-Wh7rq%}U8x8+9eSu<*tfVm84^c<-9F3ZU{mG-eY@*VD$8RqPln zuIXK*Iyi=3$%>*7smbP6R$cRSV*)$6!`WVc?QNw5WHc=vSOBGCl!TDIvm1Kwc4AfT}^Ki|>W`9q^@HsA(hm8=Gj z0~*Vw>8L{BMepAXl}^9BaQ1YHjt1@>7~()17Ww`)Y4uX%V!?AWcsReSC`G5aYtO-)T}YifSm{|FZ6I)#~0c zY6$POv@XJ0r)@kG(K+`tI(tae@BMkAI94gMhn(?Ut>#;D6=hJhYtV}1ReHDYBFdx9;xLwFJvO{l2grVno>z$5I> zZ!@M|0G5x@?B8oR9iI&YGT@?h=wlhZ)9M~n_UzQvd$oQ?CDZqS6tPNTB&7~=@_R0N zh4DeQ)YFcFklrl8cujsLn!__nnJ+bM+0&qk4Jzn?!0w@ES~xb`oV)xD=5ryZka*-i zT#6Z7s`6}?N)oV22pqVXCf3OZrltW1+A!4?+jvbuTun`F*WEjISs?!@pE$9;e}MfP z)My5u-}b4PieXQ?+xZx9g^6BFvBhy~Y%(b&( zhK7RK^4|=?2oyk{!%nB3Z7Z5~VP~(e8$B1&^Z2%MC-_}gW0z4{s(1~)xW$|TJbSP-Bk z3f%Jh>l2(WBQz*U<%mvu$uO)E6V2}K^_YHKa<=**tV@^XMsz+Qm}WD;~QY5;gb-fl?0CEZI&`Yad#nkuj; zE_xtF2g!>>O;lrmVrGxB@6N*aoVzQ&p$bc%%mmtT`t+*(r|D%now!=JfXhSyYXIwv zarb(R!Gr}1;0cR58dw@Bu78TQ%y|Qs*kLa#BeOoysNDGZ6=^OKmev)`+)lc^hq7kd z8e-k)?0OuZtwZ^>*n#k;$bGPbo zD6O_EGJ_LN2%4-n_33X(h!jpa)>ndezL4xCk4uJHTQ$VF+R0CGP_zNF3_E2pKfrr% z4&dF!;x%QGV=mCc#~XVNuhE4COOKi{MbGg+=6r0%r>O?4C>OqJ`Bwz!nxJBe4qieT z!cF1G@Lo&OD%l0cBhE&Padp+ivC*83Zm|{Tl41|Gtt*j}I(J!Lr6heYEX%;j+xs;y z6Kxo1&|tW%ASW))6s2}q(YLIss-5q2ETxl(p~W*`xDi0ez!PEwNVM{r!TE<}fyU!Xs>Wfv-3oRl&h zEy5o?dIZW$ZI^4C4pm#^UyjZ3L?2n-;{hHZ3KZgWt|mzIg+mc}VNt!_Lo)ObdD9ZJ zodYaT$$v1<4DO($3ZwSXAUOT<=v|w&tJH1#+(r=Ym;(|FBU-iCelOd(%uPw@^Ts-+ z4PEKnfXd0}GNk0Jgd6y_9i4Cq_`m&`oRG9`MTln3gNLx{WH20_ukFEwlsYyln@POJdGfv z@fIsG+LB;Y0Im7vnW2OY4t2xksg2fFs>VU`cGRG>t8!M1wU`g!fA?mA(|C8gufLxt zO2BL7Mz;tqpJRV%b29ha>IgD!wj_S}eT%IGOH{Ak0>JbJFt(VM4BsV@O>ZahZ`|jC z7^DxsvOW)*5I1s7>|Wm|Zy!8=eoD9hE79yDdstMCt&!x4wdcD<@$q&hLl|4Mnjp}7 zknGpQ3n93H(mf}_X*6VFchWh(w_W#UL6sQU`0900bIXGx|YdJAdBzF_3RrU&CI|kDCs(Jo9TzmzkZm3R9Tm92FN1>bqkUJuN=6X^}21ns{G>0+8E4= z5uD@9^DhGfCQ{s1NMzO+=x{&L$!b3#J&l`aG5=k^qTM*rSYDpgVQk=4%KfH$;U7)nSq?}LlY-LGkdZr5+{cq4j7mov{|Wl~9w9k2;WV6_ zoXUSUUxGgWq$GBeR%S!6>~qz~ztYNOQ%71`i>~SH+LwSx@U9v#_??~4m(;Uv zml?o-Nm-vGe8>WxdDyiA7|OeqrKM@VP9{Te>2bt74{9`kWkX#lLAiSoRuuKiU*a%= zkuPAyjxPc2>gDM{u|eTa3C1jYBDNT&$Cd z?mvNHz75W&kGzl;=H`;JDjp!+&|Ceq8V;a?N=6v`{m{?Z{>8G_o<|><8JOEQ&J6Vv zsMkg-fz!W{*0n{1BCc^n^-7Ppa$N!WgJ#bz&nT-C6;~0C7=Uz{Xy_Rj)-HOlbr8N? zjg*A*|ChyNXn2j|d;&U^GAkp!pgo5rnlEkdBF)*aeY#%{)vczfwQ*mA z#nbha8~lV%P6uGwWLX0a(UUpTklxF|0htr)J?n61VG4p4#6b~w^f)XWg+vP~zsA^T z-7e=(K;%cY3m-HS2E~kjjBj)>K+><#hbN=8$@4J64*i#j zj)cn2&TmFmXHU~f2cM^YVJEntF6Mjty5Cgp$(NO5m%4RS-xR5NZDFI?^+)g6f5bA{ z^I1msKRohLZi`_Q%2iE19eTENAIbC~0V#4$ZDH>AAU6v8nZWc0rQ4I>tV61KvORBk z#Zm?wnz8BFv&Am6F$=6b3vcnb5^lMME+k&cD-!#*>wN3G&qN?_-!ji&F<()E5{q%bO)QNJ4?9u zzgn&UGs!Fp@rgKcUTR*)qTfiWdKJ&V=V!yJw(e;?$#USLTCds@nJ2ySeg?70ARB23 z5-=7nij5A;qI{I?6qpojzT;wOCRn-nmt9F!x<)G&KHw{#zV#tAT`%HN*pv8))8m}M z8;TDcF9x}UlT->lQuBZVRnTx6^(^=)m<@|Ndw%dqa#XXIaNV0K>MoE8DKIVehDy>C zWv?XWmH+0kq}YqGX$HAyS;J5&UGKpCj=)zZsfXp}>V`Bd!r{YFc&w32*O^yy;_uK% zt}Auslr6{?O6xxmx$==i-8w@o1;h7NM@4Y@v7#5N=%vF$$lIDkqZnN^wONh$p)o60 z#VF1jwPN3v_9`x^&(V;uR^B5oPbE{TFUEt-KMXF{+|yE&eX;kwNoSi8UbXngD+(um zbc^JT`FrsyQX}uyiRzQtmG#q^++aM`d(m9B2$avE0`n#|<(GK(7`pJgt42XVsYcGQ ztLV62Ta52O}zL7)IeTAT6JbgXKF6_rUguZ#TlMBmPA4z2Ao;zyIpQqUi*17*D=G`!~w zm>c*$eW0$=OEjvhznC2U>wWpS6{?3j*6wA-^xL22uJTbs6Z@WCiwg=@!_$8%vHmV+ z016*E*|LJ)^?aPHU-DXjf!LAxS85{rrCv?YbqaD?x)v=MXD4u$dI}6m8cxsV3$j~x zqPv$}eREj?IscFnt=Dui*B%%$7M2f~Yx$J?CxG1(AYT_2MUj2tl==$7IwXP4qtBaZ zFz555Ebty{k_SS!;)tbBb^6&jjX7z zAA49HP6UA+JUaX5!}@^Zn)!jc8reYAsk%90ablh`4%&FMMS394^|CE+bezNduA$WB zm;MvVUQL2nBg&&i+n(^WMP)n5r0HHwQ0UR^FT?mrrmw87j)64Z>HHEWaDcD%@>Q71 z%x@%-ZMed1su~*pjy`S#fz*wF$(-X&zQ0vN?kataZyMdVCQ%Gjm&hwOH&Q4?3yw|r`>_7UQ0k`c zJrNH%9$%C>ll4u`6I90X>b)ajW=K)=jGPa?T6&OxX|&#dD4lCuIy_s03Fw-*I~@Xt zleYXPDljU>`%7^cR>KUkXz+%X)sXT{$QRDGiq-7)erUN)LYb%4pywMX0t{7riU`4s z;?cT2xBY{2ojcXD(5dDHi|+F^MQCL67mk~z=XWnajFXpZ;%3gO+zAf;qMrZ-E6bId z#r?^wE?V{(KVrZ*PVW9Wnun8;j55eS>r!Xx_N9!g?)>v+Qo0w2y=or~p1fhxs!ypD z)TAl-7B1$TDym$Xcx6MEg(W2~F^?yCLUUE1_;Hl}Qu0coPCVW?#>OrEy|g zK_FCsew3iwpE%!feShjHCA_YoCyL+D)^Z+|Y0Fx!QKk7Wa&ErU00%YdME4~)PPj2O z_*gPA3pxAl#XZ{i@XtW{q$EPy2|8LS?>;DvfZq8&DP8=n*Wx6}LJ!=V(tg_YIV*e` zB2_-_iYAluWf_G%DN9Pi$2d9Bh!yQ48ft^Q>fDupmP-a&z1gPxYCs-=+w}g1q7^6` zK;oSR3lUu517u-Qto-YbI{}~HUY?YX?}JCHGC3EYyd9eyI(A0Zp2I zN!>2#X+x_8pYdiDR-Whix%^$cI!~s3v4!PipO7Yg?Rx=9*P>NF$Thsa$2dg@yIoaY=o}IUt-$apzI8NwN1K%ESYIee6>@zv z>k{Q6W^XI$GZ&Fg>!Q66D-1KLw|;DAH?yM7?5H;8OizSG2Q&ICZOjNEK*E)$4Ug_}Ff?RCre5sh z7yOTA1^%pjqmmKwQ#wTl96b)Yyc^m6DxCatTcHwDJGjiQ{@qmuGb*Edk7i0v506%} zAN5QXElQr$$Y9pGd($?r-x-hg$#6stEbm$l>h`(%%Czzf@{eKtwbrJ!Jc;`%& z;mD;?I{a&RSU|8}3RUm>^I`d;iH7t%5n&{ox&k^;7`t^Tlu6z2TXA5o`L-6eq1Qa$ zSw2MvWEJt~a`V_Tk~F6U;~kNy4hbFB2T!W76ickx^#0{4<3CXeCv7Vf(T%R|xyk@k zlII+51EcsMRhl*48^R<|$WiDqH8J67o6->F%YkX(?4`IjrI~NVfdu=*Q2=AQx9dy_ z)D7JoF{_&c`1L>98BR2rrvV_jb|YFa_s2wGA-meHuN93Aa=>1)1XH^*r64CKPML+zN1ZoIyf?ArLAC%6A0J$juvDyhfUv#3BGfH7Xu-ECmG? z5IcgT*|vVO&`mx?-<{u^Gc68s=REPJsvH0&XFA*HRqNGw_|c@`0@azd9;jdj8F9Bw zm^t2t%aCpN&+*m_9=$oGJ7e&laocO{ z6X=eVIRi2NFM~X@DMwEvZptB8l=!3U;3UbJ$V6cIB0^+jRAhAaq)We)Za@4n(1VK6 zimu|h#9alko^2^H^Xu0WI?gWB6yp(UARV>tSsUX8fn57S_~cOP?8I9mZGG~^KZEB1 zIHzTWnFW|t_s!ITgHR^5uVMUN++E7|x@qRBWz1cybzhSY9=N}r^U3-CT1;YU>!KQ4 z_*Bl_mmKS$mU#z{E*)NRliv*kF7h`Y^<~~%-Wl6C*0?TIDZwIXUWpV7WDED7kfpZ+ z@#Ar;DFA*j>f$#N+_8}~yzd|e$cA<0z`u2TEg=DbPY%|G#4}~T8E=*_xyJhFuMp3h zPj#fgt-J3MjkJj3^67C**>gV`_x5MxL>WH?71%2H?Y$^o1JU&n2jq^>Ms zePNfZ858Y6s#1$UjPLQZ?XQh3GyW-T?R1w))wycJHD2|ExPM$;UM>!tH{g;hE&UEA ze@`4lcL|5O@qo)7G!ERg9Q5CqJS8Rz&tBMDwGcx!?D+GsPbJ-qS^$F*Vl}SN6T$iJ z_$unWITiHr;>$J=p|KWK8C~`1R!jjFenjr>jx*AtX-a>C#3w~*-jx<4^X=#1@7rYn zgaE3Mj8q}Rt{m#|1M(RQ$law(Q- z{T^$Z#N+oGYW<5pDlnHB+@;j}hXY+PT@E(|zQ%BhaReqVohQ1LEIzGAUXEkvo7|KZrSLkWkuIsRG&i}TZP28H93m>V#u*R?dDMmHU zCwRxIqRlUa6OWJmbANPpYB8M!)~w*nSM;l7&Ds6c={rfs8$?Fssn6*}h%p zx4*W!zOL-EHM>6%D5gwfx@N`%+?8JbGjccY8h^`Wp!CvUQ=qwBky#Pcf2W8MKus)B zD1F>4n0W;3H_lF}B3a+XH+eulTCnX&bT$_~)%EMw)eXx=SHTD1d;ShZ9cy+ z^LO@v-}Y}_Ifp0BEI>Yx$c2ssVf_pRfo#6Oqs^ueY9K=J9U599gC386RY|1iM7Dca z1$fKx)D)4@v(?<)+#aMl7_up!9Nlc3m8?D?7xnw@_dE{tW0awKwlDVcurctIMLC>G zpv&Wxr#z)9`K3Q!KU2xSX6Ue*&{(=C_Tz~7)Aadn;{Y+Re)?h-Ne*O;7>wA$AP|(` zpWA;1yec^?rr3mw&o1ox#^^#IkiqXADrP3nhl1DueV{TSj+oBtc`PUwHLstfP^S8Lr8ZI-Q6*W5aNybW8Z4KY?B6WJ>&QSBKRRA;QQwdqorB>&SSAW%d2x!ce8qrdh_N~ zhq_Ed;=vvZgL>4#OGN@_XJ?c5lhrw=5S*EpF~7WpFU6WKynARFkWTJapDrDE-DFY2 z@3G=P&&YG5U{I*>;28Lc@ z?gvY4bycz@$|Ey#K0(`=_>`0-K~C~;#-pJ1Gj)QYAyq@Y28V-@XI@xp$Zjg`1G(zH zzND>A=h715Hln%S96#5 zIQNqz-0X51BMk{7P?z)EA&5c56PC)7p*4OmMHIx66ag(4K1*G^F-fRBGIRIfYtnbn zY}sMJO&cG-2Nps{;J21DF-Rt1|DBHn+a-OlJ%m_5ux7VFN|~F3F%{Kc;@*=jj%eM* zb8&P$_+~6z+eW6VaQSwe7>15G^bZJd?GnDY{#kC4CphGxA#{;QgL3;bO?7Gwg7WcM z7O9{cI1zBA1Z<*YvVP0QOioMnGJ3Vtf2W%=red#)W{vi1#`5K34zUijnb-VczJuCc ziiKY&ruMT_OZLG4*#WkZ}EQzK?5aaCy6IXM_gy8$SO6 z#rr!YU1<+Tbm03>9Ni=~-`;fVj+;AB{p45Puh-~oHbKDM`I@l!=Z=Pb=oXg03kpzP zN*dj9mi@QbKksPSDH2%k&@13y$lJVmk$k;T;N4q7dggKkh_m7GmS`^RrqIj}TVse^ zd_(b6YHx4vB`J2Cw7SFQ@T+1(?)*Iz;lH6UdzjSNbN8O$+LMk`vVsQ+LQxNPg@(?* zPXfB$!5eB%bw3KHjzW=;m{?3!5ovJJZgID_lv#UgIHNh;3q1%S;KKMf+V}PV z7|}yOhe^RKcR5h`g!xEyIq)+Q#RhTXc%p&>K! zI}bw}2e=Q3iHQ#;K~9)Qga54~OP7RwT(J4hR@|?AUw=3=ZQ@7k)2h;*#gWF#-R`E2 zGhKdG;+QM{#@%fK?q38N({>^q9^VGal%OByP-#sz|90b}yX^-P2(gtA=B(sadJx$z z&{TtfdWoE#{}#0|m485>pb}YQvetS`fJYDB-BX_nO>46F@6!$7({?CZT!0^-OP|-U zF4r4(N4oEs+zmGB7211LqhfFjk$YlWwVBoQaFLMyicEZMtg=eCMg_eHu_606h+15o z65{*Qlp{|Rtc<}0N@ zbDguvbLNnEW+JHyTQ>rauX`(+H%W%?SPTjBzs!ICGVn!!`Y|$#JzU;k@S2ze8$ctC z61l(A&K2W=p9$8KW=DsIpPX%RAw(Z!ot#Rod}t+LctI{qK8Oi1qvQMK*chPu2vCh^ z&;;8K)A)AD7mK_HOaQo0`1oj*6t2Yn9jrwpyt;ariu>E`{}5sr8K&|7XQ@Bh<2t`` z_>HseJfiE?LpTi#%DzC`V*MvRJJLwB9C|U!FG%9MnS(9__GSO=9VQr7JcbwBScq*l zV1FAM>sti{fSGtZ@0O&{dM3>N`xXSEciP#sO|fz-@LNBX@(_5Vo}Pj(GIxKtl@U+Z zJxM4H)h}^%RvyhWSG;ncE;+OQ?>iD&Q9qd93t`8RY;iUxzn2=pf8_2=y;vC-{I&2Z zV2$U0CIe~}U!=lpVOGAC#&M67Ds_mhMiT$eqenY+!p@_IUjL2f<3pgAYZA>GB5Q0U z)}5GQNgwKoP4-#=nFaU|B;>!H{=(C^eW@&diXxI#*-xNZTcYwGoPw0xFv;1qA+YG* z`|WYBS#Hh-ZhE-YW0Lp#Q0q4Zs{JYRf~#~oxBeD*aD&pm!UPa15DM0C=Y`4LU7i{( zHBrZ$D(fKUOfJ+ELkgETpp2a_^SWfl4 z7`HVZAqCauw$42N`?+snPrAwx6AW4@T#;yas|!E5)gz${WvVj>i+`8~qI2q^WIy7# za?RP+P(<>FQS;1uzBJqT z5E9Y@Y)SKe#;3oN+9^{@LV!5|wV_w$jh11eee*K#|7M$O#EoEmr`;OsAyc?Fv3mDwNs-|30(ajWqH$dJ#j+-kQy`2Qz_ zm;1p0j*z{Y9Vj2w`R@4%_zV|?Eyc#Kv%ayhQ1c&7iCY3`OS%eb(6&b-caRKH zpc?{33+hzzAD)t+dc|icJO0lYKTQ!wpGRL~4dI*)!xW?7orfBa18L@CTZ|FVd9-V) z$-v-GW3tO-KP}xy9D0(vkHnYOG|$ieX}BGtJAF{xtc71U9VT`XZ&^j)?-&aXin*4* ztk8Vy{mfSJ5g4ErC$zI3e`fV~u2lciXAny(cT|fLQt25_)1UiU{>A1*G-L<%^Z z37(xsYx|~ngQ6$J4GoF2_x`=EbTow*E&nCj>g}_nhVmR~zXuPOuOu%B`X=YU5z-0^ zJ5pNP|9cbU&Q*z0w?;xKf7EHOsL23?Z8?^cU!eUA0&qyeO#*Ejra;nO&MAYt2q=RD z9>cmvH9-7Q;G2{4FC1uS>WC`a{yTgN7-4iFY1UKALdMbWB^s1NgA}RKY`}mv*7|KF z4}On~?8z;K6G|d8I|j3wn?>DYQgT+dG9V1^LS16G&dvhpq#Cl~DU(OW*@63yKFj6q!76K0m*5LPa{^ z`TeKuO1*)pc_s<@Bm;5$W-pX;jVASo)$WwmZ<*pzwRZqK6N67k$o~8gZL&YOxX6Th z@|G0wbLQvF4l}BI*=>cUJ~MTt_kVhmYayke`qZ9i3c1 z3a+a|MX#<1w%eokLG~skqn#I<6`XYqB2cGGn?2{_tJ$pH^dQhI1tmL0GOPOCp+qs} zkZ3_=`~-YfrE-T7ySx%x{hRt6>C|dO4E&9rd(+98d8*=-K0fhZNM`jNERla4XJ%N? zz-Q=`S8|j+{(?gf6U3Tp@yi!hWx$Xq ztK+2rL!u)>9Nh5YBz+-Z)8b+FhzMn~78?$b5Ah@QTSsM@3Rz67;4?qVvZ_CGQ#Cclw5Y)x2m=9pvAuaB*oz0E#95V|`7%R1RX4 zM;pA3&-<^lw`^xVo`wL1=EVmLs}`Uj>weJkJF#Zx!^6(4z{Q&>Dt2`hVtQ>+@~lFp=&=4!}|r z+*UFW(zk&_GE@#=oMS(4?OGlYvE*+Yf52#TRzmnRSO3+N7H@64tPkXx91=f6yUYAqF0nQ`clv8fN zqe$=#)QVyMUidE-MxA`M>{n5X650g{^Y>^ncYYyLX=^iz8b=bnBy8Lv#wT`|pj}^C zK%o$v+h6Bqu@)9$M+?V0OX{)jz>3G%b~3TcS|JO@J$E_mt2Ph@+hdH?XLF{a29 z9UY0v0!3zqpEwjga#8XZ(}j9h{)bZ~+eGSGygza+5yYi)> zUyJ}MjV-?6LnYTWF65G9JtYtrtIjz55ox z-5x)fMnL&+46AyJ-FBuNjUB5Jdrn>sNcLPE}KgAw{kg~ zH}zsm^~y4QZ$fmcOAJ!0$ZJsD4D!`Ub&+C7j&Rzh8p`a|)PYOMLBFQdrmd~9IJ^2E z<%tMtc^o~A2&(HB)gFnhxO$6z7gdDeBgT*|3tK~|)M^o~&_>~$K|+Dd)Psi$y}eH+ zt3{p(2}wYupfAzL7jsH!YScu5IBzx*SwRp5fI$^CBPfZO#q9b_V#dcJo_ZlxKV7*2 z{2Z>(p>QAv4R}vf(hmEx@a{lhKP8bLVv?`6a8!EYxYi0{;J70862BM&w`Owy z#CQc&3`TQ=LPKfQ;CgaV@Kt%PnuYi=0EInxk}lc~&&}Ui_+o(`i_+-PG&x>6>$)*NZYD*Swot-Kmx%FT@6#n}uJTsJMOlVQ(D{f6X1Tjw;f@jRvJL{3A8^PgKjx zIY_nHaqX3v7@ny9S_NpP-r*W?9^4OeqG|97WbrO6T5A;3h3auoLq zQY3QK-175(=IH^cnK_NujLU9AIDhQCO~T|0Xlu z@4~Ut?{Rg9mg$pg|4~`@?zd-b0zWzXpvhEz=y7FY0dWq+15d0beUxF2C ztwEU=EFeA24FollgH#JnA&_Tq$!9>Isz>> zh0KXSGf}ZijNLiobf)-{Y-9T!e~+U_V4|HHd?j=xgn~lP3$4zY+WIHN8cqlYdVcC{ z4O>k5&aG{)xKF>mO|O+)Squ#5jj0%-<|G(`)bmP)kuI;nrLu&^W~_7c;Kp92Zm2cBg%a5$HMArta2YSR~ zdG=uS9vjSqYxIn9?T*!_vzDS`L-`VK=4vU219`{q0Z_&g7>qw{b9rKR%KDSB@6@$f zBx{|QSX8Sl!9(qnpYhj@Hw01q0DqmVu^lZ*yCRGmIo7Dl&P*rW(BNkE^|*}eK;(Mq zH+hAR?{Yu15G|XB>LNKxI6F%Zk-*!=@!Q|clD3uD-5x$YzHXP z)(O5Vw3_x>5kM_Q2)fVA#bOr1T<`$I6KitYz>%Z85RlM*xZG>;Dpsqqa`Si7$t+(K z1Q}VJ5?vVVpfBWwHWrroz_QnM{^6ny7pzae^flHsyL@IpKVEI{HC*wJdC5m7DvFeBNh+%UIE6Ury{=_=y{Q6%gb(ie|p^|*mz# z%RyEfCuIq`Gvq0#TmVXbhn2rh^!h6GX3hBKAqsykOOe=fVo!hZIcN@nt3J+}MFN3A zqvQ>&J_PGN`)(h+5OYXl*WQVz_s89>sG+U0*n4Dgm_^R`QnIwMjT^vF9zU<*(n}BB zzx?4>VB`5|!66q)C$BY{^(iCcPNGYh_Mi4ARn^4|NFa~`a+gXAo_G^Dbd)I|@- zWo&57a!|Pavykbg`iPRnW~ApED2HOvV&8>7xokf_Z9;q;J#wI0x%%VDK?C&AV8df` zvLAK&X?qX~<#)H-ekZ_X$nO@10s7ikER(4k0bl*ZB%?Tl0DOBK;PH7f^)2zUfK^FWcUQVhwQ#cJ+QM=v$NefL+8 za3>MlKqH>_&$rKiMu%6WeRuzEP_aaNttE{9?-A>EKKJycSomSxmp(O`scLZHi+ zez|GnBoNmh_E`xJ#Qw!a?PgHksDZ=Oq(`YRsecLHnNeEU(9lp+6ar63OkCJ|jv6O) z;{*0L#UN{MZ_~*}cKJzZh%r#u#7ml>4oI6~rbl@11FO_HgA0@;!bLCko2tPc6`H)4 z5eml(+Fh{-3w(U(TCL2YBJ1h;JB(7VrKQObU%l?+!vOtwe?<}-M4U%#xlzX5Rw)BV z*dQ24yX0;d_#Dmr;i4M}9?_@bIz0NTqk|-19D)X&b1xNVDzBak1PD?OkfnUF``WPH3(#f^ij%7lmFTih*=AM@3sMz*QN-) z&lld*apJ&nn{d4{>#!Xgbvpnjs(=}XLZ9i?*e`qmDoHfD^=LHWzgoq#{{LW?PA&hg zj>GThjX)7nV@L0dPzI**9|pGCJka_N7UzaJVs+lzRo|)rFYYBl^q-)8G_uL-nI!w; zU|K?{-TKPpvo?9IPgM_o|6VsKr;n~rR+w$}h=tqCG`js+9}Y8ndSN2e*rov@(P}lk zY%`2&K8^9J^mbY1bVb&jzvyF|Et{jz`TAUOzp!yY z1|;k2>&Khp#^=7e^BAb7BYRKOc(1M6YdGfefV#-v#FIY2b^l0JepO=oeTW{=T;+gP zuK#3r8QEo*{Z{+&mfCJ@43!PlKXIyEF1^-ey(0+$;Wj9pG;6at#ksoKeoTKFsgagx z*hmvsxIQ`_#Vs9(`$oerA?)_q^-dW z=I7rw21q5de1`fwuHGCaLe=un;PP}k34nDOQMH4o`>0>xbEFU*aKSy>O?1+nglWa9 z?09mU=*;DBIk9W6A8b*g*yNt;C*0^@R8(Fj6tP!~_iX{7QeR=82TKlXyb7GBhn=Cn z^IXc?>>$$cfP9SG^;hVyr~R)Npem44l@}k#%u1HUSyC&H_Q-p@=(Qf!nSp_m;_%+s zf#!-m(n-NbM@RN7EAIk@_XU@Q4FZ5#(BE3T4gx`XHi(_G(seth>F<(5vVrX$8~nvw z#-Fd=-T|!QtBz^#s!MTND?}{7Z6yn}ET^NJn2-RM$uGEQEa=W(Dk5L%jSKc>=Kqc% zJ^%#Ti&n*pj=5^;2+{@JvWS_sAjaFG+yMPo*!9~pmrqeaF^odag0_OXe*iqhV7fZb_2%b0605cVdZ8NcGG=->%{KSH)v3CImNIo9egG%wDZmwD~u!sJiHq6N>FFeng zP&&9@VObn{zNy1V!)E413D}}xf8B+;jgNI+JscFX(Qa0wOT$BC) zT*Q(zAW}}DeLjKm042Oax?52WJ}$_}f*arCEv%*3vn#}p>RWW6y~_I383(s;a*Fa) z{xwszH?zBHgX04;rD9jMtcw^;Cnbf1jJ~mhd{Y^uQyUyg{ni_F3CDayPyIhh2Isp# zYaC6fm#x*)7H?9~0dZ&}w#YS4UnX);Qa2g9G9IwvL;I(I&Dv$-lR?@Wn4i~>Lh|R8 z&;g`O{#i28i;U!(xMqqf9YpM2mLS5w9mz_!;>k8GrlEOY6(i6R8Ga(L%L z+m>PNQ!9uWmJjb7R)WRi^CqB(m+yTYpDMpQ-kB}A8M&q>R}qz#NoR$25&So3`WNuD z6wmSljX+jC-Y4z!p}I4$MaQ1XqtqK}z&MnWa8YlW!)4-@VL(W~v9WO=M82wd9?nV) z#M3&unsvH`i|$CZaiD-R9X|~Z3;f%E!0u1^t@IQt>3Kr0iok|RoZ#d+l1WHj#8)rP zy6b+Q|%RVYZ*qD{f7jB9?E zx}EP7uDj~)Y(oH0C)&)~$YfPUA3L4rWy$q(8#V*G-I}bKlsConvC7=lDSGL0}A?~ zE1|V7+NBOizYwoVLKt-1&h|s3f|xhfEsPo-37-(XV+N&3zJjm|X|gK-;n-&hCfK*& zP(v>JcPERB(A)eGcJ``*;9<#sM=&d`(KNpzH5(*10?1r*&`cj6uMeU9^#hjhjH2L*k41Y7aY5|* z-_uFYQaGGlU2pWxgiwJ{v?Q-vUfELvC$gmeA9aa|iDy}9?5qls^rYll7*h1e5)%h# znf-g=j-}W>MZwPQRyLNrG?-=VvcJ zIAn=<9M`I!e{@+cv_w|2)dNCrVn~<+>I3u&n65&>VStkg=0Q%H1Lc-fPBC)CeV{y5 zpOK%+-sP-b^?|kse&|X#t57&+DIQmH3Q*(=c#fxMG|{c`l_Kyw9X-QKp4YKC z_DYzp4#_&q=Y++s63S}x)akBeaUMG=^9S=lT+CeKPIDdj`H zXp28QwotiafAXxWuIRo!`>S`0muCYdUeWhx95qIYbORzFK2}O9xzOr5l}p9>!xuH1 zYN)}RqXpY1^hmv9>0Q#Cu9l6^Krnzs=mH#I8Css#$0 z3Ed%6M!?@?jub$lMj}jX{z3ugq->ex=^`gHK46jT~n*4vz2ii@Zcp(I!5d zjStFSSK%%(kYIq4hG*tOO=p!Kr?Ur z$c};np){)tlKs{~ChAbm_wu%uXmW;wm%~)c{VzJq)SY1`habqX!(~wKq9B8_HQ)-5 z=!Rf$!-U{H)ao~*HfL(}riNXONj?MgeCg?acD}+3IgtdZvLEwBnYAA1p&G>eSfi#p z*m$Y8v{LasT!wk#8EQD=UO|HW9oVCyl3u5{n!H-p_5m_;BN^ohN1<&ZAWF*)HK4pd zE-lBZjhQR6{S{~_d3pOZn)lNtu6H!v*8Wl!L@ur901MAAC@8q?=)`LG`ad)-q`iW9 zYZiAKB>^=y|EsTGvRPi&DUz2g@Tv1{ww1M4;3Ae)Gqok?CVyNc(aGdL(Edn0G-~4_ za)h(4U`&?_%MN8&VenPTDPS|MON`M@?0P`k-oDYI-wxwIDK(WtU8(#F=%?y zrBtB6`$Vnj^67OyONLv-vAim&egmN-kc`~ka<=5E89v_c@$&kU!iH=hAf8aI=Wv`n z7A-@g_Wi$59q5Z2C$OEiFw?`>y5jZvKDLeV?C6Jg4*DhQy}rL}-8F_yMJ1I8#y@_- z`Bxn6({&M#L_du!JO7*+kFTKV5I!9SJ?;q&4J`rMQ4O7kZ;SnEX_-eqx2;5{6Au&w z@pl=22^EXW+J@5=4!@}_)Y;5Z+Ak+TputPnpFJfu1^c|emvW@BkVvVMc9wpZgi3u_ zjM}s3CPkQS%-wmZBtlvik{>j7z%iftyrZ~?!qaYz#aPXpkr`JfVDsL<-JstYJjItJ z9cG2Lh3bNbH0n*6tmlQ{2w*ClQ zj8|+$23fI>7)`dxEaJuzi?%tj{ozxg4}4EU`u6! z+xeS*BpgOPv|;kLF@oZU)6Q_Mg&uv7)HfNmA0?kvDK1+G@~G9H%=?U)p?-;8(FcvH zv@dsPfUbI~)-VnKU@=%-bv#REm4+%KgITK&y4@O|-}t?eineDTQIYs)(QG(#-&ntM z3E;XSNQ-EDi=>mEV1Kubdu;foyu!;XZ+V4H+&TpqplDL@quoXQlqUEGo0*;>ZjZO) zDLBW#foh>Fp2Z~kCbK?WbD9_;stpeZd*!j}k?Fk65iY3E)eDMUCz_Ki-N$#{-KsLFLDL^*QiL_J?Sdu( zaJtt3b@jTic4-C`lubdMSY238rH@ivTB2tzvSrs3=Kk|=vAGuML6Lew_C1eZGuTVi z=H(0a5@Ct>bkWOKMkwde(i&Xn>!GqQk zwGfguuPR$D@(6*;^@si*(QuP!8@$7t;VBMPlvNCdr^T@?)~Z8uPn(oTz7BWb3dK_H zpICuF2I>@H$OKC_baA_%GlMEad7(RKCTM_FFvH}w45pk|)@sn8V8VOM4V5rEXRx$= zV_CwY%K&D05!oBT#itLE?L~fMi>(kU9KLUubTIGRSFTlQr_e|i@{PNnx3~Y%l!u&@ zvY7JZbwzwuwQCh+>$+uCyM`t2xJ$8mL{UU$bdl7ZKQOM9m&#omzDPZ#s4CI_M>BUd6{2D z`MMzmInXBMRaL_oM9*v7XZbl5V9eZ4^or$;f+Jz0#`lf$O1f){^FQ!|9;)SaJXjhD zoTr@LOXN@sd7D`* z4P8m2w8raKK;!xYsc^V~VVvnE!#dN8@Lo!LPak}|Pe*cAai;kMmAp>3Xh4` z|4_jM98)h`o&8v>q$r|NhGa0`J%|u3^5g4`8XQZoL4}_2EKzD*= z|5EMP`yeKvPkHt#<(X9#AaVF^M~vuL(!^yaPUu$~&Ke3u;kl`3d4qWkcAyjSZBw~u zru`tPM3~e-EkWnjR9p4HMpJ?#l^uKru~o%d#YIQGWc&0ku+%x~m?-9vCSx%}G0d zUw4H|8p`nEF@j{kygr1hL!4GCK^6B%8Wa|~CQS6POOzu|AX|2XQVI=6{#gASi!Qa% zw$Uyi;+v)(x_{DjSeU|%(u^WNu9n*6d3sT*JR|2yMlX$-IEDORe*R`A;x@kebT}Xl zKr=3Z;j1j5*{VJ_$Pj`I3tkdfvc!4x{7>Uh2>kBScc3|Dg}53>lOZ{_o^Jn&O1@&T z>?5csDOjhFvZQJ&iZD_CwOu@UAT&xUVWFvptfND;iErL0E7SS4GwnJ45KaA2%&%eX z^oCShM0q!oQT1^k!$f%(mye=1h?Q}u%WxNN5941e4}NLyf2Cm#6!4}Drz*Q`5p;T; zOPkX6k9Px5;1o@CkeDC8ffdcJl5VeJ zpJn&i)73RgTz1D7SqhGp!~TBwIHCIH{z=kUfb*m3f&rkz0NHt*HJ0}Yv09(My!@i` zUX2u((Uw#}(6;Zw0fzX&fLGSo& zHn6fD`NBcl`(iPk;Ah%XJa4?C#;|k#8aAtAF8|)x&w|iq7}P#6z*Qh|!#H|yjUT1P zrjn=j(#Cs)Ksu>ImdmC7PGBS^WQdXQ;vP_&ISB~wv{oPP>rlh5-uMA)3KsU2kF2Qd z>>^Yy?8HTPVFjuX3Xe)l#gOG`>0{I9kCh=bm9*scl72DtZO=<7!Dhy`d8_?BPJT`6UJ z7Ya>|h*BAjvfzVk;Jnke_m;Rc0@|klh zj_tS~xN^2F5wB8rpTHz{j5CAW(R=U1$QYUVZ#LOtX}Q;4GoRY|7dYzeIBn4?hK7c# z-$*d>rNqjuh)L}7mqiVV!f8q{i9D8FJV7|J6F7swr~Ts?;} z8y`g`8ygesZzIph=-Y-LA?BChA0@x3=?0px@8HeRmR?7GCS#M@oByu27feH~^!npH z4?J6f`fYT|FLJWn@@h38a~>E>1$febYFT zU=ZhVyU*^t)MM^ImS}UZt>7MeTQB(Fk8fPOXoI828^0KvuS>mZ$Fo%I5-&V_X2W^F;L3<)2*5_mdsFDD{L2w4NU&|5%9+Fx#USixIFVT zel(C|JIh*kaasPLJ)b$Z3YJP_3(h)jh!;xeJ(e5Pkv-RyeSlsn^m0bn6s!X*k~LO1 z934EopW}q#^J{Ol3X@K$_P|B`H9rYgJ0>-|G+9!(Mr|hHLA8pkpIke}y0A$+EH_yi za8j#dO*0g|?8-nh{UL%BxU~h;!;U!abw>k{NWt9N#1c?Vm`$!v6jXi}TJUDzjgcbI zEhi0_vGB6)OmN?dLrK(bbb7tP$I@5l+I2!#tb0gnfN_j$RPgJ?lW=yj)h%l)> z8=zW#h2}C6U^~p`K(ipOM~LjlcmW`VHh|@+x6;VM#TB?0cJh<@eTSZ<%q{oVs&z8~ zq$7-nDX*P1u=nxP&Gi+KWV-a9vo|GCsfre+X0ZYfbQ7bJYQ)hu>r6wu3_G>DX+QD9 zE7>z?${SzB2t(Mo0yR*+aDemCsOvM~zAxhbQOcfqP?w|uKZG$Kz?dER6KN#rBRs|| zcUrtf#jXknw+(Q?!K*~yGR6z{qS!dQ=P0{3ECenFdxC$oW>IAf0Qn*b!Ot5VoK(hJ zS~*O0`};P|VV$=g4Hy4oZ~17+;o~^bmJ%*<52n{U`#}j%hJoqnCeI5OFRX#%t;xxW z3E$LLIYVm`6FOd1B&w>amnzTVA9i|9aVb2A!T~P2oekrcLrE%C8>xlZlm@97w67io zh^j|jK=Sm-f#^VN_R(aBu`tQ8W;RsLk@k8wtjh!QIjg=R-mBLbUER?c&w12;rHh`n zJclIsKGj2ay8Tg+32;js`BvwwAsWSrft@70^G)Mb6#lc9FXf@xbt2O!M2KgkwaSrjmEq~Q^j)*j&M8ZXZT&j01Wr?_ zBVpGz#V{U>^TdhF`}6k!TNfN+C=sj@dQbo<-bk}HTd;H_e zX3vXb(vk|-2($^?tMI>g!Ojy#{hY@WxFH3c(^XQk8s&wFTL7n^mQ!1W$f$2Sz0iuu zBhvSdd|srurhj&^?TDW@+!wD)lOt%oV+#9h`a%y~^jS0o=*YApi#@d_XagvA?N8f- zZ0y44uV#|)zI|bn14%GaUj3|~?(S6qc~yxElu$_-nm-N>4Ly*1YvgEkFf+UTj1WRC z5F$)R7FB2khy7*@viYi5 z&1RG-oaBDA;x4grS6harjE|3ayh;mo4m1)++uya3c6p1%xE)BKjJnd1A%2E>Um7RA zY6B1*=hyl22A}3en}%gk`B*`r~_+-KVDh6U#n2l%eRo zVT&5x*C0R{8MINc9>L#v^PhJ-d-i^XF|*_~L-!q{I=Vs6Jp=J!_hfySga6_QWm+wXveu`nL1(GOu#k6?E^xf_4b z3K=0YSFcrb`H-XBA4DTl{zM|}ttLGPxL>G=1WwTV=DKFqYZ6_{P(TkeNo1u62r=R7 z(|m{dJmN{be06m-r9Dxt%K37uDIi$J$1mTJv8eB2LyrCHr6L4igLgNGe-*QLNuM3F z$lEW3;RlB7zpLQ+^769W{Szeef@l4@54f-!C%L1$dn?09EYDAlm0?CRx{$SeAHcK=b(r(k!6E*#H~EP5Mf+{ct-kkIgHO zROH|fAJ9U7s!lWNh#t%$Z@Z?M4y2?Hw?Q70O4KTnQ)ve)CMXXlLN#xh?*n>jLbfhS zDZK05?yhzK>t}$pdUC{XuE51TGJH@gW|OUvQ4;B!6jN$ZJJB8wKi2KAC2_(7THc3g z&5AK0Qu4)}9+mei*|B}_e~ijch;0;-LQ3T1HeXo?Gzr^2T29>C+k5tYWVhgKs@^%s zFrU*g=cBOAATRpk6)QVfcrt;IWyMsNBTyg&&yW>1aa>bMjvyr3eId!)<}xaIUT4@= zOCLyN?hI5`)@regk0pq(!z{xj49uuS;|LJt{0u-;oPsvK z?d;~?#39=U+Lyt$=_ZI6#Jf;dho%oi<5a9ya$K(Z>Z*a|U!h}_|LX;iCof@z!PLED zdt+Q#TKuaUG|sQJXXd#XBxS!1Jd@QcWF=X;fkbfrtr1~Id8Irbc?^VU>{%#&l5MR!k#9|6wC+Vqn` z6n_BmV}YhVc@kJm;D%4ZOWT*1{=L{)hz@22ucbxDfYb#+Y@cS5wWr!(z`0%U25g&)!jo`&U{BTX(MqT|z;w0JZZw)b0S>BaK^Umzfe zJkj>=uWZdKGP{U(*ZHHO%|07aWnBD;C!Pu@1YDBSPnu639DW*gqPqR71SO)^>jXQ^ zEhXoWa2Y38SKHak)k)-BO5RuJ2Q0(G492IAMe-C#;&CE371|*}k!^&x@bk z6qi7d#_1%evPPJT0i{sbcZk#d0UAmmR=75y78OqDb%905JI&a62m!XnCcCw?ia0>w zeFFk@C%}JrVS&hPw#n`f>8-5|(NAhvu6) z@COxu_4kI%x(6AWYkeM+-U~e?^kU?Yx!Lesm*D(B@NV-8e7m zpw(^*xjY`e6gir79Uz+?;;Bz147;-=Vbe2aBIVvIS_IsulU#G6Mb* zUMB8;*~NS58ndN!w~D2Yf8n6WuIG?07SXX_S|}-Q#H|+LVcMj()era?Yq#!29%uOn z7sT`4_bI;&`db~qBuuvwoo6rvpFL~i_R|0^Sq^ieqq4*iSu$-QuN)-Bls&i#NZU5d zQq5m*Dp^qx2qz11Tku)rOlJ67G)MM7zngH~Mo zE!1@thTAu4DJ~~sWHR(CMR|w6&kx5o9X#j z$=rs93znNhvWw4CKqXc)v7{ZncxPIwjek+B(4MzCrWBicd#vSuwCyC-S zhc{dE$-udQET!jZQJ}$ zoaYz0^e?KFJ#d2H+?E9*at?{MIUJH>j;ovNBk%qvythiaTrYT`K~A#tP1aa|?MuUc z3}+p!iU=}^-0Q`lHMMJu=l6Elsrm#PLDeWzft!;RsfN_*4Tk6 zh5bL8zB($(?hAK7noqjB28IUdmWH9bySt@RrMo2s8M;FnR2l@NLAtxU@9Xd0d)E6G zYi126-W|_=_H&w&dz-5L0|(z4a}W$BcI(OfBNZsT^@f*aHoUlUb0+)RC7J$QISU+W z?(+&0J7!*K8D-miNnGqh>)P=<(62+|Qp?~2?<$9~R8RT`+tig!LZj5%w8F1gZJx@4 z|Ju>+VX9yJ=gIhj=l=wRPKr-7p&AC=)MHO179OQo-NaPhh#iTc)JGKxZ`d?)9S66pjur!vCuilq==m{5qQd^*+UN^? zS4lS+!gCATrinW3ygm0nb$aRNqp-K7DlA@XZc=(%Ha!=)=U~$Acl=j+U{}=~8KX$( z167PGeOt)#)##+oxxfr_P{CcSe9@a}-0$IIkn>c|^%u#H`Ac^@@!X zj7n~iWWNFr7F(qkc=7D9Q*y;%_@JV+?0-4yiTX=A=kM<#`-Qq$ZZ{%g2CeVJP&R+;WYGDW^&iS;#D2Y5BFH;XR*BAr72i)H?L z|A^zq`1Pjm#Z1!i>*L&uWWjAMW~U>gv>OriHcX3y_|}l`RYdQCyHsVs z7=-!*uhoDg(f(V_Dnh=zCf z;Gf8ZG~a~TCGq^W2)c#w%~X5TVE+E{4Y}*SXO;=t#|}j3|1SM$VD`~m>ETtarYR)t*mtE z^D&_^c9rF>L>F`Ke|(eBjV%$l96Jv~D+hzl2Ziht7vqkW@6}zr+SwzP?0Ju=-HC4) zrR)3zenmus@Ds=#56z^!5jm8j=vR>+5TFI06&?}Rv&!4*gB|pR`m=C|*f?k~PZHtcs&KVZ(eM(uHGTFdN&Rpo34=&s&d}(DUTM+Q#)bAE3K>i zXdiN{7C`*EVsFo6d1-Y)0C_7SI?aA%fd4O0_Gg;m5rj&;Eo+TVGx&aLiO5)*QN{23 zxE!YX)l$=ZNS#GnQc6iF#@>F5y{pCScUrguA|M~RwqWV!$sw#b+o183KZK4YLtijy7&%ljZLHE zl9g80qCbw~P_tagI;(!7=-L0mQP^(&FVz$J!_WaeikdR^%^@U)X{H(JPW>x#ZjZI? zN$pR?5B}WGBcnKm*DOJNT)JU6Fjx8hKY{_g>P1S15=7>uOTE{;PM3usPR7CB9?-Rk zDy^yll7x#4bQ}gm=xfHG{D4!D8vli-*u<-JlwW~`J{ovRViKs1p~+<(Z#wkSx9H?1 zJth$%LZQ_a0^?H^WknG(kgo1$F3F5kvejjtfu# ze8?}HVD3vN1fY55=wBk6Ee&k$hNuaS^Z6%3X~|&cqHw|p1(1~+yQaH)A={1RVuMWr zXRj4lOjNO(O@9TU?Meqt!?9AGg#h@^X$rHlT4~}J+dOoUzW9bFUkP9*rFJw~Z|Po4 zE=-C2ec$*~Rr9Dfd3N@2bMvWOVKdS2JOr}BE-&Rdb<~rxMhGGPlFovk0p8zs3R3{u zTA5WFnFQbrH8$17qn!5~D=K1W6v{bDU)|B^Us?uzsL0!zeQIrh3`5F*uB@XyOWZ=E z1&g%>eaAq^AuOhB6w+(4y)D13(g-^U&-Sc-x4uBIys>){6TRBpDO+7 z0v|$54pi!ydarFBye5utZ7;rBmI3lpfOHfLCOwiYVJRMpqX5`nTAE~0GeROg-~CgD zAmt|vUCyUdD~~WGReP=@^LN#R5W5K77cvLHb$7dM?!XibGT2SDq3K07QwV$l0tK%G zQ16~v14H60k_?=Qdf2hl^!z+g%nXaYp{61G;%`NWN;sCxT?;-_h?^9j-zw8MR@NFB z7poz(%)b3aLW1fS^PiG& z1LHHe5ci9s&*~f9S$Qd7!O8`BxICJR`?sbtX$%t`x(qeieR!Rw5RlpG#o!EExOv!S z!sux19m{JRN;7EG*(yr6A-z9>@?QV=B5Yd)Ovw(bCNVXkjtNz|?r-ZJiK-dWM~@(e zMmm=r#C<*;i$O3;qN@D`X4QXpQ|adIuEI9(Ruywl@4ga)XkmC~G&@FA6QNW%i3SJU zfAB?ydMIu1gP%7xScg|{ax|MSgVmtepOC21V zC$j+l12<_)#=t}=RxGp;cWLkq1So|kFR1CM*iypQfi72D{V$XHYKAN*-kSJUQ2a{s zthJ|rVH2I1!`3BztvGr0Z&a?QHQt(Ok9Y0uS`{h|^iqUz|*=}s1>M_zhZ7rNxfW%YI~Eod7XXQq0|;IJVf z>CRdnD8_`wZaN&(879%&VSgB-v+1HP$T215z910;)z%F4)RvP}o`rj=p@RUYqZ6x==!R|` zAX^K4FwiCEa9-`|{G$pm7Cx{T);-W6Q5izf(jcpQCwt%2{9+6+2(l5f980`~gjMH$ zkBuD+FcDkOpF*C|u$@lT^*(tzntk$&Wf6;fbRKwJyspsdT+JLwTQL-PYLD7PXP3a6 zc9W9^@cHT&?bGPOC(-P;BUKG$*$wO3L&>uUw=OQqFOnKuW?z#tx{`+iiFgvkKlTvO zVPlUZN6N)ZCxNxNf{O>?=KaAb3;0ous1lC>L+asseYUAWUV@tcStN?vhIxbo9hL5@ zo|$|l8p*nio_!BpJhSnL2QFq>a@c1L`ETxu0X|+G@iIA@HY)cwc0DF;g-KU(*A+ks z%b53jkmJc~I(BjygCFLU6N%tech3F3{D=7O(Eu7z`LLXsT3+lfP%&->4+E@OU0q#u zb#-J!DScWSuSjlupS?m*%?J3FACo&y4OCG(F~Ahk!SeBUiD0F1 zMWDe9L;zIK{)s|F|N6T+UwCPcj*_eM?hE0!fDF&~NDl~DbEIP*vXua+_aL=MS^jS! zWKMJDPV-$AIl89g29R>{78+L2 zR`%X$Y)_*I;4>V4Pc4_l+kb?v0Kl&ZC(-jM`*W@xyMa}0Frg)-+FwH|l$tB`tU+CrQqTpIBZ#-NdM1yw0gCOPwokRqxs?w~QlP=~HI0dd{VL5}A zv04Xk#Cy1Gj+xER$~@S8(wxpolOzrU@G}UqQc+UB=5s$rErYhqOQqJw({!2hN0m$m zj-_{@hR8Vv-{mGpkasXv&{(D1HxL+4HTQ%Z^5DVJX1mAg{Vn^q$Z872l#_q)NatoInfWr%+f)@izBq#7mGZ}%&5NS@0{j;UzOtYafT zeF@%SSHm!rPF9~Po2@L3+JdOJLwH#g^a_2Xu7+jYZV8&8 zh_Q==5FQTp2}VL1T6B!3r86FF*E2uXi``!9q*ZO1lS{pMFqCiqz0@4zzb$Rlzcz%- zWg=Q(q%wIjqtac_E~mQGKBY}=%3L=R5k}0xIP$t2p{+feL;UWKBow_4uAt ztWk{aLxpS9W2Z8O7qG+(gdf9zPz!-|WN;)OGq47N<}G_oq?}SNt&n<(t2dR(yQTyL zpcAr`Zc47_K1)Mb#>`f$KS8davkP!W6CjfkOF&z(LjmIB^XGJw2NxfomaeY6ZCM%M zy?FcfE#Ri}a&oqsx4!`bDe8FO*;2 z>OrG~VpbTPb=4WsNY<*r(BCEGO^{HSQMhPA@t>nm3HPsS%d4~)ZdCNMcFG^2@-^!N` zICM5>GW`!@{Kar_a&_|7`BD=`wPxJGYy+IeKPc^;yg&3Q?96SQ-0trrv|L}j>z+zK zjz>Ce$xWNy*Kx1IfZaG=Z7MxTqscIQULXfVvi=BcrX23Zv~9%*y}GDb+SJw;kmC^6 zHJd(l)&;aqE{RQu{0C1O^6p`pWpFO#H<~5HM^B~&ZyHy&Ep?WA6FmqQfMO4GDAzas zYfw!R7Qg^%akW|k<3Mfc@!?=VeElJ zCfY^S=G z=AWoM4>O93wMKC~R6A?E_jkrP zNpQ`6zOF@(mRFiX=r0PSsR|6+SH!cLaWhE@{&_FPU&_QBj*k8>qpV_|-bMZDn%x)15Or88$mR8&=Gsq@prD zHa6BG_~i2NKizy)0r!#W+tUEFNVjHG7tGbRaMp%aI^WqfMnwp7L{Ujf!EEg5>=&6%c|gEl338- zXs67{*0yc$er50ODZLn2#aeY<+~=rPUKTZ7A!T{~pGSf%ITNt4)kUq<8}By#EMwhc z+EV{sKa~RuUE}!IGNO6=VFl*5#D$?{2!i(k)<+_w-s893VJH)sM>8tM_LC}{ z@Dfac4rfYdblk1q9UL^n?&Rb|%J=em)al?#rjx$vdtnVmbHSrPIH!VyA>x>$<1p6A zQt%F%c{j*9x#(VzY_8i{`1J@Gdsu|8N8L{*_C)7?#U`KPRQKTrO%aQyu4YvAxWmN6vV`?!(PeqipR7L^(Pex~Wsx^ptJ?mdR~>U0;j2o<<+s+bi8;GL?5V#1e-h1d|R| zIi$lwg(<{>UxX>IannV58;kn;Wp>|OM@69)GizySoiBnwUtzGm*6OW-QUoDmI`RvF zD2k|LIP-EEVzmg(YsK^;f%}IOVsc~E)TwB5LC(CdSLNm5X7uHSZEdYhO%|^&{oi?a z=WNbmy&5zth2XMM2JKvpeZ&+daUvr6A0c7vAgme2Pe zrwqz8y(A?o>*UKI3JzsWamUB0jk)#8SW{swBXpx{NU)tM!_sgwlrV&ZICYCY6xdiq zuTgz~xSApi?7~Q2R$cxP6CaPQj@zi~Rpy!)2zwH}jLQI_Xn4@|3jWGPLR}px zI(otpJ{UCr_b)=ogvqlOiiUPaT4Ar;+$T9r_fl68$|Iho>!*o$S`((48WW9~*0k+7 zOLy8Ysf|^~c#b8eP71??Y}*m3#_N)7)CtJ-58m#F%*dF&!lq)v^x65B)WNk(Qd+T= z*TJ6&Dk6+PNAy+N>Xet%Zd~D~7i4qp}oISbk8~)zxi$Hfyv{p& z`KRwWrs+UMPkErAQBya3y5MkA+&jY`RiFyuBK2(?wXiF=Hh_=0-O=YiD2PKyNQjsB zJFjS0{rB(n1o7%@%B3N_4;_JUr&U#6pwiOHCp!mbyr>jI4H9ywfZ3YHewikDW+Qjd z;m+0FZj6Tq@PKO5m-H2!N5K@%&SNzt!*K64Gw4Qz&Q&6M1h$ZLgJ4n%FM)gZgPXn)> zC&ACNvr0kPJbmDhzwPufpT)|8v>MB!j4~!IjYswzb-fxqerUq1zS zz=Je3wd0$b-@K1aJR850A4<4WU8iFHSlpIe#3n_s+9{1v+q8lfp=O%ZdcCXQp^!jP z4J<26$;sJh#V~(mUeVEop}9Hb@Q}GYOA);xNr0*>q38 z8ZyvmQ^e)XtnU4g{Jc3$!<)y4A-Z4_M%jPb`Pkgc>3V-kEh+^(odxGG;+465268ggqYp3UEVKGzVr}`l6G)#0Ad0w zE2|d)H{i4b2Q^?_~jf8*k8UD7QSgsHZoJz2AOZR*K}VT6Ydw$jBuWcGE?z`4$S zBqs-*%^c31dV8L+x&=kTrzceucrsY^B~DKZK9iv3KA;wa)In&=1_3u#rWbhs} z0DHLe8n;esX69=ayL8~uos}@02>d;X^3PMPIJ%k#2;URn! zei{CO4mLK--&JMJs6tSFo++Z|ohD2XnH4AZk>MeRmc=F_4J&=FI%VJumMG&FVT#fK zVbi6VO5|46e?~}I#9ABui(?SQSf|!WF5+ORHZJeFq-?8qy7togZyuE!-mGuIH$$mu z$CLXPe;LXiY6kdLW8QRpB{PmZdL37-5e{0^RD&;Of+tdda#c!|!vA8^ocjIF$}Us* zw{r?6st(V5hO&oEqEZyT1>dBkHDntjMrB|N%G7s43$jft+I{zGD@2W|WH8Nbx(}=W zEmfMc8+&Qy>DgFPGBESwgYi^s{>`7W&s3jjY}KONfHzG|=U{)ouI*OX^25K8-U&1j zB8Bw#_s6QVd_tAcZo|1_XH9~G4^Zj(6hp}VvdQ(d`E*EY(v39N@^zON%;w(x&7!0A zOXmuo$TKq+S8oimIy<$j)k3+EvZ`O%SEg_VpP=iV_amWi@SBElmljJ= zw-&sUMg>vLTy<;ye%)^he9W@8HvgnM(^g*?XW#sL+=)$YD1q*JB+ESLijK#yivvlI zn2w;KL*WxbHz)@;op2|Ea0hPfXD2E>2i$u}4=#|V?8uC#ev%ak!W_c{jhE!7%c-qn zTj!GdC0BQ3&+kR7k?L=g<{!Y3lZpP-*pv*%9@E*kgvYV z$o%NObA9*|FY^ha`MJdN6G@4+D;^tS?SM%VLj z^Ng3VeNs*Kc-3~uzG7}QB#w_SfsfC{#W^qNs#K)gCS;$|oDS0YMR}K2KTg#zD*-<* zY(B$WNohOlyHz{CQTh5zpHqlaspdP;Vn%=4;|f-CQofR6W!yf{FVF%9dx{_QO~qs`sW!ZZS7QL}m&#ZfD*>7jca#~}nT-R1kah}Oq`{f~ zD4dCwH0fq?qW~J{Vkf0pZ<#>4i0Of0#y9ff?zqwP#e8q2EqnjUZauHs>qeapUMLNsi?d`@u={NlT6~)nT$}Wj6DOvx@;5Y;xC@Jp1C5?3E(uCH^mm&rZsjSQdAxe=^QqIq~`dd&?KK3F;E-qVFo6!*&MbgCM^ z_C29jY&N@elSS<{DEdF+B{(MPh(UP*xM=HxA}SF|9Q^y<(2#Ff6v*IZGF4On7II`O z5+^D(L%LHvqi}mWV34!a^A2s8Qck{rG@~~tDd|@mt8lMoc?>oVg-V>3dI6__$EV2; z4RkFYNpfoWxdB+adW)!`@0AZnJ+nkIPSyPq6F*4A%Da;3Y3Yv>lab*yxGLuf+c7aw z51xE8EyU4X3fdjd=VL9RBx-}BYd*j4?UkZQitIDjo=jd{a3xbz+ki553S3){o=yj3 z2P_g@k#U|o3Fqb^4W5<2y|=bG%*md84ZD7Dz9&tM#(q6g0KV}JUjK?%l~i{)x)dn?R(WFZ-#fXSA#d=4T_} zVfL|~K2hm#yieSaK0OXusLaL=loOV;E4#LY?~zwu#|LK2rgzeJSubhYP(_;>R$d>q z)t>s!E=nP66Gaz>-{4Ax@WucE6)9+*l4Il8W)uIv%$$MU2Yn;JD*3PiR*9zjhVISS zptPTwW-4gSXYRaVSPyj8B-K1`)|L#-U6Vk%8k;4Zu$`S<4QgXQOgQ!HXksVEhh5aa zd%WWFFWM>r{RuqM-Pje2$W@QoVNOI=P#ckNMiF@XC$$(ea$89aZx4RzF8)Vjvt0sx zQutpYkkq$$eNz=VReP{5ElSu{Ps&Ra*QR;~OEdD`cL+}o9ex)5Px7?w#7OAR$8NN{ z0J4Is()F4Ky&)v|heJ)K!z#QGw;^uy0Z&td_dq;(CuK&0m^(2sAw^?B><-%7-(RQs zYy}u%N5`WS6;ZdQmdD=S-oe4ao(RnQw@CW>`tjsKA2vS4O>V^3SmpiMd@~>|y+7K# z5>N}PYw*qfU}>S z{yc0piT2ESg{K=4(tfNczu0~xAoDN7kl zHxfe^sw`t;Y7O?o3h%s6kdTr4LaS^|Bodb+O!)9O+X9|r{lXKh&F!_(TFje0mgolr z7#r~t1}XnzySMNF`99!c?Pr->k$!TU;^aE^+_VOosjoL4PeV!y z@Emy^hQ2u;8++*A34hQ{Tmd7Xie*OV#?}TYu)~f&&0o1vL7EY1+`$O)u9Y{f%0Bk_ z$fx=^ofakdi1V@aAFn2fs5!+vHhM!@L6L7n#?J6{38=&FK6Mu+<0^KBo%zx#;)P4mOqD zZ=Xz!rwqN{idgklhO`B-yTS^wu*aaoe|mO~-JV1t zj2V%qS0}no%KIhYX)gHr1oL(E^~vV-MCJ81nDb@Cgl%lRWX3RygxU4;I|Om~elumV zT58UnUc^DIf(l|qoSae!T!?;f_$3=+f9%(9h_96$$xt_W*NxUcE?^7QPusn|{>=E- zfNOW}X?SE%k*YDxOj)ZOJa`!dk`oXMDF$dM==SyeIQp>$9Gu_PL*r2>-wOvG zuezPi(NL8vDwHrE$)C#vktjOgtaWdkoU+2+`2(L$GLZI*k1=x}4ZJx{&VH*au;bwd zb~1NhfkZFU5#p{t$Z>c=X4q+!9bx^=(x0l?;NAn0bQxqBTKeWDOHIW$vRj>VGsR*# zqCq>}aqG9?tB*(R`EL`c>T43vj=g3X;YrybXwAKnLe$5feycvXF?n(2j&)C9V*VVz z)SU=C%GB0Q*ELY6tV+vB10HE$c82zfZ9r=k!@sQ@ud0>-gF+gos`RCpV>4~Z@ErTZ2L9vfln$>k*N#j#V-?~)ZsXerEL z5YB0lnxDgzmlKmeL{Z~=(x8jr5n0CExyArza78F9{ZHz4{E=OavrIGy;81rZ`@*%{ zmwJ0YHUE3>x&*HI@_nBZVt?|LtbFQ5TzxrP?Ek9L>at6NeIlOiv0MBn5UUp7H|Zcb-z?rr{ch^?NUk;f$h zwd46a#jueGu!OyW+xN+2lb4GRW6{ZO8-y{Gv?%JjK#*BU@_sf-P$X%f$B?3TP^m$~ z_2+hPwoal_SAabza`{w31e{Cv(~Vz|Jq|lLSUD#U$B?KV1-n-=tSbQ1MCfBsmX?-&ep#=jaJ!R}-ODdE17fEfGAlWLm;an9R0b^e z>b@#waGE?6+|r5)^8J1-4ZTqC<~7#0c}+HH`}P6jJb&7BGu?VpH#?W0o78V zHP7U3QS6A{BM2aKu$}>&I98D-%A`|hWF!)?Yq3=eOcmDB@GI~cet3a4H5zfcPoGSi zKO^0}Jq_q!>pLg^=M+)Yk9?M%wq+a+LkUfUXXabH&DPb*?ArXUVL(ct?ZD{qr~!x- z45ctAVfG~oddi5r0X@F%um1UX+IgK9Rk)R)G{h~vptV8D1&QkZ^fTROGpOK&ZZFxY zxvImUcSZ8d(W}E*Gu2agA`K0&Veh>>Jd7-++OfZYe?IdbKn2vY(0@>y_1J5J#IamZ ze>+icwEC%g{+q!!EB;Ty6sqar_obmV)h4@=umKd9bIKY&S$Siv2XkxNi&91V)zwwx z<%#W@bad7)ldk3E0YRa5W+o;$Q^zA2Mu)bKA3rMUZ}1UeHLQC|N1g9XuOfu7uRLrV zfodS3F1%p1|Azmvk=F4+jI^|tzta6;QBX=w?Lm;hHe)BLC)LhB@fe+STh=jtH6Y+_%Lc$-m;7l7C(c)#` zV{6Ey1g{XLagv+XT-;&`fIq_`DMOp4YrWzXdh1l!fCm|FuSLu?FkJY!A z0CkeO^0YU{pF*<9(YX*cQ%O>Wwr+Sql`O2%->jN52=$)Cq|<^Mzf_i7Wi!qtI9Y0? z>rWfGyAh-lL;KR-ieu4j3GYAg8wiqv*yPmn6iPDQ@lEYdh2@zyl?RGS1q1xBqLPY) z5r;XCJm^wYtm@x9WskWhL}_d#MU1+(H1~ErHj}QU)zxuCAyN|hR;(~Q)&LD6P=5d) z`EqeD$Bd`ImomKC@$g6g;EUTktRDjxHo@{irddtvvM1U6quWxyT$bkfMLFxn%@^9; zB*mSZYaLs{NIPP}*6?AYadE)oZ((uU-+!{&Apmgl`FNU|+On4BIf9PtHQ@k9gXW;z z4%2?~Lw^}X{he!GB*z_MV&d0!Rw=$XY?hr|%wny=XE{Ld^1>(N8Q4bFmO?r|WszH( z?T|h4%PqrNgQ#a~1`9IgUb>dQwv7$#2Ej3J`PHWp0`FzIG>doJi8=qK5&?z#9U71; zfU=1;F4hf)KX$&}_!}aC!iTE5>BK+{9fo4=tBSin>!Ei84D@;39wjnZZ+{k2H5**T z;O_pxJ^3{UP6QQWZ6#vYb0(j{J}~dx|)(lyltj#b(x)m{W}?~BA@dk z-Vx-n;v!o6wtw}3boiXctApMO|JP_8gzDhKhbF#iVjdUTp!rlO>7lMUz%jT8`ND>*RZ&sd*VNu1A|n%a+vpA9 zb$uEbXjMw+y4lOU69TDD&CH;>x;XxBnPJGrAtY|DwwzWNRMY$Z?!%6%_z)^>Dm-j= z{wbSf@yJ;1>yi*UN71Z}=0tLHabY*Vd8}ohhqRrC#TyWXvdWtfgY&^?gHMf&Nf{dZ z1W+Bi1f< zsEUouFAbNg|A9=gv>53K8RJ+XN>@AGAJ+Hw0D1zm4lD4(g#|FH^L0tk9vH!euSjm) zD|Agy*N1MWYd=%_=md}x^{P}z48B->k+1nXA`AC&UGwbl>}8;#VW2T}`sR19`O$k{ zXASqXJL{*jjh=|ag-p>u+$NN5euRLS_PE}u<-dtC*BB}4h$Z29luqwO74~Wt#m&s5 zN&RBRm)}~Bd|FjdPb+THV5R;h74`}7=#m;meOh=Q1rPK&2OjD49sG9m+s_^SKMagKvEV!|MY5;?Sqf2Z;H>SPscG6fiJW~K!!!v_ zNNE41ITbgs32ws48A}xGWxoaVB7@J7gA2NitIN#pt&U~mQ+2d&Zf{KK>l$TB%QR z_8tln$rLz~5_agYsdWg5Fi0C*2Awj`3K#fzPv!TB?SeXkf*=n4Lgv0P|16{d&4n-k zZhug6#5Jtveh^1$`p#WB?D7v_W_c8A>G(6ha3WzBMV@tW9-N5IE-W~eL!xxk_IB3L zvc=`KkAjo}<1pd=WA3R5xEt>6MQHvSl5|S>DoQxSb*psb;YuE3EWrkezT@nFj*rhL z6QigtECROU!TB93s03e{1-;3@tq>B0_&v9BdWTO#NQ20&DphnM%)n3}n~D{hUb9*6R-!CW`~X+p#2Eq90#Sd?Ud%fWGxC{==Szq}iN@h3Z86A4|dO&DMV zT6$aE$|TcQsSsj(NwMF)OY|1ccQrpEib$_0_tPKBlohLj&<+)GszZ9qfAZktN8|j#V8NOqcm!f|H}G#+<|Ynx@H=)LJn% z{uxN|1c8ti^PQ6hPn493N&;sXRbSY*?BQ@Ac;9APRT@ZBic$;1Z&w21R(>3jUlIRt zC>#JDnJ?HYYO&W5N^|Zb3{2wciiL$mmpG%BKJ!b0;<19Da`Fh;2ny_dS%qVZx!F;; z&@!)_;Zw9JcXdiKt!@y z`AK|o5$62X-aD~q^YCaX4=x`ZXoDaW$bLT}S2!bfe~D!$k8M>MEE^g1%drpuiogvd zG1PLl>sIi)z@F?K9qoLJcXQA%k3=nPzgub0KRK?tXueaW=SuxBbg?Tozp+uM6h%uA z(`U{(mD6I(^?LaqjF4qXzE(q=(II7dets|lEfko6u|$0kI~`@$7wGHocl+|#Mz!Pg zd;ADtaT8GdY6x)dsah|J98#grp@qT>SEzBd6q{_>r5=5NYxf_dp#M3ltUOC0H0!!G zm?u@}v6{k?IOZH=*dI-?=U7=yvI_qLx+5qyW>uE7p+`Hzjmmb|dbU{H+YHw?;Ko5OFx>7rpGqVqg9sHN59QrRbM`lp4Msh)8!OYcYT}{+ln(Vo`2vIT9rKt|PkyfN-#=Wb4Z~Ez=ahiq5=cr1 zeeLeH`bstCg@+rhlkl5Zo? z;y51__?KbHP5eAIO_qU4~u5D{Ng| z&-_;(R{#h`_r-8a2hPvmU#PtucrbCyw|%VxCfqY*OLZ+f=2vQ_Eq~iyj zG#`(P>|qcQI!iPKMgbWUcFduCS8WPuECf_k+V~jXX52|}IeC0Qd|WdM$sjw}Id-|F z?hG=3mly!36whURbC(a{*gwvvs-N0mLV5g=Bh;X)B-JGFYo-zv1I1E!5MW7w zaoYXb71ub;!#7~udw38(auM|gS^fC9P{|H}Bs6mvU3h_59l#{m^n#?-FgE5V`SRqa zOcu0TQ=9eQf=rE)MN@|G#M64o50fqRlhB6X9=9;)_|8gc2H7Mt(t8VpWaq{N-C$qY zmbryU2!$upJar!D<4A#==N(@-3R_&YY9vYi4Ad1ab#LeHYBS*;3sj8|frq`|?`2G! z>Ujb97O4gt(AD+zd4YM4rdn2ViShjzKAY`F!CwE*{Mk4I04c!PaD&%tbo4ko4=Lo~ z`nvP-a-xbAMD=*H-w&SWgdi?lAfX=8DQWywj;v<>qMa$>{#88LIMwRAebk`MyZctf zKi(gyP?FOo6|-c1^`~hL7r2!vq_u zf!>OIzBAAu=3wu)(=Dz(1(^^boEf9ONjPam0eMgE=a)=*C3`aAh>s-ebU;SN zhuoVM-rGhcu9t?ntB+MeaX?3sH8>k$nbeU~k&%*ij53kH$~7Mo01+f`!$BUFEfZPU zTww(DTNIZ?`*XLO)rOe#h?s}B%5jwuIO4Xf6TFnus7 zB2>bMH4m@4U&k%|O_jQ;cYS^O{bd#g-cdGZnVV(P(yE)QsGGNRIFzum0!s7-Ox2|Y z{%p=(!baXIRbp?*YkHoW2{K-NICDki)<)-5Vg1^=FadR5VC zKZ>Tfm-{Wqp5u0uueOLgj4D#{s!s*<1|C@NYb<)0t&MsF?b#Y$O=o`c*y%xX|e+UOEfP`wG@#u}5R84tQ!|28ga zpl4vPz(~^EbXnT6I^iZlVZtF?z46cE0-VQyB#L0963G72>LrQ4TgIeA*)%uIsQ&1< zQa{R)?Fz?TT&=QPGpJhX1()r7CwZ4KFmG~Ixx719(?l7DS+c**ZH1WD_Q9xISZ+rx zQxXf|96lX)piSlJyP~f0(g_z^oGKHE<&#{P#cyThAot^}V0(i7gwUihQ7nbO2%G%=scS}Hz^haZ8WTjcHZsLpca8WuCY5c_YA?pV(Ot(OS{kHC0% zh(2Kfg_IQ{fb3d@$sd)Tk1e2jaHq?2r{`%NNrQIMoUDJ^SyC$0wwL8XGuBbW6eS+4 znMO5>03=5^S5t*y#t+&G-38n<3J%jr(UfzH?_(0JHkJ(Jnif_0DOXSw_RDU9a8ir? zObrD3V{csC)G?1&zQjjf7a}M`_<1;Rs+EuTdyLLEi4UAAr0>Sj-I03$T+QbcU#BTx zN*yY|1eG{hT&1jbwF))sdC35-yCS&WBQy!PWe{tH=cwx(b;1E^VgRv@g>4guIo}eo zO1M%>IBn?49Io=WWnN&I5vB%{KttUa3$>UUjjbw9U2-Bu86yLex{=@ra$;p9D|Of> zT#Zf&aS0SIHUL{>n4GkeUf}8LU@t2#g}ZMne+Eoop3doP;dm|K=Jxd$gRfQ|)JE4~ z1c6KfzKq2Xizql0S^P|BSa*{>Ov)at-Zso0ctqFe(PW z#en}2h0CCCU;x}0bjukJ>|RWtZXfI{!vLy7xhuKwCk8P`JN3r1Erg5IY{!t!9L!K< z_m?o0-e@qdJ!hBE>6^Yr7W{kd(a4Wl8XG=&>Y9gG2;zygoDz&c^s1(viy#x5NCc{A z(L5q&t!u$i=(xD{k6Ug5iY!3=feOhFLy1ntL> zN-*@ZxHfj2Q_>{etGpsfRcV1A7UiduWvIA!SNYoqOQk zE`qP;QDark-;3=|D-QB4i^C2FzSq>SR{(d)voI+C)>@3^Iy5tR=WI zm10TjPFblUcZp(r7b_I}WYN*GzNY?zcAEgKo@%*09{#AdRY+bvdF8TCO_TXNayO06s4gXC=w>BYHog6!4-Eu}|a!A@Jw zwe?6l{VF67R^Ig*#TMP{(G&=j1&LEb%iAdi)1iXWt?HGVwB+@Z@({!lj&_P9nBU5A z>t_{%V)Plpj^Ih?%Jh@V!FEbhmHMU?{F~gAgYOkrChBUOT)tW22Rwy;3S}T?K<)>B zZ}KTQ2V4gTI4Rh-NMDGkd7J450A-z{Ez6g5uzo+ginX+@$Es&63FRTc=$|gpy00WE zNOka9M1_O))v+4HF>L`R)^Y)mKmu_9-q6~jE_%6O##4j^hG5MLbNNs9dalypz5IddlNxrbktd4`xTq`$yEcTrG|@hE@j`kWZ4EI4ntX6j#Z zh5y=xh?<^8_Fd>SwbLJq#Qg2@Au_KFD8f5wYH)l$RJH_(Zt`PinkUaWcqtvu^r9?E zWu`UK25%A}%nuoa18Tt5EhxMlJ(6|xUG+1-`T&X%TnNgPOU)Ukmj2>gri5n3b)a>00qOBor=!*MhjaACfj7M{j^K zS}>e@=&S{vYH2`%1|&h#CkyKYn^H;C%3g|r;cqQo>*K!Jyu^qIp0|M2|w;&KY zm+6ug4iy?u6-8Yp&};1*b~26tQWl=Eqy?^dPC@f-_=`6>MAWh?zH!_Nx73-@ zIJv}Ydyrxc*oL!bCHzp%^iHiDKK(Y%n9G%X&>98nc?dV$n)aU0NnQpj2U7+-*|dxJ z9xy`D?B9JHfZjk4`;(rbC;nf9svsSSw%SCCIMj_(<}=f6o&;A##^)#Y2Vw{fLGUK6 zkFP1_;ub=GW8X9OphVt{nVP=x1E~Q{jSL9DV!lIoK>DaV30iG*6d+Geqj_j1ndN9R z7+U|fkn;*uQ)&4-3!}$C9cM!3hf`oi>?TA35o9ARmIyK!^a?H8ICUxevHhaLA`Q2A z%0S~pe832+23Zz-s~D@$@2{806exbI@a510$q&E@!8WgQ2g5jtOq`7Zk>cI^R3;4G zx|HN{BvTM-d!T@Ts_=OtbN@x-O;9#4w5k)s<0yR;qJH0)>LjWEKub*|``&W?C*IO5 zKD{X=fYbMCF* zn7NHb*dQGl(k-K=Cf*<=l$rMs<-#@np@+DJhzcWheJ$ZyL1xtSOdG&i63T#a6K84k zON>QyX=Fjz?8F09Jk+KhR)sE6AhpCR1m_7Ioo*8a5M6wJURs0gZ&|%5OHu@1CQBQbqM^d#DCQ-7pgZ zQBcqjwgh51BmK>EU}amJWouhnZwbZ4CUid5kSWl%(XG z3p0Vt%fjW*mi#Q66idwUneIZkc3*o zIRXSy73jTzD(*S8it&<#G3TL9X8l(h2e=l$eR~!tYwS3bs8*6Z;VP!c2yI>O5c@OG zos)ogj^DZRM%9!hZEl+hQK69>;hl-J7?_)U`+aSuY2zm%YF9q4+Oa18Vtox6{xBM! zJTmo3@Ac^PQ_dSV?t9UEnej3BQbFWK;2%HPxds9cqdb94Dzh(#c2eQ5OXn1Vy^nwL zofu4UrSmgqs>VHai)0r}8sjhNd?tM1#R4-;L)tFMQJT4T6BAB?sD{&BN6oFw7D-=3 zKaY>)69>Fjhv|AYG)y!RC9*kVV_u-B>+I@E+^{t?tA)T&2jE<>il#6Y2Fooy^5(gb*3U6>k= ztvZuLbbi%1!#ocTsJdD<`u@zZAHPSd9h9ZIENXHlyUP(^=F~V{sf$<5tX<6IRg@Pt zAhysOedF#bxdXj}yvwYb#vMixur0!NEt7(2K@P}^W2xgQp{ZrWgBH?|FcZrrn%9J2 z&*5wn(0e}i7iW{TvvyZ5+c-*1a=ZFaEbueI{cc?ctt6}=j`)zKT^3+Ft!obz&%e9` z#N}cTJx{xWRh@_D`bpaTr2X>0a8sal2?G(hs}3&pSGIP53(uGYULv6~dp;E)FH`r; z**ZejUZ&`WJKfl*;xj+Z78Oxz=u73F&;9&gwD?eW%*_IsfT5bZjK12RDd7-d*7A#J zkPJ2WN*M0{NuDZU-i?$b_x1Cg8kSZ46KPEiPqe?mxl^e6t~}(~@C!u&4A_)ywKFCv zZlbyc5j(MVgpg;RwP7!fg9zLL^uAPR99HsDh`-%hHH!_;B3R~Qd&qM`*`2~?U0!hT zgGPZcDmZUUayby5{VLYZylb&TWrrr?K+FN@U762}(H2oSdAs zl^}%yfAL}UsfokVVj$dM>C#n9fQjSf+ui6i4ncl?LH^W2(_;42#kz+zionFepMo2? zZcI`?nq_+HzQ3Ucs@3=}+E$_VGVZJ9o@VB>=H|2?yiV05C0T~#iReQW!f?Kom;v2R zV|Wl^Pc(jpA3sM8M{oxPq2KTmyUP{7NUhQ z(R7rIi?JiA-7x58jF+IsnaUxP5>dxw2o z?dg0I(ylY8j?Of2tN=mD<^RogSjzVHxSB1F?yCj6 zY|RRLLt?Sq^W>x>6&+gHjFW4i0U?NQm&xO>PqmPN!O4N(mGTiWutG#Kd4KU(61LZg zU5yhg6f4}h$Kh6h<>yCzRt2h* zam}7}SUaI{=bn{d-*_oxSB?5CJoiKt>{}iEuX@~6ReXM-6T&laulKaM~WtVCe%}&|dH77fa^%$&q4_-i->7OSh14j87uY%WkWpmv(C?|)dFRfz6CmWj}>`(G7y4&OwxzyVk0W(Aj zvsLseT@{RvFQITSOc`zBL#5dp`7MSuHf}=pknzIsmvnd(Kte?3N7ZDlHP3Dl!@-4n zrt?BduRSEO2B)?wHLEYgwTi<$hygA7H#MFu1<~fjO89eCpyC2i_oi~nT0W-cqm4|% za}Nu$NOa0K`EB|cQE%e=)rGfHBAxK3T{))@LD!pniF!H~fB3Kk#ZI z(E_Z;23&6TzT%?ZCwqGZN&04{YLtTB;-h(h50q95wai_H|>-lM!kNgfsiJwrVMailZgBWucc|&+0 z!NqP&FSm2a0THXeWfmdLLEShqqsK@^EU5b1)SMCrGMUTY~ZYZ z82_hwY0K^Es1GJlJYHGi@$s<|H5gP?RdoVz-C0kbopFGeguMuY1MF5jT1rZ&60X2t zc^2X%aj~a8%lF&qhomp#{7aI=rkGjAqKShuFwM1%n(g|YCCkR*v7?PHII&YEFgm~_ z395hx)%piuG+yY_*8!Vq(PumMTp!3Ns-CF{hr>?0ul`~+aPazbWSA2Ar)F~LYf!d` z!klX(E1j77LY0lrES34MYCkM514S7loGYWtKMve)j!}N9)80#)nVXBUse42#bP%`7 zfS>v#Y;%WkwJ?f36pXPh!#E`A&mStEv=wOE@hg3*`wK&hxBJ>816~GFokBx)q1a)s z{*dhExio+Uct>Zvqw6-?A-Q|-i0~6pC9RabP z|1x?@E|7V*W3)S`Fc0l{5W%&E4r)v1IZT4bmxb?K2{rms9Dk;?Y;6J6C8zGqG@>j2 zd!F@U6BgQgir*o7CTa}CDUUL+y{9DL4A734QfLB%q>lNN08u}?aIBpQyY z*$=^r@BoT#W;agmxLKubT_co|MCrjBz z5ul)fIFOKgmFHqX-_rL%B+|sgBe%s< zRoRjwkyT1Tvd@yKK~J?-O&VrNe1c z@ULYk*cgPHa4y9?ke*OJfM+kba3hwAI)1mV>EfUq!mmN$GLWV8W_MGT1WSR}N1tDoIeH^cQ$Jt^to5NRbh}$kMR>dIgyO!W2S)7cWuD&oAAWgc4QGsa#E%ShW z(z#VM30BFj@x{Tcw)<@o-23MV&+py{5?V58yJCW<4mcTlFuue~z-lA``auvU-*O?q~k{*nj4^SJQc2 zB|hiDeuv*-wZDm4BMf;3{pLXU?Ev5~Tt?&ZP$-kk5^Wda^x8o+)rkJ9^bEh^r|u35 z2ZKn$-uxCfo84|@4*-8wD>DBhHTV^X<;pB{9;`lZ4t)FOzhgM(9g0F$BQ%^6IHefs z?PdZXQ}2CMiF9tw}1Lx|1y~?$Dtp#r+jtILneyO z!A<`v|KD}3_P@L!+3Niww+DBT|u+kJOb0?;e#k|Mkv)LaxNqAG_*Dm9d?+ zOTNm_hj;ID4ir=}$e*Xwhdil;3=IIq>iVcRSRxHTV_L-C|D@e;w^E$|@cU={um76k z7->WD{r<2p1QAY#FI8&|f7P~-A)U`&9($gdpfYIr{;c=y0Ke%BmyPzMvkUzgm;MK! zIKNjpu#V7^l>1emuNe($PG<`LbfPH60n53_Vfs$J`vQ82YqMBFypo}}Oj$M?kGWm4 zxg`$WmJQba{O@H;$=&V+vYW8@48C!4#1tg+2(l;NrGNW(^N*F2O?#OL^1rGe<>D%?Xd^*%?s(~z~5g; z@181m=BNmMma;8L(6FKIEpdMpP|B~m)XYgwwWQY=EnjhHCqHNpc&g5Re3joza-5J< zZI{bct6R-0yGbR3V0QQ~q~f!;)icsPjFQV0g;#}Xg4il8`oAWSsTT70Je>IaRxqyHWDS211|ZI=aS>qt2`a;g`&(v`hE zuoso^x|Wv7((5<>Yeg?GD&@C=LOujZ$T>CNZTOP-9yZxC0w7!nHLXY*Iq&hA%}xg{ zPh{aFX9AJc?dEaO1-`0e*w>ltxL+*63|OOZk_k~UK1uq3#DB)Hva){GkONyzOiC3Kwsb$e9u3d z;5h=7_#j)5f|+YvFB0UhL9!-}+#q03$y8L-8@;Tojl3Z47K?qlTW_5d)8D;W!|#Qu z|Nd2JX0;}R9FpRweSz)l3l%AD^kIqAB?V!c|G(Ia8@*q&+3m*3n=i*2DiwJDWm%MnM(_F%NovhO6zbrUk`*m6)~4hIaJt-TkN!r5`i&#pHp| zco7)R%;6X+e2E>V;1gX=TNC$LdoKpY!7CtyN~WvWf?;t6VomfoR98^Q8d4<^eVw$! z2D!|k&7!V`Mn9#szF0qCwjR>h1qH3V_N7_TpWKx;NnRFiv@I%37Fw3KKzk=$k4W!E zFwm_ak4tpNIL>@FklcB<&&gRIY!Z}=@JV+e@;9f(4yByXyX`+s4wJ{c+#|D43T?@x ztf$`_VRR5(4SALdNO||9zUL!92@654F*c|vgAc@)B|It#`j^R_3%=J>=eCN-4p7+D zqoxFc{YushK8H10LWth8KAPkaJd_ciSb8X?(_F?!J1?hPHGK4R{wNcHfsk)s=+HJ} z#?z^8oS}M-gW>JP=~mV444M{dHP6HohW)?bZuui@iU9BJjQ%kse~D?kE0mp9k?GLu z$@_VJq`_TR_jY9_$;o_bbO8LS{+Up5IZA-~ReQ}uY#+@=PBqg_`np`$Qb+rHD`BmBzi;Z0zaFL0{{(K*csV(|Ihx$#A zEmUb4^sfA;-Frp}Y|?ZOZcKDG3^ok=S20(#yNURp(EZ7bu| zb^>`ypS_IMTCTq%h>A()SF%=Cd(O<1n0|fUk&P2}uW{g&Cq6LyT92EhTC1$HGrL`w zvx^b>)SWV4slOjWO9t|*Xy&ir9@mcQqtVr!9vm#pZZKVadA#xVGEep6()AJ0#+6LZ zwRpT!WMMnwyC#Q=%N=Z6Co|5TbrGhOv9KR7!6SX zjza}mAI(l4xj9Gj^0qcjSpz6qJ~lz!+GaF=U>apZIOK4Z|p8w7B)A>4< zqp`!U4I#K4kRz_a)U`%^c<@I0$<2!bvcac%AtkB5wEXw4xrs+jlIZkIQQQ}8OTBH@0 z?Xgna$}V)Pb41uysIqj`B3oS*aJnKm~x*qTCG>eU--YV>ql)c{ZpO+*W{uGQ615`03C0?HeTk4;KTo@VUbv$>M+sTBkNgl^@s`grM z1}0CRIk|gG6T1Zg2`&K6_}rX<&HPV^u6~fw{$AdcN?K0Q2C8a0ST*5};A;CL&~IN_ zof6-<&{S;*NqB{M9~aC1yX({9Eb2S4wMdyOz{`7^Mo_&c@U8+1@qfko_d+?xUgO!n zFbiE@=b51tr?P&#o0XjJP<}yYYnA=}oVn0$f*C~ZFLqE3J$wHMY&Gp@g^c%=PQ4K% zHE?94(2kJ-92Tfs98}8=%;*MqafqoD-xWW1cpeU&^Ke;H2ZZ~>b1=37@6F&QSsM)$ zRMq5U4cQ>&myscfA|_tz{zWV0_y+kGVw>|V59q`y00Gn$5F9KR6;;)av9JJe*V*5e z4Pt2g0DZsuYHI8qfTc~&qC;ELcHk`f{d-I~;{_t9Ywd3BW>0{O8C;`*e43FV7quZP zoCtM9Ucd#~WUwbQ_=M0#{|vMwCW^ZqAEjq?tc?G5L&i_WLKuZt=({FDLNE60@RPI) z&PY{6LZ)IstIZN?-FJ6ts*}A)BC=zsUDHM_sDD^V%I?eQ!X3&BkqVNRDvzCkw!igr zcKitbMH{4nRDDW@W@{LU;fn6P;kxhJiwKnZhzNKdW2s?h{P=Ca%BH6M?ahy071`$LBxI(dJ%xgMR!M> z=i`O2B7q)ppxO6b196FjJ>4RovQ1aDeY|?T=pACKLo0X+-TOHiKI)pi-np{&ob>6R zI20^Uj*WvuV(fhllj#)(HIz&u&%~z#$M0aS7CXYb;?x5a`{6NLXx9@>dmur%;$ed} z%T0TFw6lCB`*$8_aH7ib_bpio^wiPiHG6Iw;Whf>9eHC-gw9(oX z&`DvBu?t}7s>J>OKsWBMSGJ8)H$2b`@?SU0tc~HWsCImRE{>||0g$1PX+Dz0J)V%! zG}D3H*$*@yX$@jK8e9|zH>Pd-0eCv|(BecI&&a12g}y7zoI3`OqwxTrtQM0QQ;6E> zxb&E?XRo()+~?yrG!!FN^DhhjX5cUa_){a@?3i3<7Vs|2RJcX_!BIVyjhX&W^%wDJ z**!X zwGXv)8yj!9Za7`1hxUlz$xN$!@!BW1R`m4b}``p5lH?5 zY{V>x6@`Vgs{j)#H)Tad)yxbcko48FZ*;u9I*g}PItz!ry>_@Hdw~2Em9h^h#k7vn zRvtTHh;f|JQ+@_g4ydw|5*qJx%1g!u@i7dA2tVH0Z>@J~z}gaHyQrvOLbg~P80~>T znzeK?u2Y5ZWtntVdQx3=hl6kbRKgXKn$4378sHPKw~t+U z4~=|}o&Yr0cc^MyZORA8|6?ZOB1mX4`HP`#)~->>75%U2aUKm}p<};UCVwDS(L8vh3g{uV8=4cNRwmSR5Vzx%S`(vuC}CMwVSO z>Gq|O<;niVjvkbkm$xPs^{uFn^X_&;ATWjOOF1*y7{?mA^sXIHr_j*>@ZVYaeWRm_ zL_B7OelOcFE6>M`J~}%)zaw_PF~|z2$@agS6Wf1wQb7ce<_x?TiV^621e?yPC<`Rd zDSin^4IzZ`)8{8+i%g-@P}Jj2P|NBKSq*m%rLID#F;7=%>FP!PXv`8Pyj5oKhHNA8 z^3=Nn$8n2wxIz77FGZmkG+>}(bQCihx$Ng@{6H+gjq%ApkYDjUKFq3x0;xZ;XIH9m}Lz@z@i{n#Nv2!olC-!UT$*zHO=)6$dm4?I@thF`?NKMFL5Poj&!b4HOOyq>TwAVFTi3 zsZO`(?akP;?u*r0ZzoBO02nQ_fNaAUI`R7J&%z)YjR6Y__Z_l>6hg z=!2fz20yz$VO{qUhfAc%jg+2B_ zmx>zD=%}Hsy!)RAa$gC(l05&qLL^Y}?MkzN1C)X!fL5nU#SNQ6+sI0d?dGGF#6+kQ zM+ZHSjns}u(Lcr}AaqfX+rVCeuDM%KUC-jhQ(TSDNzZ%Lkkek9@F^nRpmh<_ts`4x zThW&WEM^zK>y8fJ2%nonLBTRxq$w}A;k6||L|ucl6(vlksp%3A<$cm0XUoUTR36(w zhV)-JDa}w>Sy`qjQU@QeT)WO555lRT{BH(zNj&+fXB{XKE6We(T3>^%re`Y3%0OLb zi+cTIO@@+_;Dlfeu{CVmm9EY1MqWCPQZ-MpQT4`4B;G05KM!VrtkJ^Z)cx+M3sb{+ z*PO^EWQt-}Hu>_+`=2=o`H&xMxM5XfyUCP1CDK49QDRnj3RKMA=8=24O9G?pTpNBpLml^+-ToOPdcEZg$@feH&w$$RnP@oDI~DRjvGmFE zbJngeo42RPRclsg}li9E{OCUiS`-L*bMj_7Q;+;T00NvZSS%jD;c2!%joPOx;Wa|Ig#| zZ&I1hWZ6!!&sTj%ne%@0ynQ?S>pG!XB@yHPWL2v}h-FUEGspT@n!)WweUF`Y$KSC& zglh>2%^Bv+L|dErgyojY17bS@CG}BNd0B;~rZ9Rm!cFRDlkpNqW^;SQ#8JO=b#!_k zTaH;qsN*G^+w%fKY0}b`)6qV#aZl5Y;61~R())|yMQ{2jgivV*&)Rt-w0>>Dn=0B!;KoO9L9Ahe{~nM3fOTL zSZB0qVlLKwk=aF3usF34x{?#xKWoQ`pIXOtwK%2l9@oQx@;vClW*B5A?LiOWZqCk) zb<|5rE!^DPLj`!WpE+*r9|1X29){_{Qzqm&JlgY&bBpO^rxq4;6F-}A)2qrhm`1_F zR(^gB+EA%Jf_WqzGHth)Y8*0O#uxkmmUGSCFy{FtB=vTM_Pr%5ef&VeU1M4fi`+9{ zO{md@)lDWGsq#Etw+kyBo|ghRnF5!_f0;Fs&OH^;f7Ic8R*cC0>6E{nHMyo1N`r^{ z$$ppU)IvX-`kvH#T*2)794Aq$n8(VBY-f>B$7YPAmd3IUBsBU@5_8OtdOsV1+OWM% zBZ-qdujAi$yCaUDb~LM%q%=RIF4wJ}iDMD=0TgOC?&k-NS0k=CF@BF} z1y0HE`E@5wBu!UK3zH2hi)WbRe2|WSx9_vwriv_e+Uv03;@s!2Z;O1bXop9`PRi}P z_c26*R~N@RiWM-FYBeRe2AlsVaI`E-N=RUF^6Z}SvdeSxfX5}g@7?uDarDb;y(;rV z-dNIlp6!3gCLp8D)j4KKbUU@tRSqseNeI7$WqeIW0+yh>Zp6eQRd*NDn3Z(|d>tLM z6$b4clmT*xR=>fS`deE3R{6L=myh&SC{?le9Y67%l#10XrfU1_oblZj*s zpq&CztYRp)mQ{f}UTDC47ru`Gj^y`X_0F{NHq%3+#Kn}8AlW1%|ACU zn~NKylChnVkRLdq`QR1Cox(WrT`ZIG0%wLn^c~czwrYBOJX7&Qa(I0aFimJ<^Rr`O zXlRGq`sa`p0r`k@6fok}4bXuNloLi0O*lMGR=c6m^Z;)v#}yeNOLDpsf0q6YZUNAe zRUi9|!c)b?rLIZqxcWPeaCP6}Fa?zcM~;c!VUpbPZ8l#LAy zFBRbZ)KNj?FyVDK-QsR?mN4Ff=G7COTUe+lbH7sMXv<@T&arRDNX}Jhpoy(t2pK(J zm-e`_Z_s+TJNe7U!Q%R0OOq$Y*X6E@6)Pp1h=fGVZWNeKs&j>%F_Z$cIVjLl?P+gq zQOw95+a54}QCvLNDGu7-O9P17+uU~FzpZc$4cGTth)KYHXiMLLC>NV9fG=Rco_>_P zx$P7ojMTM0>Z%mpGt+zOk)3KKN zRrx$yvBbjCwJd5DN8_5N@tCn0&8zufrM#*hicPAxLaI@6Fi=K>34YpR*6X|TFOO$& z?tEv+yvy$E1<3}m@I9rRK_16o$>P?Hvo%4K1QM8nC>>Q= zptmd_<%u6QX|8$pJu;r7EGDq0z-Q^rq=@n36|sN(%U!R~rlHg(#V8kWYq=9;8pAYt zv7XIH2jSF#7BPFZpll{(9k*oLMz?)WPk;=AC?C}8L)G*IOulf_NC6w6!0Xg+VoTFA z?33@KkNzZ}3n<{E6xi>x`9o zWknlA@*aGc56l%vCWZXl($#L0I)J?3iumx*3V3<|cx+G4_C{kU8#lSQ#Mmbn@td~h zwXS=4y~6&`qWHZdOTE26P1b2m$`Q48$Sz-QICV(Ja{<$qDptcSlo{vhVq6YJ>fT-G zMnB&exZCx)t^Y}xBk?yRbf;eFgP@RoT4=aSLeY=@BfutmwllkN-kJ$27VvOuq=fb+ zShIGd;B#HDH?UIpPQ9dPe2k=0gt{hhq`t&49L4~)_6^D3xAY<`)HSZjP~_y$qQb&f z;Hx|io7ZW{M>YxlVR$l_)WdO1sBhPBM8Tcp5z`VX;h~<#4(V?APMgHoEKAWG2pl?Q zt6gaU7x&*rCE8bablJWh4|RGpl=Hq+r^~w4$satl-;(eNoeXYiUWB+ zZe|(*UBD>b=~9rFwXvKXHJGjg`Zj^a=hKtA=+*aVpieM`J7^bmQpfBI*@P zgPS$80u>Pby?$2zS`l*cKQ$dnv?lB>s1K5w=Gx6X)5XED`L(tX=4x?Q!Ge-Js4>Y7 z5j{K&iwW9QxN9_;VJL4RUYo~1FfX^Kay54Hsnx>>I&WKe_;T}sB=lZnE`IHI*Y215 z`&+sGgg}6>I66AoNZh`EIH8B#lEoOR5~SfNZ(-#1*89FiuN-+h!j9O8Bar01W34FK zej@@P+v14;zNWZbvNa+HOETk}z}Ib=50-M<#OWI<)ci~v(MzF_W$4`+fnci8T=rq1m~>d^&GmJ1 zBt2S#xV@2awvTo*fW*|btz66eU;E)y&ue4GKKnqb6v+tK`QI=V8 zR5^;o?J3J7I&Tu2n=W1%uSK})GP&-CoI%^}5ig01x6A_5643Y`!5yK_386)DyM$p8 z$0Y9s;zxq#6e+()Pb4yG0*?yWfI6_B0B#_%x`~ceAF!gPSly`@yLW_9A143e8%azR zSI?~7$9?0l!>6K*@wL@_{yVd%`tVfNki~&5W7h+VhK43z3he3+HHWY8bomK2b!W0=w5oki2{ZJ-59 z!7WIQ(+Q|@BP*2lL1Hqgr5H(7JxoU{BS0KFCA1M zr%W7Ci}6E^1Bn&~BhE@7`BBJbJ3{9GGP7!t>ZVY+qtQO_`hyY17PPP*?$WL$G8*rE zAZ%wa{mPM&=F>Q# z7gcL<4|kfzL1^R2_R^;sVQA0ekV*$qRxsp@@MCiU|KBpg-n_x3R8 zayMZmPsWqE2U0ia&eG<-CN(LJ4=; zv5>yCi6Ao?#^ur^HQ7NB(XLBPrIGkWA|x98?B5oDr8j1ZrmS_A#rW}u1F4W>G>ocM za>{INF1hYWc@LJf3;{cpL5hn|U^dZ_-zPkEE-@u(T~xNI`Yl|q^i`BlPgU=3X^RHm zaBH0YyRgvcv%LE`A7g%AJR|5#qoW)Kqs_qq7jGi<-e)TxtXl#(4%g}VH-L)5EXK!l z6gW8)`rU%&54o6^TWOO^df)zOkeYmBChvSvW+$mu;0Kmke$s?ocw2Q7;25gyjRWs0 z19I||Uu2B9J*neG%-rQI6!N_y8QgIc40d>L2Xqt}~N28NQ8snh2G;R)j<3kHD) zA|N&${f=|Muj;0mnIzz2i0+$X(e#umC7#&i4AN^UJ?ByFks+$Yt%x&CZM>@sOJALU z8Zo`krf5&)qMR@88{KQJCo0Xa&96}3+u4a6PCzX~GUZ83OH12S*%?HoL!+&wZG0SC zAUpb?Gpdl-mk=mVW4s}q#!1K#lo+WIozpS4b$t%_E*1W+J0CJO-%@76Iha`{zWM8w zf!Y6<`vQN2b3G(#LN^32px8-g^Az`M=lQYBxMvez~VpaCPN+F7Ah(IHy)p0YfOb$-H!&&KFsDoc~?0xhR)afEb3D z6fV7ol)+zSLPw~oqABs=>VYcJD3gYRROEG{qN)ing1L?vpYs{ipX-lC`Tw7}Wi)@2 z#B!_L*ZQPLzsRo#o6x-8MqS3wTr?PysmUHnFyT$pRNnHRbG!jNr#Q?jV4nB}{ar%Y zuqv3w##1N;{?LN6Q5BmWN@QSFmFdQrF`UK4x=oWiiCFl!hxHiF(8|s`t#Q4gNXDRV* zZr}8>UJ&4>dTm_b?dMdF7naKy0CD2OX6|`A1Q9By80V1)#u=}@$dfQ-hEOsDCeF(X z7N!#u52U#|qPG((N?lNpj88cOGKyxgMO82YKCIxduEZ$Io)Tg8!O z=B6|WM8e|aaBP3ihmitH&PS(-$-HLnCo)Z|z9yP4n3la8rB z94H#8KXWj;Bq(BKRM?-4kbi@!IE(~in2X%2wH>{^g}WvU5_p|QI2BspZJ+k{H#9dl zH1kt}A6uh}VnP!XadGCj($D?^kJt^t0$xNhX@T-6t;^E){1gBdYzK^)fAgQQ;vO8) zTD-W}9us*S0q)c8?wI%|hBzg0dvO6@Gk!zyC(9JNu@DXeR8_~SbZAmgwH5iIkJXaB zx>R=-%3ewK!n}COxISG?oWl z3&w?}Y>4A!sXieg;oovn!QsTH%uExmL=t1@j5%G8hx$ArxZ~)P&!z3@P3!e&wcz*A zow$*7R{Vz6OD2{IR{83BR;D6A&AHPh3N0E63cM|$Z3g;)v6k)kOc>dbxG2@DV0h7t zMr8+_1qcf{&^J(eeW>53MoHk!UDAAz*jCAH11@Lr_$UzXQ7SjPja; za-V5iU*gt|TG7tHa-<214o&27bgW?TwD$XbI6WG`7UMfHZb zbiE#Pj7d?sF@&ArfyIkcK24zRs%t#ldw5!t=J_0$0^(+wlrHgfDq5vTKEQ@|!{xead-xxe*$x!eaW&(fmoQ<2iAOk<>_cL$~8_{21rE3@zzRyF%IF z)-XI}iHoYsY`kmd`*!Oq*3xn1Z$F;G`mTWCP%3XAFVr9`UObgY!Ic=gqtNjOY{jNI zNZ@}iv1iCn$C|Gi(fjH*^=_lfaxpulCBz1H0Tspv7Se5qi@WYPl9_~m+q&Y{J3649 zbzq3)_5e(q<4iXjPCUl&8e2($+3#Q36vO0cvj040#fD4C7wg2vX?rG*TW*L}m(6ZKLYG93< zO_piX`S9ppb6)f|WbM>DED(5`42QiI7wERhHqNK_=nj`!e>LPK44C``iZ~#UyM2bx zZHF3;xV;KH`7xb#%AwAks2rMPFZUW}K5m=?K}HN&gxVf^Gtzr}*V8roId4d^?NKXz za+~q@6c2;Q(6jXOJ$Y^RmA`-84Cd~_o6jnDKcti0Ap3vSEm5K3}$ZSy!&iZ)?%q5Uum-n`|UzF3gNnqcE?O* zeW^O_X`wz?cC)YVR)^l@Sjm>Uqpb4Es;iAxrf0&}Oo`0L6$4;3tKFvoWOp`rA*)lHP@CT9 zsutd65+nbdFbY1ZV(Po-q?C(}5=&13s>8jC@p@>6ZVW-7rLLtVFqfef7%S$oud1Bj z&KT!A2ZIb`4JTP+T>?+Ei%Tlw_pvv=aRywPUR?YPi=_=f%GCY+m}pHa^jn)uhp6C%xuK-SVM}P|6Z_V_Jg!_@ZPmAeB9EBf z-&N2|Bpbu{%hZ_Qbu;sJG`U0S0zJ#6a5&-FAJy>c^fyxE)9bT?`}K1Thk-2p!lT=? z3J66foJM^DP`=H>?%y@3n`a|l+wkp8yPk-j=fDL38i<9Hp+fWX^F}PeuHePk(N?;~ zC4tMUNDbcnAx=8%z^7dHp&~4J6)w9{+y{4A`oWm^t68q#O=({~SYqU?G0geKQ%=x?7H>XCiJL&{{7LXRrO=i6krnT$7l-Yob(c#ZOufSs4pZ5*YJ$7F|a z3*$Pf_K2>{BP_d9tW;_H_=koXalYPw<%OM|UR>@wPQR#ZZxHV9b#Ux!E7jYJWfc~H zVtd=BY1=LXyr!T*PL4Ax`Z5W1Qh%ykn7IAg1_z2tE7D>LwRd>aMfGe^wd_()e&5Ln zISh)8G_-AsD%a{A=PtKAI}#(nO?u-qPpckXZLHGwdP{hGcyZC$$*DR8mX?F&do`%N zHmd6w78(jxMYP^((qpcGsY5qCDB|d5ln3p7`j6}z|49Q#0eV02e@tCvR8?)T21O|; zK@boSq!EyoMw&x6lG4%*(uk5$0*CHCq;wxd0SN)=IFxiF-Ed#f@7~M${(Q@|&fa_W zyfe={^UUl&f9i`g%VgU@PPXTE#UF4tHLiU*qR+^;@vYQ$M-nR96470>Uq;Uhj+HN8jOTP0|U(QqM2zZ@q*Sv47dtrir6XSUt-g$1u!~G z5Vb$BdxXVa7(rA7FD8nj$5V|%7&cs@ClQEVoZQy0VH*j90Gf=P zd2rpK)$Ln}G_PE@)(hN!abvxk`yEknV)9W;Ju3$vGb1s;2;P#h*H^4I*jNg0eV>H4 zF+5JP_lH4{jg3;B+_y=y5b2%i{-di_)SZSMCg_Tlc?)g40OW~uo9*);ZxH?_VkFKX zW}s;I-5aKJ9Kjj%SOcLiq$w9)PF#^oz_f9d?q^=0XNVOli7lK~AJ`L%$6$X_Iq5Mg z-HApq(;^^)i5{XKe#4;3IB;b#_uTCddaNoc1(ak+NCE(ORO?cCT%Fo==e|i%y2CDB z)x%bt0~b_NK!MK;EWrmQSp^%N&uY}xR##&gk@P2gF(Sgx ztgq|0dO|Wmna&EQ=&ZN1L|LBoRo~VZJdDX7&Xeq{)J*%r|D#P7xT5P1#Lo~W1r>Y&ex+uFfL{7<99q&G; zmlhi7)Q)T>2BB2EgqbmucYt25Pp+7m_iWJ1 zyk|9MxeJ-k4G$+|VL6@33!!mcZel@>hhu?$qwgw>;s#8bO;T@scuX zwmdY&)%vw>nRcT29SwR0CdKM^W*=QHf_szlwEz-<9Lkpr#Z?Q_WIS-U@4D!{2FLv} z(AlegGE%#lsc{RL$8ll5hYP@>0!^0s?E7%ZPt+k(sIkGFu78-T!XE$iFC}zfazM2P z>S6?vL}kv4*}Hwpu?}^ZNZG@*^K>vAqF5p2h8$WWhMJh8LgMyb%HioN3lSO&Z1yv# zfF8j~-xcY5``!6J&msk8X5jihSs6FUDWKHH{BrYh2}^0>`^1@XkFmq$#MS%ho`D?j zT8ol2h;c4W^;vC5RV^FcB7>7iNyn_mUw~-yd8&Ww)1C&yqwI+ML$(?wLZ(p#aD;Vv z=jFAp#L<32cWPW}YCNs+>E&v#lvWb|ls2UB?AiN;b!XxkqL z=N{9*r?n@t*<8}Buq;Y)@CF{VH*%g%%q@=jK$nH$ioQ*jRh+)Exr%peCaF=8)1@$E z{>9fJ!B z>cfAuzhCso%0DSD=XZGe%IIh-zsHX7U=wUk%It`RU$yYqHPu(aERD_c-!cXa4WlI* z6vc+RXTIYL3GPc6lnE5utvi$bR)4Zee^a0Nu_~mV?e6#cR#sQH>&oSlW97rd#a9le zIJ8siEA&3?P?mCsO}(WlQ8gCllrLYNzsq?wNb1AnJ8O~UKjKyq@bI|vHwdX_Jzch& zw!gU?=5+*>o7b>H4^OB8Demp9n8;LJr-4qDd!T8D7SyUPP2$hN?Yi^M4Ha)|XO?yS z^87r!7Cjbxig1-)nX;H*a#OvNag$!=b5Mp7*CV1Do?qH@(WC)4oI9tll= zL9ZM~0?0@k>p@0!gwpe&=YgsmlZbFHIsS@?GH_1CQ}v)Sm*?dT^^Hx9P2dyIpE4%9 z({PPGAhz6nFj`{gdj_koVApNb@@Q$~K%^;mx!3Nu<2V$J`q=*Um#+qRH?)?;A4}<# zek~qFXFO7N8?=Y7k|pJ>zEC@8kRWoU*T2D(8+k|vPszgt#o_{|-394H4Sh4((|^tH z=lCiN8#My9=Y`oo_9P;PaKmisRlcIT%T>d+6y+JG`Npm zsm5|?DPnt^`(>GA#bq^RTkOAR@l@O%t#4@#`sMw&0<)xeNfIpy6=|^i`upqisayuV zu~?SKVRXjP`_Zzk$)krJz5BRRot;vHD7rT2S7z8v4kKz*S+}`gMQ?KYUvDhhsod#u z;;U5uI9uF!YUdHF&D*Op9=NSfjj!*uh>_nEOFL^i-}zDheGW^c@2$&aK*o-7YHBMPAfc6huU{7=Aa=UtbWhmz4CG9y|V6PZc-^ ze7d~;aTH~$o3d@=;VO?s{UCvZQ<6nVN5LP~GxWv?xquuwr7R~^4>fX(*Xt;~m;OAy z@^;r{61&!3C8svQ1-nNr@r-!R(+9_wa$`Ie+Mn`>HS5A8G(nvV8a)$J+|bT;Lwoi3 zmr-*>b&vf$P4}4^6?cScFQ42KJ~zwjh^@JPbr)~C!Q0b3bHM&IGborI3Mt9SQ&}RT zskjgKc)Ve>xj+^EmZv$h@ButC`=;HC^geVMH)X7~=w2!zXKL{FhOTqKR9ImB8nk$5 zf4F|PZ`I`#-SEQq=ZK3rA}y}F{8Yy!eG?k0uI3o}%UW_0KH5zb0ThG^ z8`MLs5JgI`S^t5)j07t1=e&*dwX@(fUobk|MWndOyJjlAGWhADkznAmlW5e%rDw$d zq*pk!ca~iw96W_`shGT3H)~=z`@5k{M?*P)opZ9>e z4xLB+4jIjj!O`Sh6ah$di+vvEaF!6u8_h2N3ZIx}1+Fqp=SeEONyvK0b1lZn4;j>& zo&45iYw5HVniexNeo9>jIG@FbBK4s@X^&zQ3|d@mPCu6AM_N~N6=(3sl-Zmjaw6adLJH15vvw+u8>*J|TGzGCd`>OSujmcyLCHoQn^9bGS`jfUwrs;Ifv@Y6fa8Q zA9DsV`U9B`Sd2*CI7xjjnys-Yi*(te@Tm( zxmg=ixV*gj4%60vmOHCM>S&ai4_lh$)830gITE~7rNFr-aZK`xIzB&VCzFapsv-K@ zn3U8<>4vtt|E~td!vZO)<#_G*Ed3MSfYx*u{K@`s!k@y$O@y8vT^8u!sWC#U0=>a5 z<-1ra_j2~sAzPJ|(`(L7w9nv6W#v~Zi)p34u|4iK_b0I7_iED{Yio)Ax?e%u@83>< zNhv8|UN%agYsFe?`s9cxNyS{tEV)0Z%}JG2LLmHYQGMu<;*Ep0EHiOrW3#HR&iI}9*1rNB^lDfkZd z^d9yH#O^kB{bKr+b<4Y@r8Hj_{rU{7Z50x%E5`_iL{0G`!(0-*F+D>m3xs*PpzCkZ zN(*cji?hC$-KVIh7s4KP_hG`TXtu(~tshX2x2KCD_Wn6*ChQD1g(QkHi`63ToE5RD zB4}}#!}YKlZ~r(~eJI+=siWsi_v*I`>7uaEULMqVdNj(b@>w~Vzf=7x28dJw+y;m= zX#fwVyEeO)P)~#2I$W0-rQ<3`vms#g22*DP{%W6%Aj^4yB#^>(mudWkB^==+wi>YL zI$R=-ZF=Z1a{sg_1^@Gy{Y2(FU9xPZQJao*Sjt?4eg!Ra5h^raXBw za4t!va?4Lwb5ik@R$VRUmDyWcTZ`A`yqvK0yx=0%_=A+)Jy=@H8}HNHG;b+`3!(UY zlb^%n2FcU7PevKv8!YxSmkq9MsL*H=x+za<246-6*R&gXr+99u);Tm7*fPqn(F}2j zizmuSu8ZfWFjP+vyoNr2hwN6xb;(#(9ZY{z?vvn$2^eC-$pqdhojrZ{4<}>gD_owO zuCy>8?9Zp=HtRY`S7aCI&%1H&8JWOM(t*g`0 zG$%%}vbCkm>fiA)WAVtkUlF`o%KkcUn}LqX1*s%Qki@DcPegL-{)8G!&|F?VM@dPK z8|U&E@>Ee3jDV|SGx@jTTDx~FZrM&~yO$lKsbY72bfPh&rc(3SvuB>i+gzIBS}@u( zNV+-u67$Nov9;#&Jlc?t4_0_We#Wye>^?J17FT738w{&M{^f=0u&|4UvK@5T$;JL` z64Qnmst@1k4*5JI@SynweC`Y-XK|M-@P75ReLQSsCS8W>ysXW;WN4fMZJ0zmzQ_L z8M}$9?dXfIt5=20QFdGPAgOmL8)M&#Fh%59x^_a zahH-Zug7Pg{H=SHEILwBkf&09Is2pXb++N}b6njT0|my*zD!BHJ?FQU1%@gSSbAVvay*t-7sD-2m@%10YbvfD+nfH6wJ~g|$OZ^i3AM1S$MM5fW zZ26l`cXf=4(?&xo$a11o%Ej57F>*dtPAm1IZh2+?*EK-`CwXSwFHUZ_8YJZxfUKz( zKLG9#EBl^!upW&#QIQ2vFmbIaEEQX6`xQ<8_?dy$*a)+xRZ!2f@sWG$gEIC*Lvfxe zfFWZa_jMo3%DyO2BbI*fxU40$hnU~PO8{LVoZ)g*SdV1F1teeaNl+CUC`1N2=|WFF z8!t_O$T+ZYI|k;XOG;|{4zNyc(^5er=W7b%8X$U`kN<#*Q^-d1*Abp#07p>2q^{#R z&EjmL4V*iA8wR$gz_NAV^u*$Y?eJ(k{v>sl>=MdUgNh^QWH6aw&$G~V!8L$h3Nr3~ z6oJQ-={4@tz?IW@xJW>NfQlQVAQA=zy)FKfn5al@i3ht(tCTMX`$bQ#;<2ZscbT!4 z=`#yw+Vf@=xMol3UR1!yXdb|CYBdq(6u!d+(B8>4VmvHRLyskiS{v4KTRl#5s-(Fi zIIzP6!)$K`ijW*~1D(uPDe<)fn|)RB;ei1Lb)=Ml-2m?}vKU!p=`EfT+Onw54B^3F*{^s&e&xR>)TDCVeyxN1l zs6Jm9(=lYUwJ2Dt#iCL-lslVZF>P{zBXDlGat8Ebn)WV;*FFX2TWf|u%W7-gF8iNb zjoY@_CQx7qVYg0n#I`YQo0mySO6G(*Q|n?m;43+qW&%-E#v&t4)n~S)yMY6M}za|AGCTG>-daDqsS5eI7&jLc5m)m@+h*BCbVD-CtCpC-CymF4 zhxglAdq$+!_ugUpejEWpBsDa8*r!1$Nug*)q_lVEVPVC+?mhIyTbs$PPc#_q&`QTQ z5e4xH(HVhI%eQ*Rm?0mO-b+DN$iO zOi)9%e>00+zzpDCE~I>d=hfu69w5WY69(0Zun3?Y5yl5&F2`&~mfqgwt}221pvO^X zL5FU0ye;!+#S~HF{dJBHvOY&@D10Lr5wV#U$cd07034P=imq$XFG35JgJ>hlBPfI% z$(*nk9&J*xkdyqImzhP>u>B6iY*3p9Nm18Zax?`LosM1IP36e~*sZ*6vAU)4aRpl; z^g+nTl1Rihb&DnKvr(TxH8&NJ6ihH2J1!rqfiJ#eFBh#RklyuRTsrwhe`iTDIaR6D>y|c+S6O#BZpibs0Cg{UWad4cV zUNb_o#R8%gX+FG>pobccPDm-#{@ygl;vzC(P2TDKK*aa}kQvY~JJ`b@65Bjwd#Y|N zL)xf^-TLSg1C-~)Oli!8E@ptQo9$P?RLSVhA@=(+`pp%MACGR15)#!0s_=W_hb7@)vAi<&rT?tg2n*-ws7V_$MEsCU{x$)QQS=vB%J|Km{w(?XafJV~7xON{` z*QfSL&H1PIBg@VzG!|rsUT1}68`yl{z%=rI&WvQMu6;E1pLZe^KLsiFJUlICRN)8a zr#SzGo9l_6LE76wG(Kx6#xl9l)xOdz`lvTO7wz3L_ugn`Ts}g~-ck;>fV1HZW)Up= zv$QuFzCWO^o^GU5x6Vf!iImOwU{_Na^f&GeH$3&FCwBRb(<;N9Q%%BO#wnB}jlc)V zn0h+W>lKT{2Q>Qj5W?W?m~B~+uICk2(5IGJ=OY_|eCMuD9YhLao#UK%#O!OB8hXiS zf({2+a)&HnD$p;3{~HS2MY`O_s?U-sLVt`L|EM`$#6(<9S@wX9Ux57#ywSljz9$(x z4RiTmnX*b;(x)4eG>osQweo zD}0yg%~40}Um4DjNWoVe@7m?6=ayiYE4F)bL+hPOcG_P}2i&V(z`w)A;li7avn{CH z=sDhhqrpI8`r6r9w)AiSaFePm_beh}s~!&E5vmzjTr6YNFDe_Ws=9y)sQ)r+;n&KD*l}n4c-;N#^=R8mOgoTdn}3?v!)j|BKBMyH+tie z-Feo&2((o7{Y;=Je9wxQ(*mXkI2RiF*QLH@u|pK=j|E z(H)X3-m8(eFGOgv=b-_;B_EfhxLe4qW~pJoutju1iMq-*0p&x{vj(#3^*Y_c1lCHs zz{-?l1Tk=a@c6#jPh9I2>z(0p#uI_i?qol3PknYC?m&T1X;3eG4m}55d-~Bg80M62 zY`vo`WdtXD1d&B0ESoF0u!+7OrYfuvGys8X8r&5L>RAI-r6u<03TA9+^UQfJU5H_2I&#A_wBfD@a?-G zz_Sr}o9Mm&nM8xp_>O{e>`y4@z@N&q%6ilAAm`4pzp^dZAw6=s(Q_fGQB_gaDQ{%i zQcY%;yHint8@kS$&FvEIiHtou+$b8Uy)yq|O7* zBR}~c;=Q?K=D$JaO#p~5r3vTVj=9`M{r7%pCOI{&{h?lj50ZzI8M^egnMt=~tdudx z^Z9~qLToEM6W1GY>Izfo+DryHD%E7uD&!-HD&)x*3&vAv8$-9LVo;_vA0p=hKHwIa@SkN}5Qf?c+isO>pm)!GH`hPW_nmivIfm#( zGnxWY{`kdc`*_QGd^RUl9yOOKXcj%H&>PzlDsCfPdK~{}WXfDB|0>JoD1HxLoWNED zmh

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

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


!plsER_WS1P?J41NfhQ@d&Zw_i!X@H(Ij_91ie`J|qU&2p0H zu5`|KznvFIuJ)tYQ`nD3Nhv`erXXfi}no25IVMqO~@vW~b5a2vA}@$dmp2 z6LpBbOG69SsL$ekg+=_JpKg-jT8MAjG3U9l-VY_pe+!_hu-QQjtPNb8sTGyBNh8sQtxeL`x752CZ2GqA=WB zMMRUvcSN`gyhf=AT3AJKzTi*3tPonPiu(`ApFPOyjD~BXZkq`!GfpM^W%=sgMXOzE zQ@a;Cg-FOh=+^-@Dfl^@tFO6wtEJDEi#*Wx!@3y+2Pwp#EE(w^iE^g9zu&q+%Hb(3 z?b&6B)?@$3x}p>UfGFowSmS-M&^>G-%E)@&B@-=yjNB!}0vO|BJ zsWi>t+XuRSacoy_)_!WXzuUV?lgw~PQo*JK6{2gB^;T>BAk3|C z$7dROMfMkHkJ!+^W()utw6Rjd=C(ZWx;{*0Mr7-xfi_IlZC($6XAJ$vvULL$gLHQ) zwIoY`wf?}3sa%Hg8l1Ru5yLM<*?+#`B#F0KNkRo6ZynQj3g;9~A7TJa-3C2qVL(!H z@2%f1hm;t34nAD$>Db4}Prx1k(!~RfpSvFo*Z{-Y1jHri))SY7d$979&)mzdyM ztB02*Fl%)??f9V7$?$w2yR{I;c_^kNUB>i}TjU&9Jcp`QYEPm2*ZQG|jcH!EI2-WV7tkg4tL*-*WEejsyZkMQC@!6Qu`o{-HknX3s zHNL)KPd!tG0>$ZYoC_wtd==!{qg|-(vKlSkS;KQg(7TK5H%Y=dS%I8a?$`-6uTX{O zTzu8`#U?FRZneyHI8uK&+pMZVLN~-W`6iAe_rq$j+sAF+#RpNc_7z&_?THYcSvED# zze6fHC%k-8u!2WPeamGvx|YUgS_Ihst~*KpMN~~d{v#O&Aez^C-ovPThSqqzEbi+Db z7GzrODz56$E3#gj>^G4a3J}_56R4}m4DU+0eEE~BvaZs-_8sn**>oexZ%)s+UIivp z<)$e>+$d-)tpsO-3=kVvc)O+sdM&<7W5s3_A#=}Q$%;DK3Dd_sww2)X?%Jcdjf$K7 z6DWDM?NAcX800GZ9(vV%5vksuJE6$O4MR;oc zMN*5$-Yly*6;ezNiPwxEiXp9HF?HH~*Tb(&=;t4RJc-N6ex$F!csw{b=qHf43r+BI zzHSFJPrChK1IoW2s>8=p*k4mcDxdjX+ib5d>9wl_(Pq8XmXg^^&gZFMGFEuRZlr8Z zL+wgbFYf)JQS zouOGM$S+a0WhHc^)-s3+@^F9jNXk62)XL{;5dDX=|J4F4>S&m%$V@$NmQAH}B>B9q zfM_tsLi5*ulGG3hz?V4;hG!L@kE`~&qEE--{tnES<#1*y!!Z6heYc-|8M^jtk>zk4 z$dp8piMca*&LNdHG!DOS_@}HklPy5Q0rnDu-ip|1$mov}=0~LuF*aN0k?=c=#EvBA zJO78?blk4BoQ`-aP!o<>lQPqrtLAoDwvelp2g%E)FyX%bvXU3}J%jM5S+=B|F;fAU zX9EDY=84YQ<~l-daj7!w^@Q{ON?zsKTkY^aJ1mM=i!2W%osO#POPU#JGe*wSg@&&f zkgIKIe8gZQSu$H+<$bV{0RK zYl*Yq*KG)&7Q)-YT7OchsE=A0_W?8i63#`9^owYT&V(w>b^RJUSfG5AJ8XR_qMUf( zk0wNW`;AMqrEfgksXy&ephu+x9Ag=8B!PUBoR`5BilO&x6!{Opp*?s8y8{Brd(zu| zM#|K%uu;7VPSo{^B@RgQG5>!~^wynnR<8hyg62rVNr|+j$i5RT%xvcnI~0-7{cL7t z(mKU^zMROW(Z~aW-f5uS4MOQZTC2Ne862;w4XArC$GQUDf}Yl=Ho{BXKQ%}xdc5XE zgHjy9p5Aln&XKnYjkaI`e6Zapeo(jrjB4?rB$qthn_ba{--!%i;{OJB-}r432_R31 z($jxQBD65vf4}n&{BwYhDhImTLvIn8LzPUk|J9+9BraH3X>1`@Jp_P;a~l?^aDo} z;f)sf#;NNa^J)CB$xE8LO0FP1jT$@l6ox}!8zA2WVy6F|ELEe**kPe$Oo0Qa3lF&> zmk1PYk&yYHxPD;l!HN8p|E&NTr{urCkw+vk>BgP-H~&&Am0L$69;xZ$a~B*LYN@z(uV)g;*e6-Xx+Bn(?T&Y^1lep5EQ7$#B2NXV4M@Uu z0m}2Bh23YpC`|Ku%diXmYs;MA)Cttr;J^W=Yq>Ma09$Rm)UG_oUc?dqxuQ%gK^Ta)>5!h~a7+aV=k1Gbl7Ln+@x3!H95B$NC3BVC zNE`%^!vKu!)yo24?&&vwH_cs4Kf+OF(eRPz|D)=?!{Pp(_u(Z$A`&f1NRZWAi0D0n zgy`(*y;~)Etg;eGbRv51ZP$`uiJs^sh~9!A+UmWo{VmD+^L?K4hl}fSo!2RIX70IX z=A4DyEv;DGNc_EV2DF+TYzm+8$5~&+tD7-!+;c%4v1pnlb)d8;c5bZ6_2fD56D4_! z;SRUem5w0W`9Z8WiZtvIaS50x$&m>`@H2h?HG3674_|tEIR`+kRz&JU(-hWt%HY3B z5pd}x{8extmS%Z_e^5j@n2XYX$7SN{%SDs@)5BkOv^zvzCW*F!z6IVTCitgICdqUU zbfq&zUSj4_2-0-qz9250PT6QDiI#hY*V=FWJ1}Z~UYjD|;e1M1!*_oc25MSC%_w z?`6l6mw-t!hs*y1@NC^7q-zErSX7g~s?|L+qO!8%qft*zN&z$CQ|90)ue;ocp&by<%gR*|W zMt%IBS3^{hj!yk>4G<{Zxu}NInfR_$pUY_WGhFR1yI84drF`@Qk5YyTgZht@2LL|H zTyDi>9zkyQQ@+b{75HYM)T`q&wXkmBDkA7>R-I>fLLA<|MKzNRDCtcjkd?S}{XXbl z_8Z7>sip*rKXtA%86*UHU9L;%%3m@jMrU@91771tZ^?7MO8HO1_|>|f_}Xw;5&)Z& zp8e*XkZeQbXm_IK;9w(41I&*G2EXa#QPoSbnQ?)2N^TbF+VvRt@wm~r<|B|)3K8Gmze#+F*;cvGAa!tA58@RTJh`?FH+}s|2^>SNw$U- z=kwx}QD5-krGow@c(a^~d?3H#)YjI!$0g#m#rvDjjNU)n7v|~?(KA>c&VVVsU^pfT zBA+_@bop^JenoVt7fze=VU_phwy+5ozY6yUb1r(CPIrm&v8%A-?OBKz%?k58{N`OP zuF_##?r&wj!Uo}es`v6*1|ppwE_+cygdN`#%i}fEJKwG7jmCbT9nFM&mx(7QKbbE( zo**)9tT>gyHW@aJNt%ajzE`y7V#C=V*8OJLT;lz%Yq;x^FiyxI)7!`vWow?b-z8l3 z`q%p4iW9ZVPT|9qk01^C2cxaGbuO3lTee5B7=}IkmN>aD)K2)3Y5nexp$=IYT$#bm znO%%ff2vFJB=_lsAomZ zlawdKjAs($b$D1CsmV37JC>AWaUyJP%02T?L|1hGotHasx$;8f`F+B5rB`0B$}aIc zfJD)A>!8=jTAmL?yrwK4{$hOR7Arz0CSI;f(*8x5>z;#7<{%oAYiw^3hjRi*?x%!5 zfXazv+TBC?mLzKjUaKQ- zojMFmlBQM_GFoww%pSfb$E(Y>&8%>!L1D&@4Gi23#zxorLDpiLHq)@x25OS!i4pfY z{nNx81>G7Q!#hvf9~PQl3TueMlyk3hTxai#yv47@)lbzEaXFSt~5bfEo>uL=4WJ5$Pe971$iHY!)8;Qujbwl<5i@82HeGFE$AYG=xYF`9cKn? zsMwzw2|dhFMg{ObW51K99KaVGur~qolff)LSF1-I7o!(yOfM86iyCVUzMze@Qj;6e ze~vE+y1+M`iwVv+=Ot*zd+gcMp`Y1=cS(wynktOf?(vewg>;h3xVRo}L#jJ&?&bX0 zW@_Au^)v6OshtaXF@oO8BmeOJD|{=g%|cviMaU7-h{Yv;+jzcEz6?1`Y^8w6L%XY& zE|f04nX3ZFp+CFIojebWWhj9D#t6ful(_2LV973k4ckPCdf> zoJ%*A{Rim)A4+iP@ltVLv@1TXZVyDRP(C20 z4NkQqFCVamS%Dfhfn3_;p467ATT?sDswtE&FZH#j*-0{ZcUNg83|AU*yiap7E#u0s z99>jaI1_(Nc_dk8^k^z3gpxQkWW)Ep?@_F6-*`ekikcNTZ)aRq7xSW3OIf~qQJIZ8 z9E7mV)wJ%7=bqbz))BVdf(|B*bYd zYGZgEZLk=V>o|7wwucSb_GLYoUfqTQXDvE)FT7Ad1L3joFLpl$!IE^|Jhs9aMjuZG z4`ZLNaaUO?wYar*7uiYDO*_VQUyN2^6mB5FEP1%str1bi@PD>XLI;#Yyri4`%DMh6-{yxLm_$Wwq8#bD?nvW#OixYeLjB>z;l_$1nXOxM9 z4g)e@Kp&gjgnG?&q%`-vK?0`z%WvD2$3jV*{=_l+_;vo*UC~`TArDwTV{vTak7oYG zzZ8e)CB-p)LfUkZ|Ci$^f)zuL+PuqX+hRTmURmx}S~QYteiIZi?-2KSffSnxwjjBD z_bwy7w2w4Za)(RM$Dbnj^3@dN$jNU8x8!di(Xm3-t8m>tlr4A1fpOW~bD+85lrrbb z;`WOEVS1|P6XqKt@c8bCLTbJjs=`}~3&{~--ROw)ki4oE*PBZKg^VBh@~tDz<1_Z& zZm2rG~2Ye9@G3pAFk znM`X&A-zT$BocDth$pgzd|0Lii@vHIIx+L$Lo-C-bk`$>4e;>OBoEHW5Ey5;msUxn9y zbMQdr;oe~j%vgJ%7BqeKizwOsOqwz1DX_FTu>N>6oSwI!d%Y@@L6{))t5|{IbF8Lkp7wFwhOQFi zcY;}Ylv|Ia#=KE08y`YK?8sTG%7Y#~p506T$c#e`ELL^zELi`tqjFpEZg>t%GXgJFSSigIdEfUm zISjhYzN+FdH~f~k*sRVcx1gJf6PZXuO=Ck@F<~_d_UgQ&@QJ*`OOnc`5=C)c$spXW z!57waCr(Sku=p)jLWNg|TRF7TE1xd>x##wE;FMO(WMAaA~f1)zS#wKnuS?K7P|>B2n#*k@()w$@oM#!i4Dc|_{Q3ni%;tZ6c(VvV4R($6QFRA9tc;`fQ)f zj1i}!R7xtYba)A4AbQtHK3_C3btrmq=nDkfRmOv%Xz2DoqBLTwGt++{n}&gqzkpW%j3%9w7_H`3c#4!CXin} z`9X6I%FcM);6xN_q5vw<5Qr0nHED6Mif}nE8ZDi}pnDR9B~Ot3Mo~#eO06t7ADpa> zl2j)5Z#*^&E8O}+f9aPqWsYg;nZ)ANwh@+SKWp zs;Jm;vvhY^sf?x8SJvlxofStsSqz0e@X(V;nCUHJNmi+?O^e90aDK6`#tt^;#twA* zrpDjq7BtihMcIA%+_>tq2|Gk!PiQPeey~r)hcKKg`PyF*+7MiTx8S4xw-+3j)zgz# zZ=oi!DU6kPtm4?VhEy7pM|Xv(%Xn~AZgU#S=SfuM!WkuH@nF=U=SXJH4@lkP*rb^0 zlg4YQ`Qo;qx+VoqT_wHNcqYq9cP;wqNxZC7_N|kGr`b<@MrzFa6 zc=1S$_|f_)=MVS2!=>hrJtC+2ahrhxN)R_GC6shFHE>!Fb{FM8z73?v4Aosrjf5_o z|EhWSpn{iud}~uklHA8A;M{et#W&yAWLO&Y%Gn>Wo1EW&(VjosC%We=BgS_7-$7>H z&{fBtZuy@ap`DHUyIa`XoTxmV&gR-1>fTEj#BD*ylfw(rHF(4*RaxeN<*Cn;gM5@Z zS-FyKRr0)yBgQXgK>sRdeY%UHx6mK$Ze z?t`!87Xzp4o>QvrPZGicpgSitOVTcqM{?-9gZqs&MYn8Gm}ckHVCxf=BJ_;l#oUR$Wem8WcI^>)<>`%<#90)@(` z{d7DLKrK&*h5Z0l#`oxuS;=cT7;`4U4io^ocy4W`JhT*uHUo{t76-ocm~cXb5Bs+QT?{f&PS2vI7xfs1O%y-%T?vz@SByTWkKO&!ouM z0?`P}aYNQv9h0Sjsp+h5)se^6PYhkHh>t(i`nG7-w z)s09~44w3G#ip!>F8}2%LYJ*pT1H~e>Rb5vL9Z#+x9Ko5v#-JzvL)FY6>zbh8+6i0 zoTiO;_eQgZ&K9Y+5$HjtG+lJZ9v7}Mil(z$1wh-??PKsm;ZHM1cNwv%he0MEuT40p zV#ylnRb`$R!}WdHr)8{98V7e%zzf>Q3b-D8GCY_wU&Ko)h3(E=dHEk`Ne z-Tixqrwb2OGK~$^6{=|$xc&|>hkp6x&J^sdx5<*cZQwQA(5m03CHF#fE+gnR^o!;+ z8tHUfMB4vY6RffoSyh`00F(<{`>3mLkhcdUcqJ?YJ&;dWs~1UZ81G{Z&MMl4+5kUS zRUQ86T43*&4*0w`diY9PJ|jPv_?@N>)#AeHGeAF^dL>6k?!|Wx8QAg8w?ntYkrtC& z48~s#Q11|d2_6`|9^zS-9c-#6Ja&n*_7O5Ye`$dD$7XyC!y4d|~E3Vb@g zIBkfHZD?pw7Zw(#=_s&wV16Q&0d86X(y7%f-QZxWC;O?jJ!yg`J&y=bMVJcQ zb@T$fzy8MEfV!=|(+ETj5@t|%M2^7Qrkm%gC9G#<|GO~Ibi!D7hM>c-ru~hDebFb2 zU5;9cV7w;$I9hr|Db4rjhJh-)!)O^0$Wk7FyB=cZxo~+W-mN%9yeiEeNDW?FJ{mvk zcQHUy9K9c|hesAdoMk{{ix{h_`Eufj)z4U_ybl;(caimk1zczP{DxfH>K=gn<_}rI zP;yIiZX`AH&ve&57=^rtlsIIYk{s6tXoiYb2<2c$-(_C(?C)F*$#o0x9UW$bg}oW) z4}*T$@`rt;>e$)Y-&tL?zpIct(8;bUT+Z$DvpIPX#}8JPc=-s)%QMX{;Fg#C@pk_` z9Ud*@oZSsGfn-@L0hu&g_Nm;B4J%6GqOce%QIckU#F9@2BLN{{`*a9bnv4IM#5CKf zpL6Rh_kb$D%wApU-(8A7i}6Y{h(^&<5Pl(ca%>dMEWxdaQhGp(msx0rt|0SZkR7k0iyWEC9e6Du_8_vuoHnE2EYSJ3 zFzCQ6;JOg}5&B?vLjLW~6zS{jw4$;f*TWkNcNf-9%sduxuJYezj3|-o_oAN~_3(Eo zr-|?#swBHDZyxk*@@GGMDr~I!6K()$1^qf8&;m=7m6V3iW6yhHFiq+>za4J z7iwD=l=Y{9y3mjTG&{+o^i`j^9(DY?^}kW?%*WMFD^?vJH?vHabvycgtzo!>G0<(# z5{!pmV`|qkf7th+waztX@*VE$R|kdgbvbt5LtGPtzym;#re(@H1gH5s{*WI7tL%WV z9FA}cNjgK?H>S7I3ZCxy{T|yd?Vsx=Ue}|irw4(kt!r*{++okG<(j&;#qv}=3rO+q z&5#&?+*JF+Q!oFM_T1;Bb*lSt<5^Sof2%DurrYeT!l)Qj-;MXqwFDhV{8NPRs6?nE zRvnMyqir&N?swV!6Z0Wuo#E*dXd1m4t5OL(wkywA<1_5E*!`qoAPP(cAc(4_c&wNW zE&)hMGi*DXR3CHrEKP;6` zY2|4~xTLD%Rw?jhHe8aOc-KDn4T)lQ|kP}rYv$;usd1$`|Tuk5Hi}Av(FCy(4c9xl( zeA-VbuE4X z8d9J!Z-(8b$vmHb=@QUID7-QeJ48wTc(i+_f2JNQ^j<>gC>$OrHzL)vAMQ-w4*I*H z@?#E!)o6Z%Xjah>^|3F}{|w5R5_3}NKlA8VTExZdaUN>@AD+NyuxBn>!>_@bamcM&_B z-qJK6vGzu4*_*M!vez$1VO+2vua z4+h3)O^f_?_iAzl>JPG`M%~aU&>O@yG0Vg$#b8XCpJM?lgJD*jXKpF}Z9e z@9R6IFaE?vig-&;Vp&!QTq3+-yL&RyqW%%kX2vZ3c9p`RhKX3@!ofnUCDrl7tEzIo zySmdwXB};AA+zAD3jw-l(&##ECQTwEg91uO375RQSyqkv43eu1C(1noZVLKS6F#LCZ2qSABwg)HNhYM3 ziKK;T-+hHGR>`}SCL`QC0q_Y=Dr7cbZmfqB7XoA&B^18lNJc`4;V0SUxs|K&@_=t4 zLK8BqmLd5e2*CvcjjW}Syci1{`A@(^6s(}G!-&e2_XG4(brtI@o4mUBstYnMs1*h# z57o-X3>j`(#h$Y^7x(*p+e>?5<_06$wnAo=~P@Ri6ja|F> z+lYW54bE|WD{eQq-&b;;YGQH{Ej+N?f`*Tod3#q+{S$1{*K6Oa05?1=zY3|fH*kn& zY)(*To>@)QbL?he{CG_jJk>NjKHM--cs$&rUjmpFs{?%QEH4?M0Vw9iz`={%VLFXz z-LPwb8(BF&L^kh&|FdW25J<(8hqW3Xhk&w*g<1MgGu0Htuw&?&v1%MOUZgu6yK7+r z`mH7;bK~ioF>6=V+_|5;^l0@@EM1bRM{h-Ml(?f4S9T+KsT|G+L4iUx)6=b_FZhC8 zsWhFIj&Iz&IvLRPh!=Mi&1rQ?*E>Rm;Q8W3vVK|%kfLrl9SI?Xel5LadC#XXzt6?l zO2f1G^lb|V@mr?NqhG(os#O+nC2Q}28X!j9nl*p6-#a@4lLkl2>SbjA2Q24S{)mc) z7PhVP?F^+Kqz83T3Q~bAt_R8r&yI5-93)NF?yuea$=M0D7e9-h{*y{^@z@5ygn}#Vkk7IKNM91p2_M_R0STZLB80S`=BL z1^`WYS$@Jf$~WEj?-Iu;JWf~La7*{pXVV$s4uMy`E`y%VI^c%a?~TikPf;thl?hZY z3(IL$wtCNmzSVjoBFP5NyHgym)kl6+%Kf4RrxYV9J{e`%b`^u#wIWjdq7_-qM3YWaUewmQ608OU+7^V@^;{`Bolwu}6^|kS30RIe7Pn?{+36L+7#P zE?bL{tB401xTFBbYouhX356U*}Mt}w81(SUcRDmV2LNu zBiSIZ;fnD(^W13WATCM2&k*n1(U{_pv=k5CkjDSwre-}#H8DH8B|O00hI=ROsx^j0 zMfaC2)({4#Kfe$J~D=;I+ z;{~-dgj?7BcDZnlutQSPivgMAGNZXWw!w93*nPf>YXI_{flOIP$?JC{ItF=hGb`=y z!put1`TLSs6~f-JHw{gz{&Y(NdoWixb*2J!TS#24Z58HtPE8|mFyDm_KXB(D|x zEb=R`c3-06<$Y~7GLeVSgX>9!dn~I`X%EEv);0s(KFZL-z z1MmS;VcJhWxZ4n#Y`(o2-M`#FBtH3I!NvbF-T1Yws|^HjV{6@wMrrEUB#2(`Y^(G$eb@jmlC zHghQPzrHX0VbN;-W!NKuR5iY2kazOSV1n(#;OO)A{-&zB+GYIZ+j@U|aBs|wx(hu| zZFVLZ+jN>GefzEY#OD(v7iDcL3+nZ;%`*&pi5!ZT5JBu-ex4DA)NkKfx+i>4{a1zP zI{4e*Npc@i^Y)EU>5+~F&++*$q*u=b<-p-zleyVHJ}IMFkZAmtEukJY2j_T1*Yz3T& z*scmzDMk5A=ce8+z{skj$d7 z6|ggzi`~95zmpypddrJ-KCIQ&cGv92(Fb;<17988+<;U2S9Es+_Tp^zZ04vISvI-v zex3*$$=HV#{|6FyuTcTC)4$ou<1-(AUwQ;!ZV!1QSF)F3fZ61AA)rj9w3-aGjWgNn@nGGs^aP2UP2J ze?Ocpw(GFZtNNfMyaiWI($^M_Ii&qA2q3FuXrSqIn~J6qY*Ph+PN?zj7FAwUTI=I; z=*pbezrf2=kXqXYw$tLh{dJJB+2GCZQ!6F?Yt>tV;QQp{=*~_+b-MGzc96&7W`97~ zG13{bKt$9u``1PTYrPM=7XZ*cY}O{HLZw2Cd?z)H(C>3UIakt{yM2?VO5lAOo@;nF^CE-cD73#tyZsy`)T zQNqvS>aj2(32tedGYLF(;?qkO)&qmgHVo>kL@hrmT7w*qyt~=vQWA^R%UfvyE)Ud1 zx|Jy%rNp4M6UYsU-#w-m-D_b8FYnpo-$BmI4T6{Rm^s}(lll64E>K4F7*j2M9#DPI zuD5XMeQ%O2wcnTbz*q zf&KiBcV;RYyc>7>7P04pcM8wr8q|7q48b;qg@uob3RZ{TAz`0MV-kvQ*2Vk`Pfg^M zyPqF?a7K~DeCLyB1Ob2kgFC_8L;$7xh4vNi&KrZ#UV&TkZ)Vq1NwgQes z>X7?rqajlk>7H%g^an^r<=P%D8a~ zBqA!@oS_SBTupph!!UNB9X?--6KjN6U+PL?{6qx?^Vvl^llpxTwf@LjtWrY$y}%Aq z#+liAn4r{pa{SGpTR_4V-t-T>puc;!a_i6c z?6y>ZMr{tyEl=t|q3@bz@H0bt^^D%<{*+3N3%)I93wFHgWq$<1{kr+yHhzqs;FHF* zy>b`j)0XGp3jofoQLzq~LysMI*N2{yVn-)uQ|_za*w#odqQ}6G{3InPYtVr_JO_S@ zMBcAPKVCi7YLVko%TANKkK$cH5Ax}Nc;h}w4+H&o(ISc+Qpx)Zxw*NGLK@@CQdC^3 z+Bg5a4v^#Jd{*(bZnun7xOp~lf~vStygpF~raff~8xwGJRLsdX2Br~Fkq zCnqP*)D?F#BTri=Jzw`&_ba;s6pya8HpgiaF5f8EH!jZ~Exg!oIf*Z5tQd_ilBk(64PE zOi#ld+RNr#PwZ*5_=Gc9SqDJNtYDJ#4PamcIwNy2`N8-=>NLDV#=lJ;M7WWj8D$)# zFC>-0h)4FuG+S9dEa!$JAS=Zd-dEE-vM*%9)nM@B!B)t^t!B@^!>$eG%0e+fOH{u< zU7JzE-7?(orYAd>w$>&ELc%FlcxzSF*q#v*( zfZv+P7&N|*{Iod5iWj)*k-+je<(spXYFOoK%Z1+V8aTW}h$D|9tel4-YJso#QGmsc z;FJDTHl=EU|GcnM;N+}~o*})rp=mWw|DcESHALS@3NY9qp?CBHq|^g3|j@BMwj=a19-1QM@4?_R>v#ivobi>ufLY} zE+NeA%aEZL0lFCa_4f}XIc{)@f2TuoSJvs1B`%IlwnYWzhArB zmQV+O*qC<(&F` zK>f;UUWqdqwRCO!Px-_mveuD z@tfLFg#XWZXJ^g(BVpg@kaUO__Q*gUc^c&`A6OfW+$4GkZ8Li@jylJyw!T?kIrH^iu5HbHWpV6h!grT z^Rw(W5xlIDFs>pN9a$A7E-kx9?s3-f%lg8Zj0M34tNlj-;F@kwKt5vet_2;~TaG7KLqJGArwSKc$o12#TN@bGU23(@qgZ@g4F2is>DN=-$Mcsq( z`P{d36F~YPkbb;1C>|7V52lXa)83~GcgqVH6v5xA`9vCbeha_T23(p(vb`F6yakjF zqYyN$XR|Vh%$`iqhN{92QhOIiU}$ie7((W8mSQ@BOBd$a7aFo9l$wF95nOt;DNQ`Oj@Ry!|xOW8TP4}$L?uJLCWT;=caTKg&Bx=pA#}i z^0<+f8%%@se&I6l(JAr(#}X$&DH>yiboV}mBj2Oh>3cG?(TpS;or)0i)1@M@bU5HG z+)eZD7>#`OJzMF&wvZf0uuDdgBgDyXaWF~8cJKZuM!+e+p!6W_@WC1z0kewk*ZO}x z76jPqw+=%Kxo_p3>DZmjL@zcGXT2pEH!w~&)@9(kVQK(!8JW|mYXYF__~wP|sr8N) zj)z8kSyZ(x!48mft8Yv<3MNRtNv7+9d_4S0Cd|$+OvWIt%$vX0$qg7EwT_f-N8cfj|TNS5)vnOf1*bv!JqFS#eH>8vbx2HWbxjZ zy380L401ZdyFvOHiPp(#wuLTDoIqkKDynbxoE4+}LC%lcLEhJG>HiWs(|FoXj8m6z zSF=2ZqaoSNMLe4D5vD3(euHdr&Nk%-r^k{-Y8m{gYGWd!c!CdywYXn6v?-+jw$nVV zwA+r{s79nB{kbi9)s|ZXuvJnX%Rk7Ja`LJl;Atofs{7H|M0^=_c6M}f#GQ1~TBY zlgxe`MJt}EUP#$VmXfHTnP3e9^@+)R6es!?>h4z6Tog}!Gw)^`dQ=U*XuBbl4Wi^j z7N`t5iL<|xOLyly=eSU>_UNIMeK^QTXqfi=`ZqhL8)lNUcx<WO{B( zu6U^yNpMixji3S9{y)z>8??2LDobGa;9V|&=j;9Z%Zu75sIGP_E1)$IWSpR9+!@V0 zpBZ4soLaETM7x+`3#wenhl5K_RG4AXIMU%9tvkDM2^IYQL%{_fWqVrWh)%g(u*%ll z5S6R zdQg0+z?-mjQ|hdw6;`4ErK=SXOG!$HbbR6N8O@UijpTGkin$Q@);furM*P)?D+gzh zH3T2K9Y5$N|7n@ySY^K;VEW1Q*$XO=nx>ZK?y}LyJIJEZ3tU^VQN$OE1)+*yLcdLE zihV`OyxQ|7qkcSMn8!~{yBm1ySw+_II500W4m3i)&&9cCVZi4@0Fq^T^X}<492gAz zAKX|wQUlFqOBmj^uD3gS8XJjofHf&jgy4R@w?(z_SwC)4tcJgGAlLA;D0sy9{$!&f zT|AWP{O7XaK1h-;4L>2Xg~%;XQ0AQ=&Y@3#@)>-MlIUQ0-;@eh;^g@pm#t!uBGPo! zfR~84%6_P=V~~RW!bK;{9aP-NhTV$Q}Cni5nRK%Z@h*Z!SFTKhX!dm$un(Gebf;?L_eb1oGYG5h~XK zZRNS}uo!P^pOY~c@1sbZX6KoS#AP`Q(8!HQGNs|H&WG3=drHK^b5Z>{&HNFHb2B?b z-D2E$fpf2hdyDBja|QF2kjCL0=wBMP6R*9nHMRyQXhid}<)r)z+YY0Fnn8tBz^i=x zkXSuX?B`6-J*MD`dm)1)q#<>EZKJEiuFC&{*#oG$<5|su?;Zll)Yc}1`Et>0&)t87 z*QX`wQ?!CW3Jqkk_uD(9qbV}43w?>~_j~lB{C8gQO{@QM0W8yR9dh;EiYLw@vg&yv z84Mp?7;ETfJe>C`ySN`1LNZ3E+RO$5DFFzKH1Wwo`2GldM4_7pR=mtT|HG2EDW1Dp zoMzv?c3bY$wLQ9U#1#d&U;aNPv>{-vLfo$_|EDtY ziC%%KL+ttZn;*{WJd%7NwFvPw?AX7ySfT|2sP|dX5UT9={0A4Owb6cIhmAuJH6J ze#INtKDo}H(v{rS@ zuENMhNI&DAWy;6rc%s@TBKFCLjwEK-iAI2dXjAR+{BLIl4>mjpb%0|qc)9jf$Dp#_ zB9T#j%FPciFSIZUo?azJ#c)PBfUYROoUaH@yjcEHKTej?o%61^pWAkPb<^ou(?zP% zp#HlH<@=0#ng+V8E5bji#%E_uO-;9|{#s`8^uiZCaxXI{Xe|Nq!YM#1JpAOe43eOM zrO^U>iMpc#nbcF_61B?VuHwoE6rN{~UP#CfPQc)?Wy})%BievLY+_Fo_gyj$9VVJ6 zKL%KDqYm-U0uzT5&Fg@3OR|yv3rGiTwoQ0jJjs`V(D_SSoH zO0Z@VUA*v-r=kfiT9$C*89<35{PBERNJ*T)2<2i*kPe=m#BHquDplKC>1gUq5T59a z+c@sNtItd_tZ{eSE;FS|hDkCN)c5+~fO=V~AfE@?dA2i0}m?eFQ%*T!T$LBTu3c?Y1 zpYdo%rYp2R_0u+Ocb2slpkiJyY55nxZeMvzKa~Yo{kWmF@jGem$OFYaRfVaF?duwNI<~Me)qs3^1Givo=melyrufW@ z60yhOR~Aosvg8#4rW9l~00xHiaL<0R^$p!%R3ly96U#EcuTLX7b}AO8X9@2VG-E1Y=sNr6MlQT06Bv2fVx=->!2D2JHck2ddLpBBb^ffgBN>x4SQVIhOwHze|14^V_DvqEshkN zP=~n;Pa#h3214a>gb_8>Ub3i}1xom)l&*Vd?>)>jybcI6o_v-pQ+BK}DBT_2SFAP* zM+l-Hc60UbA(0y{ehaB}buKJQlK1aaIBvo;Jin5+EW;32xAT+7BQVOhLuVhK6gJD8XCIZS7)QN{L#S(J152BlICf! z^OKX^Y@d^CvMVB)sLK4X9M zsHq2a>I}N#WF5|FXMKK!AC=ZgE)! z{OlU>&6dK-+$qI5D_VZWRi;7nseFk#f9`3q81o|SQ)Kj38?*3 z{C=6*DKbJyUa_~VgZ>lXO7jm)?=c&zE!=Qo;le#hUpkQxH#WKe|4k?Gbcfn7AeWL&=r;F}G{r^eJ--RnrbnXe zE&?qw*T9xMO%LC09;-Tx(pgQIlRKV>MTC3F0&qx{9I(oBkUiok?sO>9W)sXEPe!Z* zT2wz;V8n*H)O)*l^V3Q}_lu@uokiP0`)K1&jCijNttds$tiHML<-XSy9owS#^5RS; zbo+M_W@ruT{ zhyXv-m&c2VLKntEM0fJFx3%#T2Yw2a8zA4|i$5I!4t~05ikoNHMIM>}Y>t-)vASXI z7Cb!t)oCsqcGmxosPB%a`hEXDwnRo&R5oQMd#h|AJ-oj%{+>+#^xU&q~f-S>4rpV#wwU6*Cqf~rXwUsJLT9c6?dGBVym z+HWT@w4C>uP@0yVR8ICc5m$aAmNB`3lu!`o{X0UgO(37M1Io^FOtOXPVc09*paUcI z53MPKaY61^O*uGE+Nbc8W&{Z9s%?7Tri*Ah0thknM%0%t!@{dYf=w>Y>5)5 zTqoOZYuHVW!1*w|8W(pQb;&#ZNH)t&_Ph4sEN;QR@L=sD(m-iphWGE^$LZfpO4eP$ zIG2D48}ce&e+e~eFNGmWOVW zKQ&L~V6`k4tZlCox*Inz5c$$C;B1GeS*=05E@Dp3)5Ivtnc8<7zm{X#Bu1kNNE)=T z8DUW`O3bKOAbP=`s=Ji3=0OMf9ed+fQbA?249i427ger-Cs>zrr?DVT=Ii%_f-`?A z2~FyZxN)^fCmy);TltB^DQ4H+iuV1azxK!h_Lpe5v(85&f(hTG2zK(gbL_W++aT4B z92=wapuSjC%Nd~8_4A=51*K#0b)JZr}e{ni-(%W)@!|L98FWLVP>iqM0>JSI5 z;3xf3SHOJXhRT9r=9sLFnhr%I)Yd+rJkTSG(hKMz;LYc_(lF*@t-bq7qMBRb zB1M1IFYaog6)c~tsi?QiegqkSf7@@B2;bqOShH>hB}bGX{Fmng0h^dlAwcs_P*v@~ zpbdl9ZZwea=vwX_)vFZ#*=ui)CmmM2e0#R}$<3jBx&rv?7gCJiedCHSem z%EpxmireGq?VwV}L`S~y3NIKq>(i(0nz=>K*BvUWde86nffCr$M#gjLgzu$yGlMs9 zqCuGmcFmX@{25{jOVgRsHqn z=ajD54%g}i!V&F_WI(O7N|qdTcR6yEuxbHBUKyA-0o?ueg^I%x#TcfCC1`8yiVrF& zStEZU!TGXASu$CX$@+;?A3w4ZZ4$%zXiWTqx_AATUiIDL!~N0@V8Ny9}V>lhHY5`rYvm&Ix8B$r)b zN9J5eqgx!cR9vvU!ros`b2v^@{n*n`mzR>^U%ms^^xFP zluV++Ph3EtFoZr|lCIcY(o8R+c2NN4d1kB?0zUe>r}0FSUMA*=fD7YNF%m_7D<~(9 z;IC%LYE1cSU-;hPyRE~a^L|hX*Djx4djLuL!EHfXXzOo09wU5J!?%j+Jk1H_Tksjf zy9+MmVkSckz2b*RcYLcDLCf?a)Lr$0^+tE7@s#3e)$$=_$m1$dLE=GP!b7$#>t|1$ zVw)cxe>oVVH-Ll#W;4K~Cyxb1W?<%eFgX_&9Uc8fG)$SQ3Z5x?tL0Ye3JRW~r2G1> z*uI)pBB(U))KirxrE5j`K4f)}Bzi{|!9pvocy$7Yn&~x`nJm8e3I}0Kf16 z!%k=?p}GadTMK$Z3yQOyON}AX^q(=ibhZI+8;EOrc=@|{k5Av;l-H)QF=B86r)zyL zFa~9F3|bG+=K~o7;lyq7NEfDsxW#*=9-n98o_<{@8;!q*hSz z>^~uedRQD_o0CMXxPS=m^ zyP7xAO7;3%0YwQ>%0P32EAk7y;y)6D2!1D)&++CzqVA-rm?OeS)xZCv2!>_pW|4|e z#z#Jinqu!^W?)v3+k6%RQcYdU_@HHi7pP=1jS`PT05@YZeMm zqJN_074pP0hsJozm~O7!z{D+@0j<9jCSygWXbeVy%o)u4S5v{(0>y%&P7u>XL@ye|QT*DSg`wRb)O*X;vH_MM~63;6zNE3Y~Tj%MO8h6@tr!8JxC zGvKb>F*Qz3PPi&>p9H5W1mdT^?RWonvp|uA`Nr+npj4W}W#WyOz^g3|Vv8JRY(B-O zx&aJHy9Quz`5S^iWm>KoMXrH9d*&%Bl)=b}2?F zP(nclQ=wuyZK+n)7^}vYp5U+utt`v+NEJCuQyivsOI)tdnBvDbVrU|)w)~N(|4V8+y}~6jJt36>gL{|y zLrCmD!5mO|ooe`X{yh{U@g*nRQ{&~DLP!-)Mz=7;}QY(Sx)s~g?@fk+%4ZYB?=c))R zqh^IOgmqmI2&B4j|EIpLM`Lk0{xVvGJK-m?Iz@iGSpQu$qE2N4M^shgeMJ_%`_euy z^H-KMi0ZJfNdp=_R@v^EXBcuD-AD+aZJfS*j_w*$oK4xgk-kXVdBm%ySiq~!bxYi? zqz@?$Q;NNkh-BU*FBcgOL`D}gz8j3A!z-QNDLglFIw+y?hun)?n5)ch`$%zks90f`@VNjhak8RaP?|58sGR=; z*c_~T!hzc%o04QE;OJd28}T1NS$`9FkSB^D`zr=|df#Qr@yu|!RmyF^y9hseWBYR# zOp=+Isc%yVXMGjcB8Q&W^hziZP~yJ{rJ2V=KFV|RPq!;q(_Fc4NUjlhLin7eCZW(;TS({`z^bZ6Hh!q zqBkBGzF1;3pW3mx&N_I*S2X-2Jd}8u;d$Jk%(5>Q)sIoPK)Lei!-_HRv%5~RLm>QW zpVtr6To!;@Zm@6B8&#$^|-{DlUF7DFLcv1 ztJ!6XUVqz*gyT)fXTlFafW_{k%Kn7h{La4mK6Mc62$ig9)qgMjCxq*k?mJy%=F zklR#U;da7fvWpZ{6lEeMLO$C5Jb!ZR?VXujN_vLt_owyE$dEeQ5yZ(~Y=?>Vngwen zm_Aw)oy_wK+=avSm`Olw;%oR~L+{{u-_$@P;9?^YvD)mn{ks=mwb)xPWbG&&_;5?T zz9#*4$n0BVc_Q`_@xUEXf^8m?-r{dWoz}DFk;u~>yTFJJlg~0=S8za%ar>}jp`Q1yrWRn#7Ss{`wKbumVvO5Tk zuOyl}NkYB|*stg|KhX|c$*Q_I;gZYNByW*fKl;zqbtit1Cz5~Bzc6jI5i?sQOepD= zf=woR<>L?@YP+){muRpA)D`WtpS%2@jpfK~CQvPy;_wY~iW*LYxT5{?qZ_q}q-6xU zu#dWDWHeUJ_CL7raIu`3dpGpXo&1;G-{|WcG1wlJ7lBzp1!y!UQaduW!9=zJlsqR-^kPc;8-Io*I+pA?=-&r3azAihi(0!*#liqp!?}RD`Q{TzI zysw4x`t$G0N*ShCpHy8h-spqA-^3{9nmtOCG!M)u9o(wxC92v+j+m4oDy99@? zfQ;@fEj)~wQZ-MWRZ&!&I=VbEDPHiz+13?te4lTjZr%6W&!5}BPqFmt7CX~I9zw^& zz<94=8L<!rchg@x^EPY-+&?GjcvU90VZHEgD_AF8&}frtt?3ihS%4)$j=CGM zvyJ!kuW`oOq&mB{>xVC1(ewPpicWQ9h-Zt94@e;Oj3PsgX5_}Jt>&(&AAt5_U{Rkb zd14%=a}Wa=bXGdxPfBk)E;~`Ntjma7{R_692KApR0+MX*OzJPApnOiM8Y$=pxd0i{QvlujZCJJA{^8(_ z!aDZhSe~OgNHxKeuifYiTD0J2~@PJs(zNHuw zuJN*pXNJ-Nx41y!Tv4#awTr6d7Z?4l5eQw@*^&D+dnbBHJ~v0I67Hm-sy^JzGkxa| zy3j$Ax8HJo5fIuajVg#tRmpcEBRmAA72_N6|9f>8W2vwH-Zrd=hM?-n+nz?z`jj?M zU*?cGzR4awqH1qt`H%KlTep%&!Hv>aQKrGT6JgrWjh43q5fSS~pR=qJo^vv;nwWqa z1Z``w6B?=h4~?1hIeGZ`(SB1ZK?z1|P2CjJ{pjYMN{isJQZT+2!ak z8+13yQHhUbrm{3Wd|nEAu-7^Wk1@{o;z|n$xLS^rJ3R@lnipc-fI7CPHbQm5Nyix* z52^;c!GzSaOzoi?q^*xuCOG%?+Fe?IX zdtNF{B^b>LLRI#uh19~89v~7l_(JGezr!R|y?-yQH}zxtyW`*2amUWLEX*Bg;e-*A zfk>a*4=d*{?a>RM`7eTJw%>dC2W^{z&ZinHuH}?bS`uHA;Q??)B6rA_m|I@tLMdsJ zUMxuw#0BSV&c7FkAocg3un#?spzbH`)VBuD4~IZ!ap~ibklnqT#|!FwviOG(S}x7Z z+jc$Eo?<YPts4{EJ*JVD}`*UAMyYt$qO3M_{ z`ab2pefRBK`if;`5*qocEb}FY~=zBsE4{k}f;))7_&f0K^9Nyo$*`zT(kv2>3 zD#SoTH!hT71bSqP#T;McM))~S>c?@YK2F=@M}8mIU$X3MS*HBAQS(~9Fqoj5hsc;= zB^fWKJ{=9aW;Y;6pGP13`14X=aR+#ZXei^)dion3@xl_T2+^9?MGol*2irm8&Q{8$$U@arKD&i8%S=T?Q4<#+#K0T~<7m>#tSn z$zwfm;Rf~v9EnC$z!3vucX9C&fA_n4Ayl7_3s=Jh8CF4tc4b9oEiYQzQ{m17+wb`I zY5})vJndk2Z!0|ZHfVYxcae^A9*vYOrZOUcfxe6B@J-=GsSsbH7dB^R))y8otJQYi zxzUUgR;5?k{9)?`0fRPy$3^MG+D4-j3&tp`p{{OO2()pNK(R;Fm^v&dZ(Uqt+|$<} z+g5o$Ut7|c+H8>9*->t2_KH^C_l$!({y;h5Vt%l@sIs!u*=U9XJeb_X+xz%|!+E`38kgWuhF%Xj5Ro?W$!IOU`>Ivik5Qwf} zVuTBaqR}ujQ{_~8ZP-&BBc~S3Ei17EN5Po6BEpbkoG8nR7PTBYJ{ku>6>rbWd2wvT z5Cf=Z-Sv*V(jwD>8w`U`Y8SL!U}*8W;_0DJ?1AA`+pF&avF8)olr+^toaq{#+}(Lb z{HbL=Om|okg#EZnfJ2=Zq0Od%xbbTqGTc1)bHal!Bk8RBcNco}U6Xn_z_ZM_2geSd zt(qnm<`EiJ?3lDqw@)wYhI%J3MO#2cCw0rpwF+VgUXio--1946+^#6q$bh=g^_)Y=^*%%C;@P_F>!3 zZA3PIUZpw~A6s*4qaLt;&)f7CcJv?62A#`YS5wZu_|U?$IP13|g#X*D9T2Q)4$~Q_QyXVIuc;oR4xw0WAn7baXs( z_w&8arq>@=IixA{+yc{hi>173%n6NBP1&ap#}9F&wt6})kY%zx(?kmJ95O9GGIWrYAwr+goR-oDI>jTi6N4W$j2dV{ z@(f`r5B1~B<7%m2$n$G}tKiKI?+0<3rv6B&9ng4d>`Gm43f#E+ka18EokZ|Dhf01! zoW%^sM6ZZdU0u)#)xJXq;U5ui!n+@Sh1;&Wz5{n|Uc}B^jdWxDnWGzmNT_}JyF8oD zlS0(t?xm@#y?a0FWB+?){S_C3zCl-UOjqa}*`Pm6;ojG(^Ju!^N%VSJqP0vqJj0RZ z7cU=4B>S5nE}4Fu&bDq9vpa!{z#k~k;s}hIFHVpZkqX|Y4FtQw9pAOwX>7kom%kbZ zH*Q@lEJ|PXZ8vMS{Rf)A&t8>s_}!E{Z;-<#cJJVJ{`B5ezq&kz=U|b`SJ2~KCbE$h z3D@fT>3{dm8XOyBb0tk4&E`;#!%QLHFjAnvKjLL9YH~P>XW7jBUGiqG^FY&P4MU*0 z5-8VP_q6vBhd)zP{nvSdl&=F0)hDQLbGwj}YhEZ&;*iPi*$0U!HtK*LiFRaQhv0Ln$v< z>u%Rf!t;9n#I`<=z74dB@HQ;0`0^RU&j?8u^$z8?17~%7l{@Wny;`pJ^MI?jIA8pR zo;|)sX$H!|g76~~9JNKmkIm9zjDb1=YEV!;6tKfqBV?Y|A> zxk{%$Yom1CRBb|L;foI~PQ(sqeWlM1EgXI}a_CJLcQ9^t)KQd=VjtCmgS+S0BwID&7YjR4ej&N?FCoj?{x7gOUioXLY`h$-8y zy^xUWaVb6DpPhvqM&5gOcD*cvB_mlkG$0bY;HMghZk^!7nzpzm-(H>Bn(|vu%&fg+u zlBG{x;F4g}pY*LqrdBgl^MDi-ur~#CbX0MC7Au%GZ5$>ms{Oghs%y*_&&MiEoYRY3 z*>nj$h#Oev$L=R%@1!t@v>){nFtd;n-5#d}!c1|dDXiK(tlj$p`;WUsm_2`7;s`OA zHa(mqHxGV&*!yPxG+-+m`Z$%MNA5p1ozKDZP=D%j;0pRu#T9s2|j$p#=nqz&6MvGab| z$R7q5EutRxU-~KSrI_+`oQ(aF$v4fhk!EiyTQE9{G|*T&EM;*^C)rK0%|s^b&mFKF zBlXp4&SkMl61Z(CmTJJR!%nSVp#0;74D|_ z#me@w90SlB>F)yqvFS9ySZ3g5Dn0Ed#zFeS?>KTR#g1s_Nak}7zAI!9hX|_{*$Fw7 zD{pcQRAou44=FJ;RY7NMjgBzjP=lZQBXZ|QO;;}s3%&Qh$So=C^aCG{4vblh+MTOz zj{6${?7M%?y=;}7FpblCe_S(rkHL!KDKQR({5j2=vT?eH?~ghRpv@UOTkpN&-e*I# zL&5R14OK!-3|sfXbmQgLG~hPR0FPwIptX;mTq+#})ZXlD|6fZ8$`88T{ucxzo5iRdI^N%e|V-O;74(WbSma22jf!ev5w4Q15&b*55<^8 z`i54b<7tBH`%|nyu`GnVopE^L__@d-QWcK)%#%Lt<(9;)2ekzG>@<}$z{iC}l5dwP z=xI|E7$1bMnUo>CW#&EHJaoXbq8hqY(c~@l1DzD939rw`z+iRYX=9Rm_>PVlPcRnOVU~8Su>}ug zsL|&_Z(1?$JnMyhG~f78(?*v;=yNKH-YUN=ZFi8cOfec|Gte6{`~OSjpu10|KWn-= z!_0DG6Gm%US(|xC>PpIcbq0eS%!>@iPpRd9BUn~;6db#xip{DPZ~idt5PEt1fn61} z`JNNICyzo|$}7eoGWp4WTxx0IM5qKmh645F3RNE?%|d!X$Sqi8!X6^i}ST3D^plsU=L*L8t}N3F_GH6B^N1)5!7f- zpTU=>I(@a%eW;d$_6!6g3`yzFX*@K>rHjqi8DJ8|$7Rj~Ps*nJ3R@te`)C8u;}*l< zl5`uRbdE%4W#+Zz^6fwuYn{Q~Q26MdC?BV0i`Q#qv7sl|_aot!rWh4%f9}4ahzJOW z`Vq48yp}(OB{om1%=)m5aiB6}qJ4Obv~C4x6~k{}Ox{75w0a-tf$#pR(QMtdY*HgO zpk~iCUZr%+y58T+%yXymiljs{>n()>fh9AsV0KnkvW)}Zvp8t)&UNC9aumur9_`RX z`pQTL#ovY@|E_4Hlj>HswO9YWr*anl%6Gj?j4b1q&dQ3#c=RnXbdH%;vMmS$mz9-0 zs*sbBlJfJy&&_Ix%aL}lI^Vn?eu3jWv0s-Lk0;+tPnj0Zb#)Rq!q3k?CVWSBr(t?_ zmMM9S47dc)-%XA2f#O==@eIwZVWnC|6Z2R_slM(DB%KgrzJXus@0xcLQ!@ zJu9*p_u!f8_9xG+%*YprGZ9`0Z-frO=Ty1ar2I^SjebeQM0|k*9w>WoK0RJ1`}RUx z_x}DvIy@JFpw%_P%*CtaKJrW8`Zk%LMV7w3{=)|Kx~?zbwToocgXJVmD)DEhdKB{b z8g1$Bs4%0n!3r1*BCyf)(ecWujTR-D0lxc+?tG%TkV!_Miaeci$(zF)aHA&MDSg~{zWs|JQU+`f5D+kmmfb|D;7+^QOug<23 zR_D0$w`N@9|Gxc&QJ{Ub3%LhfLLXOLaPOtN_cSC&7&^{JUOu3PKyt@_p*^*5JJ>9B zeKspRY=q~X8uX!=cd)j0p8nNkdm9#!R4MRH0z~W>t5Mq%_T3h0Mr{v{xqJV9_P1eb zZn%wj`;GZ64x>A+iaVkO;qV4ckl^0v zWoY7QO+zJFyMvQm)_B2Lb!H4#H&>v{M*R4o*^>W@bE@gvB7#aznLQ6!S*h3+VwZPM z%3EK6BfpMMAoQ8%%S0?=;DVeQb))u~tNFE=x3V)`2b04zO>fU2b{-2XT4gMF=zoiYD%GDBnvdlBhn*M zJ%L@YOAkiY$$~QwTj=GAcwg{t8*b|Ayz-cf&>`K2Z8>YVH9am0yN}rnJ;$1+AK_T|~yT5(}C%R7o@i66-bNQIbZcowk7R&B4BcZ!v}ukZSr*?q&n z=dTDpDw;ud6R(-a8ABo^OTXyhkWf%6*hmIVV0TEjad6Fy^Csu?HM0h4SbdZ29MX+f zdx$|(6%{7lElp_{okndzM@uKbWWWG89_qXtV<>ru)-B4dd`%l|7>l8Qo>)!fMx1rg zY2iPbY=kD-%={^JU^G43S33yG)C{sS^n=n>sbRIu0=^{DEuv008g92kzkL$SsRT3R z2BC!h8B^tq(xVeygO)RxHiQ3oYhBU8k<*RPI^HvBn30l64Dxfc1 z{$>p;K_E+rj_+%3L>D=m?8JUu73GH?2{j!Vh!Ni`$RGLch&Y5Kg3tq?PNtGYvFuC)ToNbzO)hx}8n~V74sS2j| z_oWBpfBxv|YM06EGy3pC#3p-n*vJV&s*MM-=4X=KVH~^c@Sfh=Av0R-DHY*VrNXf! zRZZ|&lyqVX;DI{s3G=m)k580xlQIWJC*iW z$n?5-BhljjgcPOYIh zS=@S7_&?grWqwM1ZY*~^jr>jLv0oz?y$klu228dQ!ZoyCA25xSr8Pu89deg$VrEuA zt$X^(%!A|Z2krvE5d)-;evFyp4bk|loSbJBG-KGyisn+B5et8WqS()zoVO<9gj z@Ojk~kJ!eEjy||`L?q$w3KRrV*d3hElTFZayr)z4)Uh#MUQcI+sI>w&Or~s&I71pl z2gi5^%WIap`}=Q%2oF`;bWh@R&fpuqb8mb65lLTG6ec!m%P+T3*C_-VmS96h&D@DY z^$DvFZ5g^MxJE5DI_<5E<^u_iRC6^Gmn2|8>YD9~*jm(xi;4cBo!~9?sU@IHb+Y<; zJrjbj_ysl5KVnrZZv!W|F%mWTXUW(r#M`!&RLvsp8m?^cjW)`NVR=UOj3zT`T5Qy|liljtdX=s8!&;+H2Rz z_+|_9nMGEl9GMh2oXy3X_?mqLrx_YBWW9@?v*WD8#raMEW-WTKR|KyRguH=a@5^4C z?2m*i`UL`6OhJIV-A!IQ@->$my_SeTAiJ4CRz^^wGwYLp`7>m=0qWjp$+8h!#-KOS`)zq)XL>cQ?bGf9?w^ zN%#Bso&~qF52@^0SAWh5#J~u_gjGcV$t0s-D7lzM5}?%8#q-&d$3Q6}A9bViS6)g= zNO)b{zQwxImT-6UXGFzlUbYx?{n?$s<@}w#RQB{=4nKb=d=THrJVdtiG`j#5x-K=; zF3r_0p%}~*4@w@Pt@1n}T_J>i`RjYp?G~!RDus@LD!Ji0=Y?;Gg&I_rQ^t*V^s>Ge z`0%dtT^~E`A}EkBct30NKZ!2`LV6RA0VcgLGoL}N=vE#4xv42-#fWY=B59(aqH({n zMa^1Z)?DUAgH!$9Cynu;l67wOgj0&AG4Rp$aHD4s<aaH+f;xjlN%q+P(dL02m zG#b4OwhJ~lY0)EFG74=R2@t!1&D5sp9rBXf&b-iu=Z1 zEMJu>QE3!Z6^#nm_qrt?(&*6AE2_QZDN6QJLTGRi@`nXEEgY+)F@zF(h4Z!cIf$|b znLAjlpk^L*ppFA<{-dAoJg@9x)Dw9}fDU};Uq{y%{>&-~AD9J2U0cf9l5}NikT)Jx z*~!*x<5A0=P_V|>`o3$Z(eM&1cXaTsz1eAOfO2gKUX1Rgw~BdD;z-BT_Wdlge2Os@ zC46YF$J=!AZ1FJxC_M2Q2r`)DvF($l8W}+!J4){qBRKh-Gx3ri&HW#-ST?{yi>KTU z<-T11uNU-}H~#hntd-tx9EyIu4M?f~0k0^n_LH|D+@y6+66O&z ztFitJcC|?~y;a1gL+FG>-1NH?*%6+hRctEUhS%HOO^2P$sR96xDbHpacQ; zOOB{oUTE_Nazr=&V@yZT#<=TblZKmPVh=|o3^~KD72WS6Ht0^N9V_c2h|9)msc;5< z1N5WN*L!JJ&-bIV>`UpO0%Du{PIqi@e>9PEAWgOpz1DYWHf9{Zp4%@N5x-qx0?_(1*LOGS?d{K zJrf7-frrWZjN9@h^&&l3@ROBtnGsdKTKH~p_N!HoEayZO~mK}0o`dg+w513i=Lg4gw;`;iyia~qqIpIxdO!@men1d!z?rY1MYW`E- zFs5x=f6n-61#cQFYOoo>o1InSmRkUcysD;z<7aE61bkZ<@H$?Me#I&eUbqLSkmS4HJ;iaJi>r<)s2)!qT*u2ar{2T_X!hT5k7G}nrW#cY zEq$(oRz1!8bgo)@BMwX2Dfcob1n(faC@e1>WjI_+mD(%e2oufeZgs0l9KLEfEO&gi zZy}9svb~Zc-!R}(*X3O(ro0hYl?;M^&wF57H*+>+(VbTgxHtorE1hbZn&fy#Gki2Z zJn?>qhh*)TY=|7&I1O%Hq&YP}ep{%3UdxJWu)A%@AEvjTi(&gCCN!24@Bzs1_D5UQ z20Fqmp&;K=e*}k^dEQYxmub6z_$Ml7ZK(A@KZ3OwrMgmfZ9sN~#S1b03XLEqC62tsNvfoi`arM)B_)G&rnH*<0@1RDa;*tYjkQJ)ch!&5BSbV1 zllli0@(pl!ZCV*-=G50Y|8wun=K7B+V1S<}EegXRBr)VcK2%V=|5)W-@n}vj4>Y6| zZP#LRD@1F7W$Q1>XGIt<_=Ce(fy+Q6hVq3Ibfb-2Ry6_6Z8hO0$WOPW0tUmj47ovn zj?FLTfnDXlY9wgWHaU&T){=cXQ_lIUS4jgQ`Q(eoSP82@a(EW&J$=!LU%qAqY_S%u z-a7|t6PZac5DB z?JCy!V02tQ`p%Yk#(j;PQaELPREco|%2SR>F6-DlBA28D_YM8>@bItAP5YBp&lX_8 zod2hR9~uYDrt-K{oMD>LVNutIM_ulr+5Dwd`IEIoMoNeDA^}{I=U!YkV6_kS`YA!s zS$%LAH5i<rDLbCu`wYxujoA$>CMYq5B5U%_PLL z$kaP8Rdr=g_nair{$ARRv1uYnuB?_ZqXX+=T5$Sh`>3pO$HUa1?{u$X=fR#0fCiQ7 zf4mJ?FnDafUAHV;Q&ME4oT8mk6-$Iq6&eV_MFL0Z6VbvJBXnOnxU6$6 zO_WaZoDXzf+yMgVcHLvUD(mtEc`@aXtM51mJa$Sy%Rh^Ee7+%BFL)zX`?fHBO|S25 z3NB;3K!w8jgTtajqep}q5b~T|M8MfPFo5Tx&LYW-{C_5%GmNC96f3sfi1Y%iMn_}y6d zhPbrG4i0`W4NvCmYXsn2E=@^nT+h!gpt{_x*0jG<@#)yleMmn(<^j$v$twqh5kOKn96RvRPZ}7xKa!)3xJMx zbIQ{?i`eT}?Gk?brN`%SuD;OS-(rf?*6DOv}@TBF2&TEUs!uhaxS;A>Z3Uw zrX6y696!>~?N7pQ*g=UunJ|{1p`;~IKCiUH+&*!$JSs!0{eQJQ8ffU+=93P6%e!vq zJ!iI+v7Ckb9Z`8KD;@C%EJ9w9GuLt)x9=fR(?F)6lMx;7AI>CPGT!<~>2fD$aAA8v z0J|qpA-6iamRC_`{^!`y4@anuMHr3=G;xB)sIvR&%id%uaU^Exd6~Dna6Z}8SOG^z z^pxa}-t2DRIRIoc^Q*I}TV)50z&;b9%Y8wp@2o++>G(y0^D}vp$|l%QT-; z`0A;MlyuN)4ddE&P@pdromLD9km>X3DeWRcf)770Sd~Z`f9T z0R}UCCb#u^A>lfln-?MYMVUOeoCnCRlM43GXL|ghr?Cq2gW~Afh-7Pdp5=iYWG-sTp7<|+kX zGF|4LFn#c7vPJ}@e2T$Cil=(9xRjK{c{i36f9u$lTQzZ?br*{RD_iO1PyLS(GQf699 z(|vIGtn^|9McaM7E_nxaoglRC!X+;lt=xZUK*A|9J)pDi=s!hhXEc%tp3w)6D>$R*H-;g^_I7RD$0mIHG!JZ#$2gCBk8yoglo7^6%+Il!}q}lCGe+xD{=fc=6_?tJOd;|TYrQqnt za8_KBIIqkYs~E5em#Q%eHZQC(E9>@0@E!eAV!?Mm0>>LQW}o)JGT6;pfR+dMlh+ym zdAZVeAk6vtYcg5!q&gNb8`aR68-$PbmayQjCN9s62I-2yboFgs@I?Wbqnn6G(2>!E z!1Ou1c5Z$?OTUgHl>C##kc}jOS=o=<=@^QI8 za0>5xEg)$@3e<2o3$o)Xr2}Y&A5Zc01G8DrCpetqDXF&ATSwg~WGa3BafO20WWyF& ztFE8&e{sVf$^6zL$z|9MxF@o90_+U0FEGEF=x8IT zSDi!%0**s32-3+A0VmFsml~H8iIxo(p+F*_JjaR4XA|`Kjh_hW4+`U;O@mC#xbk3y z0l)iCooDsm0u{#1vT9TpNyh}o3smJz@KR;YA2iK8K zh0xBwz1iEjPe#NP6zbdB#V=Vk5=846p6Nl;iyRo)kWI2m8g-NYOqS0di@E;R7V(}r z-E{V@r(14ygfGuTO4P-QE_+J5vk9`Yy7BA4BfgEOQ9dlBr59AfH_CqcBHWmn0)z{q z`N1q?Es6(v0ucq}66b;L>V$bE(cXU~!T?5aCFVqp$V@t<&C zL;z6TvgdBr{Vou0eo^L7oiKFPD`ER=>DQ}Ov&KZu{2sk7aW*Brv)n=d#l~3p688LJ zf219|B}cEn4h1BTe;8;>EzP9kwnz^JPKl#L)t>gP_(lhWS`1FbO%}MLOH|r$(8WQ{ zQFI^=Et~`#TW2fjYF9d>lOg{hbz-I<+8bf5Vo4o;TE9sJZ|^NtuVAph^-xfG#sIPD zFuzoCKHsNL^8#vB2A36u+glyKp#+O4g*k4bOLHMQD4EbGV$GaPne1SRJ3E`dTOQ?6 z+6Uf7H$q3s_Q&fIyUEEn;78DnP-Lwddj%Q}O+S^!9TV1oq+p%$wz`12=X3e99KnP1 zY>4{7btInf=l&Yr@cKu<{iwPZ;XiPEc8bSK)lJ8R+kvF9jZCoL(ZOX`Xk|``<^T{& zkBJ>CZpRlndzM31wJTt^87M&>l*H^ck(94h9LL(T)IeLa@H6sT)$(NW1huWN_U1p7 zg7pZPW^GO;7E!A)N2z882d zR@v_4WM$oP3YhP)r@;V3XMa9%(tl=to@a32{BmU!a18vf4rX>JP@>GXp_E3j{~j(s zx-OiE{Ed@I(x`H8-`=i+hjHUR#d+zA5blF=X~sf;x~t(cha9Ny>9LGuv7=82LHMx~ zAZFV;JTQED*6JuYd6lRn+pp7Ds!(fqTt%|?VJsLven3~T|;#Ct-gFIUZE z`4wKqs6s`Xm~MEukIeyd_zfignCTw%(sZ~jynCP zQre7MMP74Tg{BD)?;Flu14K-+C$*Ph@FN0PM*^4+=XP z#6REngoSLsw^`s=qbjTHfX5X|mZ~$FKl@%kRJUKe;8XGx0c3CHI}Q3=0VMP1+3))%k&B{vtK#}H)?>9{f!|_$s4lls>V%+t!Xl8GL;#UUoEE= z)VFZw^PZ4(8MpWnQ8NhWd4PLOSHsso9p6V1D+E$xh$qU6yc1{8u>6JWG>HT>7`-xg zvL7ghwAF*9Yda34cx-rQXHgEGU8K0z5We`;^k@jX_{}S-ZZAMD#)~U4=i-3tT#Ber zpl^BCQyQgaNeqmh0t@aCs@ymeWv49ZN!+9F1o)$rOF}cRMxAOS&l_#YqXkAQ);BZ; zr(=>E9Gy@v%}?ep=&c^qUM`+R7l`wWkcc^Ayo}B3q30{(0-?KhD|d1Ql?Ymo2TRoR zaqUxtMjLqWl#Y&$zAZ&LpE|4#1-N=QIb^UtEU&qLIm6zUPbGM^7D`AEbedmvwJ&!C zh~w<-!FG1V{{H9P+-)>S@YE_`lnlO-y!5euG%(I#L@}EiYD%Vlfk$(yA7mw5*b4#zU++m?|n~YRmQ6EpurNjk?F*g~l zIKAetg~vK&ZogzGs(Yl!7RTRC!F=+9oh^b|HC`dbF5l6tdE$NgJwXZ)99bpBi2(y` zONhbb=aMteqtE_m2anMzGCgn!rM6;9I!*}O*|gGeDdF&$d<^B{iLe%3gKXd9hFDI} zBg-+~3LpvbK-ivITTmYi!NB45lkYmSaGFNSu4Jz@Jj&5nf1O~rV9(&W=e9rdNLK=n znZuL!saQ2;e=E9FY$fChtF9XJ=&^ycw~A8op`piS;85~t7H!s$r)|g4BEhxK>oix& zt3aS{Uti|=)HYs@s4UhH2qJm4wxW#EkK(qCTdTjqCofI17nQYd&X2NAW7N4>LzGG) zBUN9+4{WY{3A%{bXqEI}VvBgM+}(d=I=MKz%KP~PwJP5ZJ&mv7^631Jy5BRW<8im{ zn`Y)@ebbUHk)`Kil7F7gP6w-?^i9T#AVKjn7J7sfzU$>1Vumz0uP;l5Q=~VLhtnrc<=l9o&U}`yK}y~ zvu9^!cV|Xurf}uKQ>NGLpI|~*m1^`AG$7Yf#fld?<-snzb%PiV4nB5pjn#eF zgZfa`+Q|0hF>Lkq#Q&0Jjpr)9(#;N*3|ad#!_w0r(I$zpfwTcAju8XZ#^5W>y-qdm zjwJ6~ozQ;`4v?WP4FjIyQyqkhpQwg?AFk$X>2(ws)tEBhtu=ePs+TD2Y}r1?Hy%gTq&BRA1(GJj9hDkIEhP!M_Ov zLf^(_|NoJk`5aeiBQXp3{^ic)&hONghk9+)IbZhi`OyXgzF4#t6xgu=tlMzKskSmL-un&9~wW(%s zAr8(IE)1%z656HPX>@gYmGA^#%X*iN9>5QYRm*&?RHhvF$Vc82+wb|~p!WYqo%6;X zogX^=CcxFuP%jPsz|6@+*R<mOkb&^m^@1vH(^DVVTQY~OB>aLH1GL7F>y4hHy7 zI^=Kx2#kt)X`WbcnDl0)l=l)plnARp0k7Gidk;4{R{-Q?7SYNPR%atB0qj zfxB|p#I_U@%(#_V;Azbe|)Ew=qjR$9?6M@nD{6O z^K+rbg7ex}mv(K?kJZ!UjoE>HCrUm}2D??Uz$ikNMwQyNPfpHpx}SQ|)8pa`zhiP% znIp*}B);XcG1xLivd8$s>6$>t#VnH865efC8&=|e>ji>KHi_)(^(p=MMp{c{9~0#=2m!Eg7G>Q_Wq#9a#8r( zy&*dt%-&0cX)#FvYSNnwd-r|xCpz`%=-l_E8N2I=r9*;7ng6^Cz~&Q_nFvdKh5zX z9#gU2xC!XI%QGIJL^mF-Qe_ipKLfXydvE+AEkn~j1+QRGovm3YFs{#BtZ#>iV<|2u zlt@7pm~~3WL)7uoHQc7$N@|Q(KdmdbaPIop!`bL8p59BmdqHyVSf63}WVfLX3wTtr zLU-yF@A68wHgy02aokwrDv>yxFd$S@`_aCjTPg3Hev3OS2XA_v(lS&==T`&c5S;~J z;0FyQeNgs-^jO~kS4BTkIak3jr_H8g>+o1w4fXUZCRqK&&28bA`xasxe!P6&8Ewb{ zluXm##P3118BLPdvNA}SUX6!Iw`?xH zrZv8mfLl;yN5_(d0+I zr~-fDM<&xYeW@xHDmO7Q`OnNW$`lQgji3GSDV@Dxh(M2cZ5fl#VE%$VfqlYY!SdPW zb1Dk9u+3-pQ^wTtD=Nk(U#_52kMfwK^M9mE-iZu1y`_|Il5a0$Yn)mugce4pI0OQK#$kGzi&2(_{;r6ew=)A%0+@+7MoJ!m|Zy}N?8w}ohu@;HbMdfC?_ zx61K;SC#8{Njyg zrxZbRQwxh>gaFv?u6kz()Vn5tyC>s_DP|8!`x=!$TaBgeOx82b_Sy2C;>wm`O=WM> z$Fc9h#8`gzQhDLX1#+ET(sQxXah(}m1{mKqJ1 zKb(jv2`isppg9NX98hRGp1Oc7n|&17Ep}Z6uJ1>q%gEQsU8oBsWH)=*SrBaOmW+%W zEl{g`YEX6|s+0*`sGZsXkUD9*%D*#8wYF%`n#+efR-y`AtZjD>vUupGLRHd9qlvSB z6D;e<$jllM5s<4ZDk(QUU?N*)TBbiQ@{@@zTwM8n7I(3pP3&#&cX6H=m{82{M?b$j z{yQIV^aK1-l)b%GgujOPaM{H(pjP;{#JBKzvzAP6<+_#0gB3yII*;?EcC?#c;iDvy zq{lz#WU>iO+JdPIS?s!|K)7K#`e$snDn!QmdlbL8F@VQ&bkX}a?iLST1E;w`}FQyo3!Qce)HfAY;eWV+0g!l6eCrW!U}zlvr3C#gC3d zkkRA{c470de&?~v<5FMULZvjmb#__F01YpEHYIvfOM%FX$gdM>%Nn zmfRB0o_jpj%~7A4G^F%NG&-LYJNRV$X%T=MctV-{)I?b>bS z-UtS(=Ly+f*5W!GIIc3kkS|FO6t~ZOx8DYh_Jm}*(oS(#de#W4z>E!{6o)mW_93;y zO2QXfek3GWPnT6Tl>ytAqTU;mLOW}{(*$I=^p)beEn?Bc549U-bt`>n8N3tWC}=Js z8tkz&udQ&PhJguhz5bFME0MDcW&#>ZdhY%aw9dF`nDy*U(1o*xcuZcO`8u>Q@|w$k zb=EJtvYbkfHVHn(YsgBIQ(C@OxJv!75=*0du6C`JOpKmy`ll*8>XT zWlJJ2e@-5?aiB4H#rvOQo<6>2185rzZ)g+!gF69F`%6);>wNq!9IoVz>44rBS5E#ZJV@OideXi?)oh(nU@z3&U1)1sJBKfDhgNMl z_j{#uUgTH5ug=~5x;Wo>D1;f~-Y>-?096DcAgBihz{=pjLWu!(KkC`9u0Hm+=tO&j z{gQl(O=SKQ$$Ww!c_+pu1q|_TPM+LIdhF71y??tq%lfV>3pVGv88X|nB zrW4f@8F?Z%g&;34XAWnUOJPC;H8%~;*!X3TRDi~9wLCvrX`aj?1RRI{I@!1KI+Ari zsmLpNmfuJwr)aN=ST+|3XB9fJBFS3gn{o&>?uW6Fcoy{E|c&9e)^$rROR3zbqgmYXCP|g`mPCj3Fgq zl+g)tm?ea;zc$-qu|HkivLtYdUw*(sGfVF7fsJKY8m-BV)GlwwZ6oLAj*KBfhIF&J z^&n70gDc#7D9ysdx=QCDTz%Vav8$fJWJR2e55E(i@FG#>GSb$jSoGR5SH(4WBE%_O z7=?_rz*fUF9p%_2LFd}q5yA%YX*T7&o;mVxMc zQn80YaoxtlzkCUF*d?bOrHQ75xOAKJnb1+aX))O^-|Xv`iWKc_9D){0E_A!DE@S$` z+597HDry^RYnp1n3#+;9GW7ZJ-6#&26*Wk&25-~$s1_o?3dx2Gg4%7wZ}W7gY`>BZ zgfA-cEr&E#52b{Zj{uR1E{tQd+-i45nstnVDi1utE5}>arzg!{12j3lv3)asVs`l) zR?S%4BX>T|)0G);#wK%!-HCgH9!FeafnI^?2j48-@k`0>GObQ9P4ZhpIsI1VpaJ@z4$iZk}oMr6|Gavz(<=z=wGhqY%F`g8XqeW z&KbprH=J;D_bREzHp-5XL@hEn4QEXI7VrjYk0+uZy$H4QODXyy&?K|j8v7uy{B%F^ zBj-`!VaY1{BAFi1P|M?qFPRx!+77x(_l^>fi*kiM+dlY;(%^$k=x>T>)XZ+?v) z|9k!sPlLQ}#c>YgCrneyex;n`0BMGMl^8Cyp@{0HC2iI}0#8pX$<3 z%+_$jVTYvA8=EX_EzOLGEBesf7BtxcZ#ppbfgOLpC0O&znW)H zY6Fg^S{HXPx3cAS+H0^sTYj9hDtt0I{t^5f8eQ;gsKsGr&*^KtYlAQzW<>op zY2{U`a@ZLY)2aLd>P|De_pEm*9^M?rR^6Ls!K^9cDzJarmOPyx*_ zx?)+}eRlO#%HuMIJ~&tEd7GE(3yk4c=nf(jzpk?bbwTl9HM(Sq;Zm7hV_5v{1SRxk zqn!ycn7;0q*%lqOC7UG{BSWrrq^#5rrP8Y#$7>A?q90pyLdk>maP7Kx(`!9D%2t;r zDrBP$lQv_5n%9opyUn(nt&l#u2OXmB58Z?MaXe*@-xwQUCr~gK%JjqmXYz z`Qu??X+sH7HT(2rh`2s}G9s!#TrTJK^(^0Qh=S0U#jpCxk`qlSTDA8Ouj zP@H{jVX`F*RZxT&sxi+VppUy@DZj4#qlwcobM=={Gs2T12bn!mj_~y84`0Yar2Z z@!BEcdn=GhYQ=TVXB`<%S zTA2-~MoGd(TObIhKlBxgiNvwDsYyerKoU`hc6BpLQ+kW|A~5~EI`HA%DdaSe?^kw# zJ{{8fw=(XX(^E4aT5$wftq7&^Yk}#k1vtHu%;Cm_O~2nGenc$pa1!fByq_i@D%2#s z+6x9B>iLbH93wf2Zox-{sae-_;rK_X4zKe4CGXtWJqYYj?GudoA1b z4FkD~>bellv;LKPyFHCR(1HA(pLB=(R`h`Pyi8v9%ol4hvpkqag8#fFH-DX!<`_}; zIaZssB~NYFwVA9M|HMrgg z>)3()R=-NH_}2L8pE<@%sGTTnpe{(aRH;*1Cevf#aWRY0*X4v6$&5;Su+cG>8bhzY zT868ylyB<}48EJxZJGryhoL6_G>3X{t@+*iYj6QJ-cRIo2EW&dj!K`-Y0nu{BJK0- z5PDDMa!z~~+66^NQ;+rbk;Gs7e~2xo?zB0R;OT(X3aTI;=DTNH1WeVu)Ffo4yWd!~ zuLB>?k61QsD6)P|jEQRUpNk0H!MFTKP`L5AYWaY2&=mJpMbYnk00X46ubs4-1o1e9 zfDJAG5E&6qhb)Zh`Se0V)+4G6oqUG_W>;E&2Dyo?RcPIHxm4J?cXEUIOqZW(%Y-`o zo7T4-iV_gqM@0#^E+N4{1QPH0RhXCegQ%!kkgbQ$pG^>1l@nkBT zkzfv_RFVEXM%KcZbQ;3Jl)50$L$zb@^PEoT8jJC<+h$Af;kTC4eD~woel&__qlr7(}n~QD}zo*<&*XI|kqpWu#Lmn&=n2 zRZiUZ0v7K-kb;2^66#JT`aXxLJYeU1x0y?DJqwMsPfF@zS&x@1b+ivY*B7&sg(@#{ zu;|5pR!r&Pq7VfDvMcPpge_a|-7S;ReE)tq{rn-ogY&-vm$q_Q#)A}9^54hrZc+?c zN2C+((%A#YXvR&S?n_u!9OJ!)g3 zA)%DuI$B&5fS_ULCv#@OPoW0V%;iEmL?f|naNG-pRzyfDl z`$WpiB z;Sn%@01;kjb182|h)$PKn0{6eFm?TmiFJn&E2xG8C&JE^v0{dgPE6p`FkPIWPWpnEO{*({BK~;^(oRQQ(P-Wd2h^Z$9 z9n3ldGo=hFn>dD#Eq($M3YXfn_Ab&p4JU|)U6g_!C5v~459KF|h0TA|CHSxC~Wer9XBK(|mu6C08{Jt%4F)aJSpxrlxymAz!xqP5N4oK5Tsl#Wk}l`gekebGT2DW5jv_l#zD$|}y!mU9&qc`K=t`8BmVU_)J}o;vpMh`@iGm295nQuk gW)b~OVb#CHi`RlHybQT+p7(~Dk`|;)(dza81N!exKmY&$ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/path_green_light.png new file mode 100644 index 0000000000000000000000000000000000000000..920d913d98c17b5ce0535e30c6c98e8c88499cc2 GIT binary patch literal 23635 zcmYiO1yt1E_XP|OAc%B#cXy|vba#gcNFzwMbVxTyGa?K_m$cF)(hW*Vmz30V`TqXz z`#iIjBCPSwx%cj~&pz=XT0>196O9ZF0)b#ED!kHyKoChF5QG&}MDP>6&dvAW%d>Y1 zhTtn9-s2yHvoK;p2!sZr`09m@x7q%(k3YFruJrxvN9Vz0M)7pc{1ejcc-Nfb!=w^c z&Yv=@so{8Ys_CYcj0euFsa&hb9n$IFYoB5+LjC7eErcl+2^y6@2x(;3+f6Vz?Jh;G z_e3YmrDG4a2qxPE27Q#EO0Y6+v^Gv&9h0YO<((KSz-a{{8!RNC+atH@D+UfkI${U)oI>wlpKRVio6|F_#;$AG>cF@s>(=VZ>sf zud$Ee*Hf90$+v2&e>w{}D68t5-A8u?hbEqwRb39$&_gQpTIKK`OtCTC6I!3y&i}L& z${`Go*1EQU9L{?t)UqJ-yWYLLgS3dXN|+@W{COwR(}~^P-QC`Pb_q**N6STl!LIxa z@*K`V^8|u}6`^aNrUchA%jA{|)ie|s@|}snW=G$oFvWss;fb_RY_Z!wR*b6Xs2cye z7{2$8JFg(@+A1h!u)Gc5jG5iL8;&>bA?HHzg|uz7LVi_7?q?{gL=Q? zXg}!+DM5uOB`InoCO&he{gIfli^OG$f`Y=v#tw-($AkDf-9C3#ejwU8X@>?4A4oUf zHH>vIr2~W0s9_kAB)b73_dUGkyo(+7?*k?o)sw(U-*5bM8eUZRlID=E#>JMjY6-HObR=~uK zN=9HO)o@z)d#4_L!~!4Fy4h{QCokA$?dv(ojpN&VdbTg&W;I5|(;wSyK8R3YomhB# zd*7z{d=D3~#!V`up~a7pD>8{PPDH7+6E*NZ{x#db`=p(){o?6C?cVW>Z@VnP-L)^UBc;*RVPot+E{5-G-X64C=npJDKG-G7XC zEd?Yp4ct?RR}1Lot!}GnI%`%3+71XJ)bD=0-J5^4u&^j$Ha0N?g)}RmJ|9mmD*R2G zzxwpo$TdGFxskik@)a>BN#|G!=_`Kq{%{#L`dG5IUuL+v(-@i&rlundUSw=ETsCgrEkm|bj$L-JM z9zy19Hb1Sx#=|#Jt|wj2O_%4FaHE=`j-Hj-)kqB6dA!92nQt0K_r5B`(1BC~YXsVL z>o?GjrlQ&FU~NM*0Sf!(yQfXV+OI0r@imATZPAx-@U8K}DZ`EbHL)n;dpoqReV8k* z`z4X*4NH3Q_6rQY*SzBT_ewKmuw<6e&ghf6R;wP3$T>I5LG8)W!)-Cyvn&|_yg1o6 zXNIiLkY8#&Rb--xk-D4FRaJEkYXzl$){RlT}By~ z#(KrPdNY1Pyq(kQm=qDpUNtJIltiF8Nu;RwlURpnG;7E6OJ2u8{jJXaQ2HMHkL1Na z-dSPOm{S4YgSx6gZHBbZaFstaisjpK>aLnKMsO4jeQn~{-c+vymp@VMt{xm3>MySSR5lSB zUUIolj$ZQ6z^Cu=GG&~57AM~pU0ZL<13Onvg6Vhk?*m3}eo|21!`jk+9fmZJP*$aV z2?}_azBErOm5p(MCH`~lAz(acQ)I)zpzys*tR-mnyjy74o9$Uo$K+hE94#&?x{5(L zTdkC3<>Mq^V9-4igej^L zmAjrB^+XE(P%ZySYQloU34O_yCmqqdr{loyM~3ODJLRIk%0Jxb;uvOPU!D?a*O(r{B zuz*5Oeu`x>>R{p`C*f`g4b8j6xMh3vrDl>pKKGLFO9_LA+=&{3EJN8>bZYE_24x)e zX+;xjTGrzwCEWOBI$D$AWDPdKAz>d>hq#d)8HiZB77m#JaCJ8b%C)J z*}To?GX2PZYbZd!XHtHDu@X5~>#5(LZ$I1B1GVibkd6~v4i>KOE>%i@hOWuwvS3`QRYrw05c#YT_d6a@5_f1)JLF@L1%2M}917{k7*h_{O~z97d(4ITKXnV6WB8HsB$(FK1e;`l?^ILO6FLGYs)3yjRQ*6=cV8rSFb zXH|zWfwP%P**K%R7cXRNY*)ydIc#EUZM9-Pmqfh8T>GG-o#nQ0E#Z>Ttg%%$ZELf2 zfUi|N!|}Ly&K^qT;NWFrvbNQ8OXb;bYoUP8miol8>fU(8lpgJw1SC_+UH9l>8uIDx zl^ zYmMbE`SEVc-)bJ{!IIyRw@b1*?(G9@C*8a*JZ2p!$;9$=@B_8UW_KFm2${Fm(y^!pgVrck* zM?TS>;a>XUnqa1j{~h_Ma?tF}Pv(xB6_zVM%iqU%m7MRo2W-hdLV+9*BvD>i#A%OEVVJhN&<^y&P|=f^m;r`jNNuk>ao`x*)R#2Rsd=>trgn5B zbqCVxXqEZ2T+0|pGZh&KK1M$(68Q3AihLN|wfsTvdW&iZw8N|oBVH3Q7O|qgy{4_h znpRK{DQcz(yP^zt#lb|0eS|UVa%1Zw-ySGe#IA5Y5fTx?zWboB(^Z2;B zO}^h&Ku=e<{r=xxlESO1*{1sXrDoUSl9E@j>5hv92Z=FaBBDx@ueHU+FN?<==c<4I z882>Ht=wlDehtFQ=$8AFj3ox+w6{a8H~Zr$x!Ks*SXq7c z;7t&duWpP4Xw%cviqvHV1zqbWujp_gg&I-YKDlb!?qW}$KK02XM(_2kwiWRG`$x0p z-AMrr?M}uDO69d-SUHzHSHgxJ@(h(=N7M0}Sq!A*Z{O&0H^-Eko)i`0P$M4$7+-$k zW;f3Y8Tm96So{!C%fkQBTb^z_YTgP9C6suP3$dDbe$Qb~Jy&v*!hOs5w93;&7dCa? zaL%lrkMaI>#OoQj+1t@3H;U59ofa2&^A`VTYeSTeG^qXR6vR&o3o8p@b$kCB_At7q zIN&DjzSmhP{W=&l@3`-`GAfu7tmmK8bgZbelvH5socqR;JK&$)-1+$UXu*hsYis#j z;g&COp1epLB7O$cD>Gl=2lg6vzoOrzIiXmtD1)s?)@mNVlwWqXjR&n~L4$@~UfC{o zE~hlLjT_il)vvzqxQz-R4^~|3X&;i*k(|#wE%{0m>3yD$t+xVB*oSX5+kWaU30KZcp@UWe;1W)F)!;UrlpvC}fqT=q{WPI-qm^bxhAhq+ayV$rWitpe0H`PEqFS#PB+;zHWS=x8h>M7^=b!oQDYz@3@oNT>0y7mh9@PJpRnE> zJO-b(uq}8ikY>q&4kxQI(1B(j`;bJx!icEhmO}}prNBb6Ah9{$orV}08xt#b`fB0d zN77rRKkC}g75F8y8~B2K>GDe$5*UzN(_AmHBZ4X-PXePcBPfB7SHXVy4E+zqTanhS z)^=`5%hikIqwfGotKjIBIyb7sgJ{#1&NbQ{!eJghdkoT&y@C|7qN1j6(naD!gTEEN zfN%_xVaoX=_FR$RbfVF4b8}N2|yyfv?!1x-blB=HEgp>F$$S9%Uu zRR|W64jxr*>@${0#>X`fQg#9?gm-?+(D;ehmpo%<(`nPd&$p?`wTYu&egFM#bRv7D z!wjxxY;GKM@qNCgDG^uR{`~wL047&D$PD&+<-F3X!CVX<^$HR--*fh*vZB1A0#AIg z*I6{;H3mxPydzd5NSC{73@Qo>fA__aL!nT!Dq*77`2$bb^uoddo5%XKzf_tM8W?#<+Z65))Wwh2%qmJ9l;k%z6DB+Nohz ze%E)=J&a`F2sXnl-$u8Esh|^Y{qW3#S60{UI zovT$}-ikc^^aG*Pn*;TG!w-j3SfR$Bk+1w~yklqZQlrrOno*XUe~&Ln*vl7Oh;Xz> z>^n0Y8XmE@nW@D^cISbCv)l1vd8odkcV4IWNm1Lz1XTG{J8AJi&HwB0CZ0B%J_ti! z1zjeUYSq>XYTdK)5hk--igqH!+Fz6kgGD1g$iZJTACf5&=WVO!Q_Y%XzuCI&1QeXB zM<;y!QM%VtD?&R0?TsuPP84j(4=c$NxgB5ac>iL_JfO5?v#dNrtD+!Lg=cfr(>Sorb8HQU-Ju5ZJdP{#GUwjoZ#tnAAC+i*1Jc6i(aC3Rjuyb*ezgU|vL=tPAyl zDROXJ^|RAcj6U~!^}Hu{);VuM+IVKgMb`Yel`&dGLceDIMy%r(gZPs6%6sx7k&%m) zKJh>TNz`8{<>?O}DX&Y)k%PUD^K0nWl%>k-uhn+mp9&kkyI{OfU~nsRdd(!zQ&h9g z98XM4C|ueLDR z+XXVT4$Mo(R{0aXXtSGr2Yipd5ep-~4#rhm0Te`px_Ohjdb!?m=fBH;_Kx_svxbL< zNFxkeeGkg`@r71hDTrg`?wp&T1vCU$!f-n=j|+mav)+rfiR1|q>b?D4_k?EJp6ncF zDZl%rQ|sZB#{Dx1>S#H4qg)+2wOuL_vM*(ouMN|;uU9%&aL1zB2e_7tr)`m?23w(& z(1F`x8rrkBQu6NvDeN=-tqBH?;v^wLPbnb_(`Ip9_d)SDk(M1~#qFH$ipLEanX23v z$V7Pjl}y}~m#PC^Ed6Q4MGJS-Gd5LS&U*j$2`Y%bMsba>Qdm{zSb?y~S5Mg*;*_xM z>%=i)Qc~O^&BlV~!?nz6xf`T~Hg<7(Fv*~uwisPbn7QZXu4t2=MzN-#(3EMLdrOBi zbS=R5lO*yrGE&C}4HlhLbF1OH*X{v+dE4E;s|RgQ|FuQ4uQ)UqA-tzznEKK{1EAT4 zN8UWdo;r<)T>OoN$^c$=Xpza1Mvz3o_ZM-F!rk3g@+EJ6(zw~NN9=SGUhYACm3Es` z@+R5#3lV}XpN^u6HKT1o*R5q}qw=WgsHvpsT56L5gC$>fDmN13l_-~l#K>`5_G<`+ zmj{X|*NQDmHK9qfI|x|sO`6viuCsSr__t9=3fBM4TiEs-y+?Y(`9Ts%GVq&u7twRf zKfE|3QN5PRr~N{-TXdh~@Q(;IHOh3@Je|oKzi2uXf(qod%@nyZ<$8L0@|c`jM#JoE zwthBmpi;4!v}}D8rimomWzL`Ll9ub#`2aL$Q-g=q^7ny#2?ChR-TO20ykv1uMriNF zRoC16RpzSjf!0>Wyd>OQx$aX5^y;-;t#K0cSBNj-ypY+-5gjwp(I^2$CB=(IzVbM|Izot5%Gt)~zZ4##Z1gZh&SGvJ0>~GeSab~J z9ZFQ=BDOMkS(+MV*{B^42_{x#sP+7d*@9XAMpfTDR`t?ZyLz(Nc{<Z!UCjDl?$_3JVr3f|Za7hana;JQxOqA>Rr}7__`Uwo^qNCy}fTe&hLQR+XW* zp$jC$Qi8g${glyjke7Ev-x#SEeffg=Tvs>E+xPC@xod{}yrYnHlFGMe#5(H;{5B`$ zbe%6A4S8#5vDm@l1NtOv1efn9m=D}j-Ny~%*XxZAUTHJIT4Bojj1Uh(8*x`N&G-H^Xx?Rv%MR}xIcig2yaaQ{iHXQAFlVX2Jvai5FI-NM!l z(w!V_|9VS)=z3QO4<`OD^^ho6Y^Y_GAV((#*Mn09yp+X3fP|P-|J1M*Amg-&9kj9} z>9ZA3GNt7h-pV?&9MA0EGi>lr6Ce;d0LXa_0s%6QPrAFiyN{Hp0FxjoKDV&&SXe1i6DlM#RUS9i|NDgW7C9o(c$i4q+ zGE`Kr^syexU83f1N4x`N5)>v@>9J&9{evEZx>G2H2kF<>*6SRTvzfAh&OHdEN5Mt(Nv+^CiV(;^jWRNH*xUiioOe6F11Qy77x)^Hx(E?$a@ zQ4vKyB4Ss$j!LbwPjIYU@ATBPtSnZnENR%wjzSh{LUCn-JUBvkpA?2@0L^L^IdX8Tq8=( zO52Eujdo7p{9PZu^3lyq192*MCUStosnD0NpYvK=6=8b)N2FwK*qDqDwE)SMy6d+; zeKs5B4LbwdNs4Bx%=PQ-nHpcl*pOCQU4W~=;%i{eSLThrL7#zF>*$ak%p$2l{3;(# zm>f)lvAOv(mbL2JrVN7XQ4||<_DE?JH7%?vQnNXp4LYfFw7Y~u5xZgom?0F@j(&kx zRwPL-rhbLXt6q}7+HgraIxUugmG};vb*0Pv)}z6R6`=alZ2Y+iRT!~aYoycrX)@X^kE8L>|!@)^r6G&e{8XDi-Rj}Owp)n zGGr=9{r48oS1Y2&9Q^~YHvaW_q!-GVc8purOcCq;F84-e=OA2dx%dt~|Ix5E1vy-! zLMH2eKH9G_Az>V769bhsv}S7-nmBG|V zpCL5rch(mEs4_|hh4ys?4ee-UbJg^ZK4I|;KH=`%5kTE@2{hB~i?Y&l*4Lo!@+3Lxnv#Ih~ z?)B*3O-O6!Ym|g{{>WeXJ7M3Ts;X+=;Om%VY5}rHj$yOTz-5~{xOwOO)yaB|!H9E{ zzOJqz2a(<4t2ntjyUEY-@$nx%d>9%Uy1l)fELB%_N!GMEhB2duhlC|wEuAx`uXv@D zuLZjvzg$^p#Lo+fiboEibuP2$dokUtG9RyyeT<_Z08u0a?jfY0N8;G$mbK-Rarcex8rrzj26j%D;SRe)n4jM6|B6 zwcN+pSn%s-;Y&zFWMph??Ah5_WMm}xTRl(0=jNa(wh5tn-ceFga?R{DMZch+pkfAU z7VoYja~6xMc$`mlhUjAXuAj92eBL%|)Ssd6a#TNe1lm77ln;5WOrA#$Z0_#b$M$}& ztx$q4)Z3*P!Lgno0(&qqF(t*j^b&ZT-qx*Hlx_1>ZDCOAGCq@00X23y>g4LRL_#2vGb?vyDfqzKM*b2nJ z!bUJaDR4%)g>i61qTj4$i?9*}n^TA{ygmCD!us=pO>!F({bEx_nL;I~SkS#ha9^KX z>7>v3t}XYJz|o{+ z`iMOgTdf>S@BiN{0EFo7@P1gId(V4$cNzxlo|v3OvUqpgm(J;h5{kru9*=I)@)v7t zPlooup{kweA(f)^S>$vu+E1jKcbRc=P&Hi0?{@~JIhJ0&AY<3p_c~Y*+(ef7oDdSW zkxlAlO@4a%QLb37xDz$#jn&ep7scbYe1?##yTF=~FJBa(T8iuLATSt79-5~pL0hi3 zau8mv#J|Hjj95nrCLt!T$I#;;)Ih?JL!|#nLxEw;L6kD6V{D9mjM0r0B8T)S1E=h9 zu_ArUdX?ClBD?K-yjTfx2y{Y%$8ESE7~RLUldk~A%F4=GTa9;NV-)CGq>Od1UdSkX z>b0M?#~jjno>Gc^jfnD+3Make>P%u4luwtJCGS^USG?Eb6d1lwyB_4*J}toBMV8~i zB83uJe;|ZBk0YTL_c`4d7*G({6(spNH>aUx`LwGR5t4?Mq=2D;@Jm$fR(=>lf|<1$^UG0`$uky*c;R=#$9^auQoQu0S0L3f@GM(eVs=0Uqt ztgSN>dUO6B`;H7It3xbK<@4d6UMj zZ`Fj<6^>5q+_J+|I$1_Kah!4WmfBwrfBZRSKq*ztc-1=z93;AC|LfDwsyUz^B|`B| zLs@Lq#a@w_7|OEm#eOJw9Cw~5I6e}5^x zmUty392<;UTU!I9@`2Q>v%v&r>s6Ui#`gZmlLS!f=TR{=&HXD1sG@9gN62yR-SMv% zWr>M)iuYp?i5!;p!lNB^%SIYJnlTU!yD7Qin!5Kr+vGPd05&S%Z_Vbi}qA74Km>!0Gy+YIt~;MN^0$3Y4fR&OWW`W_|IzZ>%H7p$tI zd~(NI%JcX4!H5X^yvSAQKbJQ}nh>$h)rX5k7bFYa@}tpM6zY^?aU z`xYbkmX8zx8bXv@F)_Cp#a%T7C;HXG;vymCzQowm&=+M#k%^?4$L3hH^R~&N2PwnD zW3#q@A!PJSpF* zVf7mqPuY{iRVXpu*I$jHJb9t;G4dUl&xj-pCyR^NYD$?00TyCWW3cb(r>>r`Hkj!t zlmq|r%ALpL5xvmGv@?-WT>&CRQ9%L8bNvis zxSD639&E<`+5iJ0zIO=x@^r>{t;jNLzqX;K4J$!LRy>^CaR-(6Zx%l-crY+Ac`;J*^Q&g}KqMI6T=VGw z>{mJ&jkyP@H*yLLlp3xL>|EVGdyIC!-_2R@0ESFcg6hFYBS2J^%2$VK8N&4%j3}`p zdr6m#;2^Vl7ShG@aq*yW@qnJ59&j*N`~2U`%naPP3Gqu+mHAgUs1g+KNnv$04rI9Y za>ehcD)1b3bJ(g*W^Jr1C^q*Dl9->*O_izg=1iif<%|1m$A`=56&?26&r!%{HQ%ze z<+edx#g_^)C8NXG%XZj?3TU5@-OhpMt1X0AuhkjCr*|Ly|!2LxvTt0 zF;GrAU((=c2=J1|y$S7i6j}rn)?fr*J(Bi5F7QX8qeYJmVYnp4hyZ0o1CFh;YY_M| zIE~Zu^H*nQ^|iFL%*`J_`Lc#%nCE01iW2&I^0TVt;&`p~Fqc`|A9pc!HZ~nLa5TGr z{_v2+AtNJ;DOd?Qz^Sv)>BGxJ#w){D@t}E!gu8LU*LRBzcb>#X%&-Fftem0O#c%?QCi@9gVdz8 zVYZo`&n4RVgbd`vK7|90LhMQ7A0n6 zcx?x2_IIXMX`bwx!*8l0bd=WoaIrgz-K!^1JUA(?LB39OVHRForZs)IP)Tiqx8ymlp- zqT^i6y7VNf*-ajyFhu3GCPc{nqQA9ub61T?a{*aS5w8wqe%!dW6jxYZpl`O0p58zI z4t+Bp~670Ma4Z-_bS>laB67hJ8-rKkAI8%5@h8rinnhPV?>%6MNv9hVhQ>_NtA zhjp<`XjPOMs+0NQJqWVmUTP9TBp9);6VsZfcn8r47-B=(pe#73Z9r&Dl&vK(pvpKn zz~&Zd@%UffV~zhY$baSKbqU1O*F^K)R(CR&+kSj69Uy=QKZqvb8bMRiKOq)b&!?P8NV6@gpzFw8$3c@WooShSI zvw(BmO+j#S(+Wfx&uIY1dJS_nfmUocIG8t08^R!vt-1|!f*t~DWVf}obq1GdvbiqK zY>vINGZo3Z1@xTeYGyJd?&lCoi6Y)V9~&24I!#Ted8DN~>+5y)5$zlu37-50wR-(Z z6T=qwG9{={t0#QgUef=H2Xd0XEU$V73l(1)ZPGTmF+}RQJI{b9?ny9DQnNt0ZlzN!pYxZ5Qx}lZ%VA z$8PE=87+Douuhf^*C(Zg1{F|d%=ByEJMI{V|n zR8d4bp<7SbQqqp#w6uFt0#gQ9I)Mon(AF9Qz3t5}tp0m%#T z@ceT7`gn4(JF?Mxwz#z#pu&+2rJ|*iC43sJ6Rnseko87M@h!b&y$PksX>~OzV&I$I z1u~Y&kaMzDJ-Jik+e@=a-;niE_88~>gP|hL)1SV(-RgstDxs@K;Pn&$y?l=mNrke#=iDB!!Og?ob6)#cKgC-{wxv5xZxo`qg{`3Jw1G$ zMYQkoQ8Bv?l@>T1LoswBkDj`4k@}GPv_~JEs+Hb>b76kD>~=+Q3#f{$;q?;=k$2Ax zvkNYh%yzD1{>Y4dV8|t%Y-rr-hFq8jsF{ge{~d|$Iixfu=mNEZ3=aHg_6_FRdB?A~ zVf@v$50P&L(ePxn1nd4GY*Q~b;H2>m?NEK(rTMH#0E zCg?go9b@b}&zZgTtoQSCIE~@H@%0jRd|C~2%0HEoiNXN;cWotaY-$njnY%LU?l(52 zlqMBnOMgS;x>i-(prR08{FyU(+2&_jZfYi-U#@&Aaj>b=jc3CF{(2Zra+Ey-L+RDt z?UfYIf??5eiWa}VWlXh(Cs;5Adpb9{$UJOu5PDUHI!FX;ZruU3IWf=Oa`#^9CClH% zCvL{2n89Vs1k%*`0{GLi8y8{;`_)Y8Lnwah7%GI zXE7yql0mYNv2fAro3l6*7k5XZJB$d6c`+v)O4_fHAz?URiic|PAN4vH5~Sl}K1(br zEf{(k@Xvn17?C(4FNi182g>}A4!65|W?0@+$$!rj5kMKygll#R`{eJ1jdINibO=nJ z5^$!noUx{vOAb;HFodbtAe_CyJsjkPPrE8Sf?!_tq@c-Tf#S$@K$+)c&O}sp6uc!g zvEt(hvL8YnH1 zXUogfW)_{%BSF11NNKac*cgt?Km}-VaHP+z=hg>_7c&If$kbATTYk@S78;j05BgAH zIDG72KR7Zr;SmqX9O)OlnrjTnVs)Vi^zo3qQITIG)H-rtuq!dqgnx7DBzl1VjnFl( zXi%;>uS-&*qr9pyLoD=h2xB90i}|p+iKPlx1_C?|(IT>)(Jn>-V8gF^jmUaO$3}F* z3zrMZ#c9t2UiWB&wo~=8e6u5YOfRvqet)Z3o<#uFS_Oj^&17HQH<9huRcBGPsfn^6 z6}PG(WY_=OF$c5#rM2II1u;f|B=n7yw3qi(;|h!~CrPVN2|+HrD4qVzO;GzXn;?m# zL4%$RDn6o&@Q~YGQmkFR@oy9{c1KuyFrQ=N@93-XFa7V#H2IJ=t5S_Scx2UYzE>J5 z4q#|dg9>uW6fG+4S?K?r-y{+3dTOT@mPN)^x@YW^@4$f)0Jw+< z8MpEKzlb6y>l0UF8vRJ{lCF0Vb;GQYE|3k>l&4-BMGf& z1gJF7_+YnLzW2C3Wxx_CSzpFnJfZr{zv3-x6~D$jMWEC&FHUP12h4eHf(FGL6WD+9 zbNA5Jx1H>H?)>=S!SZyYOVQQ0D>luEtE8s@Acuqoyq-^KML&S039iE~NO6dj=3l#r z?sPQvU$>mP@oCQnntjs!5C7dk&omeIBx--O=on^WO_cb`xIF^^2}?8tv+P#R!0QHm zz$V^%xVy8&4y--z{P##bwK{Ie_A9vR4J_kQ z_`9Ij6L-$Mv1FlFGQ2K*?a^&6ax*pD9$T?V{OkG33XOnwNQc(5E^t^O3z7>PH_K{m zvn>P?ewg|5xc+i0Zi00fiDpo5QKtkEM%RtYk-&2+1YpY&FI;v38tB66or!YMf3;NE z7%;(b!Q|ipYkgC7hMJ6=z;gb}RksDri|F&ps+yl$q9f=AD154aMUS*ad8u3WDwRZn zuBAMuAavre;g9#v`^iEb;N_6AIqCZw;0*DpCmnU=<0Y|H8eMrgDvZ z`}FdQv}B)kH`T@q#=++T_OVu9NF`JyR@FOhuNe4Oj6L+5jr-$%s*3$}s5%?i54B28 zc)`<(;Ai#N8Qf=DZLTVUF;8xU7WRugZHVVVOC%eqV|tU>Qk*QiORr-OYVEkz#VzGJesCKl#I&H z=wyPX6ms8p3jbWo+7kagQxF2fs-iL6KRrR8&tsAgU6v7dEb8MdG*V)8U5^C6NXs0_R%x* z`n@_0U&G&%)Y=#+h|K>FJ$%ZVnn|^`RKTH|x>x8b!D9eI2tLHV$-ZN;Isvp_6Ves_ zzp?25ja^Jff7Gm7%-L*vy=6Yff}bbj5_x_?&cXz4UHD%!=Zv!}rjH~~ zOiy$w;-k*+dpQ)X(R*20_15SZGQdbPhrMNt3IQR&+c;BemxVpGiEb86}gnO77QHMLePlBQYFG;A%5i*(joGcwGq62>+w65?U_6F588DGp9TSe5E-;z zZwI-K!sKNFM^r3P2h~5EP%^N(pW`RG1sd5? z*fHPsF#sZhb(MA&`0c&AJt0~)ET=%^gtw@mX5k4sCG{#N(Yaavc0_R<^3jS8(&=0)>#m;f z^*TxuBBSAn7_V{<7}#0Umz{#@O*@dIEb-Z*{Ug2>MElaM3*}8T?G~oHeRym|J`vi*GCplHI{{MJ>S*$4sm8qTj_%m%@?3wmDzCn zk78~ZhK{}obOQyY?Ff}shzIO9AGtWlDn$3`c#vyV-n5o5aiPM>F}IQVq^&6N>-TKB zp(wnU4yRmyFXYpXq&e%AX$I*4+HbB$IT!-QxOJJ_p$f^LbwWyX8UF`;UylbJ zW@*(Wc~gOLowJhb7pRIr{SNxZP(}3wOvz3-@1kLe^fYMoc#!vo-kHh=c^|#lgtL}T zeeAYd`86K~G&mL2m|I{-$wfyLo z(YLIwh4A`J|5P4YQScm(Rg*xah79^09v}bz|9y$gqV@}P4BOx-jpP^Quqmt1o@12ZwX zJf9Sw9qjg}ydBIEyrM?SlmMR5n_)Pj00iO$0nCG~T8)TZLbp!0f5)#Lf-tswk$lJk z(8pAh<&qWqtf8&|U8I1)t%QwBIejcfbaw3oYy{#^4LaY zxkgRZ_2L%uB*9yaCeTJ-*>WKdYJoeC{mNzN1gflhHxZa(e(V~zZo zApui4>3%P{k?nXFkF#Fz@iBHFN>@ngch()J7%6fYA|!A@q>r6KLjmr`ESctK&r2B_ zAo;C|K72s19;YY{@FY(EOKEu@bpGFv2hs5Hw}!HKStf>IKr#QLrDWA)tW>4gj|XKtk0_@Jl=L!8HFDp?~B!3%R5-BNoCi1Mr)-sB`-siyDBLCSpm0~AsL8gY`rBq zZpHCe=ruUWi(tyHX!7s?x`0A!_Xw-$k|CEs%_GLCct*T{?0Zuk{QohC;!2o-zo`+OGC$^-;FV5&ewLdXuYPmz1lt-EJUYT za>!ZAAX{sk9WUIkqI-;{R*80!svz(&!=I|`@Yb`(Zgq{Iq~QWLzv3PwTT+X+e->s% z113Ej)6%PM6JVp$KRvU)ZsW$aYas)I=tO=GJhyqme4is|z$ zt%dU3#CZT|!;d{15K!D%wLXdiWttvN#gbEGS~$*2g-1t^{c#v^06<_l8%08^CHyQ7 zg~_S~T=iOQ_ew3O2(@{cuE^6hI%}rm{P(ye`{;7p34n&(PN4d1&yDPN%Nmwgg^R}= z#Huo%iB(S!Py*|UBI=`hCmmQnVTr|acR6Tmw|yxy{ff*zr(Wi#6z*?p0nzNpSUC@##xY&kRcf3SliSXfh&p0IQU4$3q@ZBaG7tji&k+gq z!?Z|+mf=Bq`iSv&tibOIAU}Bgy#UwbC(j^P%@5RlX`Szdq?-@d*JD0!gswLoS3HDw z{uv%po=hD=NeZ*V0yiZ%rB8id@cDQ>Zd=HC&fs3@da|RGx}BoRD+(Ry!C}4=@d}pL zne1t&x?JvqLGZXcO@ zN?T3ti*~R7Tk*P%-SEOqz5(Pmb5#_$4kdxK`RuD^LhvsLj~2ha-%e4NGIV4^fe1qk zIxKwt4VHptG3bblqeJfQ?#!=;^qX^+I*c!M&Coo#_$jI+Ry=+9vwt|Vcl9_2fQmoA}&UMZ` zeA%&V%-Sh0mY1%SVQTnlfbNlx`$|D%^M5M?CIb_1C1RzS&4o58PxozrNj; ze)v17Ue$$ml6TL1(|MX!1xZxO>%w1qVYTP{%V1ji)`~gs^fV*?g23*tbZ1-Vo~`vX zCAZ6U7xlw$1Rvw9IRyHSGzHh}xoWuqx<`J?xiSd)w^NFbjxXDIh*IEVo#EYbAfErU z8aT$R&yyeYxbL4e9t&Mp*k3@Yd|c0Xn?OMK)-ZLI*+2R+{NJqesoA zxYg`4TJ1;1l?C>g-mni%oM4P~2zxIUPY&UgiMh3%iUhlum|kzy2yZ*9D$4NTJO&nm zIHMFEihE|~^U$FQ0v+GJzJSpYlPXZ7q5!^YXlJDSrZ@da!Eq`(YWKU@xkW39MA@IC zBVz0x)|fC38Q>|}I{Kxri4#kjr?JVf9#U%EE$j9HAIAWDF0E6B3}heR7UIE?M9*L-j&!nF+JpaO4QZ#GGR*NbrCd&CW-yj&=JB^Bb( zf@#9QIdKJJJ_DL@qqfA9exmUJD3Bggcn=4t{seXY#-DI16MmN~;wob(fL{L6P2&OP^@^ZxVZ&t$W^Gds_- z^O>EQGuUcJLm!`N-{aaWpQ?Bu^$!@UAmaWr>lxKFKsQOWZ2)EDsKeK%@Oeb=;gIM+DutlaYCrGYyE;Jz!k zWW`;241ib(JZyOO8r-GtbTtH5grWi!o(o-|!5Y6inBSYR1KAd>ed9t4XXuR=+?<{* zug3D8b~2HE8ShdIoHqetM=4JMI@kwdD^`iGnFw*7bzF{XHH*!a;0jXJY+dof;%Xfc zTUS0kL~Mtj=UW=(bs)i3OVE5xy_QYWe`jlI0 zIv=*f*N)_jbBa35rc%!*AAP^`VgiXScP2vBX>rGJ23c4d9n%q#PyS?VcKm2_H<)addIdxCZu^ycKam3T z>lsU+cg=z!1#nOFRfj1=$q7xB%=(`j{ER&*KZ>}`-$CzI6cn{Qf11y*ao#!aS`?nF zMis&1!Cn)TfaU|SKBG(19UbX!oM=}L(gRF@_e3Jf9%z=40&~l`*~2c))|Rg5%dgfi zS>>m&sXGlGi7PJnm=p-AXcakawFDp4A5R0pK+gGUF~4SlrNz-j@a|v$Y#$xZZZcH} z-WLt0biX{|g&sJ*8nA_?WUysezCqfT1*z3+gft4_SUktjha4V1aI0abN?UJ{rZM>A zTr!4zj-aLE|2M{S6RUtdDdSNEUEVj!)(3mq>raSn&I0gQGTd9TUVEu6zX=X1u5(GOhkM+|U(C?&HSM_bf0~;e_&`!z__JUubqpOKT=c2>fhM1M;6q$glRWu7sIQs1Jtzcs>@H;Nx}=}%MoHlYwhZ*b@blC;*`3bB3H9Td&e$bUKgJ5-Y8Ui)mC z*skp9jUw7EMj$Gj`TmpBu7nDOGjH5i$QrTR`HBj=l*Jq|&DB{$t7{H}{!NDQuE;9+N3-?<2wKg%IzlC1$oyl(?-A4GT&TlwO^UN_KN~RCvn~I2U z8|iz5<1pRJn{G zkRjYHn8FC8W6K*z8nSw$2-hD{U+_)y>S0Bd-Xx2m&#A`@ahe}Uh_ao*l#=a%ID})e z@uw^6rPoWKYf?PtT#3!5m4m=T?)eNS@hZGgrN}EgS$<*m2d|>+&pJ2Y4p)rlVXSn) zT&%t;*u&TF-_bSvOov{Ewr$feCKR(Gv<5RduJC89&x9h7mU5Tqfr0+lTGY0%Nu%PB zpU)#uFID)c(~J%vg->a2u?|CArDvszV+$&Cc!Ad%Q^FJ2ATXp8e| zU!%0%2DDvGjy?|=B{yu1hZK$kXr{rbU8v>>udYmgR6Qb8zGM?sOVP7Kz4p<+-qW-q#)6N_$`8z$4E*)2Jn=ih{RO)-pP<_?+Z3J zP8F8w$2UoLK$LvPCN(bcjq{6-jzmochF&VW>FLv0^SZtmr^+9kVfA&WKwJ;XO`6gI z67hQge&-;~P~=ck_^NGG_iXa7k%?pf1OJ_|Rao8Z=co2sjWxV3y+3rzvhM z>7Zj-O}zP~U#$=)Ww=wgUwk!FD|HODJ}<~)!=SGnil1umF?oPP`=AHdd*p6#hb({To%<*~cVnUN`kK=X*`RCx`$3;F;=qZOWDkko*5`XGRz&|gn zCn&#$9~dA5f^YeTCqbgrAE|IP@ptxrDBI``6jgK|PK&f_>brNNzn-bpyTgyt+a>yD zr33dorxC4x$8!CfsLwe+lP0!|^ltNjZKS>AGR{UsMMVlzr%DS5g6hLS z$01K#IXI)4;7Pci^%P%-!xLr+BE{baeR>5@TH@uZNXXhJg7rQmA8*Zk*Ff?DyaIhA zAUby7)-|P#i70T&yG9+sF=H5!&%kfZQ2LhtX=~8=xbM=$0qS8s4a$SAP?(8ZWp$vY zmR3apamrLx`(q#b5QD0jpw9;aD%tviCF&t00nxQHfJD$Pgt~U47Cx9;2zne+X^9WG z>7Vg|T(=v(x6=y|PkD!Rq^`21Zy`Zny_sZbDI_nXZ}%&QiOZ##`#dJZxH+|G~jx0m6WTg ze?ZR>>Irg!W|(V0XXetS2oxqBx?dYAE*L>IH0XLljC@4d>3=*BMwsk^>9V93DA+$?R5YfMIkBj|~XI_)Oj?3}SANB}tzx$qodME`(#No*u0o;zq{XCVD zK@`_?dbe7?Z{R`7tGl-ZIaJ}-48JTgLcwWP;A z@x8>Y{7V_;9NHSNJF0I{HUCh+mm@Vb)u9*y!8b0M6?`l*H8O0s>)PC0^QBmc;@9{R z3pqAp<4EHjSuE+Fqs{!h!xMzPb(4cp-h>wnTbnm+XDE2OZM~CP`zvl`jmF$E2en9Qyb-G8m$^J4U|g|D+HUSJ>51Bpb-E32V+v0Jof%#B z#EEk~NkHeSacGvF-!vEMXazex?E@Ws*7Bai5k`d2V@(mw5`sB9Y#bKYZ!E`-Q0&oH z{r!W-SR;Ky^Ui%d?FiizHehw?7h&MFUT<~kDjrx zD#B`$X505Gv8gyQHFUvpZ1QfN5`Py&YdYJ(u^q?-eF~=wyr4lT8+_QNcfdzniI2&f z90{FCMy$6KD)(MwP9AhU;23{l4XHSdn8!-4EVPomkYa+ zo_eE@&J5G*SEU_#Ry&>Sh+#0P(qt%j;CLWk&LpJ>ikCn4`4Ul>7&g1#X z+R2py6=`Xy<4U$6UCX=n^;(R`~E}iDaQ2$F<-+UE_xgZN#w*2}^PwwSpM`Xia#@b(Uwt=e zMc(|STe+SmyOW2t!-qX!ZNyLDVR{MR>t`L}of;Y%o;yxBZPCv)StUk^JOo8juXNF- zJMk0?a|GOsU07Oryt#OD$-ifFEjrircY~H`*m~m)t)-us zh&)BL)-s?|%`J!TY^XSXjV#>`&87u7fwiFMhuw`9uYy?8-A?+ZZvmWCQu%G=7TD@g z%Ykk8X{i8Fv4OrY@(z`9B{Z|URK_(OBUNTj_kmN(T|o6{Vl8EsMM%hq>z4PluS(5z zo3`Ap`a1_l%040U7W_*+*Rug~Uky=+)3KeXRqa7CP8L(xXeVJ{{iP~mR0C*PtTs%& z7Cz8|SN=lTT7KTRCa|;T7+Y+x<^x%XcegAp>#&?P;d?qg_XfxKPC{@F?1RBo5Wj8= z*prW4_Z#m#eOd%-C}pgTCws5Ic?dES1i)2rB49oRcf%>eGGIT?9+pEh(L0M7q$;FW zBHIAN$?Ot-n`a|YMcG;VX&9bZ8b9#JvETD}oC{5Ctr1g}U2jgJg%2MX>f34=uZOf0 z5^sHZDZKp2ud3TayguRe>z>kqL}RTa{#vWmNl4=Awu$4`HjC0L8EAvRufyVq{SpQ^ zbU8)L?#F)I<)ardA1_YqD_l%|zkj3$b;`|j8aR9)zvJflAbVHa*luYGy}Q@@+u{)S zT+EDtcYh7%X9ijLzR>z2iXxF;XGZNQSI_PzwRI+uZ+(_3;?F8d5K@CeXvI2|3x3zFpK5mVR!8 z{o3>OTR*4y;qYw^{MoL}BVoZ|lhHkwA0_>gGgpBNpcrUjGH1fc#mU+G{K4`M%=7&v z)Y4vN&Ydg@&-w-R5RlLV>uGfM-6tUh-6|}Y=09u!K-96gdd+6B)k(?p!`VMv#Xj=$ z=P#(mK`khO0$|QB<>kn)h1JzQz0=GMPB9Qm`k6~AZrZxyGBSQ?(xr7N_~>2~BO$yc6@>4F;>OV))8c{O@GU595c_;c@&F9Ujw-e*5XbfTyYFc9KqWZY?ommaaskTL_%dc}fj*VWrccOb|Qc(fXX0MLiDoGcDGMN?C>ytC0kn z@4CFzg7R{5ZCV(W*YT#Ndq|HH4PUz;9L_@Q^~Yob9>KRFf9gyxpxCdU<&Sdm+pdZ+ zZ}N{$L=w5-oAoNc;M~r!49;8;>+|FN!?aQRG4Di}nS*Ac&%P7E*!}S+0`(Qi>vBS_ zle$_bUSSNL%*>y?*zVzyJWP zOwo@J@=MazU7vDS%SXm^G3ITb5>|(WZZHe$I12T0DO+o8rIl9Q;Cywfihdw?J<%3EzFL%Sju-IK`^dlIg?*%g%m7IMo0b}^6@@SdF!PH)dSK7cG}IL;c`aNqdQd>VLXL$HdPx2;r0 z{g0VeQwK7rveaw+&L0hEj@9`fkOEV&gfw_^sd#@-aj`trU2Hn4%1OmOiAPfSD{I%=C zx*5^q&q|ub2BQ70?50ZDqE<69cdZ=%XqPM87a-ajbJYqrOjLvg+cVo|Z%8OO)Y$oG z8)+8CLO3%nQhLsgvH|b_G-GI|X}4fPUOoE|kZO!}pe;E&5^=IXK>)~z zGuT-6C0i|z?hx(OOER+0(*CT#{{m>eps2?#G5Kgo`c)k7NKR3lU75m-6e!p_=qSLD ziki+!w1^TEF6TlI$_Ir0qZYX>T|K=VkwB_+HP!zojRxia5b(dhl50hbPrJKIG~ZV9 zlK2POkr%(_E#$Tr1>E?T5z9T<-r30!slT8R8P|!Vn{oLU1^jO&KguXAExlt23gFiP zfplqEK;bO^%&Kv2Rv^OBd&Thyg(N?|=OjHr)7u znc1>5g@<|)h&7?|j2B?kf6?~WK>odoMAQ?#{}co0cUVo$F8E(N0anpc`cI))dr{S6 zLqoG}Agjp#e|!IT^MALIBzd`R!Q3hs2^iwP7sa&wW#1Wt|JG54&6K!8ZEdZRUbx-` kVGKl2JNe9i3U&lufz@BQ)`kX(fI*`=6-QAZ)y1Tnu3F+?cll9DcIf&cJ+>%VI$uEV)I zX3sqHOl+f6m1W)_6Cwiu@J3EnQXK%G@c{s89T6IQqTRde3jRQHlGOu$;$Xi1fw~IA z!vO$tKu%Ij)9b_Wny;Ior9aQZM$eDDN7>@XpB=ihBkAVjEyq9We~V($aJ8#J$IX4C z2om>R&ETdyD#af0UgAH|=PYEMhTok|PL~#iL11f=L+O8KoWtvEI$ZD9Y92?eKswqn zWyRUrZD}+~meADPER&JMNjPB@kUvQ2nEuc8 zR`aMGbkN1cMOT*~z($}H?j8QHKX`HD%WBm5#WBuxa}vg*)BoGa4pQ$jCgc*%|0Kf0e2o&CJ3K z69bTd%(luHEu4JHfBgtoL&I@0306c@&CTdYwg&7=lE%=$&GE`WLu?VmM!<6O?Xif{ z!C2|GBWZ^Davy=khel~b7QA+RGO~PsI;q7SONvnA!~*ZAch23<|8{)4%>?DO+4bU-fs6BCVB9kYb2>!@8Eyl{PND<#!qocX4Gw^ z*GcRXw5Xce%;xmwO~;86nO)VYI)XJ@gVa!SQPLlqK;Iuo8fI$v)K(Zr%^JT6iRYWA zlSWFP9v33P-Sc$cKg!zIv`BSpE48g@(JB8i;7}!Jq8Y2laF0-m z1y|~Se|5ww##z)wCgMZ&kxW4q8AMWvIGG&83!+uv#niT3(ZM;8OJo|o^|_Lk9zsFc zcuo;fqkiYI%MJuBi6a`CVk)yZK!7tvQ*s;g~C;J&R0iDAmw0}EvT0lxlO8=Z=N-$GH z6g3_I{9~SiwdJnP#oYVFCu_Vvob3l)EBPWCxZNY2ZZ4(frqfO%XNoWVQleSE^5vmS zvtO*{J9waBiBK#N?;Ful7t*&c+AQjT#cPqEF!^x~j+7IFR@*ZR%9!N_$0=c;0CHIS zuV??DQ#Ph=PX>-k(@!oIg;^wS!%s7Akkxo; z^zUlhgYfVif$Ybp=H95={clOEj$07R&- z7OoVcB_=$}O0%B(&zBKv?SU_!Pj~4#`1mRv_0QCoNkB1}50E11$1gk&GN*m~eYkg1 zg+&Ju1A=DB{5DpWP=J<6BEZ-|1i=CYu)FWSb$xl}3moS#s}s<-WRpsN<4bMDHv%kG z<@w>nNsbyaPF;Bz%hL*9VuiG!q4yBm>^ zHcir0D`cay(rwVqO)6A$k_v9T0C$rze4}0?*-eeY-TjS|DkD9c?6ka82!_8#1Xgv` z@7CBv`;!hAgWCRncRe{_U*l+MIPlCXV@WqD-MW!mIt?CGN%lhQYLXj1Y!zrXfPhIY z8%Z`&iu>lrt0kqa+}jMNIWEZ6;!l8*ZacXw&(o&;zlY}AO-KobZTIAau>tSaUg zn>Fk_qqO`R;shB1)`q8Jy|o{FQHdaeaf`b-7x_p2t=}uZv4B-fqW<#2$x`xRYswssS_q~H#Jss?{Y+>X$(I^p&3+o0 z;wC?jNskb4iIrKKX)5R=`7Q^iIO+H!LXfI=IJXq&G}$v)s?nCJ?{ayLfVVa@Bsa3E zv(&8)(LT6?RaN}XA&POYXSWcAb^qav5l#5+&*|Dz{u2{Ul;RwpzzGb zzC*E`?0JN5lXm!da}qazdlHX>li47z4v0h(f?}RZ__r03nG1r@%n%ZcwH&9VY=r?Y=niNpU<-hJn3sAjEKO%-ll5f~~>r{&5E{Req zT1(~mgJ)>Y&;PxU(p(X>3w&*HqeS{{Q3&N?pSG5^`>oqP-&Ga2R`@rH#!=!-RId&p z?HKn)Usqnt7CrkDyw$U=?aBVa{-SS1u6UF6sGaQ=uAIa)Fxrm2?&_HLp=iQ_UXM2s zai!%d`SeUoO!V~LXWh3zL3K4FVO$4SXUyg0C3LVT6D~}U6(_@Z!;BR%DJdxl3C*_7 zj8$q81VER%n6K1W=BSVY4{k@{6u`qR)TgoT>^C=cp`;x;*7l{wY!BGx2e5H)7c`d) z+x$$t+<1qR=GNvW*zJ_uC+=hRy@SgkHabtWzdjp^p~p%Wd-ko)EQ`%?!hsW5u8R~y z#w>344E$St9BiEST!f1ndU6u zBFQj}F#rJMt1i=F6F2Y`KE0?S`FC>VF!oRToBE4)QfkuDmckp4j<+eEjoCHYF$*Ui zyuZYCxe&{^rJ`nPwG~l9t$E z8FjTrNCUdkT%jxkGplN6ae1Ng2}0K$r^+iy8u6`AmJ_-$Lz$j!fsdTVFQmVK9C524 zpQG=m?28+N9OoNilw@l5A6@y8^}0Xo^6m#m?6_0>8?dDomX=^deSLk?e^gIdulMqX zX+s1FS_GD^Dl{>Ne=Y8M#NlAVLSf^R5WxZ2Wy}^a+_Kbq(3u@50C!GY!X+`!?T^ps zI9_>Z@S)q=+x<~n#GO&wWx@{-09h0Yeefr=7$zd@D?PNpAF|>E%?kKg|1pvrajEuw z&h_zeC=uoi!&t$$KF}ZB8wHy0F8AIOy=3Im2&_IC1%PCUJd>GsBadB87#Vn$dx2kq zuU@d>&at(%xw^V+o{AbY6`azsuVT;n!59B|C0l=y%@Z{-O+Pd=)S-3NqHz}o`^>&; z%4VFVQu5g-y|Amx^lZI*hsL9G&7oBT+nhV+#6w`%8C-cXwLQoPEE=_RbX1g;<&!lv zHB)nPRyQ_O@>D*2YhY@J2XZE)31ebnh=_<5SgoJ39_vU8OGZ+mYLQxfzci(48kd;X z=gMrHM~KtrbZ^h)FJFe9$q;%VC@4^1f{x?2qc=RAg1W?J__%)t<2a*rHYp(iAt5O= zAeTH+(pm(;V==0LRR2_Oq#2W8{m>3U3>h_}q>z-nufWF|y^%;5)=*bh*U`a?8Dx1c zxKBi6YK0gnQ3O%IoQ_Q@BVgB;n&Tv>!IY|R`tMU$H+6KKC*PSXJB;fzR z3Gn7l>N2(XKYCoN_<>gYMcelMdlDdQU<(8ysJ?@_avC}PjiWZunH}nHeR=$xgOnUo zg1G!!SX;lN|L9Gg4}!;OK}gDO`379juin5(zyJKVhrBuyHuC!(?&`M_=OgFmBW&&3 z*t-@RN+)YpoIVF*G%n2JE|1|ivQ}j(g1oOEM8J=e@_W$7&7G*?XlP_}PNzk1l_@X; z=6b^Jhp7(?X-wlwmKn##fBsAhQ~wJH{5S3|yuq+Qs)WVc6t2Bgg$u9E+$kB!A~n+T z{pb5QvojMgcq_pZ*S1dz{RI_7+>_HX(uSPv_*gh&*0PTcWm~Q*U^&TQ;HvB49$1=g ze*b$g=3&ttHWapoU-(=3$*2w=DH;+QmlV9b!khB--~*Rl{lnms6<2vxAN?lw;u*8O zSPP$Lq#J5=Y;%7!dypV#>e`flf8{gU!=F2)-CPWe$lY6I%VB|7kOsxLJI>_tC?t=C zs^cnSq#EK=LvYkN`kFOCMb9$UVFfk~#rnU{L4n*96$kf_u*Sc;1IA~+>G)l1DLX!@ zK+DNbtzLydDjHs@R>!Fx&}ZRWSeQteh?#(_8pf6!&7M1Fx#8b(1C88(W6SlMP}ovg z!naN!Ure6uJ%k&LxLct(tUm!gpeoTqL;pcRMF9jiCb!q^12`tN8voTZLGMPd%6#5NkFT3eLXN!eio?I}atyn?E=;&6z|WJL z+-m{PvtLR!VIauO#+CB%@d+Gx9vT%>Ac|8Hlak=07tQp2mmG+PS9dFEt7tQk8Hhg- zaB+2k0NKgyD&tn znnah7g6=KXjc9Xr4}s5LXn31XM-^Qpi8P;j|+i zh4IkB&CTh8jk8{#r>YkC)O4ot8Dlm<&XO>3PC#Z(hxK!YdAp598po1%^LADF zxQ3qE!B^)7YW*fuIhc4GiXPF*WTXVct(vyKa;tAvEwC}an@E0W?Beo zX@~3@Gp4ec_ikL-Iy1ZYf2PU%rGhK5`?x&OlVi63emE{(=#8(#^#-NEx@kTBJ#hjZ zGPH=W@+iB48o(A%&HDRl6xTJ6<4k{;D{mhz_^jQ#xoXz`U&fx7P}D9Bs<;-G^EF(F?DZd?5wp)fy4kJv=l)r(prdcc1G=b}!FX z16Oxf9tKb-IwdySzO`iZpQ4|(x0ZAo+-lQ*tk>mEwS%xQ(4vJF7PR28?;C3xn|`xm zn{H5qnJ(!_h0Fl;PT!5$GF!=?@pdh%2H#--Az~+;~QHc0}xdRvK2gK5+V{N zm!QQ5H1w2@n2IzAQfjm*ay28>5^D2bM1+@}RBc~l5KXFmeb$1nU(o>uhB8_TAK!ga zNf-Xyhq7hj_%QBbP_xWJs5g#i+8Y-3%YSHxZ&!3Y)O^Rw~%k;K$z@{05&U)SXO7!e9dygDy`QXt$Fq^he z+9wwos&5-Zc|C|O&zP2$=K0GR0f2=L=2_3wbIx%CpB!HAs`%S*jE4-m)E0ePT;Q7i zsq1%2ynQ9*ak8>7<7_n55Qstqb56N-h*Wq5BnG(@ zUpKTwHo6G5DA<_yk4xK+&w8JbuvM}8qjZ^u*kb3lV1WpekqpjLvT{gO$yc+<&vTft zCRTQz42L~8_lVDs;Uu2?pB}VR#eY(XSx@Ze=;JlXH?2_}Z9LnH1fBo>GNaG^|n z->;8oV@fMZe${$s2Xlpm2*->ntFaN_vk@`F!xP76iA;XadXRaPP`9#CRfJaUlQ%fA z5CFcSqRf4C<0zkH5T*S&YP?rOFJ9r_R-r~l-7$!#0k`iTU{574go+tvvGu_}&8X9% zgV649B+r4`X(qToJSs#K1_E#nsJbeR!yp#PR#i5JhqFXd6?6*W5@VSsDW*@ezyDy! z60r}7t&j*|er9ruF0#r_r?*eI@H*vwCO||alKEbdcX)5e!Gs*!iEH*wQ(YO zi6sFsY!GoM6cAzC`p1zf%wnLBIqdJ4i)(TIqhaB)pvxcCJdQxaKr#wW6nG?Yjj&l^=;(N( z!7+Sj;qQ?%WMpn2sInCgkpAE!=T9sCsgGQ2+2L~8av`l}s9FbwpFgM!s?V4cx^HLC zX4aw0hf7}#3i$RhVWJD40*pt|k*3&B&V#{WJqnUX!kGH81UF- z@{z?BRYXTeM?^$qXA_<*Yg;sW-=40m`1DB^J0C69bb6drRa9i28GZ;$2N_vub5atR zNKvmWZ5j!0tUv^GEgpWx9!%*qE|+P$7#6riPgpQAGv}TGX=Yozr;`F_KgP#7axCKq zs_N=I`E$FwyBnC!R$CLy!=qnwbMwH!z}ngx@LEP$dhhA(;qmbF+|bZ4GouDTn3;wAAKa)h zp@7i-uhw&Apg6P3Rs~j`)I{(BEBs3|cMnfO^N;@i{yI83fq^1GZ2a3_o*Pd|BZx|& zq`k-7RfsHLsMk+QGpu`CDv7yJv z0jR)8h-iS-C_8YeTtxmgJ53)qW*4-&bw-`q*tocZGm0iAUYQUOF^4if ztejUHL8($pedx4(3FKP8?@k~i{CT{GZ_&^-zp^&qBY1cP=EJxhe#zGI#jm!zmixq@ zOR2rr($dr8YaCY1dkY1qf(#MaZ(BHH91cJo$ey_Q{Q38RrDCCV^p`GmHy!{8LJQ}O zr&1|^jG5LeDk}cT2iXa>)X8e=*|%_%4(yp)d}*u7udgc#TG;x!>WZw=BS9Jf+jl?$ z05Upgfb2WxidCXT!QS%n@}?%Ym*=No(SnMKit1_wS1e$2rP&rVn&I>Fugi9Oyr;RI z>n3{X(8y+h^@9$t3rXnY zBzY2&i>=@un>q29bOlCzNZ9aWK$Cp*FN3-#?!`ZV38FDfJB3UmqC4S zxjXLAno|U6U9Abo1rLXZFwS$`d;em4ctQFR7E{RK$-MQ_3=>`*f<_9ayS2;X7W9(t##f7S>*ie1=$l;TDLMR|t z`1R+Hv3VAJ0TebMhb^oJeGJ_fvJO1BH093K#@CU#tM{*dcK5k$U@`=a|n525CyhWlytH5 zGGvhY9c{!t8_E|rrk#JTa>*d90V55;`(o%pMUrBPaKYw!%IW4VctBA!bbaQ?l}51| z6ACWM1lvWRp`YNn;M7%DEf_IEO3p&3!Sp;i07MR`X==`IY}7rPDe{-k>FMhJTwbmW za9Or%DJr6rQiDf8z`L8Hk7i(DX<0o9AxA|;rS^mgqY@F}@wCC)@8mjaNY7pF5f0tfjZdLL0{-BrIDR*+zg_oL*@#yC1|kd4 z2O5!#j11lfjt+5bsn^0GHa2gra>B4g2sJCK<7$ijhq{cS3eaG$!1OBg{TsgyZcP&t zimWmZUSduqnPN2%3BfcE=mbw#XBe5vw?@V}ra566pRfH(iQI|}w5yd|1KkPYXn}%? z@brN%g5v1%$f(KJU^RZlu0@vGlsjj5Xh`-6HDwfg5Dg;!|GfY)gMPyKOyl9<;nKxP zs9#_}M+qhbIF%yB3ys+j0p;?PeecF)V&riA2+$;oAZpm5{p15|V2I2#ekrKp;pY0e z-?W|~T3ju4K(#o_M^E>0nrLXyxJJy7%h=KUGy#Xn}VFbv+M<$NQ8`7HqN&Arlt9 zk0-5ENr+jAD`DE4IE{ZiwLN6hV5-6HG#pO&XGaOiJ|5%<7qZC7 z%tVBRrlFzPa{6h;{=Ua=*@|;-e_sO|4v5jd)1|@E((>cAdjn5LOIyNhAl>Q^_sLX_ za2|u6l@&}XgX9AS=-t@(`LiMrUfdQTl$sGSM07|!R+?(q`F10)*Js?K(fYOw2OB$a zCBz2hzSPUbMcp1La=?sx@W5?vZ!g(1g(kR+f@gTLzE36u`;!IL`Hb9RdU+4qg!_i4 z(QXu0Y7x*EuaH6O>*Mki03_;in>F(N3wT0N|1$=jL#-jjl0_pQ5w6~~A|8h50UEdj zE1BqTTj!l;J=MbV{?zo*v+L{176QVwa=^KoUOWW(yXl)`SU^or8+OZC4m#*9P`9+Y zyi6}C5qr!*7zDk1>LhO(TNqp>iZK9O!ABKALdYwMc{r6)YNw7ZOJ$de6C8LwVoMMK zFVAC$qa)o?EQA3LZsXzCe$QQ;Jh*ODpLB$yXxekk0p(kb0Cj4q9~DbeWg^vOk9hYI8yqxHCW2N7j9S3sNX8&EU4P>hR`}pDQ05NBetCV9BbC^7Yuav^3D==J>HN z5!4&Axpr5;seH+oi-X732HK#56 z{<+h&fg@DkS-zi(hNb29{gqJuo#fV^KTo|+_GiN)r+@EHMO1BMzCApum-?=6!{ec-E# zGVWV6G`pXwGpn7Q-MMZW5UF?4#Rj$Sw{_FYtU0Dut+LgzEqM+1Zec{1mm7OKZr8C8 z(6n!E;E!(#lQF+8$A$pF#^ZN7(!eKo88+U$90mA^2X6Z!5UWkB2m##)HH100XlZE& zJUj)|0ohq6lPw}N!ShP87v1jalfMl_~q6P1mVF(nb4BN z8*V6?;OMD|s*TK{3X=h-yu>u2q3_~jG8MU&>QW5&F$cOX5CXrR94{}+ej8PT{#zQ zoVd7zl#5d3&RliuP--OjP`z}b$A@)BhG>^x2wfilUTrlK%gk;tbaU$J@+;ox$5txz8WA}bWpaw?i{-HZz#_5_BsviZI8YYD?Tcw5)42!{uv_d zaba3Mcb~U90me~m>9RXX3K=2r14$1)aH1x9`pMW*%l;34n>#wb&dFH|50eF+G=KJ% z|5p|YmHzbOSRw}NZy}ohr!OhOes^D=N#%9GJou>OJ9xkj8bdsD!Xjp{=slmduI?WQ z(=iF@dZW3*eMA;anYP>#4BDN!_f-AIl_62RW!d-duZbM3hhKVZpMDkpvahS^4qj*n!BvnH6NRyP)DyH~=;#+;Z795)Gzr zXQ>Bwa+LmgL}rrKchX{y{B}8@^Wo~=+E%U?s(=%$txsdiD8ztC(BQy3gaT{eQ)(K0 zO$|l{3J{G(5~B5ojQZ&fhCUWPHR8l3n2Pkh*4moOkLTvhbX;>0y!w&-&&Nv41y(ZuB4|Z#6mbQ3gD!f zUO@)p({T|*H^cFWrv!`b=Y6YpP+6iVJ?c=0lf2ve#pMVq8w0 z1`_KYq|$e<`8nvCnhOo817j;Q$&IGOHO7z&**?+}lRp2yW|0k1= z49Xw;-f6zi4ZQoh5`wM|_LqwL#FyuDbMb7)B8nq@#tvIBQen!!aM5IZdoN;eE$9|N3w@9X*V_j%cBhKEWuU0qog>4v&XXXycQu>)Hr zVWqG=3vf-E8dzQzQlP7zHgvjY71tPXkZdSlJG|h{3-IX){e>Z}4-O6WV}0&zBTrK~ zuW}V5qs;jxR;rql6-uF0k+{J-I0|gEP*{qfdyTL@m{p9|RgZayySh>$#OVr=9;cFX zf^tap;MUPP$kEnlDx^qi&<6t&H(jh)RYLH*msyfd5jQKf5huW5%sXKp36SE0C{n}0 zSWVtaN;||mR2BEX*Di4Mcss(UKfj(p`}{(wqrQ1e?TG%JgNq4{f2uS1ID19oeT}0& z7pPZjBWWJ|l2#6&k~4M9z!us?(5Qo1C8wsQ?`Mv57^XIk!`Nb0P#{+MU;q6J)}H4y z&1>+CV5N}S*A^q-HGDfOyZvj*q~)Wd9~{=_TP-57!4&6fGu$*2cqH(EhU=C7ZlsM; z)t@@%^0`V!@ho6p7Cjq=!Q=*|kXUFebI?AxU*W5E8TF|W387efr!rv@{ zu?<@|xH*k0FHm_FpNO61icnNsDpivg@}B~ZdAOE+Iz?sF@bw)-2FiQx-ig1ix8c2C z^!M$R6->cKFz+1ZN^O;k*oBYSF0r$6SYLHg=8@tv(fy-xNkM9oNsrS7eeAVSP>7uV zH{)$m?eik`dk6yHKDmBC?!uz8h?@!7hYlj9r4Ew{}>`T)05K; z-xb<^%8`|Xrmq6Yb@qau+|OVBB-3u5d#6V~2+dptPgLu$f-PMN6hWX{M5`XIx8T-c$(~q-Tut@qDUnP;nt646PFvHj}K(J$dCpE)ko;8mrB5ehlhw6|9-sbN< z3~}4nq$Kvtsh7-uJGOFX_U)w>&jO!PbSJLXIEsU&mGM#(oAHH9&FqWV2maJ%fxnTrCD&LhYhYu4gAIL$ zIjRx5-_RJuk8tEL{24(zJmkJIi!O6NzF$7-Q;JHiO8@J-#(;f)A|$FHh{WSO7h_s7;3c=#!s z`5-+7~C``x5P`o^ZH?Uah(mBEgQM(vElC zy45`$E528IUwjcu|9cyf4X?M@N*j85x0*#%v!RpmlDtWQ64Kny;qfO>SBRriZvI$L z&Vszj0X**?Eti#c4U`JLvI6a@p>)$Lhdvc>oFpX8b1AY3!>c=5br`P-GtFOrOn}%x z$+$Ajw%_tys+F;7@Av}t18QOnj<%B+Bo|aXPAw$`17s=Y%}nEH^3(}XH!Ku>GljD# zvw^uMbP#(Q6Qk+JSA9Qe7k&Mzx)H_>n=UJ6T~%E!v%%T>H$OPj(G@A0hn>C1QTzaG zfhp8WHpq8gjv1SOLxWf<0?MHulXbF;t8Q7<{y^- zJuAVQynH%SCpNw~m`i{)XDw_efY@ve_81zhHh89gnLRWMn|%X1BjfS)QyEaD6!#|& z47L;buO76+ra29p!)H;H<_aJWi-TT0f1FA6|9oA&pVT*M6A%aAi4w#rJOYZ_N;GA&yASLg6Mk}`#IYIQdS9;7KKIzgHr z*;__MwRxm4QU?YY@(LjIuMRr$X`=9oo6?7 zdc;D$_lJkGJQS%nAQccttU&~EM8>zO`dTT=PA*&veT)}e0G0KvJ+(7~!2i5y3<&sE z5nSF_YghJNGFDHo{uU6ma=^{bk>KL;QWg+b2pPZX)pI-MZZY#dyQG>QnH5^`&5VtQ=y z&^7foh6Ub6!T`|0dgalDv0yE+AyvP^8A^_?#(x*b5MACCTxKJ)FTA+HZpNpn*gKzi zu*eNQ+di0tmQxKuN=gO0l8oPYr;35x+nn2|ed<;!{}kfB;P-@6Jxu75ABt!BW;pU! z^uiperzB41q%{$`xDPl$9Aa{bWA^xo(T1`UgKtmy{g^)xc*3~E_0n8N{9C#B0h1Hz zUs^4Oab7AV2W1-(hB*$nJMX3ow*B&ZzxyOZ*Jt{RIEAWBOf~FRF8^vp+||Q}UOtP~ zhv=RK9r6NpIG~DwK-*hVOZ~Rp0O&i+T3Hr0s-qNUKp%4f*AQcM+vhrsYh}OtVUIV{ z!EWuu${H#&ng)S)&ycdqNCW9|FAhnr@cA3L}e0fxQH&@rTvb-8_zm20D76yVN(3aA;lF?#CAU zk76m|J!rkgJpsQ14)$_NWvsftf$axn)EAnJ3!ke~Fu;2lvZ{oIn7px)tyje54NC<1 zXn0-bd4qut81mgjF={vVC>tz2CiUB_r{SVZ22MX@im3k5^c z&>Axa107f?D+g^xTRwe##gmg(qd@2H+S{pj1GwS*%zr+y_ zz^R#qKopA;pJT7WMu4{A{pz!s6kYdr}-`liDTs_K#5=XFp#|rg*<6-toI%{&E zAfUq;ha`Kth#STZ4ITpZL146fcAz(64g4$U%O|8|uPBY{4&%7A>I#`L{+?f^=(()p zee4lFl0%WFX8Yn-{Lf#Y`mj+<8xw1mc=ANh( zz%kL>-ZZ6lOE)V=Rb2{Lma>K|zET}I%w?5$ba^nQ{O=1O zs@zZt$O3(<^O`=#x=n>9!PyY{0_{&?kjB@ggKKoPw>QI*J8;uuZkQ3$a}J5jE_iK= zZI$gqh}+4XU2a4N8k>6VDgvqEgT0HIa9a{yG=LcC->_wmq^f7T;S}S;&U1si4j`W z`n;ApR6Pmbnw#TD_)Bah!7=Gp)ygjYW?+owd1#GO&Z2veHWkiw9?HD)qR?l-3s7VD zAS>%ZqDX}YYr3IdT?RMkG6?AVx61gO?d@kG zBJNv=YfYjh&jm44vtAFE%HEt=ygRSaZH%4CcUwrD00EqW)&6tl%IZ=TRfuXC`2FSh zW9jc;EVt|w4{KhM##AeXNP`Dbo@!Hq$Rwt(k?@6X5gTowr_!;LL}W$+f5Qs~aiD>d zhb`s}Y)$hN{s;zX3!&UDHPrGiQhO`Jg?Ul+1REL1YRTz7ZXs+I7DTV@+etw1;v#t0 z2H3Q+uJ`bGWyqA9_br{Q3-a9SmW`t11+O6>c+2Mq^eXOGl!pUcOi3ZC5n$*_5cS!n z^l8wjvr%%@Xoh(pP9+J1mA6v@`ubsedt6hPOjHT%V1JZ6-nUr=T$=#^B!sJg2zLsILVC*_Zy_nR?v$hTcBtbvb+)oEwt3w6- z%ZlV^GvIol)tz)}RbAw3*@p6G6h9&XU&rrp$v@HwB>s7;@%}M^H2@Y6uHOc2SJS9> z;V!MgbHx2Qq4)3a8zL2)_2|GUFOi8d-H0{*rF;6!M_Icm%(7T{Gu%d&-Ok zEC0_`sf2n{DD+&58=CQz8Cmom3k2i?LdT@g_D~5s+*RY5TE`lz$~S4>cD5Dw3i2O_M@uEpU4otF5mnUqn5yZ zd>{y>4@wld=%0px!Iw&$Y<>4!)EYiV>(KqTOUx4_sTE^m^8Q$35YXkN;0tnWt3_$R zkY9d3+Edt=U8gKhMvwT&oJ9Abyp@|{>FYGExI)m!2FMA%PWg@fm&!Df>+g}Ud{JSW zEF`#xXx0ua4wDYZ`lR`2)i7q%pqk*AD%F?)%#QrH9ndjs^D1N+OdiT{xy>ahNI=-cFm|Mla|4zf>D$*F#+T=>IR=9rs*Z;5tw zN^5=eDrJU|V zLjD8+0DkxD{|msXKSin1MJn<-xPZPzQMj!w6~a+6lbRz<8{yske!dQh{gyChYA&c) zdl%f^3Pwx|Efvi*O(|Gr-F3AB;tY>fXkhSlC;{@L>0e*`q4nO_eR$>3;M%FYbGjNy ztA{s~^Zj!IFL-`2dp7kz^}w>(avrbFtX<)1?SO%~wC81F`{GasA-Is9zG&8Ffe_V2 z5Y4iJeY56B6MG;>7mvfj7jddv^YA=Rd~G)8eK1buhc*wA>k@@VwxRnR>O0IHOj4{gySi)nx`AFn(cw^{?{x2cduX+P$vk!__TEDaEwlRV*+-7j8$M%n zU3)&@QKhbfLXrOc%10OYz$8(0Wk}foV9dLyj_S@46G6Y?`GV4L-Lbpq`7vFj)U5aG zMLtxY&NEKX;1%uHv+{V3Kw=-WMGpVn9#56tYI}+@U+%_FX$bA(b>9y~CUPGwjg_`u zjxx6nRccIZ3rUcGmy91R zgu|^b$U$0mG6M-Omd|J(Z1?WpzjQsK7*)UoObMIhx{C zlXAuq(=awvYyu8O;u~S^~I|ZL9sJM z(0F^hY6Nn;5h{7a;C^HPoBnCsNpvQaIHzM=wokw8gDeEu$z%JTOy>3(t>p~%liJPR zS!Ur?SxRv+Pb<(jIs*+OaP0y_<^3rguFZ)LTyQ$=G+mI0n0zVwRty-oU4C>Pm$6*O zCBGcGMO_M1e(Y$D`_H#FDa#t<;Qe0}R~`>#^z|Q%GASCOkZq7Hp&=wYQI-)QOURyG z%93Rm``9B%)<{{R$)2@j8QGWY8L~|FeV>{4(XaRY{NDeb`ONb<=icu*_uO-ybHBH6 zO*pzK4b0y2STWx&DgGQZOH|XnkbMaNzm=t-NETx3;29L@CNrYc7S1iIB0?Z=QQBOH z8OC%52vpFsw8}SE)|8v(4`exLHVO^zxo4HULXz};zIgtEkc7NtEtHGoEng(Q4F)9l&0~9P+e@ zDZ7XWCV+>DHN8f5=Q1^r>f~~Ny)xaXsMc53YCg5VL+18z#*X@)hkc_6lawk);NxA! z_X7EK>%Ym5t2bD^4>=Vx4Q!oW##t*l?11@VXSV5b5n?LGKxlP28heNoPVegLzkbk2 zGPn^N@_p;J`q9&R^MuxeSZ^7VhHQ5)?4pv&f~bAHdB`8RlGOCEv8JTAUt2L(`KX%W zTdUfi%C$2f)-yLc6*Ty2DQ3{Y({Os!tJ;04<~hzs7OGA*U@Hb}7wJ^ymRmoVDV?R& zj@8O-yLoAC9E3~_N>TYrl6dF|reCP1uHy9;tbs%o!}vCz-37fp_2vk3{TQ#xC7Ry> zrs7>#%&Y7G4wpa4du^NKY@b5c-}b&m$$ng$BW+4&f7A@kOOdY23*{Y~$dukNw2vAh zia(zIMW*vH2MN@n*H3{F%4ck+fmV#2jM>e}eK$vo&i3D{okBg(&aR2b0fK6t^*>qS zt(os83#XHZALu)Qo5gmkg+C$Q;-~!9R7{Q?sdnDTV&KN2So1}fsqq}AvyWJOld&hc zY~{hvqbujS0Liv^sEo$Fv9a`W#JFHMh7+P9z}UILi0(~`yh=3MR6SK;s4Siuk|o3A z>T8Cg0)S2hKj}@10AeYa*}RC;yoW<_EO-Up1`o7dX##8Hg1nDiP&!8udZrzb!}>2o-;i$4+G4GH-Cz$?nNVg)jVwkd-=W`0=u=s#JpJqlD!2VLJLum)<=EpqKOpBX|+WdolSna}NkQ1%k|Ua-#J*6U*stonI6= z&*;ILBjyt1}vV%6X1i*QUh=3`mj}!Vvlw_=av!wcmApY4sEgiY?kl1$ZvS*CZrnyeqEv zX81{>s6CJ;HuDXv3hIi&Ep*}ljr4!A0YTWcgiaTZ@tT3zqba2Ya+2qa z4B%Nj<4d)(09fwVm|i`iZ^kkMYNK1eE%R1Af&3{09mHMHX~wd`Jg&d#x*hm=muvKg z1CzH=7qa2<^Go@aACk$m2lnK8V10c=XOkc`%ek&bA4Hw+^_l$68t-x2`Bf_UD2zXg zsO7HZSY@JSstN*&uRDkA=G%N<-{^1@cj{1=0aP zsggQE3t34|?b&n-3gqV^owDk9HATRVZrVwajARo6n!XlC0E)Y>7o-Nv-p~SOc=$>= z*YTDV*|r(QR2HIeBNVCIe;xq4Q{3LsLj#2kX0-+K@}V5#n1<#4sS@o*M)|g@vYAJ0K=u`@T zMeNyL9wS1c@Zfe^eVWu6d)k0Qc8>ungqsrL+o}S6z~aYsbyVSlGk3;?y&JD@g^m(7 z*tXl5p1(ChSzr4h5E!GIc0$)dJ2^$W{<;VTn5kdH)9M~s-j`8cNbj4IIaCy%d3o|M zcfUgTsV}fDOSf7sfA$-8DfGs0f;I_6`4K8{!XPMUNkuKl%6nvGfPo99~k$^+Gv zjOmJxWfe7-uXwSuja$l6vKW6BqoH^awi>ZIyc^H>el8luFEYF9cN7>)uJ-eKhUg@0 zZ>;Xs_H2oMm9wBDF2(){%Q|fP={K09iay$n(#ZFEyp8B-9~CiZmEV*am5KglYDAqC zAok@^)js9Q%F01*MRP?BvtZD$yA!P|tjnfz%Uf5$8ydjcVa|ljl#K9G<=q~I@HBoN+MnTezVV+Qg*Pm}@s3+<=}AiZSQ6L5oT;Q7892OEV<^EbRP z$<#LUMlHuha5z4`Q&Ft*O9Bxv{_N{V1)62D$6`nAU={-mR%GQ>Stv7EE%a$Eq9Lg< z+GRvU{+Zv12-EwQXYkY$W9U~8MnA8vG>|ORIrg7Wl zt^S^Br~c`o6KTyIthmI@1(MSa@YfS|dmBGWA~|7L5G)YH){(t3}sIvXR`dR5iVKI@z;B5q$j)%L`{&AcoQN*lz@Wlqy40ubnS z(u1^w$}*u2XJHs@;FWWIsnxs`KXeMB&8Xu*A-&{6l>=4(I2? zMsf(m$jHe4{QdyO-ezFl9hqNvu)OH|u+h?Oogneb^vas?A8H;R9!F>zmj?bC6Lsyv=a6EC>2qlB+8{jXM^IeWat?v3_S;&0w`H`yyTJ#pg zojy_dE3JN78HI~Q42f@M^E1@F3)=uuZjI~+gb@@DHwZA8Uj3AAk6hn>@C;$iVvM-= z@?7S9om9yiOTEDrB*pF58T6}~I0E9u-LN=LV)lJ0`a0JiYYaPn zzYuDwHXj~2m=0HtO^^B8T0YHpSEF3x*1(^^6`W1W*!rG6@isCb?YVhi@pJ!`;DagB z0)||T{45B&Q^|+GB2D$!GXvIFwkww4^!u^c6qbTvvLYRah1~k4r1sjXyw`Pyxc$Yw z!Dx+gnY1sD5tdxcNXM5Z@udd`D(a+1r6aVntA2jMtbUZJkNP*S5D}4=rcmn zXsZF!IQi-qD_h@yx*6>s=gFos^!0qSUBi`Kqz41>_F<=waYg<)u`t}bbG1TJ zzaIW1uGRE(zQ5mXG*<*haBwy4!ts)szxdD$_O>eVQ)WMp6mWAWNw1yZm=Vi;ey7gq z%xl&gFR}HvOStPIBk$WFrDE6#Q3fo3QpFGBh>Vnt0n*Rr?63G<#g>(MTH+~12*LfW zOwhaOC^9pdB(mEv^IO4%MrT_cchLUly*aC#*rtwKi>&C#5~(EXs5a2GR3O=xS9azl zRc^)`o1~Qs+21qv$Ynu#&t|?uD|q2>klN@7RivO{s7B|kl=u1mq^Kz%*Ye(ZC58|SQf1kPFM7}oT(qb)rX*v7rG_%}~$~V6Qt||#lxyyT>yQ_}r zvd=q{!_?Up+B=Los=tH;Bi@#pTruGfOrM4ROb;Hm*yfAtk!ki@IXQ!cN0@dsVC+ zD~r^G5OKRp7ndv8DeBNGjlEhv>#|Yr==nJs+)E&P)Io#3FvyRh{|HgRsN5CIX>Dwzy9wkXvD~gGGIKM>%-s;i?*VPms%!4<@o*&UzYi{07aEFZk}W+c}P>!ADTw ziajcFmKxRXWph)g`f_kM4Fmpd4T|J8$bhGSK;8RpZSNXfpH#c3XaO2Y!_?H2w6l31 z|7OT-gpRq;hGRKG3dY;iviL!&J4SJGVt@OHThP4 zmX5BF&jHOvarw{k^8LRNxT&R_$GjjVNKZYXiD_mTMP06z0K^FhuXOSRgP<#JJp2?b zkGDHM{KnL&cc97YQ>!MT9rm)T@SUEKK}#yj%FA|;Ypr_~)Z7jp_$TdPjoX~nfl@9F zK;6;NakDg*6jsSI0JG$PN_-DhB`nOY@XvWwq$Xtr9UX1enE-X+T)}~u1m=aRnP%Zk zKT^%aQX0$JT`SfkFN%5(Ct3md%(l><)$riJw8rtvBbRlH)cX7SxEYIhgD!fgQA&S) zJaFZxRpexEZW8?WP#x{HrEwu%qOmwdHxD2DCxnx=ghrxdyNeX&fooNUwwF2ux>eUI~hPjQX48OZyb%ExLu=& z8BRhWTxw&9)~I(+v_MYNi_`qEEE=r}hgCo(35P4xKs7{(Qu@his|Y`VM9U7^M-8ze z$)M;2+S6m=U^&APx_$}`5s+v1R-p2|HA*La9qY7IoY52%0ftY&J(PGQ?8oO+u33MwZD6&njy8D+v;;%*b5czjTT9`qjfH~>V;Vc?%n>z`H z_UC}WV+hnN&#J$`FflgKa=c!B?XdVco2re$`xGQ;5DR$4e*4lpXh_DUdl{ z0SP$I+k3~-Gh2tlps0m;lkEWBSv$lap_-7rub1*J1t5fQQB1r=uQv8F z{bHw^<2!~=oq+IY+-Dti8t=}rs! zY5s|_PQ)aNLVJVl?0=i`-+0_%l_I`|;C*x^X!(C)g5E}{!X2Tkp!>ng8>yeFCIGHV zamt{&zhiB=XwLyXfn4CTfXi%-%s*Hz7?&Kmr9_D5i2OI){~uv@T2R@~_V!25XBX28d^W8I{BOI|G!26y^dQ$*GABdp65>HAMT!2dqOl91qLT}K&R|? j%s_SW_g|bqWJ#QYV-D8ZD#c*`3jpq@>8O?{TcZC5g_%M@ literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/ttcs.png new file mode 100644 index 0000000000000000000000000000000000000000..3bc4465d74b0d454f377dd080dece7c24a88a283 GIT binary patch literal 28315 zcmaG|byOQqw5GIFplFfeZbgeb1%kV~ySKQfXmNKh?h>qcvEuH~AjKs(!Qm~xciz8m zPtGCPWM^k*?%eO*?|ws=l7b{EG66CI0s^YE6i5XD0Z|J9;l=V>MBq&7fU^Q-qG6ZRmh?{T;5}5{g#^S%BdeLH+c2NYZIkK z<>SMMR3ov6lIa)o=mWhlu;{;I3-#6Cw&j)~2SW1N0X&^j+6D`@TXsj}tVF(n2(5+H<63NSAmy2ui%-Kp(LS>z(_t z#%g7F47-{G7AtsrtF39Cu7C&n&PEq|3xmOy5bZoIzuerNeR%7qqjcS)sf?{5*x_-S z_b8-AnlnDXvNHBaf&9eu^=9nl!Yby|Rl-9||Fv)%A}~x!;|o97Fb5%eYhw7#zZ72g z#2^`vVbI0e&;9^zAm3}m932xgJ~EQJ&b~CVU}bl81my)MY>%{M0vFeKR;ER4Y-|J> z|FaRwaRk0gwB0PG8)~qfALva>`2dVFS>TQd{1cuAKeWE57co$n>#WrcrUQGlc%CBO z8l@2h(2`sai0gV7O}K2a%TNKBkMErC-@o6i$buM~=+l^ty{!lY&Ieo>w%wXu4)bo# zkS>u$Poq(U6UXcwPZ-6#KsYzbV7Em7(BI#GK#6v~We9!$=!8XADg3I2#xrjh=kM$$ z!M8p1Gzn`IBFf)8sZP25L0vL&rTawV_ zUxuSuQi>L$_6lJ&Jjgg%)EMTcV(ce!Va&k~PPzPRg2zb;yTevPd&{B2Mi?blTs-^_G`Gd^DFYe!;tg0|In^%~N zelRQ?02xt86+qW zlxExUl(62BlStg!9N~dhyPs^6wJL{As#_N~F9r$+u4Wu@Yb$;t45}GSiVdJ1;Ki;A z7O%5GTSGnO#RD$g;|;S*!(0YnR?O@ zT^WHfJ_nd?^OP4-i-b0M#d=Gfzc>}0U87ii%nK~#o)jsXW;+L0cDxvFGiI_-;FpA- z43b}qyscT}{gLS+1&&Q-&;J@~Q!G5=`>C}H;w)HN>gy0aKk3(0KK{`qpJG0gp??}R zf;gsfr|!||!fD(Co#|@k;=dzN5G`up2ni|>#VSGe_5~R?C4R1NWFT9Uwi{%|OuBS* z;F4-O-GybWlMybzNT;10`;zwM0sd{xNJd)Py6yQe$&X;$B=gAMh{q}i&+9{kQM4Yv zlwtQoZA16@IS_lhi@x(muESE z)w^j_bDpQS`EJp z*#RFal@ZtSeFiobrwS*Fk9xB5M13bbcBBJNOB}@i0bxv;8|fxTj4uQaMqWa?A9uzaX#WO`*SvMAd}$>kAbZ@;pnaf#iFT` z+ksx2M_e_8j+Mhq{xkbg8s07vR9^`Zm^d@LF>TKdo7lM}OD+D;O=!WPtN{%ZM(l0c zfF6_&biv$yK;$&_hC!CmMXaai2YOw{1b#Ys4}Y-e3&4dgPv@VC(H;+;KN5TP$z$r7;P+kD# z&Y^i6FD+$H`+EDomH8%%TT$Le1MznH%^6}$nRc|F{gf>(I`Iu8=lg%lRUm>o4O{LCrv-;(?B(iDxGUoE)LO?VIL-}Nk40H5m zJ9O9LV!Ql}!K}a_HkI_5SG)h0@1ZukIj8_mTx2H8RmS)IoNqOCII^I^DxHwjO)|}< z_q2&kFi)eUz?^*d$rN{L|6z(PC6b37faRKUOFT?io<7K|n~{nF4p?)u23GAavI-ql zZPyhf1ScB;15WGtg@wNh3vKoFyO&3Af8fD^D-|JrY!*IWkK}s$68d7kl#@9* zBW8SOxf3khTB%Pn?obmlRY{Q}z(N0*p{&k{6_yImk^ct3LWX}&x@qX#!otYo{Fc*? z9+Y|kES;yD$J_i8x4w8mlj|vOm`H*%UzS3#D*tzbC*ce> zQ4G;VqnPX#W8YaBrrSUwQZfjOZ3&_TXkVzIzO*YICnMM=&1jur*PzX#mSL$-xMfnW zs)6vkycUl*24X5+4rR$%>fl>_B9&5{nole**Ru4e6;TPAES(gWwU&be@c@tF65O`a z-t=?|LlU}b*isT#9?Rlyy7g;EpG9vlJo0kuzQau>VQ;D8u#HviS6aZDQeLaFb^w7uFZcz1!ZNc z$K0s_vxf49@Y1gCM!`HT{oqiPH!KrfNvvbF5)|VFYv~RWju1|qo5uaBppK3=YOeHH z?=Y2l+TfmwLS|8k|IGEq>8te~o5^iC+&C2bs&Bdc=n&C(mdxcA*bB zy}{(<;20fSQA*_X`}@A^-Y~PQtgf!E*DdcRM-!I-f<~|t>%6xx6$!Qov9JSM=vun? zmiR4juJkqS7i~4*CT+WL@nuDUsD_D|Q>Gp8{+-fc*3SLw)_CyaLJRn+`g=QP3xe+# zwOo-#p#S33!^v8jnj#xq)&c^>Nrj@K%#CzL-O6h?yBYEEGU?&fOS*U`Sa8j+$bdE< zaE@=QX-f3X2bgu0_vppc^-bsp7GY?uP?6#D{)((mBr$(X7*r=2pSZa0>j8IR6zXu& zk8JYV)G=SpSvsbyOg4=AVUp3#ajLXVwMEt6L{odSr^;$zsM2oeWU5e>Iz@LrrjK0N zSs**IKi}E;JWh&=NMj@+Ac*WQRm}};BIEPygeggdNqnfQ;~wa(O^M>})o{>cwExCZ zL@)$B`T*^L_T1)g4R`;Cpr2PlbVliW>{|Z$PcI(2a1A@XQD(`}`+Kry_G&$(bOM}= zaDW#hX<9pTc&JAO`4|SWrMq$Yx}!*N^oHt6KGZid7r4;Mff zW#iRG>BVSTJ+h+|nH{cO*Z{wyk){y+bWt24!9`P?sq*Pt3oj>Up)TU?>9rPkV%GQA zCdN`#fxen(sKDshxg7{Qp-D%jf3*RK{H>$Hz+wI|EU4Z&=+wi+m|U6czTU&t_a$X) z7oR9XiCBxv`cOx--_BU87V?mjWCo|RNLOb4DweE>n=T)@=eV~fi6pR&c9sLGOHZZ( z0O-x;b++*F$xPP7*KkRg(i%}hF58b^6?S^Ky;D^+CCmm!G^j;+tI>m%9oF!g!3Jo$ ze&eTw?TY!@jY{lbTClC#?MIe-z;nczlVbwjH}Nw{gbsg6nXLbBCR~4u0bw+e63y!i zWP}mNBdcw(#=Ixq1C`j&Z6Ed}mgXu)cN{4Z2|n`6%PZ@RubZ0#>DpF*pF;xumR^Ue ziwhzlACJq2B=bh{Tr^MCRAm45BflpI|Ziq;kc1wI$LcFPitUgKjIL{wWZ7+SG6FK) zthCffOEFDNO?Sq!OvQS#v$HP^>+%{yzViVfUh-zCRD=>|z(iU_*B_fIukVq_TP`It zK+d0WMqeDlvBb6qL@u(!-RY@Fj1^n~HCRs-b;f1yawXJ_Z6>zjfm;b3NQ+3M1ovo$ z4D)l$SgapGTQyg$rC{5nmK<*xlxYr& z|A0BkWgA1qneq);eoAk?2@3!jcfe0m?CJR#~!2uUPcOJvTAEhy3A1 zpoBv7F1os0E zJldzHi%FMn_+wBa1B&bo-PkeUs_w3iY4f11?vB}H*w6VPf>L7MSRq9CSA^GXI>gYh zyzRIT+oNAF!MiviEqjD*=qlR$W)B|jeFGbwO!_|GZmqpi{@a?_o8MCu&E?JJJKj~w zVbR@#1JkBCRrJ4K7cD0^f8u(7JAc4?i=dRR5rAQIUh-(Y8j@MQH&#F5hIPKwiGkVf zO!y%Asb_(L78awIjQPIUcMHgwo`W~2#W7@bDWO^m`8kYTD5$r5xyW0II=N3(!c_t} zF!JHL;GQl!dEyJ(tv8K&H@R?{+Sr~OX$xzpzQ5LuS-qLcvdk9f*@oTTvgefCLoNZd zm7TBd9Ct`TvPCiJ{0wjEp#k0eHP-f9c#c`imknE7N;`H?Fo9&gQ8nCY02rThgX8h+ zLY87S(qE*jlASaj((I+GzAZmV(3PPAACl-v>ghcWvrJnJR$RA7@U!JwD$P8IZXYPk z57X25`1>rz1SACxxyVuGUjPx4Ee}aV77;%AbF1&@&liXCmEAK#P5MoJLOt{56+xZz zqsM;{d>1V$V#svm#R#Rk7uRHEQJzI@zv4hYp4WwGc? zcMENNWSr^fu455gJ`+KS`LWK>qjq90NJ47p^~4##c2l+H0KSF|4WBYb6$A?_f;W*g`FhSVYn*NF7H=(;5cQWs#D5jW2O!2k5t?2oY z!gfc}*zaF3rg`NYRCZ^-7C3itEFKosA^!0iJeBF;ua@y}`3e{$&n<@VvrN;U;^hf; zqRGzDm}!~p(TPtuG-fw)x`fA=g1{`f@c`4(nWk|C8y0xnwP$!p=sU~4!isYqNMq@# zr@tO?&pC~{wYtpI?l3FEcywzMOCrwX=Sz7YG!oXY?aHw?GWxDR+`)`e&|UqoRJ|92 z&&saa?|OO51pph^d1XhJpXAnb{wk? z@@!Ig2dilDl>@+FOS))iy=!DufpE4Zj}G%vXkNFQjE9gV*5*g|rO0)U@V(f>=Mv_| zjk|43EurZ*>~~RvgDE|P-yu6Ff|3F)A?a9E-O9HS?8&iBymX#k4wR;)oTdAM0u-Sy-t#5TPPJ=fKwv;6Sw z=gN%0z*VnJ%m-zPA(;yw&znE5vNHbQbX@4tpQTW% z2mHYfby$Z(AorW&$4O|5<`|j>+}S$D7Q8T8;RP5Q=Z~yTT%o8Bp&fBjHOpX&Izd*! z_S;7sWBJ8|&@&t<{q}Z-CVsZoM9vD=qf3!tnfH+~F&{8n^RmZx2;01pI_EvBuY{q_ z=-`66)+e~WfvL}ZWq;+dw&BeZ1Bk=J`6SL!P!t3Zk8Ohg_Se*P`sJvqArKa(9^7Hi z{1oY@v8O9ySV~OirN?{|dv*T#Qgz!OFa?FzcI$YJdzzn7`hyk71#n@F!gZ(ptij_h z5yW^^lCEQh&u-9wH$x+GO>xF`6#J_HE`OshKjwpeYHFn z)Q6DCeW-?!V}U9Us#P51`_ic@Z1ZY=`)Te_b@p=7%KiIrw%(>Yjz+V2@L{hlz>lh_ zyxI@Y)=g#lyB78zfy;}c{l-p-jJ{Oy;?8`+ z@F;XmI5Q8Xevf=pQ~l+-b^+xTVns(~XY1c*GK|Z|KlfBE|9%+xe9&O5vj}L+%4Cd@g9OLC3sI#>rK4V8?vZDaT!)PQoZd~_*uN_$kB;%YM2@n}L>omh@Fl{> zD--8))vzF4b>Hy37N}S=F5KL^w)uvTogK6(UuhY;tl6;^2KgZkkxy zXWD$dos7wA{=T33?|}H;!5bSJ2M48LswCOo*C;8SMvJC51$!U-luqgYktho=R0&kY zSBTARc5FsbaxbKu1sy)HtR$~86&|YzFob)9`ie1>mogmuzRe!Xdslbmd`^;ab#ud- zgu|94B_%K2ZLfVg-jI0w-Z>A;qYGzXDW@B{JMMhi&Tx#5j#f}mcpcbf#9HEMa0&2@ zxtSigB&j*v*}-MYzD9m4m1W+b(~9jnHd1Bm#f_*=Buv31sl#RuN)bmv2H#c2vf#Y!azonX=LjiSicuoL$f!HeR*44^Qh> zh)IAK>;zzHP3az=;iIa*V-A)M8n%4%sByOa5#@)irNcWRnXYS>##4Yq_Ta1KOD03_?k%afu`2EH~V zB){=AyQcS1y50#9?!DHv>W@oENa*S5S$aWHo`MyZN9Wjf`WiFLvJWoos3?%61Wn6U zq%e=esRCl{ZM=*{^!Q`RiDc=*&-8aMbe2SZG7h)B8Y2C@pOeC@&o;Qm zLJJ^gBI&qjQ<+eb)W>&?y~0-qpXbVP^W+iq%GSq)tM)7RIx19<>J zn8p<)g*`)5m0Y@`l6pmWvREB3x<0~)Ih2e7A|)^+b4dV8`oZ^-b5G5;wHD8%9pr!7 zyQj}&^&cZ8|7La87oA2IS6wYsYYXJ z%2c-plWMESe*gYrXqdx=D6WhxuDtA~EB5RjwEHa9wUswfSe^bPY19Ua#*mp^4S%&8 ze1+M5yI+34wz+Ahs+!Pef~i>znczyQphYPjQ-CgcM?jec-ZJnDX-f?Y2Q;!~utzR_ z`Fb!{c{qG}da7yY>+0f?IEvj^U;iE*z1mL#^$P~#mp*_fYx~k-kuP5x*qwx%@kavM z^cl#?CH(AoO4@CmoSa--)c866cKCXKN(#SM2erbPy}ub4*KX97v*^txixEEkQhv&n zfuL!-!h{b)u6&M;H&51k+Hi-KjH~pTyN~`I9N2zS3I)c>W^F@&QhQ)ybU-Nv9eJKe zi0v?`Qlp%i=eX@$0a)1GBCu}?y7V~WwE*W+T55gkJuQHu-o$qvg&!!^gG&FyVp;*0 z?JTHmYmX`Y2L>kU`}agVU%wFgx8PuQ8O5R_J6Bb6v%5qgen}!a^@!vSJ~KbN;S=Cp zL222xwW&?I{QLVig6_*~7Nq9q+z#go)Jq^kTuj_PetGt0^RQ=T((Q*vGg11eb8io` zeb=j&mrKX1JLkkgKB>pNtU^NB)sz>&QayaVtXdyp1bT}wt2*=A?$4DzLmA)DLDiDu z_fa$pJaK0eF)<;8{o`YI@L_h6MFZy_AM+_xmLJ;}d!#;P4=Shh4zu>ekXxUQhr6qt zieQV4K+(_RMYcu3z!;VN)3vKkd!CYQ+?6&yooiz`IK)eczXTSio!~H61B>Fa$K7U3 zNG~8N%gEW0C@mC^U22MI`#Zi%Cf<=$E%rAX-e$~_{*d1_ zfFOVZwY8Thv*%{Qa9Z4GL#!`dJUQtBG2GdvgrKA9>gaf_9$zj$EHQ3Qnq)iCIbQ~s zAHFu^Tv%Nah6p=vVOW?wz0F{mAz`clT70HGqKtjmr`YZ74<**oRN$=o{8q-q!wkDG z`ve$hSL8oQPid}R?{7E?R)IlrRHgFqY{DMYCv!^2HzRHiFJHbymlOU9ggE6Sk{nJ> z>Ks*J?kjULcXSd!gk${PL86Q)7MBE@pp66xZ1%6JwW^^}CC;Ah#;W*zQ;fsvO4~#G z*i}6`-GqD@wY0syetQ7f$f$XhyrJ77-7n|R|I-2xhM&Q<>{9GBugq?BcqvyKHSAH5 zKLdnIl#6Km!mpFqRj|zD6|>WQH}-veCog^{Nna3Sr}N>$l^ZN?i{Ugm*ez+jD#hJA zrV0`24`gFExCAmP%VSyYp6%@lmK!r_(G6banEWIg=(MAj&e}lF#*$6yYC@JIl?jj#R3{9QxDBIb20Cop%!^K9FJ5gX~ugUU0rHv$f8{ssM`Z$YM=42c_x3f8{TK1bGILNA;!TVujpc^C=4R5 z_6W6daQH+JWo3|WSFakV=ps;Sfz0Lu`TF>~?Mj-ZJmrj60a`7kjBSsh5;cNN@%F`U zJr7m64#rLN0q$*GXJVvfRePZFBY4~)tBr0-dPEZQBRFT&V#6JWFbIVG{&mW{S}3vb z(&tq?qnBOU)_e~bmrwAHxiNUy(LvqR#Yqawa?=texG5JL<}{&z`Z&eksg_GomY>Ba zCy*5TDE@EW@b6iKu0T}wpD>9>h9R`>^pF4BjgYye@Ad<~J8Y54@_iH==8R&I)?;*a zCC$@tggqbkvilM-fh=Q<<)|BFLNOs-C5>iKTH|rmk+v?#{$}os8ot z7XwHREeeR?TO-}wNK=SR>=n#>+}yNp1E_`r`q*g0NqMrC`ZrAl-cpy29>8X+LMJTN z8#P;*g}(U{H+d5Qh5^)Pu8UPG-lm;nDNq~r@WWnPpIL4m3*2Op`W^i^UOBH~hPn9n zPaj2J9qkG)gO~Z6>{XlOT@*1UD>&|&tNp4rlA*+p@D&;vsvA2VZga-wG6 zT;@|RlIB1WlZ8#c8~bXiu_-?+ zu))3@M5Q=@ih>HfbXOLqPTh(5!7X*?urcqao_6=A2k7%m3IpBat>Pz|CkEa$xHUo; z<%AQDJPIjYy~BNZCk4A8tcDorK1y^KmzR5h2qyIpy*TgY)rUzSc@9d{HvOHIm2T2% zceQg%XL_YDaMs!K;FdB>J$%+^zr3`x6dI~;OuAeR6TUo(6FBekcIn~2lJPb z=jR?ikW6|)Cq}H$-Mk%IOYk|ho349sH&6hwyUc!;n3!oOvH`HzobO!U);9juQ*?#l z2zKUnKs%SJu;GESYT1T%XZ@ zY3!C4SN0r0jQe{A*^#dYr2uKD*g^eaJRTc4*uugBe!Qv(0!qzsQbD2HjLH6m)D+>1 zcBb$oHVdIYl0kBG*dru(Wo7$rtzjjuMe;2xTo7<-D0WU>`;zi`#3=7@LG8w8*Bmd~ zgYsAnWO6`3efY z$*db;zj@HrD_DV#*n--pzT~*n8oqEqOIF7a8|=f(YH1khK#X*Z*Y0(>-%kp*t6Nl4 zhczt{BuJyg#aVZo1jag<8#Cf=Bm|G0hJ@4>o%&-^qzkiFk9KF8Pw9evA}+srjeGMy zR^?yzS5^u;K;eYTOHXa>H+>dxNdX3(9~JpeibaSw0Qa`oSRWPor@tS?&`Jm!841xp zEe#)@VQpnKAsi4Is`n1B)q-5H3m9a`GSW~p5LUu?ExY&W0PwQ;-YBn@63oKIT~|MR z6!CNRfX<_HH^Z?*8uU|%4jcL5&URkMzOhPa_ir*&%Z>#D`P(qyG#7W%K7r-6+4>>j zMw~q+uE(PGt_IZFF&zer_xQ9<@U2$TE9U~};vqU%JGz=c06tcmCA=u@i7UI=HXPu7H*f29`3}SJ{+c061W7ANu(Cn~EO2ZQyH+UJ9ETJ((ydF)6rKi!m*d zgPT9Jq_lKzn-pr+>ZMXeHkmA)Hb>fIL5pf$Nnl24qz_LaBZ%7fV}~6#)(whMIBDwx ziEZ4B^5}H?|MCi*Zj_%bjEprEvCzx8wKb;Vgye%fy$+loyu*P9 z??fqNXcFRQhB|$AvPi81jjgT2s@(?AuB6D#3n5}?na_#&^|%vY+gN$ z{vyz0gj*CYcCh<`u)P>S{PdP-DeFw^MFiOY*yIqDOaV68oLeC}^2C-2;CmO6j#^*7 zfU0LI@DqK2_yDv4-JZz>u-bqF$k+Wk!ESCEVE511=3~d>jEQo53BE`i%@?UwuOZPwV&ST z>XwgyeBz_7VOO$B>MI~{Q8EoVvy;#7 z+r>fn1VG~uZt$bOl`A>7x1LqEEA~fB#4j*jfKdNt>`wO8%_f}GQgf@Yg5j!hfDQBV zO<-{KoG$UwH*!pUpa_8)zrdWEO-Uj&GUSP)=f~2zF1(q;$B)BLVoEOsit)Yr3|9eI zNK;c@W_vnm`@@+24Zw5qyRY;;UR(-J%wK(<&%pmmxK5;_?feg@^lk|61@(3adWz05 zt?UGL1BEEt7)P?_)j(y>lxS((fk@BLd$YamWU%yDPkAn#b-p5_l&J35TWt=$J~5`S z;ZF#29!dzVZ`*j^X(O}i4!p| z3dq##HZs1rf6*i^+{&33(5#XKlAuaHa_PldchPtnv$RmOn+LmlZdTSWAZv=_O*410 zSZAeyY>09_yQNT$BDZ!bJBs$m$va-Id!Qgda=%9A{oR3!gGj?;1_w7R=;FuwwT&47 z35Mv!2}fEm$uUpAl}Z1X7L^zaprGG82%wzfNad%nSdyAa=rL26EGIj>wV!`q>A?GQ zR(qE~yTLfaMReb{stG2iYY5J95gpV1SM{>{h7$IXq)P!$NxwXWph`syFTK=p*xp_bw+!16ECHTV4- zAZb+2=S;aIxZ^Vhx)NM1NcjZ0fNo1DOI#I3N(+ z!0Tnjd7jjluo<#p(K(IVv076^Ow7@dkqM_+4$F6mg6-TybF0eYEzDR@Gjhxu^qZSo zQP$Ki>ydL{I8*{&iCY`X#2+#6RzbJ43(-O3ACGl%JRm{c>R>YG-QwWxdrs>V7uuw zAg?sFw+Gdigthxn3a^+X)K%8oXvJHn;GS@L@~y8Vk#-GyjivV-NkMm9S#&l%7JGW! z@iORqfIqpQ8*Zewy9JoK8hMJ{x&G(Oak4FGB_%?4Wn@t>A2QPL^%bo> zRh9Z(f8Gr2vD7ZF8%AFUo_z1$Ij=Af8gFFb?kURG5_*BqK)#rs{WNPel7TFUrN~)G zyulDbgi9JFc_dxtPBqIP9}#$JdmMo|_%L_68*_Z@;|z|S>h8RmPMJb{xJU`o^y`{C z>6o>~K_3}^8a!TPSb ztdwJFvSkt*{jRp5-Ph#qa&dca4i1NxlW-EDS!>9g98jU7qn`&7KG#7T$nTBv_Ly1^ ziW~n7b8Ss}Y>aDEWido+XOTX??43nh$e9f43_PeVd%ZOrd&v9su6!8R9efKA}(^XpCOj7Mi6wxJ_>}AuZ<(yY&Z6A0An?|v4r!;gt z*c!L$r*D4Fa+zYPQ1xn|*q9>)igbKv;-b1967A540pc)7yQlX-!yLeJA2tN?is#3{ z;p(V7BmYduu-WPh6f*(<_u82FRkxsg&$2wkU0yh0>T25V{Gu0rAn4rwcnq#+p9fTh zW>@x!5-)POI657gR%iz_|@r^8I2FsTLTzx^dx&emB< zsVOnju8=@xYa1wCj#6!c#CooG;H}&?H_h24Ony=#)}NkPr1wih@zbWGNMDZ2XKmd` zl1sZiJWWC77_(!1USO$fDfy#2&UV^Zdx~7|&C62gEnC*#H5L3)vplSX9oyoG`+W1u z4h0~0j*341gj5KPMTp37DTR!o9cmm zmDV5jT}C=UPEMOhEV&H?Pi&MwC)An$kt!Ymy4C2{-Pl8zw zO2U7kjy1#RL(9^A8T8aTdc10&Bj_MYu3b$E<>7I~qHmV{=qAmZ#u(27*DHnP&qZ~o zedm?sX&@=fAebRUI01t~blE*~lsnzsKr#DX*45fDK*bD2r}sePuAp!)K(K{>aJ3xy zOg~Sg6~bD}aC#^^4q0B*>|!Fb93Dx}V&hf)Dqn>%de!z#c*{`x*E$28)4eGo0_)HE ztnHZ6GyF-ejEz7Bm|U@*wNCUW+b>o&wloyt${ni@5^g-F3 z?4&&GV__I$qKjp^u|R|fxqKt9EX2B5@Q>(yA2$*D&-tbf1<<(96+YZtS-XS~+hQkA z!5`a9_MPxyTZLc=&XX6<&X8z=U3=EX>Ia1H@0ig3WRfn%GwuE2#= z_1gAoV4w@714#Utg^!rpKPnt%N2@a8;6)jRb~JfF!R~N-VZSF7$W6q0aBMeXqn>_Z zFFxQ3A=i(hM4zgYT16Qb&#z88)rB>TpA^SLH3(f;M22?w*d85vi0#bMjH`t+<>9HV z|Gj)Y-cZ!oJc22c;4!*%k{u;^7&5?1x4G~)!|iBdtwffeKDADj#!Y|=fS0exSjw!) z`G$$c^aCdfq(a(OW^cZK`u*IE%rEDPlCy$?yRgBNz_5@jd(m_sAwx?`%c*p)tt!%B z9g4~2c;MA&9YIZ_XH(a9M+h&h9Q?t|bcESAZ?<%{rHznmY+uIr$qY5Cur!sNB`pkesH$a+3 z;hER-bnqduA(8d#L9!c?pmnk+#L;7zR(GT(v4#TdiGZN~VKp5B#oFw|(S1~?U#;nF zNvQuDms3NXNH2cd5%^#%K6CQe8)IOd=E{XNN#6O?E_OQp$O^xRh{JmlXmL>t2z~T% zl)VC-tv+u39enx}I-i0PiJSf;GxLq|Jgxaet>V%Vv{xbaXsaxx_O)if8z`MJ-d)Sk z{9d4ojX`O^Yhd}_Fke)Nl!>uDOY%H{m%iXs(iRRbNifVU`GMSIu@`#OhsQr@vF2-B;cX(NnFwP zZLQ~?-K5@64IOH#D7^cOEF2pOli|Iey(XJw%DdjWF|^>$6jLz3G)K7%9}=Bo%Rfk@ zCr7&ayC7RWKT}7NW*0pjy|Tkrez@xQ&)&_{)HY%E`tBt{Nx;BL5VZ{48ik2P9wh`< zg&88ROEh2E#nSsPi-F-Ec(PRf=6%bY7gwJ03Cz!A=@Lvh33oU zyB1DA-T}oDpi)>X3}^_!XMbWK^9q|pXlzS^-IK)<*7+$|OK7A*6~f8EFie93IW`7e zHdXxz{NHwov?kX6f1m1Y`qO$n>MuZt^AiXs7P?1YSMs zMNb@;`_Z4GCmP^$%**eEE-3Ft=GC!E`0l>3 z1F8}x()x*%(9jv*vOuD#chW)(Z(3eHiaoAuJPT#_f;I)WfSoD8IhW*m@1J{Cx)v^Y ziNHoFNy&2qWS-?8St;&BhpzfoW86fW*WCBrzAQxfrZ5(V&Cm&r+=~%>&&ZqF1J~Iq zpxShRK1-HRk;9~ouZSGM$KGSDWIQz9S8$1RM46U2J@@?!h(0c;B5paY zvC+`wZS{{WcqbMKN!G)uWu75w|C8NcFZ1$qXAso?OS+j%aTcXUqtWL*1<4}?u6FBM zP;h-z(5u3EgMu1^`6~VA?EuRrArG<>(K+4i#$i-I{xyxugHM(hmq6K`$c^I3UD~3! zl>#R|8f*6=H+*%b9$AH%;yfS?f>(2#ijW(!DSvzlG5mELY#EaC)A{y|TGR=D=Q;na z>6Qj5FS3$uINy#I`x}=Rq^@Rk_O=X&TV7pO-hWQ|?T3Ef z(t23`7**YQdOJ72_3j1*e2wHLaN0>_@aq_fBA#~hO~=#kH?6{NuR_j)wT%G@&|(xb z7!OlBgq_lQ_~!2ioAcGs`;Es=@;vavKh44>Leq$dTS*M%xf{c?!A%B3@8D2iw+okF zgR-|K=R4nFZ#0n?E#Yl9_JPi-um9fgO zotzVRSt)aFlF#HonODPrWfRVmkLJ!g?XGIh_|}@Ye!+gDUYQ$^Unzp&g_gQPR@$DK zpSyhb&ke6>Fp0f)7J%y1-tm~@MX56GN}o_|WLb-;60EGbTW!?0Cqu8+QinQo7u%J> z;VrvK%^{~%7!<_N{mRDn$yv_h6Asvq`&U?Oz@8_zgvvRY< zy9o$%+tv#KTB3hX?xphBgQ#oDg83WSn)9mGj;ndF*l@M#8flndSoo)pw(`K|H0c36)@Ko$ld5v!B25^5>|#Aao_(@s%v$qH3vk>J96H%ixZ7b4|;` z-qN*Gt>t;Y>Kj5wMsb25@3wXK@#gr-y)_nzzVf+(Oohe*T|*2?@A$nC4$Q)^nbvsS z4w&9jN+_I$cw;V=g+5w~5Ulfvt_5_*gbd>?53pr1G_(XJN2th8;S`&H<-wwh_}SfM z%$e_lBaqzi$yU_Ocn>jT#SSF}EJB`Ckaur#ceK5d&DWO|+hDv&SN!-NKd#Xah(?=d zxb4@LG+Chk!L>zDVh`v71QWnvMulZB7e{n8m z(!5!;V8a&N%-tE&&n0whgZjCpj-jEr(Fay5b#gtHQ-hh>#jm0}u=^XdB#2#B1BFGxd&shZ+G;b{_IDBqUQKrS0|d zY#Dy5EdsVmoI3K{-L?w=!ro?Jmy&W%2Pd%IJeOwcuT${)Y+bNn=qQ-iCI?b6BhE?T zPOSp3=dr-SGRtUS6e2M6VT9L(Zdi!P7KmIAZQchleoz*p%5o|UqqEPysRrQ*6FRoU z4k}Y13ldo}9Hgn4dOb4O*hx-#R*r}a_-Vl|KC=8c+xpIT!~9|(ejM0w{0Ex@@|BfT zD51X-U*E%4_2h4}^On4bC_wbVJ_*oKQCtc0Ej@KxcN)JV9nkCK7R&9E+^B`oH~Ly_ z9tF8-SlxKPS#G==31m{>gvM)q{MH;=BCTb@`-!UL5~=n=mtp zPlyf920LCEZPhSY3TKhE!DQ}%YZrR zBTt0|l~33^2l?p}D9Q{@w`BPx1Qx&X8WSOl+dy^1!==K}kO z`O2S+0!%56kcpr~Rpiy<42|NobmzPS<;Ef!gzx)=goLIjhi=C!m05g{e*1?V-v~|1 zDbbcw$biPQLV|TIi6%KR3<({FU8HZ8#4sx+9YzHSrH7A&5;OPWdlgmT>5iqrrUoB_$5nx;w*(Qhn4hhLr$F!@% zEr*QE479c_w8pfz)Y(PrP;O&BWwmm=H;s%R23?cb8z zWLgh%7?8x^$fWNNpm}dhJI!V?j?DL^CpgJ?ZrN6!0K0=uc@+2o{99-T_<8eV%+cq6 zm$0PqKXtu%Jd|JjH$1JhiLBYlZc@r_kUjerBBLxL`p6B(t@B8|1X0GL2=X}=p`F!5<5tVD6fVpD$9&T3Yqxy8=AI;R2 zB?wGG78#~6{(-8Ecq_;>NnT^qPYN$Ye>KErKBQZaH4NlS^b@>Pc*_&fu`SEeD7gdh zjY-gK@lVK{rda#p31ImNupaCjm^6#NLfiF;Zb}U$!QnsK)$tPz?L97e6P@q1_h1is#w2B zhV!E&%e)!eO=}CEN^sVnq6T|>Mx*qDeV8mWTq7&a4NTDs1#Rg&GoAj}44>L76rrL{zyF-hplkk^a^vp!mIO)Mwx58wj zRW`HzHRuPj6zc=y7p-94Xp`ZWJ;=O|wLw#<_9iJ4G{U@)GFangw0}_Uuuy4eSrHS< z`=|M+Srnh~^Ystq3t&3YR$0#}NcZY^E+rUTWFt>*WX6J;G>}$u7Zvn(C>B`-S18 z<7+Z7!;O_3CzpxYBg&^Qo99i2X7XG@&wR_QSJXNO#;|$j@DAyzYlW^c#mqzow@0~= zbA$sWfU-a0624*dN0Q@S)w|mkd%T$q25+>dH;FX1*RIQ*xu{9U$p5A!@3D>I$Oah< z_EGGW@8@gtRs|yeUrH6Q%zsNmdhuQihAe6<+j>UV=++evGQ8xTXtJ*Q_MJin_lO>Cqc$E26oUbT++z&yZaswJ6Y9Zj!A4hE?!x3dFpFh(6-x)N^KL1nKD z8N`6z-d;yslgf1;1)F`dMB&Aq2W){_;Dd%}#rU%-rmzKp{8>;l3d?_5KTNwwyNLF| zxOn};5uKE>mkh29OQtGnOJ&R1LfvLB_F78<3+3u%lgaHPYAdUPlv(sea75a zX&`D1T_$_f)CWIqqd~|$9gb9uN7{ImzBm!!J-v>SfzABlK1lFkGaPD3f|Q2oc7?H{ zg4_R%|2%873m&6=sF!~ZdfJ_s8H&RUts-3gL#Wice$x zY@<(}8U2@hJ}^_Co?A$~*V)44LG4wrhxB61)?#Ikb3L7Q47tGdu+0}b_@oR*yD_0* zh~ET8$}A3denR9+$J{j({mw;VyaXu^vcNr6>k<7cMo7l^QcJXKte8}_+8-c`UV-U^ zsmDK)sMR~X<7ZmJgN@A%f=;3`()vLLp~DGa*Zwf0rwiKPO2mId{S<8dFm(T}M>!qD zP{Wt^`ZdpCMqeMemn3wru-VleUHY3vuW?ME`x_P?cb!qS?{TCEw7+z3;Nn#>ajaWB zG`0g|5u`?fpp|h?aRyVWmHU18r{Kre|7!r+)6?uuw#0nNBy6}S6C{=7DzAf?CME1& z+jC9r|2TkT+t{zUI@n%jn3+OBEKYnG)U(4P?%ZMKdL|N;+{kDr0L}PXp%O74{!}cg zyR&NOz5%-2rg9!o@7!Yr9jeo1ZN3&GW*@J21dc+W0M-L-Cc6hx0>paNdOVNIQ|KLN z&^#rQTG$gA<8Kv;YJGSAC48>^M(^ zpDXpY)J@*%>cx?Uac5*!I(J$`0f9bS_-*LrzTMQDmg??jGDI!{HT0Hysuy2Z_vt_j zv{tVwd0^L!>#(w5;4obgssXm1Yx+TZim#J=mJOhnVG+RbNcs|05Opd>=Yjzh5gO{P zgJt*j-7E+@%J0zk5H6y5eh-&fj~0VW4lFd324x;-D~c-lo3rsD>6RKOV+Pi@T^mnZ z61B%GJIp5VI(CMR2{K%|a>FK(y~ZraFrkI3LsZZhD5?0LJsZerY|7$>f4IFnlqdm> z!e79`REXh2w+RdKDKb86*|M1D|NZ*uW81H`MZ71IQ2y24`l~YN4$#dVnN7vYLj+7= z|CDJ+qq?~~kWeic*bTamhVw0;6|Yl3FCyqMG;mEUewsPY82L3bWHxmHcplh~;_taL z;FnEDJ_BlKwaUV9QuRl#sLd`Qi-ul;H-gC+u^@GjRj*I(Y6R{&cGG5|Sx6m>1J*^S zrS!Y|;dN5x1ABT0+W$`J9(1o1cm6`HcQ_ygsV__hx7Q+0OA_SOy zwY`S$#Jdam??cwpw$*uiR#M|xp!K{{WoNALBQ_V9AU8mgbA$J8;Tj+n8A9d}5YRJI z?tguW?AB9N0$q|QWJEx_+Tkf`U|(TBcmZ1ukZ}*Pzi>TaJLul`#)ke|PIn5)rau6o zn~S)Iyb?E2LdX}q49P=HHuXC{Be4gce|`b?)-@g*AK!c-VEMHl z_EVG3LT~%Ob8~HW_X3HbQ66B!(m^uk6vL$!n4kOJ(*&x{{XblQ##jBXm9f7)v`JMB z&C>sk5=^&7b12<%jC2E3lKu~4*bfd+rNI_-GP(a$1 zUSi|F*IV9h7Pt$L8mRN)S+Mola`qGerzPW9AAXGnv%_tP*2}Amop|w|UyH?~CeKse zhV)Z66SyT$D?H}w(DuEXkUqzE%{%^>cwq{;QNCB5#KC~Kc5P!P{_xBLRR?-VuxToO zW*lA{8u;()e>=d-7RZZ2_7{o}c%(@+cnqv4oqyKoac7Gfp%_(7MY zSQ46E&Oc@nr$nJ>`^k@Fv|bzf`AInTpRl~pJ5S1d&r@_0S~$fBdPI3>ChjEuVy9P5 zVq#4jWJB5@cv>By@uEKR`P{vx`PHVKxd(Gd5UQCQ-XC2rC+eS z>!U|QT=nLRwY9TT%Nxw(%hfONMl{#fO326@E;TGqHiB1w8xa*HBqX%(xakg{a&r0s zQ1EY4-k;A)F9}c_@rFd@vK|ea|Hgo= z2&f~KmXcD)_!h+?t)%DCFwt$T57_i}Ba}GDkjYPNYyf#&JfQjuV)yX!no3SxURb?( zewLZy4S|Gim|*i;ITa}M{uB^Hb|NStt{GpvdGn@SioY1mf~_4#rZ+{gc&XR8Y}Rf>cr*R_B6oE+|k3D)S&xA__JmsN&F?`JnPNZ*m0nwl!bE_8K~2MRet zMjJ*o@axx;r%&^WTWO;@6WW#Yh8D_3&&ul>CanEyEbUVO+WD?KyWJ96$_eMkreTE( z3LB#Q>@txXFJF+X2hvsu*V^F7o%j-5{x*?rn7^l=f_wbZA>Fnf1 zRJr%oR>$W(l4ZPSCLdts9UqdPHJJagp>UfvTz2Q1yga3Oz%J^DVdNf|zmb2D43Db8jXFTLDIEpL0CTp_Eho$($r zjQ97l|4!`4KkYm<52=Q+v0S<9ZgplSC9rmE-74NHWs^y^B0ZJhhCu2otD7bkFtc=Y zot?alEL-PWzfVjwl}iu6EC!umBfZQNox@SZN|-MFUW;mU?ZkXednjYM^uGh)j`e7w zvR*L;gZb5~8QlJT))_axsDXV>n(d27EX{#~ztziV~LAiN!frb;G%VitL}$WoUq-IcbD9bWYpgPR_&t2NvFXJ%%At2${EU$ogUW6{)3A4p z$QL*~UYvO3!rVE^yOM|9`#C7{;S9G)Y%t?DMfHf+#}Y^^EG$>DT;1I{b3XLXsq?#WI*rfPW=6kl@)Aw2h8OZ( zs58X{t)<1p}^1zx$p{&XNTL z)tBt5UOpd;#m4J*yq~d7&YtfS(g_iK!`@i*%!~2ti$J6arjIA@P z_Fv)+CDN(d{!=bSTDHB66A)jiNBr>E_Mvt4ntya?2qliVV)tMUhf zaC%=@MNx^A$Fx;O!&R6R7Ot^WBJw(f($KKo&2OpVjbJP)DPCWFUMdP@f^%BDLKZyz z1i|Ve_G(cQHUBZm4kN`SryOk)q`^ zzG_B5o4wp6Yk+Vy2irSIj+4(-nLE?wMx&5_g1Q(glUyzRVS^oqcn8_>fCPPPi31@) zK|sC(H@W0+QTk=zTi89-R~EJ=m|{3TckHh)tYdN+4MUDtz^#Yz_S$^&iqC^J+r##mI`-tPI@mD2!;FO&Bczu%|1_Oeq z%g$Pfje%pcuDS_ES;;4@#@OTsnnhV}-RT`ypU42BKaR_em5PdOSHt=&m4DE6?1~<+ zhTrT|m^cj*a%h#SWQ`_qi%m^UJdBC>9HK;@e8ckiB_8}8PIqJ?y^U@0{-G?DvfiJ4 zu#2Y(LD5g_& zBjgC@VjYUnW#-a)m>E#&9Js%=7~RvdJuP)d?cH+o{*qVAK8shnI{y_tq+x=vLKt5d z7z>1+MPW%&S_U}}(om+POl+ua`NQ71XI8!Y`nRLXe1%;#7+(QE z-KHiP{+Y>1bB42O?<8=a`BUhX_ivP;PGn_?UX&{=(@e-1j2Yp5)QA<}6u?)oywvjP ze4LV5_O{9M$muKxm0j^}&|}#YZI({4*C8|t>PP}pxZo2!Bnf(^4oHFmxkf<+c6Qyz z1Y>A;-D*cr)l_2b=H7;U6oT|i2#Sv%P`lxldJJF?jnq% zIF=9#6T__4os}7lrNSSkEh$dSA&c&1byLmW+rdg)Ie+4FHdl3`0Do>NpE_>$)Ceb} z;}4Q^8_mDroI2ew_#Dc%3b<8-(>T+sC(@G=6ym2#)mpa>bA>#Z=Kw#!&rfb2%uBsM zJ^rdU^XuvP`T6N-i*>3I2uSdtSw3(Fy{yx&JA0d?6mb`K_-c$fwPT-gz3Wo%c?$g2 zx%5@A+!SwuTkko5m0sTW^Y*_RMLzz9{eWCw{hLqAW@|fKCLdZXt@r7mbRUoJp9O0TFi=S~8uy4o?2L2pj6$hvBEnAT>#{mJd zl!!mJh{3;(Ypa_oOh@pRY^(sVzPlaoBXhRP{Gm0g;u#;4$t+T`GZQIX zenn~OAp2IKImu%%;L1N3h{fvh>xVYMx+Ua9iCi?+&3RRn*JQmllE%+?@WtcrKi?8Z z)*ENsM-d77xPH-)MF`?ky>8XU{%`ZSUzcfeZU@8CIj5TG(#To8!H;#j%{E#e8LirG zXQTfzS}}KCk5swJimyuV`&kj*Wt#fe^c`eUwWCiCnSNs0_YM_KXTOGwZjB}trCd?&A@l?m>%D53Hm6?D zZfP>K=@Pg$_G>b$czw4lnBdwbCvCRQxo5cj}^UD1j2t67M+zmVPHh2Xb;kTOk!hZkx^MzsX4|D$lLVRv4*^zj)d7s1? zMPw)EiMvp|ubmUG(xTQ=+H$m~=`aFe10Hx1p)`eL%4B~1K54@gPA5+(a=aiTe(<$V zQoB0WWc}-`sY9QE%J>^06HNQ!d?tnQPStG{a@YiS*T~lR^CzoZ;&QUTn%|M)ew1)-i37d@)CkBicqh))3+Ygz zm}5Ysb=~5!MMWGMty7h~8bT(!p1ZEh=nR+~YUc|%tG({BY-`(RJpHPuhBJR+%7VFiQYabA-wbt6q>?M|Y~dvn>v0w>1ngt3jH)lwhVv&_{?5 zRlv2Uwu?B~gCv<=QR&S$vH5Gnj>;p*laOJ98()pm`-^`oWv5 z`KR-?yHbj6M+%cz272rH8W}s@581cpU5o0pYUclActpPQki0GWMJftba$SflQdn7! znN?0I#{mYT;D`PrfOU-_gDCNNIwtfxoR$kgXwal-mY$yZDPwC6IwjX;G+5t85O?~> zb5Jh0;G0lL;bmwz<71wj3mlCO8I3~k-1@ZZLqavXoAdir(z~0H!U)*tWyLXEq;T5= zbUxv_mG@~4YQ2Eu^M>ed$9<|~Pz8H5Q2eIM=`ZQbi>2?TE|Z*`oVT>vr>AEp*3ZtP zwqK0~ZuM#m+JxjF>6@3MPmR9}1HQq*%AW7)gk5p^eMwWc-XG3o(>A5sf|-b@V?9ix z*zsw61sC4FMYjlfVDQU85d_H-In}c(4%+FwoN2cV)OK5u!+XK<^)2Ze`+x^%eN;N_ z^|YqCxkQ&&OrRV!WHuX;W!0iS&)OIoCYq?e*Dz70qCyo8%~n?SQ~)i!PVqDJlh@M^ zZDJW9D_l|^jF;ve7mox8#^UmF;O$E~Iy&LO!R}%ynmj4}Un`uX0bNqbRPpI`M2n{U zg>(u5APYjpqHIYG!txu#l}}C8@#{j9=RC?EO62A7CXOd~=whTUPxT=qsFs)o+MNUt) z!$+O=7bk_%Erk{7I`M(~HCrr|vh$}sA#`xUkbuUZ6v!#sJn3iJQ#0jGcTPUPWRN+W zwD}%h`RGJgZN8MqELcPccktzuc=Cnx%l`43`7%SoV!x@@KQi7;zYhELSi|77nBEuu zF2dr`_w+6_GA+T%1VfoABc9t-LFoy#xTG3kawvnOc_W4Odv0I8B^xU4FzUAzfDj&H zpjIxI9KYi0;jw{Zab&^h!0ve^pmzU_R!+N00QTiUJ0#)r^a?PM&2wZH-()k&7F8WP zkTl9^bH@jBa=dZfmgPG~qjxPdlXJt{GYKSr*H%tH{gdSbsSZ+HYmiF~gP*Z1f8Rf6 zN}93XT^K67>Ri617XemEGKyMxz*XYk_P!f)r<>pMq>StlrROr|N*1DOHYYnXXyV(wd%i79E+gOQ!wYhmHI`&pBJSRmKwPbIY_ zj}mg`d~w8$w%aTI#hXuV|Ee!;nqB7oZEiG<^KD8aN(Av;Rv@^A=3@n}%GVkgZ=I|F z$U)FZS|5u?bk~VKX~cS;G!6b+b=j?M%;Pv?HYxugTIE*d3@4M0ze576h<=C z9*LxS1#*JVqg~{k?~FL7^+~(LFUwbh?vZo6@^I{|fTL1d+}UtvAYtatsd9Y8KO;fW znK9?1K+gYVX0}Hc3W@O9y#3A7?0$o0lvFdyZmUtwE6_iTd~68gOjL+R6~y<1w-xCq z3G`(0t>Kw9A7XNZdHUsC@5?ODOvI=7=+%}8-lx3IDux(j#6kPu6FKpBlu(8jIGn~g zt-LEP&wclhk{Lfxz0>i>r}-g#=MhJUa4uX!(faZQ{>WX|-)(up1?p^MmljTyQ0ElY zmz;|Qezsa)K+Aw1^)45OYI(jXa9PpWgix&?W>tY4ce1sK!6kC6@l2RtMA>Sb#-VI3 zPJ};v?V|D0=jazL{=kW3@@1OqkY8)7xQTa-tSz||%swJv8+2pEpZ|VwF#lI%v`fT= zpeJ{d;+0!VzoU^3si=7ygOfDHOfeBLt>fSn!5`-S>5+?Zf-b;ZQkkqG*pM-=HUM3S zPnvX8rSp?_B16?e;o+0RRB_$b>%$Px|FNM0KG!!Wn*KTYVcbAtqfv} ziT(ThqN(iw*(x{ z=I;rpVP#|UO*5uZe#eD# zBACu8r{xytV`{&^8v&=R%Vdz?NrWH}W+|02W0G6#$;^BCGaMhU55n3_M0A5Nl2GlG z60A$kk<+_=&{w}Re4m4i6=a~*!-j@-#p?+1jun5aUO(Bn2`wFM?Y7%AK~d2<&zs6h zNV78kWk@9z@O6YShW6acc=y{3jozz4p>X{3-L)B4iAMi@Pd%Cs)^^Ej@p@@1-7b_0 zKhP8A$4?@r6L$P8z!F*3nE@kM0r#Jpdl8WtdjA2+gl5Kl7rQIr$OcWTbNNGnYMGZl z9rvU>YepZXlEtM)K|uk>hY=r=3o}NBQ2vx2)5J*1$P{Dk0YxDi+1x#2m7MDXC>x(O z^KcT-+uPeLP%dO>xZ9kbJ3sNLhE?|Y57MTPPbP=o#gi0IM5}tZr50VtbMdn-xyAUF zdmR7+=BE*olCk=LdHEuT-xOP<3I^rYsH~@?R5+yW(6@=gpg!0$-PK6J3iq!g`aj>+ ze3xB90^Aaa=NtJG*KoanSge#)*00uwY4VIT9%gn|?VXa|#^=`7(tur!scqi43)@ex zQT4B9Z?39=lv{HU{7p#JZmrX}pSQta(LBAAO`ph3r*R(6Vl?Ghr7HTfQ*5jt6Djgx z`WMm&vL8TdEaq|s=Ame42$0k$;;3cpoFrS!7h&Lw%nSg&loS6O;cx=oIhkNkCVe+L z-IDjCh${|~s9^SdEH-~(dUDde?u%60L`CS|)?hMlr0Bq4QlD^(txwn^-^!#DeYXE`UATgLaFrS6}uN>^|;7g1)q{g;n&90MuwtE{XN))?fu1T)Ht1M zdd!`V{WphZK?@rNA0EI!qxM783jFQFKxXeMZRw77W?p88$CbH{5=_%)QcN96;K26B zyUV5@&-u0>5C|p7+GpSsHI>x;Qy(jzH%-Rz>Szx-x$z9>~^ z_K=bBai-`_L>J+~8wK*EEyuOe0><$v+_H#Ue*7B3ijQ~sgl zZJ+dHINn=PloK$U0kLxZ=)i~MJ|+$T4Gp0L=4Ij_%R`5`Go=Pc>RWU5hyjI>)UZ$J z3NxYV;l}~HGsk<|$NR@o=CsPO{q*UJQ(YAiq(%S-85zENeGQSwP7W~6^gI3G6e-c-O!m@Iib_r9%ODW* zyH;9+w%f3ll97`7Zo0g%=hm8?*7BW>Y`cYeXCwjmGZ&ZA64HR}#_#rUUY#_}JOfA0^}AJ) z78k(iVM-f);!}R>ed0@zI2K&Y6>q05^IfS^n^N$+339(83KFLC1QiTruXj;!le*N`@Q{c1) zK5|IQ=^1!H`37kr6YTrKYPWS0UrSb0wGIDiYkFXA2dK9h$XlWz+V#koeh8&cn3*MXAlSr_!$cw zqSmfy4Fn`7{9H)|YOVP-Mq{NO>*t!!u z+G*FFcq#BtV652HFRZk#wA%ZvtZ*&S(waq+W+&#wEam z6!^oSJ*#>3v=v3tOKwTAP({CRx3{^8FUS@xUd6ZeusZgAEuyTp77I!U4XRRSq8Jt~ zfE3P%M@U!_4N8dKS`rREfb^FsGCbM)`z2u|rO927r+|L?8}`WZPz4NQ9WyIPBLBYW@BBsLn`WarofTvMA{|O5VJFJAxyD!(E=CoTb zAg0B5_HFYjkd35};#b+-b|ROo*MU-${c{LmMDqzQ0CO}vqA6=Is_g>4OszBgV-q_vM0T_{c+nfcXn63@96Gc??u8Q zn4Fw!Wo0$bB>Yt0KHx&q?kn;96!W+<@DiF2@xE>{cy5X?q#;?oVo5HJ>D$!4vgZ_1 zljC)p@9Wgf`bk3f`0R{?n3xf4?LyPFtRW*Kv#3zT&cVd+zRdLcRfk4?euDi}qj`me zg}J%V2dNorXM*mhgwh&Ulfv(79rg3b$SMvoG>uU^rNHnt@#>5Fsm_Bh>wnv1X^@pz z^h-mYGb*V~OJwkfs85zeps;OPc4n zt26oU_N6QY?fFa07owEoAiO%ILlWx;N7$PDqXo|fPm6d)dwoypni0G~5JT&}{Hg!d zshNIwBOvDY7kc-CV1JAajKfT^EDNq$8LJ!kBS$*kXo4g=rx8iPbl9etHTANlQ(LEF)-io~LNwL2p0CbdAB@9?H<`rQQrR(8&{(bNcYRgM~ICt#(GMW zlds*y;Y=oJo-y9&F}s&-BwN8;=q(qg3jA>q&(TE(N!VWw@nj@S`O86}w0V1+rFlaf zbJrOIuRRbf9LcKf1mn{dvjMN0UZdAv9c3n-J*sa%7nZz`1Fqx~|1octigjLWnS8?F zAX{R~c%;+--OBtD1c=_Ho0uCm%p|E2(aSUKv+Nb%COmC@jsLqQsw`t0nY$!!pPR8; zIgkFD{=P&M7v|PiGDd__M8Mog8TgJAxPWLzbAQ6g6^m~djhr_lnbREg)wzAq5*kg5 zMB1z@t#N}xMj7+z@%>WTsjxTIXY!hn!1*=p@@+!2 zSFV2KT(@No4!o3X{Dfw7#Lq>r3x<^RA+jh7oG~I3d99i>{k3$eACe$$)>3>&1dS{a zfa5PF!=FJ=)KCl}D;2kbGogyj`sLZJivvgeQ8k{pwc{bEWq!ynl`VdXrZT`fe7?gN+1RbC%Bl(Vuj&12an+mg@b>mDvfJsOE!D1;CXI^! z1aCOess}g>1Vr1fp3@1YVUME}+U6Da=BGc@untUFDT$lDUc*dd`~>`K7WMAZd`V%U z`|p}Ed`L;EH_jF zz7&T=xkp&)!(MMEf+55aSOzVm8lyX_or%6Nrwg#P#;V$l#dD*V@Ct%K=ao`{h3UUn%Y&Ez6wvSMX4vBVHCTh{4pCbO|g=B5VX;ky(Sv3xe zuAWCFQ$^brtgB)tm1MHg^q$?Ft+n~>W>Q9=e4L2Q9iAGsYm*T^Y!<-aN?sMTMuC@HG}6Xr@HTHo*fzE>(?|Rp zhqXrX>^Dp?kZTYx{LV)dGBSG9LH5o(IT~EVPdLZ7(oHQ+US5-1nnZB2sa&adWHMjv zGigSlGC9=+y>8BTyKKCdxaxV*9VMeNU)MHdqGWvJ6(7upYMA>%L`xUfJ*Vp!X)sEK|}8jsA%9~ykeI%b50IkI*B`ebDW}ZK=&V7*TNK|ht|$0 z3NVo0ho8=5#6*A&?1*Y3zzd6@HHY|4B%tP4F#K0a3=c(aBvdNpn-(wwsocz}vP=|Y zNf>!HQ5Y7r?^W+Nl$8Bu~Cvn9dM@?whgL}CGL1jVT3L2!zgNf-!FAAH|Fh_~+^xbF=tjHTY#%1di$VX1VKJ>B`d zq;IGPWxS1F4RpAGgFu`<=3UG|7~kPvK7OB-ewdu@T;2%LNG%V80dfUJB<#DzG$yJT zG5#DWxiE7tFIKcfNnSEVC{n4(54wvXz-rOMQ#eO&o=uWo9Xk+H?AD z5RuJFS6d^6I~d+)%ZMQN4-uoZO2eY=?p)h0~VtdvMp1b$^%R4>FL(qTh50m)MVOG?ZRMx(=A z++0ZqhNxJu@B39rlwNxWJ5t3MwaxJpV6^@P5(O< z`y<4_9-8h@iH3Q#^kMzq9qm$LBAn8N1p=h+mu1!Ch9Y z2U!ypkAIPJUVK8vqR~6W45joGehVvx7ZwGqE1{aM?>yo_$PRQ!QeY#-)*%IV^6(K|;!S{u0 zU(6_7Y5o2*kuAYCV}J?47_8PZwNXG!M1%+v_`_c?L7~v%y~bcc3^tzKR%XYK5I0s< zes$pHWOah}XR5MLpV{o12G>u@o1%2^>oJ`jI&a9|tP*bMHcy3Y>e;hCxeV1ZAh!nH z4_*9NfvhIhcM<+ANs3mhMOQj2t*8Ufel^e|mLX3?MiEaWmTpTcku~8!5siz7hYa&M zu;W}Q#Mvr_S1ufhwgBn0w#Uf0*lth}t`Xt!<+YmJe5Pqnw21nWJvFcvRuOR-zPYVH zD8YhVfD#s>;%%z)GY;aHG(K2KxT~PC$MKt*Z?RjVi|A$+1@;qX<2XdGb7@5ZA|fIs zgQX1EO}1WINWnx{n`gFh4qT=$%dxZ#es8amfm-gt|AJ~DD>MzwmqOG)w2IsIMgDVT z1`g6Z61ZW#R8&TT!!*c=&edVONdN z!Qd~hEkB^e`nkCiOQ+85_8EsMRZs_WX=%xrBplfb26dKLg+%3>Q$l-Btv_wS-*i&A zPwIpM~?@ zEdCEIq2~-rknmKr%gWwSi^qk^K>=yVE?j~G555pu51F#xsPM;wKj+j&ht@Q@q~uhy z#6@L|RavuEwJb{(wTsXlabCaGZzpEegvKCHt*N&js(2~BC;%UT;|`xA6Q%xB0HVsP z8B>E=LStBSVFxsl^|3nu{oqedse?oaA`~-BbIs$fxt1N?RY{$ex$A}$2UrLC>FG(8 zHu2G&;TTgR>{<9;7|UJb)WY6gJpwzq_`>(*+d<_w;eL(rB`zb&uXnOPIgeSZ{;tKy z(l+eiuRa|4OMgJspl4dS3HoMSE&Ty+81s@OjyBOaBSBN^eg}Nx03=t4IpEB37fngh zY{^VTpnRVES+Ag6h4+JFO=1R5g;MyKmj@=bLPLJ(gn{Acq}sc%K%+7%T}-07$bhPt z^cb^S|Cdts_R+bg8xFU4kx}}{Jm53_CcSA`X)^Nw1z!#shmiIuQ2a9=MZKbLhCK$?c-Z$5gQju!+4OnevMj4oOpJnmP4tAVumU- z9s$?tmeWFJVSr`mU0lO$BTxeP3tJiAPl>_j3Q=~*UR2SR985^V+2=Z92T0? zv9$NWZ{-(EYoT&sT{_VE5CV6;$KNr-VF|^vKl*o(Z5IT%y1Fu|GZ>726Ur&pRLM%N zlieL1j;M*6KRvapizoAskB?vY;+(atiU#fYQ}fLFS5?=nGX2$~FJS%7w#;gDa* z%$q&_S4@yYCbG9aD$DWLlM*@t>xL~iu1c{yRz-F7J*P$xRG=d=*0gwGz(@pFb?@5M zH5ebq>J$-L2rz++E6W6?-gGv80DUkhu$JVni5z~Lm6BSVMelx=LY_wZ8Qu9x=A4L7 z)!06>hA#Ix+IPK^M6~TP_$vd5R3zBSmZzko#Do@ZeY59B4F_0LQELXMQb)Xp88J!4 zi)_CFS*(~MCX``%Bb%u-1fd}#=9Hc!+fWqdACwyq=2`#ThB2Ku{=6lNPHtnJ*6Kt}bWER2pTM($dny%1LqZ$+WoXqaMP3 zFXOm4oz^HQAxt!ExSdAkt@g7ehw~e@ALBh#wb|Ngmp9Co8GeWXvBrr@r&L@|kvDl*lXpyhYATjNTpaS=v|JCzZ4|KTd@!ti?2ZPX6Uv z`exmh{(N%`IpvVQGuqa2U@!6c3H9ypd)?K5{s^;!_#XGITR)rHk2a_;+PB%4!&B*r zAu4Yw<`&JB1Yd)EQ=WHJ@}m$R1VkTZSrrTPzw;>NnBWCyh+@mXaf^BUelQTfox&gm zIgmHf(#N=!{na$R47^|eeExgM(Hq1St|B!gu?_N135U?fY*D%_e4PqR6Hd;x$YmRV ze5E?)@;iK(g16kvJxxFoWQCKc8Vg&QWvugYoSCkbJTtfT4|A7b!w++9Yj#XDt`F>) zB5Xl1%x~9=vaN=kH_w95*C}jkd(*n(;M{lPDsYlcYn7gnHOyh_L>KbBjpruaZKYrm zbRM89G{cyRewX!8oXEM;iv#+yl_dv_?7lDl-H)CC~J`ZXX+51DEg{LudJ<>E7M z1QJv--b4l@6w0kFPKJdExfe^A-q{(Z+Q!5&Q6^)V7pf{b)ADK8*Zz_3*CM zVF(eWc#GT*bG&U0+8}~wWajOM!8w45ss8X6iqEt_vocY=sQ&1NkiNn;M0}F&iqbf~ zy2==mwRYBbOgJ=+9y)!k=o{Q|P0s|xzF~;#(?i>!cCm_1Hcoufp5>L0mtK7pQHS@WH+{Z7DGvsij? zXn&Y{zidK4m7VO-aTFaXo(0Ij>Qd4kwcMyTs|!HG@8$Xtf?^cx9221~&BGz* zT>rIX^;3)+Fuwz}0Sh)TXum~!`}#gpQ6**}xg(|U%34>tp#=sg7HI35bEaVY?%v+c zp^%E|N4_(t)F>)0K5=X6Fqm&}H0CBmfeBoDIdy-4Aj~DS%8%GB4*1ht6B%^_!fO6& zG`cc32n}GM8ncPAc`5d-4^a}t3l)YUVq#$Wp$UuY=|W|}$BBq=5<%jKK7Qgc9D&yh zZELG@96!hQy(JnrkWFpv+QG5SOQ4`fm$~3m6UOH<{@cX)MJsmvw}XsV8eF8)#oD7z zFygSBoA{>^iNSn-Na8Vhp;B^BJ~KU?II^3bo__ZI%v&Oy@V9t2NK|pT%5;c4f=@|Z-Mm)o#;b)w3KoSBO-wQQ z_jS>_Q=%0Dp0l!0kP@OqeZ;@J96w_0*-^UCXy?;qp1c4Kj{hKZdLb9ymBX20!Pkoj zE>2E?x92N39JsK)Z#dldUd@GWKp_=;V)$m)CZDfutZ}umh+3{yc{pB1-D+EbEej71udAygdD)j(d*0f? zo3cJ)@8fbRs`-v!UB-L!8$QJS8$tKRQ<&yp6dnojZ_3pteS)tQ1KqcIszQ|3vn8JA z9k6}Il^AcAOewzC*)W>ED&=pzb+(&pFDoL*sA>e3gpBmkL?J%=JT8#C}=uM_w zyU28JraJ@u1LJgLT@8k{6_1q7*BV#G4X~Z^nXT`a?@W>E$jHd|@86GROW#eJmz(?k z#NMx|wUxMidV2c){vH_oMSaVO?aIo^V$g4#byQbmM^ovMqBO`wt^Ut&9FrzB2S-Q7 zBMk}LCS-wX8Kl2TDk+hqa;n%TED{tZqzN=Js~)p^~3qIWM5cU z#~q&?1*eP2UsP;|!0qtt*1CJDcK%ahzci?w|F9 zow))Ru(jz|GsG;Zd3>Zly5Upr(FCr`@741HK%=F+?t?zk_A}~sWdMN1=(q1QPY_S` zh9*eZ8Tns9l98Ou>wcQLV&~4A20CqhIt9=%^NjCxSy=)6QtIk+h06J(sXSAYlS=yf zaup=QE`0nnm}n$voh(ufoD56g|tHpX^C%CQ350Oa>z#E!3CuE)>K?Xfe6wR0aw zr~cuG|A?8l$fpi*aU_@>h%cX_W)Cd8x9UYdt--!_9N4fWS%E-A0{RIa*}R`h5m>{P zPaWU_94T&R}rFZMF zfI3g@s=WQ0191=gk*SRyghpC{?_cCsJh_&~)eoaW8Z@t&8b*3a)qL>c@rF=R(Qfqf zLVme0P+n7mHDrPespli?`q84bB63!(2AKrO+vtbcy ztQ;IRoNdQ0=|JTax;aM_jx0bzVOigG@lhz!Tu*qOeE+R{b<*DQyT0{0-4EnlWWSex zZMU6Yesu_3hZ#_WSRiWIRM3nf3PB|yu$I|0vVset(6jAHPCUI82p##av*{%A^Ygl* z9Om&kagjiy8G?SV&kvQAl>`d0D7gq)5!#587#d=Rzj5=A< z20y3;*ZB0u>Pujf1b2N5?IA?zJE>ngbsPI<$16wW%>Bn$zdrk%VLu3?lCWnby6UT_zk)Gu+@i~G{AVgTA9I$wqYf`LSW z5&Z-iunre|l%?20zxELU{KLB4fZ~$3-LBS7nj&1gbR=s(E(ay!tP54({`!xtYom@= z%c>107YB#!OG?z8@9h{ks`h>|!Hf5`7Qf@Jg$2TZ>DFyHp8UH8s>~!G3wbU@z%Qf+ znO&xrzmKp3nW|j3i*t+FendOYz5oGeS{k4P4Nm)zQ9o3lPDUrq;Bwr`0>QHfFHFf7 z=mH#iptw*!V>G8`|91~ZQ$H+|vUBSzgO@VG$-%MX!aG;0ZC<@nApwA&I;!AG7M-Tu z!ZLB{pQ1)r^SC~2m)}&uNuEOG6rMyVqS=uLjEz@42!BI?SaAO+$jwyQByMbk$NrtxrBl<~b1uic8`(kAAYDG_YSq*fM4^b<_T-~zENuF_S z-~2rTj{O4J3G*yow(G}f?FiP+fEOuTOLSBEZ&|ldv;E3H4vV5ABrAHQ2A2 z^?siGe_8;6oB7W1X%}*D4?HF1E~;ZZ(hp@0CD?X#RV;mkYu^c&f=@%KLIT-waoYa75UoPel;>?+J~-%D zCp~RKrBkB-f6EW-3%qsv^JjgTr+W*O<^NG5)9cu#%y!|j8V^gwu{JYPJU&X26dTgP zrY~H-re=A0a?-%=SKpT3`8CNe7M9m!54rEi(K3et2ZU$kZeAmngd&?@(d~}@F9Bz8 zK3^Q{_w_&+^|C4&bc<&;Tt_2#j|Y+N1+3a9f#h+V~k4NsB%n$Og=Slk)nv zfYq2J0;Eb83)U>qI5ix?Rh0f7^T z)8>Au+I)q9p|j4`<96YoLujb99>_>qpD%|9IBnp-!XkqBPTYh}`8L|d*7urSwJBv} zl91VTPf^^?yTe?q7hw`4->YjPct*@`!H#OxB41B>SP}F|vxNF|K&XrkvoUIQh zE_zZ>;? z{Wt3t`X$@CGvB)=AWFY%;N>zgkW5>#|APT3M53 zA7jiG?py4Oa>PdEZP*C|fp%|jFP&Umc;XgU+r!9e3qZ1ZYYr+zGjI*gFEo?NnD3Mh zm-dxHdc(jlJ8Y4GgX*sYG`z>J`aGGoiy@AhVAg@00o>AK{zF79hXod11-_bLz`>Azm4xvy&K>Jp&@ zGwJ@j2I>>Q*u~4|su8MD)zy4&J_~ww%@lK%&qYh#Ps$;lVsfuYMd2M`QTju8vZN9#hMdUme-+Z8)2E2EW(aAJOZ zI4BT1JG-o`Z1Z_1BF@pF-9NWdLEPuX>alcQSA=%;w#ONOD36MY8W3dph~0rpQ)jxnS zDI;!q`LJKrV&*0%FM)apyIpRhf}9u?7imv9q9f+g|_%QO+v_yHbY5}GZ=lvJX>z67sqVdcdKrviQxq#WkMD< zHY#Pkqf0^OAH!xDURQj}{zGP6^I{A02Ts_~U`5s3_0c#cgXTUa-zBC@4A)eAy8;ik zTFc4F6?(<1y)`_@@cVuwlaNFc{c-R|)J?a!zwXYXMdUXW>d$b9Hb`H6MZ;Px^IT2Z z&Z0#Kg_l1=&kr-jtCf{M4iAG54`X5bt4h4gQ2c&#_P9oT5kv`1C^{znJcC1^)z$*xLk6h|Li!|5Ub=Y>8*A{CfpdYha-!6mboX;^PenIE3m__U z2`4}z6Pjn|MbNyJRnTX~B^@%Zdd^x{Hm#M16JB(|4ehD2v_bNhh|frs!jl6Zq|y&z z$5>A77dU%87SpMn3-JU(vEIx4OdZ`~t9=8!9DoU6VPRolV5q99f{KcY=7RwJm&<Id{5(a)65{FS&6_F9_~?K<<(F{=CETIug%9S*4uuXylZ`GTOl(owv@L zp^Qd)ZFO=o})siNMT@ojqpAR&neVxo){*Mc0< z|8~UifSCXiA|AzS(&jZdj!t3e#PUW#O3yPNG(VhG7pM}=F%+b#PmOG}cpx(D_5%cv zleJ@UMFIF0++v)W+~)ZO$)qZo*WkjqSId0C+6_%MY3bz;MWlduD9fOLRhSDV5I_K7 zNK+XQgJO*RW220Tz|kd|JcUt8If#))b=Y}vsf52>#Fh3id7RP2;_G6hCO@TpG@T=W zNs%)N^lV9({%Yap=T|5PVFnh?1`eV>YyeQ^_o)X9*Le`OI1f5a8o$=(qq*fc_NrFR)Ain4Ohn zdTlsc^w!>uL?ik6m8wk;hk?(Ixnj#Xs(uRw5~EH>CB`v= zzWVc<)<2nyDwFr2Dv&qL0^Ho(8j6aU zb4Lu=GDRHQTKo2wIHHI=vY2!kCBrh9kZBN9_A^XsY%j`MU#WfoDE1QQY*IES99c0r$K}IgGq?aVzK+gq`b5T09dnt$GvT>@+#6OGJ{f*rDta7{?Rm zO1@;-tI)w_+?mhqM@MYmy>gLw-j$`K5;%zncb<*+!o*j@J%^6Ui8BJM^K1l2Fske~ z@!EF4ir~*Vn&wO!RZh>%Ia_Nym{5k&VK3w4bsFUl(^PpOonorS_zl0!ym;#F#Ka{L zrnCN|^EO%f$*_&IKxI?3Z{h9zlqZ*>LCS>lqRvuz=!vQn8$Dl|o~&sFe+>S#^08fa=X=yyyJ-lrvrn($Ta zCUJa56HZq^ef5}A4tE;1gdTL(^wgG&(aJB+YtDhqB zfF!1!=O_a`4m&6{GdNtJJ4TZI&);Z79LAd3+RSBHviH+tg)RAkXZVl|mSOu;Zs}x4 zRU*pELC@{mZ&ul&xg#Kn>a;Xm6mD-8{;R2Ix$(X7sbsDc1SC*JhES^KJkzYK;P-gG zY>-JA>9}mLu2sOG+lOTeUWAxzmL*G}GBLebMv<45-KP8b&18IfcGgMXB8f&mqYYb} zm;A?Q`@BRi0{VxMklZ1szQ-?&W&hyXPpd*9z2}eku5Ao!Mh#X>A=!_`6?(bxt@8-4#m=?uS_bjx?{x=vv(?wzKNR z|9zZ~CO!Q2c^=zhltQkFRZ1t}5%qmkrM5l4x^5WXlnHBQDr-r3xqG_1yl$crgLjVa zuuagvpb(4?a^T{>K(u>1eux?&KW5*}1OLwoj2@icrZM$tHtEmpv4`k-qQ9cd37-gi z6O*pwEVwh=?eCLUYMf<92(-8{?8Z{Xz~^GCsjBYef}=+J<80MIB?Qe|WoNd%S5e?P z|5QNeRwXTzPBfU$!}6Jdo=I8qJzd9HFwh`EV1Xw@gVJ`SjEu>~z62GD6LQ?eCV87I z{PS{!I3YE6aA3wos+zo9uKk9l)An|U0h&c#ow%*M`C*LFu_jxDs)g&Z#crxj)aBT9 z9vt+*;ym8@KO?F1!J9qOuhDpfz>LqE;63<9JO9h~weKJp1anxP zt*x!W5br(Dy~C7)ULClTZY> z3dLbN!L#Gbfe0%@R>Sx~MS2e65tJgch#^4;AJ!)(fVfn_Hl~g^)Pwn-Vw9FINrX*F z&m~HV-kBYo!f87RfvVq7aX5?@)`c5DszDzg6a=G)Nl7zuiDHRILbAs)`S|FSi#Hr(JJ1qb3By286qU$DYGOoMPo-Ar+FS zwKH`Dvcc~EO;U>)Ph=Oy=Gk91oynRA`lzt3uKesa=5v%2Zc{_kiXD~jpcwWQmM{p| zDK^g>Y(<;#GcMJ+IV2CJa5(jyIiXxI#%ks3t={l;v)U;w>EcI4NHt%zNCw+afIztpB1X{3yl6e2S$jP)gO?d^QIDE zG%N%ML4j@-Yz$t}vt&&ID!uHsKjxF2ulm;&7AF08MGuPsI;jr<%9^T?9bopEyBDs~N@$vSb=h|a@SAA+n3n}(x zWkp`Kt$HGF+@65s4eZ#IV#C=tJsk_gnxzwbEo!N`{5(6%a|ThDSoM*;f&h>eQLXxE z;|G6FAy5jcJ@GjTXn$qCc(SubSmQA-5@;Lwr6g+kG-;LT=C49-8q^~uAtB+)n?@SK z+u}QI#A91a8!;eyDohQ>7?H1;gqS@o9N6J+ek09*>3iJl^FVJVL5@g3q&xK^2y>uv@cw)zLeKOSwSBiMrMOKUx!q?XRSl61-tc!y zrxFbr(5ND5noml2?g4VS_i1|JnpN2Ih82xEQ9b!k(Pv}kT^|vS5U}pn#7`Wtkb2Ds zKp4>LY?MUWGW48R4FN3d)1Rg0R0DCC^h^l!%5lD~V5E-(lYks9TN7TIV(iCj$9g!0 zk7DE`_E43DKzpNUDJ`&|SpYdO8^Mq0+q&>5L2&lD$yP_T7bxLAhXF*Ez{Z#@B@nl= zTkG>a`wD{MbCj(j$$`U_GhxTu1(}1tp=?flO(~R^oQzLQyxQPM?w^^N2@uZ)D&_VW z=`d(4_)lh{ih;{SWX4ujd^0#f!eseV@PDhSl%jJ&)(~E?$X}@hnI@F6&#@?Y2SX`= zD4Fc$C?pk4A;pRx#+w$d5bK1c!_`n`R%IrN>xfH8=hql5ShQJ>HFGlqx%%Uyp{Q?K z^JM}Z8;>ycB4Vt8OYDD^BO!wLpkuJujH^lnJ%+;%Xs92q_QJ%CsWGkC@J}upi2F^G znf1v;c^UqQei|I;97>(J0)6+lMHY}(G->*9`hFLkFSGwmn}?? z8o*FajBUdcv)zr)elceahAUcT-q2W6kr9%RnDg&RGxJKn3%UkDrkE;N*fNO{z~g28R+g4G{o&dH zMeEsZ${j_InTvNaSKJq8NepO*TQ+lrRd;lMZqnJddSd^rq@2inaiOF10%Mj*b$mUZ zCqZ*n@3@MB5>hyz{yqF2itwIh4nl^(*x-Mki=|<+Vey*DlEDt$=}^~q)ob(RLHDG= z4(;0-JpUWQ!z~;{p<7;3qDB?fYs3Ooj{v zA0U4I{5d%2@dq=Y^1|jUxCTG>OYW7p$9_3EIkCxZYxBEJ{{!^k(5Oa6JiYj)cd|VP zZA>c!JprnCWLMLgIX=_899gpeR^s<(bL_w0I1Hw!=}el!Z5EtXte^ori;4QqtcW`` zIoZhUmmKAy4d-yzN7l`Y22zzPk_e(FvAwB{WQ(n1;liY0qclYrcwYlEzSZSn&e&Fm zh=pMUhUVy;WKom6b6M3mMiTpOL*?H`reaJ!z$t%Ujgu;2+bK`1Uk<)?ZBJo{Me`okid~|{SsFY45cG&4BOt>%5$olrKrJ)LNj@^|Zrc@v%)5Tt(a|KIE?e5Pw-Z!&6^i(C(8)2T#%hLEz}bx3 zZoQScJfO2CDa+1%YA~*N`7|#XKY~=H+K)43Ym;kCSI-q5aLuUG{2LHx2y*$H-5c8) z>lO!91+?UG-V0BvqkkCx_nGP*keoZsf2%el9|Yt1Xdu%&08T2G1AI&t3U=C+O_DFX z2DdbMIVaH!$I{@#-IuC8l|(&#ZfiSRDrZmi7lwv_3RE8KQlUm91iI{Q?QhAXRN|rr zb(izwfBi4o{*hYx!>;Vl?z1U+NSZyj0a{O!5Z~vMO5uPMV@GeaB#S67axwu7#PmXZ z{dJ(M?O9++t>`a8o-+WDz1h8en?rl*bCc35bXT`OD_fm7$u7K52nxbx-C+7i%`S~5 z>KU`>FE``P;PrHZ9hwWAAQKY`WhEe~G+y8;Yzh%)#+4;t-lm}i0jY;&H-%^TpCU_8 zAdWq?s>8}UQ7zN7#GGg^F<$z=zO}be#Jx4A$4hfYR6h%kdyy^xF9PnW9L7>-MNp)aRXNROYMXLa@J_(8U-LDJR_*Zv5562;hR(H{c#iq)9cjGbtyHDC^ zw5o>yIK*jKEjO=5s7-baPv_U5blXp6E=h={PN?01eLUhK-TxPyMO|e%L8o3u{|_zC zo?H|SN>T3^^Cu%fGb;s;)h}%=(7;7-ah)BW@YexEPNX^h;IVU~n^d%VH1kwuEE{Qv zo|F{|RD}nn9S}p8fS{K`Bb#zQu)i|1^v6s<7nXDq&(e)Oq8yjR7XQU_WNd+S2wHVh zB>AQY_Xy_9fFQPabaRs!Z=-B{fPq_^e&sd~MCrUC7)B--#f znD0QA(eH|plhY50*lwI$XDli8bV>$^WydTj?hqiirBcC^LDJnMpqt`7IUI9$MYB zEUCA-Ye|0^QQb*O zgqmM@ug^s1D@_I&CW5S-DXL0QRxN0@dyYfbzOi3agK@xD`tI&*)0rC=M`KEIY+RHA-(&YZ!&dJ2|MHq#m^op65y+v~ zLVgc41h6qUsIccIR9kJ#5OMxfZeHZfcBPciDvtK0^o#znL{N|wEtbh42dk6mtPq<8 zoQaml4`W8=h+hl3fGMqVTSWb5TkxIO+566oAlb*4A{h20*^R7(88(2((a^_@)83@} zP&9Z52>$u5e~1iz6xYHMHCxJGQKrK372siI&z_QIAhgBTy{`QaPSQv|#)J|OnkR%S zcr0^NF7WAhw63xtwI!%C>I_UR+NWkS%wCdUS&Aeo;lCdy5$y8oJ_helF&Jc<1AD>i5H!s;kp6etO4B=;eS8>U*e6rSn9@ZMJ~H9>j`A z^I&_@)m|pEpO00fXZLP<2^M$~g%QCf?^_&em&{5M4U|L0?K;qNqFQ%7TofQ_$v+6I zO0K!F2T5AtsZ?o>E&T-$D@XXgWvk{FclV?xQ@)>4%TC5}-?j{nU4iwBn%cT5-6k*Z zC?3-w^`H`jx+GxfUq(V_sPI2zfR9-VLE5*+Jp-#Baw1(ne8RnR}b_t1Zp zjD|AEC$0D-tfx7_!5+(L8dRpOjm=?c~R;*tJ(bL5RC5ctjP-sGyw!p+u z=09_!wqKrrGC9Uz5G-Sjz`qHL;xQN*c77KeC=U z2*gCHC}whs1G~T^z|8O8}{FUY{gZNtl#QpE~izRV>zM9cnR9V z7i&u~#ZpL#H?9*u8OYu$itxuFFPDN|64FpWBR~92#zR>=yA7c>LB|^nYkwgPq7;c@ zxS+G@p^SCzR>{DAN~+B+sBz|A3U}W3b+pz&9lF_d*j2GfJm!N1fKBBd&Am4RsYc%Y z)LvG4M|emF31o!R(>2*?vH}?(sI5K|C;g({p)HsTOT0#v6U`I8x2?s9R1fMJ9|AQ; z*Dw+n%l3N@n|+1lCTS%Lw=@%+`jms|N;ftX5puL4$QOI@kRNbTyul-!b-_zr|kBNJ> zZX%31FqVg9spm1EA^|qGj(S+R;8u0?);Aw#f6MB%R_wI7+MWI0rY;aZaJaRD$b< zPpfNnt_L^S{z56e&MejW_R>x9-j1y-Um*+g0z;g3*WD-X-=!iB{)MX@K709#Qd{Jn zXeX}{iZFsfNsdo-gLjhNL}~ANlF|JvtElR)p2<({tX-pji+{><3VX!?@sn+Hm+<<~ zQKxoO=<_G{RRDC+8^baA=+#N_OrZPB7e!*6H!VrD>koBZ>%RHU#w5^6<()|N=x>gc zarNpQ420|~F&gFAUumv?&h~7=6tlRzFOj%#dLiY2%5E} zD)qv7^QynZPLYXBXrl*}3ksy9$G)bBkloRLxP-oise|amB`6n=Oz^3;b-g2|GapeO zuhVQb`~oyIP}I0HXkV8$j{KbJrOAYPDZ^4aPOGF6oiI@=$_%dNdnUh^{fb2*X>(hg z9=YE!CDM9FM@OezCu4p z7>6s4g<9cWC7PZ-ZCHK#EzZcpfD@0Wv!K1by}8*Cv_~Hu9d&mr(Ek}N&ij51p6jF| zf8*_So|>}RqU&Wf=Y{V|OS_A%sn7oQ^1gi=QRE6~tgEot5Avm^=)K8Qrp&%fWtG9y z^Qw0+N+~T~nkWh#M-~Pu2GZE7oEO?a&>RG;jzP`e0wXBwIB8coyvarJ0rff`52OPh z1-K-;vEG9UPcJOw(}=-}ii+4q9c8#sH*r>m?)g1Dif6-Shy!iE(h7T#V`ueRF;7=j zCqrPO?y{E-@#VER3rdtvh=eb_&@o)P1^3;TlN*Q2R{FujFuC>)Dv{pt;gwkj_~qzh zrmfWXs_C0472jh)&tBvGSHqPqdX|VDy?@%V?<9Ef51Ov0A~!P5d*%L>jZKooA7|cf zucd8G{2HJ+QcKY}?Q+f*Sv@SMIi@ZKOpy$t4@A|=sYbaKb}~KX#@BD?Cky`60^23S(}POf@hWlPjb~|Ix=ideB6g0`4pcUR(V@4 zh%F;h#rJw#kl@|Z+_{eku2ZQ3wt}axhyHkR8c8#6fm-i`DkM@t-`Q;5qPqf=;mjz` z`PC2_!t43R2;JPEjF|D7j<_c?Pe2*W^upP!Ud~Mu(7kx_ZDJzb%L-4m>&HPjHT7QR zp{D@F94^F$N5J;E$tm7oMCyp#Q`WyI5yZg@V;nQvj9W@Vf(@Mf+V@_}(#0GP$Ei?x zXuE!5&N90g`z5V~UrNNxT-z6@!=LXyuM!vealGx#f)2V$x;|Iqz`ylMHaHu1*S z8~x84v}$r7*j8eq`;GNS5=!0456&*awPmjKF7lwr;Zp|*?iZ?9#dxK;m`yX)SrXaW zxLy^-3^A}pi2{#>_6TcFVhVA-T`c~iGK`QN?@I`KndYo=TXo&jOJB4jQ0EVQ>* zaS>c8Udr2=RF7y>s>NnRIZ}wFy5fpL^%9gcjRzcphPekkd*>sm?nX*ascmjV-g>l| z>w4m;IWhs0FSUp!E!=_4Hzj^-19&QB!TyS32Q{6OPv~16BpQYo*Q;qDEzA6m`KgVi z=>2@4Za-t`uBJ2@>^go~q?-1G$0m8S0m^+&CRpqQ>I%e)1x z5_^F`7*Fll65?XXE}hlHeJzgK18kX~?5(e_1PWEh`+&)Y%T&<$L0t;|QQ(mB`=&zt zsZ!T7=}KCGjq8N9(0lnbS}`oImG*A7i_6`2ACYw=UzUm(kDLTqEq6&qjx;4RWRMIN zx~rgNk@C5=M;#M|eLgq!ug$o@6?+psjV_a$x?exZ-w)3X=`J_|d-t6hetF(}0X^%qlEjEpcC1oufYIG!i-iLc!fsVhup2%m@EMw22TJD>uin|4@CYlb)DU_O7A&KayZd`^){D=C`MhYcr4<R3GwBsAF46cydqZzfPn>eapF2)%MWArA6$pqV6$wX=&&(=bzuR3kCDH2X_y z&-Uat1T1a2Amn+XowU1V;OdT->4XRi>|zL|q~@$aAGk+K|0ioNPXVWdwU{&h3O#MB4?e*&4-@kJS z-^6K>__$Lai#GaYXRk9_pt-GfUc7Qq9?8-LSi+ zm&GH8X9v7Sq2gN%@kV4Rhf#5Kg@v&ix_Z6h-o9S)-_Zei-r z`;o!=S^=3_bVIiOc~z1Ty13W#fbMDxfpS~1ijEddZ4@V$ovFa)3D3A3A9fjX;>&Eg;ITB@xyn-Zy5@Xr0E zL~ZYC;T2*Yh=fiXMQARQrT&n;Lk^8G%-Qe5wp4;B#Zv?BwEE!6jAacqJxlC%Fs0$p z=mNn*Gd_PA6-+`}U zv0K2>t~qk+)a6Y~4_UF~Ccdk92O8N`sbuQ#;c-Zn*cxu3m_loVB9)CN);(X>xQhTT1u5s&e^n3!jxg0Ju)g+X&yrI zE6X@4geivm={vha+Y%N8o9^mtXR6)BLOh8rC514=(B+B{HU3=$%8>jhB#fJx!~JYu zU+PUpDSG1rL+Fd ztSaJL8rc<%aK_NtXm-mhM}9j6ZEwX4Fhy`|hiVd_m!+j3m(J1IfJKcSaKhJF^`br= z-(PE&3-h_q9@iCboXghPbW|Ca)-@wsnSx#hhuVkoku2SF?obHx}* z{|&#(>rbXh-Ccd40zzIMV!j4>{A~4d(J$|^JS(`R-HYmfypY{_KPmca2M)oHw1weo zi9VV7W@@+mPy9-SEpC}KE}~t!-x~91g+Uc$q>-_X(l(E5#?qI3XmE@qP>jBe~n6 z>DY=_oE9p#+%#Xn)j^op*LXKszk;@#;2NYN$?*{i=3WOao~t0iWrlnXpKJ28={u9B z90>TSlbuEdruoVBu*j%w&l;KRc z!S!yd=*`d#SW5$4SZXL3modh(!t~JN*V^8JQpL9z1?2DshUBpHFwS_R7B4bLadwdz+M)C%3vj4h8imF3AKF#^YDq`#vYHS>;G@ zAV$}y{X~e{$-@P}Ce~}bzLiohQ( zEr0M{zs38a*l36m>^6i0-C;j^^InjaqX8lI)DJ!0J?X=Y7TaO6JR=K70_*KWmD>tP z!2==7#CS5xx`xUjKG4HqKQm8e?Bd45p9?Gm4aKPixm1&fg|Cf%n66VH0Td>E&@?|X z*R!CVJ&rwAh>1k0w{TR?7&7+bUO1gDA>jsg^j7u&Num_hSD9ygjawC20gGW614t16oOd2M8_!N-9XMs!K&3qG+htA~QsZ|N!?JMTOk3MD! zVOei;tMm1fGSSwAiS5AizTst-80Yr0_S#A&9_6-YI#xAAT;Lcyy*_EEI0@8t(>kVO z_xWc=y5S(5F=IPIX`p3<2)m)EUpy-N%gYgh4mZK+RH1owV-EA5z-m8EpW>wvEMVZCjkMlYbDw?s1mkw8l%ND{4;LN;VP`5As~(rWwZW?Ej4W6rOJ0RhPSBG!lj7 z*qTqD^c_*v=CH>(*RgNckk&$Gco#e2N0aVKB1H8c^7vv|@IdME|HyDJ#eAUU)78e< zV|la+lUDoRh+u6&I+K^`Orq(Chghomk)`7Z0h}o`OFds;I5xh?Ji$XT>W&vA{{4<%FcD~ zBdO2OtA%JD*jc`TUyK(Fmo~0#6jbE6Yfb-%k779gb&b^XvY|QWL{}Ot`-iN6j<>eD zcVJ6u==j_HJR>peHu+9p_^0o*pB@#QC_YFt=|%k=OZxhqEaTDY8DK;c?6OL~?6=sD ziZsi4Rj^zQG5Du(s@ zz^<3lU6sCMsWIFDDyJ3JXoVV*vBj$avKypH#cS!x0uQfbpk zuwTJZH5OBE&}uETa{q8=_0Ro^>+Ay%h!NXMfm$~;Qn2>VC4>*sG*?}Vzw3(I)HryY zV2Q{2a5_+3LZaB4+E=kTXhtN^O3QGS?S$psaB2L&O{}`OI-y|wp-H|Nc*m6r%;?jn z?a!$jjOF;r8V6<`{CbRU8sPc6cVSE5<^Uex1eY6Wa4#aG1f<N4Ptf(uNhP!yAh-gIR9q*!vAIW|Cc6sG>YA~@!9f-!K_#s${}Y@ z04&eO!-7?*AQU<8yZLZ4Hmno-v@bOlR!V#WXk zb8@nG{~SP)Oo2u=>lqLsjUWk$5?jT`$4A;B?Xs-&o98HGGmw4aFGf9}3{s%LYyq>q zkS7(y5V3f?5Ci~EO7rh1V}*lSeQRs$r%xxz`RA6PQ_#VI8#Wr)UTHTyKhI#nld#09 zq)@01Dy>4Kwa2V$Gg+faLIlQbg$p7yA70%Dx$izbO+}! z4NGf9!%xmsCJw!t9}2fhWxlMRkxN0YV=#eK5prLtl3!Ts>locjq!SygQ3<5QeO0k( zmvuMMF}qM~BXaRKTGhwp&xj(Uy!ye-22}mg zKIjA8c@g+s3Yw!p${AB(-ze%g%pmn%NAu2JksVj3a~c7U5NuQ!#wz8Mzw6#-rLsSNQOJ@R()?RHk zCHGkhW~St)kk9ih&t{4x#BSB`Y=Ux0+U#um0b06*pv$wKgm*J4Q&Ur4RD}t>`~UDk zq+wJMt`?hkiFfg$-`N|MrxA3+$u=TPphA8a@)*^T8c?JMgst5V}oJ?Se4b#A(m^wn);q4*N;ueE7Wj4ck znaK6J=?Xg)AE$418Ja*pWCca1YJL()Z`6f6DWRvEdkCTSiXQ)E13 zwJ*r!;c?-ZMV;amJ-pF6)nbdR-+z1H^FU^*nIiHUr|A_exq1E&M{^M1Xi#y+C7AEJ zaq5NHX09S!>4duP9Gm(i+*2SeLD8v&-H@H&fc%)S6@Ko%L-iZ;TI#NP77{wp$)u*$ z#YJwP`b;v@#fDSXiJz+1_!DT)_22&uW2rInzT1P@|GeMw#mr@^p8IY9%?RaK_kcd8 zKG+%SGl&$S>k|jR6qjjuGR2FGg)Dbdr zECWslO_*n!UdauX z23T0MwVP>;&H3>6QG6}0pu;P#*E}Tj(@IcWVHre5F!OPjhjbO_;@ZK|UO`g~E@IzNKzJcRmu&+HYE2 z8TFOGU;!@EUBC+V{SDi~35YbLlB^seZ=eu=#q)6e(UMrgx#g&^Vqv1=Oc&~Apku8< zq-3XdbU_!;h0-urwByVjq~=URRFnXcHo|Dogr(bI+Jq=H6L9Z(vi{S11!x}91&K}=|$wLDFEkMqVN z%=#ry<@Hf2)vvP@yeOO-_AV_~#@ePLRx=HoO-=A+eIy5pL>6tsT)k_z};j@a^P>o9CgAZmP2s@U8X#E;GSe>1FR0{~TIa+(#Mv5mf?Nt zT77?7Tp0nFaKaK3L5!gs>+5s2yKzw!@CYs=tXQ;%xyZ2A2#;mKBqVf9u)^C|Zpl(m zfT&Q+_PDIotbl`sWmI^jg9wc%9b+l5uC<$KK-$GsizSeE8YKIa?YddA)ty&KUz^KB(b*bj!yM?bDdO`ov=TcJUPR9_j25K=*n}SjUF7gUtWN| z5WbWkn?z4b65NG=7bbx!lRL*K^>$5>#1eGlW|eV!o=g_lqU@CraS zrRGN>t_YD$sbk-0R9Ie{tYR7Q`wX+V$V}ShN*4k52#dNyOuVw;!z@>=(&n$O@5JmZ z&`sAP0Mk@YVImL}6*Za=A-WIy&L8t#cwpa1JWKO>EO0x5v$9m!^|Lmb#$Spivql&E z14sj~JgoHre)gapEE}px;cr#i+(>jN%zD+kIbu#P0-NV_$cpBiniKBfzIsP1XtlH) zFDexJ2)F~mSxFZKA$m#g0VKmztxdBOCc}!Fw8+jN;d4PtvT1BVRaC1RMmyvUuyFQd z0ms-{QZ>&Uqx8C-Wa6D5=D$VdOt@1Sz@1M)wWvV#EPB@%Za-{8s zeqo(W)Zr$sSCd)k23VKtD3YYSUI$h=zlHO|^-pII*9j!$b;nw=LVlx7+!hWwi z18FBqU_8McZYDl&NvDHT`Rt3EpE@N?gzMRn<4G`_Dqdj;i>-6$Td~PNN4K@TO0@qXnT)CQ*qP0|MV+=ni0Hm&@zTPgaCF@T4I8a< zG-NO_jl16ghVub2eLj4vN_4s69gu4epB9gnl&!{0CR5h%)fuh!8Lmc}yEfj9j1!pf zOlAc=3^Dh+^{n8($bCnz-*C7-6LC#C;3hMfJgKY;+S7Q~t9k6f^A)qiL_wO@k3FC# z%bqLLCl%*!cm}XipOBeLc^8hsYAgr&hEzYfB9^|Gd$$I>2PV22SH#MUdTq$$IUfLv ztSO<%@ynHF>k@w+Q^2aE@g!P_!mFT8!z7~UWePDFaeDhhDK#Uq(p_qc9CyUs@IANh zuoDZjYgdEP94TqT`eVNBLnWSzWE$=nuztfzBR8Z%zP{N8tzg81*f)X-kd1duw^5r>A#^m@tgElLwh|Q)r zflop4@T|CMlSb4+t#%we-=BxD|Y0(1y;!P$&wUi2~;J` zwfcGA4f{%lKCu81wpUZd43-Mq2{u+b1E+j;}gn)F;gk7w7i zH&wYaS;W*;xq-}kr4fa~lL1%O6kKAzd_ zI)idh^70t57Zw$`xA;KtjU~y>_IB$f=1eJx2=6+xT%x<1&T5Icu8w84|KH_G!r^_o z9_l-h9zVQM95FxnlJ~GcCDp}ntc$M3$7j;QQQ^+J+%GNhyz;NlmYC|_%6ZMs-5)v0 zB|1vQUw9m_aAOm{9qJwi@18X{4tSDvG3ATNDi#KO zFMT1-vP&^cSxH9B-@OM-&o^!9&=YZjqp!#dg%tGKn)vAh-SLn>p#-~Q{LSMyd&r47 z6q_qkcl*&b}`+;E!Qp4&%Wc6@GXszhd?do`FK{y&N|l2X|GJ!fYll{2Qlni$U~CI>1W* zxm;5Pr9MaK^E`IO9#;^q)4Y$4mM-y;4lMKk+Z|6E85wDpMe$moJB&$oVyytXspB!T zB7O>c=aFu)BrL=3uu;)Rk4$NOYJu8UB}uiEriqYY%^(Tu6C}ijicf1ClR2NK6-B^% z1*F8cHAm~*)^*s=ix$t<3*c&32?D*voK6Td-(km}iP*dnfWM5I_!BnpCY0Lr7Q#YB*vn zDIE}Rc41`d1|~4R2cx!4ZJtXJyQUXJ!^BdjRnx+X7`_Yb%<|B?_>heOPaa=!o#W?e zR(l0Tt*y)hHC&;Ia;)i28EFVBDLmdAKzbZ@t?A+Qm3p-hZoWR zCc^%et+-pQ4r4Z%rbn?#cb11tejV!MRqD@i-p*a1x~?psV@>WIOqRX%NK` zC#x_hSgv32XE`ig^Y|?SfX&s~3@<->zlz{fqkMN(DmbkgTaPq3BU8AgK@o0UgipAx!=5?5iEKg0tMf33YIyozP~(9K&_ zCllzlBuQ)L7~Umo#ijOBG|af0iZ1K1%)D}p0?6-st*8?-hmpu?kCoEjO0;3@_fL)H zuB_#G%D8TByb@#$2_Dl(36>}8BTJcB!F+#YnT5(l-G$f~m zikIpwV1T$9AD@T%6eex7*7il0$VOR@-s@?GA0Ho^KE`*C#A;eoyR0XOJxhQ*B}@~q zPzW6c*s~@rK5)Z^C5aVah45BWdnd8F(gmGuH+C+%Kp8GEefQWw9AfG3#}V5WuP-b{ z+#s8vW(s0uNa_eU2`-2-KpD>3hQ;$$9t;EE#BB-(N|rEN(d-B~I4^+ity8*!$Xi8# zfYRQ-r+Q>pqa)yTGmhPQd8>0y=>iSa)rrUwiy2)>O@$iAnHnB>b+3lTP$m*tIr!RH zAfi|^LkepvrX%fux^Q`tsX}Ej=cJ3?))I+V&4K-mK#l?>o`qyn`fe-S!T(J--aSx^ zMx3A{yy-M(udH$NpCSu{C&n&IKg*z@h*qJ~lYZuRj<*E8eq-vyc`NhO0BX~>aD<;I zl=M@A0}URjmA*AI0p&(NM(8@EjINV^532l2ZbJBOM-5M>@RFDgnN>I2?Fjf<)02R? z^?MpgtTh}zL|_C@a`Dov)|=2|Al&-wgEQo98_$3staj?<-9qcy#ILSNtN;}zMq&wL zlV&BJAhZ1xTM1fvaSfYSOsm5fPi`2 zP|e~%cv|NGfq!P0Tow|QwQ;s&UFdrLrF8M~d!^{m$icjd_MRY!^GgTlr&-M;AWPD$ zej_SS_GI!g1^mc=m=C81c3~uLjo&xoM_W(?rBq)P()9AO-Nh3NI7cMPdAUBmEaB!ROC#ur{Sx9E>{);^$XktjMv%B_q&>z@L@s}`Lv7*! zfVMSPaObCJ+AW*du1r@Hh`la=rfMZHDX43;RBSd?Y$EdT;cwX2$t!00_A%3bp0LV_ z)y|8eX0BS#iWO%@h#4EW_wS`J)%|W^ zilJS^RFdTa$%glH_Bn2qzV4s{-i_JqA)gM$RU?8#Ry#$f)?6zUZ4kyN5nu1?T3{Bi^3t zqobQ@IbxDlPb>xdYIqU~_-`T5@>FbgzT;ma|I>(k3&*Y2LbsldJJ}$3!rk!v%vgbQ5wb`!uA{>|VAp8_w}E-S({=jcrC{Ra@9 z&`+a|7}-7EhwgevM8Ivcx~YI2#GA%XbYBUz$!1xYL;74%$Q(HexEMrQ?51~*S6I53 z2!LlU{yJHV=&APDBvI|3o!L*Cjv?GwKl=1}lBI_al_KftEI-kNXCa4%_93`JCe5nP zNo7>n(>PtGmr4^GD^K72rF=hJ@K02fJ6e3WCJtzYY7*H7LT3Mk7fEvJ0LI{F6R*XO zU1FNskB0Yuxtm>iWIM(cr)S&}OIaO}i?7KAsD zrlae^G`Ec>=z9`9;f*u5L(IIrbw`DV_p!1qU4Y$BF}6<-1O@cd>Sr8Bg{=yC7(4mn zmL`t_5TL8W&dJG%CSqjUtCpwMQIe>$(Ru!S4|AbVD6kYA;X;o!&>i4ZZs>(3gwO*w z<8%S!=IK?OXKfK+{>Bv0(b4gDznt0e0!~|>kArBooN%tH_-ajCT){J>ft9tLx=6Px zT~GC9lMKl+qOG+x0Dv9rCG*=%Kgjpr1CEeR_97A1hZ(|^`SwzjaTg#gqa_<0i6fs* zOG7B0mhKz zSq&T#*9>doWdL=9)=WtFo{CT?%6cuJAXh_@lB=*{6GQ#ZtseE?tzK;DP4 zA3Yuh{(4QB+mAj%@z=yMx9w)3Ua{)YRU9hEZ%omY?8f^d;o zd=wV_6l)L61DyD|-D3e)JjjMMl;K73Xx>DFmIzvKDjBhgraw7cA1%&t@6Om-RvE2( zCMSU+wZinx|0u8@tQp*I0oVYGE>yTOR1vaKwt`ciT=!3Yn$bk8JhU@YH^DsmhdJAo zx;W76Aku(*C|Y#!0T&$xolcluPDowyja%B2#zuquSgxdZ7zv0GWT_T|q?i~TpsblA zGyXUF9A{E1^#Hz2M|nr{o_yl0T6`2RFaS4+eIp}N4ZU=|3?#vgtHw5~Tyh*PAx!G+ z+Dv$f74g@%mc_0?%78)CA%6KYlo+!rb(xQUHVo9*#ozLwa^Q01dV{s_3}g)5_496iJ>h86N?82 zteYDR%UZg(aR{dyB@b zm||8+E89*%CNhi!Y>~4wz)2?}CZ_L+Uit^l=gPigRWc|~L!nlfgo%Jf*~d^A8hTya zRbj%DWjX*87e&{D02v|RQnzDHH$f_vlCPtKp0ESp(wkHsgLLJ<9gQuSTM$oo0N_h} z`G;8U;0r#ZKLFd8!u(qT@S1czAmp37B&JT*XW_SE2YYanxr1LACN#Xi=rZZl2=s|p zGZ4-J|Nblj(~n(H`GW-fCjEN|MDE~l!ZhgOa6;~2698yl94{W)?3P5G3s^sUWb zDL3DA5ov5S<3S(}yD3bp1%d6RjyMpAo?qXm%Rf`> z40EH^$CitDSj+2u<_9@ku4zn9DfQ%4yu+IRDkn3BkkJFSW@~HwygKj|YR<$1orjlO zDnKqhxZc}D{$q195Pl%K?ZR~rQWgeo2G+{9-vSAfQqdu%Q(=^-asR=*hqkZcFrh4X z1>^2Yle`F5W<2BH<(lViRuMN%M@6t(cklNAUF3~JkfFC6Us%`EAqFqMetG>5-Hlrv UzBJ(876?R1URAC_)-2@z0Q_wY<^TWy literal 0 HcmV?d00001 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp index 8b03fa66eab55..b7cd55ce2e642 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -15,74 +15,117 @@ #include "calculate_slowdown_points.hpp" #include "footprint.hpp" +#include "types.hpp" #include #include +#include -#include +#include +#include +#include +#include + +#include #include +#include +#include +#include + namespace autoware::motion_velocity_planner::out_of_lane { -bool can_decelerate( - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel) +std::optional calculate_last_avoiding_pose( + const std::vector & trajectory, + const universe_utils::Polygon2d & footprint, const lanelet::BasicPolygons2d & polygons_to_avoid, + const double min_arc_length, const double max_arc_length, const double precision) { - // TODO(Maxime): use the library function - const auto dist_ahead_of_ego = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, ego_data.pose.position, point.pose.position); - const auto acc_to_target_vel = - (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); - return acc_to_target_vel < std::abs(ego_data.max_decel); + geometry_msgs::msg::Pose interpolated_pose{}; + bool is_avoiding_pose = false; + + auto from = min_arc_length; + auto to = max_arc_length; + while (to - from > precision) { + auto l = from + 0.5 * (to - from); + interpolated_pose = motion_utils::calcInterpolatedPose(trajectory, l); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); + is_avoiding_pose = + std::all_of(polygons_to_avoid.begin(), polygons_to_avoid.end(), [&](const auto & polygon) { + return boost::geometry::disjoint(interpolated_footprint, polygon); + }); + if (is_avoiding_pose) { + from = l; + } else { + to = l; + } + } + if (is_avoiding_pose) { + return interpolated_pose; + } + return std::nullopt; } -std::optional calculate_last_in_lane_pose( - const EgoData & ego_data, const Slowdown & decision, - const autoware::universe_utils::Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params) +std::optional calculate_pose_ahead_of_collision( + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, + const universe_utils::Polygon2d & footprint, const double precision) { - const auto from_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, 0, ego_data.first_trajectory_idx); - const auto to_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, 0, decision.target_trajectory_idx); - TrajectoryPoint interpolated_point; - for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { - // TODO(Maxime): binary search - interpolated_point.pose = - autoware::motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); - const auto respect_decel_limit = - !params.skip_if_over_max_decel || prev_slowdown_point || - can_decelerate(ego_data, interpolated_point, decision.velocity); - const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.pose); - const auto is_overlap_lane = boost::geometry::overlaps( - interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); - const auto is_overlap_extra_lane = - prev_slowdown_point && - boost::geometry::overlaps( - interpolated_footprint, - prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); - if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) - return interpolated_point; + const auto first_avoid_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0UL, point_to_avoid.trajectory_index); + for (auto l = first_avoid_arc_length - precision; l >= ego_data.min_stop_arc_length; + l -= precision) { + const auto interpolated_pose = + motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); + if (boost::geometry::intersects(interpolated_footprint, point_to_avoid.outside_ring)) { + return interpolated_pose; + } } return std::nullopt; } -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional & prev_slowdown_point, PlannerParam params) +std::optional calculate_slowdown_point( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params) { + const auto point_to_avoid_it = std::find_if( + out_of_lane_data.outside_points.cbegin(), out_of_lane_data.outside_points.cend(), + [&](const auto & p) { return p.to_avoid; }); + if (point_to_avoid_it == out_of_lane_data.outside_points.cend()) { + return std::nullopt; + } + const auto raw_footprint = make_base_footprint(params, true); // ignore extra footprint offsets + const auto base_footprint = make_base_footprint(params); params.extra_front_offset += params.lon_dist_buffer; params.extra_right_offset += params.lat_dist_buffer; params.extra_left_offset += params.lat_dist_buffer; - const auto base_footprint = make_base_footprint(params); + const auto expanded_footprint = make_base_footprint(params); // with added distance buffers + lanelet::BasicPolygons2d polygons_to_avoid; + for (const auto & ll : point_to_avoid_it->overlapped_lanelets) { + polygons_to_avoid.push_back(ll.polygon2d().basicPolygon()); + } + // points are ordered by trajectory index so the first one has the smallest index and arc length + const auto first_outside_idx = out_of_lane_data.outside_points.front().trajectory_index; + const auto first_outside_arc_length = + motion_utils::calcSignedArcLength(ego_data.trajectory_points, 0UL, first_outside_idx); + std::optional slowdown_point; // search for the first slowdown decision for which a stop point can be inserted - for (const auto & decision : decisions) { - const auto last_in_lane_pose = - calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); - if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; + // we first try to use the expanded footprint (distance buffers + extra footprint offsets) + for (const auto & footprint : {expanded_footprint, base_footprint, raw_footprint}) { + slowdown_point = calculate_last_avoiding_pose( + ego_data.trajectory_points, footprint, polygons_to_avoid, ego_data.min_stop_arc_length, + first_outside_arc_length, params.precision); + if (slowdown_point) { + break; + } } - return std::nullopt; + // fallback to simply stopping ahead of the collision to avoid (regardless of being out of lane or + // not) + if (!slowdown_point) { + slowdown_point = calculate_pose_ahead_of_collision( + ego_data, *point_to_avoid_it, expanded_footprint, params.precision); + } + return slowdown_point; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index 145f21c94c0d0..394334d434558 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -19,40 +19,39 @@ #include +#include + #include -#include namespace autoware::motion_velocity_planner::out_of_lane { - -/// @brief estimate whether ego can decelerate without breaking the deceleration limit -/// @details assume ego wants to reach the target point at the target velocity -/// @param [in] ego_data ego data -/// @param [in] point target point -/// @param [in] target_vel target_velocity -bool can_decelerate( - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel); - -/// @brief calculate the last pose along the trajectory where ego does not overlap the lane to avoid +/// @brief calculate the last pose along the trajectory where ego does not go out of lane /// @param [in] ego_data ego data -/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed) /// @param [in] footprint the ego footprint -/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits -/// @param [in] params parameters +/// @param [in] min_arc_length minimum arc length for the search +/// @param [in] max_arc_length maximum arc length for the search +/// @param [in] precision [m] search precision /// @return the last pose that is not out of lane (if found) -std::optional calculate_last_in_lane_pose( - const EgoData & ego_data, const Slowdown & decision, - const autoware::universe_utils::Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params); +std::optional calculate_last_in_lane_pose( + const EgoData & ego_data, const autoware::universe_utils::Polygon2d & footprint, + const double min_arc_length, const double max_arc_length, const double precision); + +/// @brief calculate the slowdown pose just ahead of a point to avoid +/// @param ego_data ego data (trajectory, velocity, etc) +/// @param point_to_avoid the point to avoid +/// @param footprint the ego footprint +/// @param params parameters +/// @return optional slowdown point to insert in the trajectory +std::optional calculate_pose_ahead_of_collision( + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, + const universe_utils::Polygon2d & footprint, const double precision); /// @brief calculate the slowdown point to insert in the trajectory /// @param ego_data ego data (trajectory, velocity, etc) -/// @param decisions decision (before which point to stop, what lane to avoid entering, etc) -/// @param prev_slowdown_point previously calculated slowdown point +/// @param out_of_lane_data data about out of lane areas /// @param params parameters /// @return optional slowdown point to insert in the trajectory -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional & prev_slowdown_point, PlannerParam params); +std::optional calculate_slowdown_point( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp index d9a85e266f790..6febd15ef8052 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp @@ -16,12 +16,26 @@ #include "types.hpp" +#include +#include +#include #include +#include +#include +#include +#include #include +#include +#include + +#include +#include +#include +#include + #include -#include namespace autoware::motion_velocity_planner::out_of_lane::debug { @@ -36,209 +50,186 @@ visualization_msgs::msg::Marker get_base_marker() base_marker.id = 0; base_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; base_marker.action = visualization_msgs::msg::Marker::ADD; - base_marker.pose.position = autoware::universe_utils::createMarkerPosition(0.0, 0.0, 0); - base_marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); - base_marker.scale = autoware::universe_utils::createMarkerScale(0.1, 0.1, 0.1); - base_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + base_marker.pose.position = universe_utils::createMarkerPosition(0.0, 0.0, 0); + base_marker.pose.orientation = universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + base_marker.scale = universe_utils::createMarkerScale(0.1, 0.1, 0.1); + base_marker.color = universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); return base_marker; } -void add_footprint_markers( +void add_polygons_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb) + const visualization_msgs::msg::Marker & base_marker, const lanelet::BasicPolygons2d & polygons) { - auto debug_marker = get_base_marker(); - debug_marker.ns = "footprints"; - for (const auto & f : footprints) { - debug_marker.points.clear(); - for (const auto & p : f) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - debug_marker.points.clear(); + auto debug_marker = base_marker; + debug_marker.type = visualization_msgs::msg::Marker::LINE_LIST; + for (const auto & f : polygons) { + boost::geometry::for_each_segment(f, [&](const auto & s) { + const auto & [p1, p2] = s; + debug_marker.points.push_back(universe_utils::createMarkerPosition(p1.x(), p1.y(), 0.0)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p2.x(), p2.y(), 0.0)); + }); } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); + debug_marker_array.markers.push_back(debug_marker); } void add_current_overlap_marker( visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb) + const lanelet::BasicPolygon2d & current_footprint, const double z) { auto debug_marker = get_base_marker(); debug_marker.ns = "current_overlap"; debug_marker.points.clear(); for (const auto & p : current_footprint) - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z)); + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z)); if (!debug_marker.points.empty()) debug_marker.points.push_back(debug_marker.points.front()); - if (current_overlapped_lanelets.empty()) - debug_marker.color = autoware::universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); - else - debug_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + debug_marker.color = universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; - for (const auto & ll : current_overlapped_lanelets) { - debug_marker.points.clear(); - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.5)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -void add_lanelet_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color, const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = ns; - debug_marker.color = color; - for (const auto & ll : lanelets) { - debug_marker.points.clear(); - - // add a small z offset to draw above the lanelet map - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.1)); - debug_marker.points.push_back(debug_marker.points.front()); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); } -void add_range_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, - const std::vector & trajectory_points, - const size_t first_ego_idx, const double z, const size_t prev_nb) +void add_ttc_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const EgoData & ego_data, + const OutOfLaneData & out_of_lane_data, const size_t prev_nb) { auto debug_marker = get_base_marker(); - debug_marker.ns = "ranges"; - debug_marker.color = autoware::universe_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); - for (const auto & range : ranges) { - debug_marker.points.clear(); - debug_marker.points.push_back( - trajectory_points[first_ego_idx + range.entering_trajectory_idx].pose.position); - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - for (const auto & overlap : range.debug.overlaps) { - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); + debug_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + debug_marker.scale.z = 0.5; + debug_marker.ns = "ttcs"; + for (const auto & p : out_of_lane_data.outside_points) { + if (p.to_avoid) { + debug_marker.color.r = 1.0; + debug_marker.color.g = 0.0; + } else { + debug_marker.color.r = 0.0; + debug_marker.color.g = 1.0; + } + if (p.ttc) { + debug_marker.pose = ego_data.trajectory_points[p.trajectory_index].pose; + debug_marker.text = std::to_string(*p.ttc); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; } - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.exiting_point.x(), range.exiting_point.y(), z)); - debug_marker.points.push_back( - trajectory_points[first_ego_idx + range.exiting_trajectory_idx].pose.position); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker.action = visualization_msgs::msg::Marker::DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { debug_marker_array.markers.push_back(debug_marker); + } } - -void add_decision_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, +size_t add_stop_line_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const StopLinesRtree & rtree, const double z, const size_t prev_nb) { auto debug_marker = get_base_marker(); - debug_marker.action = debug_marker.ADD; - debug_marker.id = 0; - debug_marker.ns = "decisions"; - debug_marker.color = autoware::universe_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); - debug_marker.points.clear(); - for (const auto & range : ranges) { - debug_marker.type = debug_marker.LINE_STRIP; - if (range.debug.decision) { - debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - debug_marker.points.push_back( - range.debug.object->kinematics.initial_pose_with_covariance.pose.position); + debug_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + debug_marker.ns = "stop_lines"; + const auto & add_lanelets_markers = [&](const auto & lanelets) { + for (const auto & ll : lanelets) { + debug_marker.points.clear(); + for (const auto & p : ll.polygon2d().basicPolygon()) { + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); + } + debug_marker.points.push_back(debug_marker.points.front()); + debug_marker_array.markers.push_back(debug_marker); + ++debug_marker.id; } - debug_marker_array.markers.push_back(debug_marker); + }; + for (const auto & [_, stop_line] : rtree) { debug_marker.points.clear(); - debug_marker.id++; - - debug_marker.type = debug_marker.TEXT_VIEW_FACING; - debug_marker.pose.position.x = range.entering_point.x(); - debug_marker.pose.position.y = range.entering_point.y(); - debug_marker.pose.position.z = z; - std::stringstream ss; - ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time - << "\n"; - if (range.debug.object) { - debug_marker.pose.position.x += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x; - debug_marker.pose.position.y += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y; - debug_marker.pose.position.x /= 2; - debug_marker.pose.position.y /= 2; - ss << "Obj: " << range.debug.times.object.enter_time << " - " - << range.debug.times.object.exit_time << "\n"; + debug_marker.color.r = 1.0; + for (const auto & p : stop_line.stop_line) { + debug_marker.points.push_back(universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); } - debug_marker.scale.z = 1.0; - debug_marker.text = ss.str(); debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; + ++debug_marker.id; + debug_marker.color.r = 0.0; + add_lanelets_markers(stop_line.lanelets); } - debug_marker.action = debug_marker.DELETE; + const auto max_id = debug_marker.id; + debug_marker.action = visualization_msgs::msg::Marker::DELETE; for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { debug_marker_array.markers.push_back(debug_marker); } + return max_id; } } // namespace -visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data) + +visualization_msgs::msg::MarkerArray create_debug_marker_array( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedObjects & objects, DebugData & debug_data) { - constexpr auto z = 0.0; + const auto z = ego_data.pose.position.z; visualization_msgs::msg::MarkerArray debug_marker_array; - debug::add_footprint_markers( - debug_marker_array, debug_data.footprints, z, debug_data.prev_footprints); - debug::add_current_overlap_marker( - debug_marker_array, debug_data.current_footprint, debug_data.current_overlapped_lanelets, z, - debug_data.prev_current_overlapped_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.trajectory_lanelets, "trajectory_lanelets", - autoware::universe_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), - debug_data.prev_trajectory_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.ignored_lanelets, "ignored_lanelets", - autoware::universe_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), - debug_data.prev_ignored_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data.other_lanelets, "other_lanelets", - autoware::universe_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), - debug_data.prev_other_lanelets); - debug::add_range_markers( - debug_marker_array, debug_data.ranges, debug_data.trajectory_points, - debug_data.first_trajectory_idx, z, debug_data.prev_ranges); - debug::add_decision_markers(debug_marker_array, debug_data.ranges, z, debug_data.prev_ranges); + auto base_marker = get_base_marker(); + base_marker.pose.position.z = z + 0.5; + base_marker.ns = "footprints"; + base_marker.color = universe_utils::createMarkerColor(1.0, 1.0, 1.0, 1.0); + // TODO(Maxime): move the debug marker publishing AFTER the trajectory generation + // disabled to prevent performance issues when publishing the debug markers + // add_polygons_markers(debug_marker_array, base_marker, ego_data.trajectory_footprints); + + lanelet::BasicPolygons2d drivable_lane_polygons; + for (const auto & poly : ego_data.drivable_lane_polygons) { + drivable_lane_polygons.push_back(poly.outer); + } + base_marker.ns = "ego_lane"; + base_marker.color = universe_utils::createMarkerColor(0.0, 0.0, 1.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, drivable_lane_polygons); + + lanelet::BasicPolygons2d out_of_lane_areas; + for (const auto & p : out_of_lane_data.outside_points) { + out_of_lane_areas.push_back(p.outside_ring); + } + base_marker.ns = "out_of_lane_areas"; + base_marker.color = universe_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, out_of_lane_areas); + for (const auto & [bbox, i] : out_of_lane_data.outside_areas_rtree) { + const auto & a = out_of_lane_data.outside_points[i]; + debug_marker_array.markers.back().points.push_back( + ego_data.trajectory_points[a.trajectory_index].pose.position); + const auto centroid = boost::geometry::return_centroid(a.outside_ring); + debug_marker_array.markers.back().points.push_back( + geometry_msgs::msg::Point().set__x(centroid.x()).set__y(centroid.y())); + } + + lanelet::BasicPolygons2d object_polygons; + for (const auto & o : objects.objects) { + for (const auto & path : o.kinematics.predicted_paths) { + for (const auto & pose : path.path) { + // limit the draw distance to improve performance + if (universe_utils::calcDistance2d(pose, ego_data.pose) < 50.0) { + const auto poly = universe_utils::toPolygon2d(pose, o.shape).outer(); + lanelet::BasicPolygon2d ll_poly(poly.begin(), poly.end()); + object_polygons.push_back(ll_poly); + } + } + } + } + base_marker.ns = "objects"; + base_marker.color = universe_utils::createMarkerColor(0.0, 1.0, 0.0, 1.0); + add_polygons_markers(debug_marker_array, base_marker, object_polygons); + + add_current_overlap_marker(debug_marker_array, ego_data.current_footprint, z); + + add_ttc_markers(debug_marker_array, ego_data, out_of_lane_data, debug_data.prev_ttcs); + debug_data.prev_ttcs = out_of_lane_data.outside_points.size(); + + debug_data.prev_stop_line = add_stop_line_markers( + debug_marker_array, ego_data.stop_lines_rtree, z, debug_data.prev_stop_line); + return debug_marker_array; } -autoware::motion_utils::VirtualWalls create_virtual_walls( - const DebugData & debug_data, const PlannerParam & params) +motion_utils::VirtualWalls create_virtual_walls( + const geometry_msgs::msg::Pose & pose, const bool stop, const PlannerParam & params) { - autoware::motion_utils::VirtualWalls virtual_walls; - autoware::motion_utils::VirtualWall wall; + motion_utils::VirtualWalls virtual_walls; + motion_utils::VirtualWall wall; wall.text = "out_of_lane"; wall.longitudinal_offset = params.front_offset; - wall.style = autoware::motion_utils::VirtualWallType::slowdown; - for (const auto & slowdown : debug_data.slowdowns) { - wall.pose = slowdown.point.pose; - virtual_walls.push_back(wall); - } + wall.style = stop ? motion_utils::VirtualWallType::stop : motion_utils::VirtualWallType::slowdown; + wall.pose = pose; + virtual_walls.push_back(wall); return virtual_walls; } } // namespace autoware::motion_velocity_planner::out_of_lane::debug diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp index ea225442443c8..dc1f942655612 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp @@ -23,9 +23,11 @@ namespace autoware::motion_velocity_planner::out_of_lane::debug { -visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data); -autoware::motion_utils::VirtualWalls create_virtual_walls( - const DebugData & debug_data, const PlannerParam & params); +visualization_msgs::msg::MarkerArray create_debug_marker_array( + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedObjects & objects, DebugData & debug_data); +motion_utils::VirtualWalls create_virtual_walls( + const geometry_msgs::msg::Pose & pose, const bool stop, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane::debug #endif // DEBUG_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp deleted file mode 100644 index fc487a2626b88..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp +++ /dev/null @@ -1,389 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "decisions.hpp" - -#include -#include -#include -#include - -#include - -#include -#include -#include - -#include -#include -#include -#include -namespace autoware::motion_velocity_planner::out_of_lane -{ -double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx) -{ - return autoware::motion_utils::calcSignedArcLength( - ego_data.trajectory_points, ego_data.pose.position, ego_data.first_trajectory_idx + target_idx); -} - -double time_along_trajectory( - const EgoData & ego_data, const size_t target_idx, const double min_velocity) -{ - const auto dist = distance_along_trajectory(ego_data, target_idx); - const auto v = std::max( - std::max(ego_data.velocity, min_velocity), - ego_data.trajectory_points[ego_data.first_trajectory_idx + target_idx] - .longitudinal_velocity_mps * - 0.5); - return dist / v; -} - -bool object_is_incoming( - const lanelet::BasicPoint2d & object_position, - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lane) -{ - const auto lanelets = route_handler->getPrecedingLaneletSequence(lane, 50.0); - if (boost::geometry::within(object_position, lane.polygon2d().basicPolygon())) return true; - for (const auto & lls : lanelets) - for (const auto & ll : lls) - if (boost::geometry::within(object_position, ll.polygon2d().basicPolygon())) return true; - return false; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger) -{ - // skip the dynamic object if it is not in a lane preceding the overlapped lane - // lane changes are intentionally not considered - const auto object_point = lanelet::BasicPoint2d( - object.kinematics.initial_pose_with_covariance.pose.position.x, - object.kinematics.initial_pose_with_covariance.pose.position.y); - if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; - - const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer; - const auto max_lon_deviation = object.shape.dimensions.x / 2.0; - auto worst_enter_time = std::optional(); - auto worst_exit_time = std::optional(); - - for (const auto & predicted_path : object.kinematics.predicted_paths) { - const auto unique_path_points = - autoware::motion_utils::removeOverlapPoints(predicted_path.path); - if (unique_path_points.size() < 2) continue; - const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds(); - const auto enter_point = - geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); - const auto enter_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, enter_segment_idx, enter_point); - const auto enter_lat_dist = std::abs(autoware::motion_utils::calcLateralOffset( - unique_path_points, enter_point, enter_segment_idx)); - const auto enter_segment_length = autoware::universe_utils::calcDistance2d( - unique_path_points[enter_segment_idx], unique_path_points[enter_segment_idx + 1]); - const auto enter_offset_ratio = enter_offset / enter_segment_length; - const auto enter_time = - static_cast(enter_segment_idx) * time_step + enter_offset_ratio * time_step; - - const auto exit_point = - geometry_msgs::msg::Point().set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); - const auto exit_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, exit_segment_idx, exit_point); - const auto exit_lat_dist = std::abs( - autoware::motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); - const auto exit_segment_length = autoware::universe_utils::calcDistance2d( - unique_path_points[exit_segment_idx], unique_path_points[exit_segment_idx + 1]); - const auto exit_offset_ratio = exit_offset / static_cast(exit_segment_length); - const auto exit_time = - static_cast(exit_segment_idx) * time_step + exit_offset_ratio * time_step; - - RCLCPP_DEBUG( - logger, "\t\t\tPredicted path (time step = %2.2fs): enter @ %2.2fs, exit @ %2.2fs", time_step, - enter_time, exit_time); - // predicted path is too far from the overlapping range to be relevant - const auto is_far_from_entering_point = enter_lat_dist > max_deviation; - const auto is_far_from_exiting_point = exit_lat_dist > max_deviation; - if (is_far_from_entering_point && is_far_from_exiting_point) { - RCLCPP_DEBUG( - logger, - " * far_from_enter (%d) = %2.2fm | far_from_exit (%d) = %2.2fm | max_dev = %2.2fm\n", - is_far_from_entering_point, enter_lat_dist, is_far_from_exiting_point, exit_lat_dist, - max_deviation); - continue; - } - const auto is_last_predicted_path_point = - (exit_segment_idx + 2 == unique_path_points.size() || - enter_segment_idx + 2 == unique_path_points.size()); - const auto does_not_reach_overlap = - is_last_predicted_path_point && (std::min(exit_offset, enter_offset) > max_lon_deviation); - if (does_not_reach_overlap) { - RCLCPP_DEBUG( - logger, " * does not reach the overlap = %2.2fm | max_dev = %2.2fm\n", - std::min(exit_offset, enter_offset), max_lon_deviation); - continue; - } - - const auto same_driving_direction_as_ego = enter_time < exit_time; - if (same_driving_direction_as_ego) { - worst_enter_time = worst_enter_time ? std::min(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::max(*worst_exit_time, exit_time) : exit_time; - } else { - worst_enter_time = worst_enter_time ? std::max(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::min(*worst_exit_time, exit_time) : exit_time; - } - } - if (worst_enter_time && worst_exit_time) { - RCLCPP_DEBUG( - logger, "\t\t\t * found enter/exit time [%2.2f, %2.2f]\n", *worst_enter_time, - *worst_exit_time); - return std::make_pair(*worst_enter_time, *worst_exit_time); - } - RCLCPP_DEBUG(logger, "\t\t\t * enter/exit time not found\n"); - return {}; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger) -{ - const auto & p = object.kinematics.initial_pose_with_covariance.pose.position; - const auto object_point = lanelet::BasicPoint2d(p.x, p.y); - const auto half_size = object.shape.dimensions.x / 2.0; - lanelet::ConstLanelets object_lanelets; - for (const auto & ll : inputs.lanelets) - if (boost::geometry::within(object_point, ll.polygon2d().basicPolygon())) - object_lanelets.push_back(ll); - - geometry_msgs::msg::Pose pose; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto range_enter_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto range_exit_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - const auto range_size = std::abs(range_enter_length - range_exit_length); - auto worst_enter_dist = std::optional(); - auto worst_exit_dist = std::optional(); - for (const auto & lane : object_lanelets) { - const auto path = inputs.route_handler->getRoutingGraphPtr()->shortestPath(lane, range.lane); - RCLCPP_DEBUG( - logger, "\t\t\tPath ? %d [from %ld to %ld]\n", path.has_value(), lane.id(), range.lane.id()); - if (path) { - lanelet::ConstLanelets lls; - for (const auto & ll : *path) lls.push_back(ll); - pose.position.set__x(object_point.x()).set__y(object_point.y()); - const auto object_curr_length = lanelet::utils::getArcCoordinates(lls, pose).length; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - RCLCPP_DEBUG( - logger, "\t\t\t%2.2f -> [%2.2f(%2.2f, %2.2f) - %2.2f(%2.2f, %2.2f)]\n", object_curr_length, - enter_dist, range.entering_point.x(), range.entering_point.y(), exit_dist, - range.exiting_point.x(), range.exiting_point.y()); - const auto already_entered_range = std::abs(enter_dist - exit_dist) > range_size * 2.0; - if (already_entered_range) continue; - // multiple paths to the overlap -> be conservative and use the "worst" case - // "worst" = min/max arc length depending on if the lane is running opposite to the ego - // trajectory - const auto is_opposite = enter_dist > exit_dist; - if (!worst_enter_dist) - worst_enter_dist = enter_dist; - else if (is_opposite) - worst_enter_dist = std::max(*worst_enter_dist, enter_dist); - else - worst_enter_dist = std::min(*worst_enter_dist, enter_dist); - if (!worst_exit_dist) - worst_exit_dist = exit_dist; - else if (is_opposite) - worst_exit_dist = std::max(*worst_exit_dist, exit_dist); - else - worst_exit_dist = std::min(*worst_exit_dist, exit_dist); - } - } - if (worst_enter_dist && worst_exit_dist) { - const auto v = object.kinematics.initial_twist_with_covariance.twist.linear.x; - return std::make_pair((*worst_enter_dist - half_size) / v, (*worst_exit_dist + half_size) / v); - } - return {}; -} - -bool threshold_condition(const RangeTimes & range_times, const PlannerParam & params) -{ - const auto enter_within_threshold = - range_times.object.enter_time > 0.0 && range_times.object.enter_time < params.time_threshold; - const auto exit_within_threshold = - range_times.object.exit_time > 0.0 && range_times.object.exit_time < params.time_threshold; - return enter_within_threshold || exit_within_threshold; -} - -bool intervals_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto opposite_way_condition = [&]() -> bool { - const auto ego_exits_before_object_enters = - range_times.ego.exit_time + params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] (opposite way) ego exit %2.2fs < obj enter %2.2fs ? -> should not " - "enter = %d\n", - range_times.ego.exit_time + params.intervals_ego_buffer, - range_times.object.enter_time + params.intervals_obj_buffer, ego_exits_before_object_enters); - return ego_exits_before_object_enters; - }; - const auto same_way_condition = [&]() -> bool { - const auto object_enters_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer && - range_times.object.enter_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - const auto object_exits_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.exit_time + params.intervals_obj_buffer && - range_times.object.exit_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] obj enters during overlap ? %d OR obj exits during overlap %d ? -> should " - "not " - "enter = %d\n", - object_enters_during_overlap, object_exits_during_overlap, - object_enters_during_overlap || object_exits_during_overlap); - return object_enters_during_overlap || object_exits_during_overlap; - }; - - const auto object_is_going_same_way = - range_times.object.enter_time < range_times.object.exit_time; - return (object_is_going_same_way && same_way_condition()) || - (!object_is_going_same_way && opposite_way_condition()); -} - -bool ttc_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto ttc_at_enter = range_times.ego.enter_time - range_times.object.enter_time; - const auto ttc_at_exit = range_times.ego.exit_time - range_times.object.exit_time; - const auto collision_during_overlap = (ttc_at_enter < 0.0) != (ttc_at_exit < 0.0); - const auto ttc_is_bellow_threshold = - std::min(std::abs(ttc_at_enter), std::abs(ttc_at_exit)) <= params.ttc_threshold; - RCLCPP_DEBUG( - logger, "\t\t\t[TTC] (%2.2fs - %2.2fs) -> %d\n", ttc_at_enter, ttc_at_exit, - (collision_during_overlap || ttc_is_bellow_threshold)); - return collision_during_overlap || ttc_is_bellow_threshold; -} - -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - RCLCPP_DEBUG( - logger, " enter at %2.2fs, exits at %2.2fs\n", range_times.object.enter_time, - range_times.object.exit_time); - return (params.mode == "threshold" && threshold_condition(range_times, params)) || - (params.mode == "intervals" && intervals_condition(range_times, params, logger)) || - (params.mode == "ttc" && ttc_condition(range_times, params, logger)); -} - -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - RangeTimes range_times{}; - range_times.ego.enter_time = - time_along_trajectory(inputs.ego_data, range.entering_trajectory_idx, params.ego_min_velocity); - range_times.ego.exit_time = - time_along_trajectory(inputs.ego_data, range.exiting_trajectory_idx, params.ego_min_velocity); - RCLCPP_DEBUG( - logger, "\t[%lu -> %lu] %ld | ego enters at %2.2f, exits at %2.2f\n", - range.entering_trajectory_idx, range.exiting_trajectory_idx, range.lane.id(), - range_times.ego.enter_time, range_times.ego.exit_time); - for (const auto & object : inputs.objects.objects) { - RCLCPP_DEBUG( - logger, "\t\t[%s] going at %2.2fm/s", - autoware::universe_utils::toHexString(object.object_id).c_str(), - object.kinematics.initial_twist_with_covariance.twist.linear.x); - if (object.kinematics.initial_twist_with_covariance.twist.linear.x < params.objects_min_vel) { - RCLCPP_DEBUG(logger, " SKIP (velocity bellow threshold %2.2fm/s)\n", params.objects_min_vel); - continue; // skip objects with velocity bellow a threshold - } - // skip objects that are already on the interval - const auto enter_exit_time = - params.objects_use_predicted_paths - ? object_time_to_range( - object, range, inputs.route_handler, params.objects_dist_buffer, logger) - : object_time_to_range(object, range, inputs, logger); - if (!enter_exit_time) { - RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); - continue; // skip objects that are not driving towards the overlapping range - } - - range_times.object.enter_time = enter_exit_time->first; - range_times.object.exit_time = enter_exit_time->second; - if (will_collide_on_range(range_times, params, logger)) { - range.debug.times = range_times; - range.debug.object = object; - return true; - } - } - range.debug.times = range_times; - return false; -} - -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params) -{ - if (distance < params.stop_dist_threshold) { - decision->velocity = 0.0; - } else if (distance < params.slow_dist_threshold) { - decision->velocity = params.slow_velocity; - } else { - decision.reset(); - } -} - -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - std::optional decision; - if (should_not_enter(range, inputs, params, logger)) { - decision.emplace(); - decision->target_trajectory_idx = inputs.ego_data.first_trajectory_idx + - range.entering_trajectory_idx; // add offset from curr pose - decision->lane_to_avoid = range.lane; - const auto ego_dist_to_range = - distance_along_trajectory(inputs.ego_data, range.entering_trajectory_idx); - set_decision_velocity(decision, ego_dist_to_range, params); - } - return decision; -} - -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger) -{ - std::vector decisions; - for (const auto & range : inputs.ranges) { - if (range.entering_trajectory_idx == 0UL) continue; // skip if we already entered the range - const auto optional_decision = calculate_decision(range, inputs, params, logger); - range.debug.decision = optional_decision; - if (optional_decision) decisions.push_back(*optional_decision); - } - return decisions; -} - -} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp deleted file mode 100644 index 455cee272f7be..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp +++ /dev/null @@ -1,116 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef DECISIONS_HPP_ -#define DECISIONS_HPP_ - -#include "types.hpp" - -#include -#include - -#include - -#include - -#include -#include -#include -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ -/// @brief calculate the distance along the ego trajectory between ego and some target trajectory -/// index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego trajectory index -/// @return distance between ego and the target [m] -double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx); -/// @brief estimate the time when ego will reach some target trajectory index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego trajectory index -/// @param [in] min_velocity minimum ego velocity used to estimate the time -/// @return time taken by ego to reach the target [s] -double time_along_trajectory(const EgoData & ego_data, const size_t target_idx); -/// @brief use an object's predicted paths to estimate the times it will reach the enter and exit -/// points of an overlapping range -/// @details times when the predicted paths of the object enters/exits the range are calculated -/// but may not exist (e.g,, predicted path ends before reaching the end of the range) -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] route_handler route handler used to estimate the path of the dynamic object -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger); -/// @brief use the lanelet map to estimate the times when an object will reach the enter and exit -/// points of an overlapping range -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit. -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger); -/// @brief decide whether an object is coming in the range at the same time as ego -/// @details the condition depends on the mode (threshold, intervals, ttc) -/// @param [in] range_times times when ego and the object enter/exit the range -/// @param [in] params parameters -/// @param [in] logger ros logger -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger); -/// @brief check whether we should avoid entering the given range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return true if we should avoid entering the range -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief set the velocity of a decision (or unset it) based on the distance away from the range -/// @param [out] decision decision to update (either set its velocity or unset the decision) -/// @param [in] distance distance between ego and the range corresponding to the decision -/// @param [in] params parameters -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params); -/// @brief calculate the decision to slowdown or stop before an overlapping range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return an optional decision to slowdown or stop -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief calculate decisions to slowdown or stop before some overlapping ranges -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return the calculated decisions to slowdown or stop -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); -} // namespace autoware::motion_velocity_planner::out_of_lane - -#endif // DECISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index a53129f372e3d..79bdefee4c4c7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -53,7 +54,7 @@ void cut_predicted_path_beyond_line( auto cut_idx = stop_line_idx; double arc_length = 0; while (cut_idx > 0 && arc_length < object_front_overhang) { - arc_length += autoware::universe_utils::calcDistance2d( + arc_length += universe_utils::calcDistance2d( predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]); --cut_idx; } @@ -102,12 +103,11 @@ void cut_predicted_path_beyond_red_lights( } autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const std::shared_ptr planner_data, const EgoData & ego_data, - const PlannerParam & params) + const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params) { autoware_perception_msgs::msg::PredictedObjects filtered_objects; - filtered_objects.header = planner_data->predicted_objects.header; - for (const auto & object : planner_data->predicted_objects.objects) { + filtered_objects.header = planner_data.predicted_objects.header; + for (const auto & object : planner_data.predicted_objects.objects) { const auto is_pedestrian = std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; @@ -125,10 +125,10 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( auto filtered_object = object; const auto is_invalid_predicted_path = [&](const auto & predicted_path) { const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; - const auto no_overlap_path = autoware::motion_utils::removeOverlapPoints(predicted_path.path); + const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path); if (no_overlap_path.size() <= 1) return true; - const auto lat_offset_to_current_ego = std::abs( - autoware::motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); + const auto lat_offset_to_current_ego = + std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); const auto is_crossing_ego = lat_offset_to_current_ego <= object.shape.dimensions.y / 2.0 + std::max( @@ -136,23 +136,21 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( params.right_offset + params.extra_right_offset); return is_low_confidence || is_crossing_ego; }; - if (params.objects_use_predicted_paths) { - auto & predicted_paths = filtered_object.kinematics.predicted_paths; - const auto new_end = - std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); - predicted_paths.erase(new_end, predicted_paths.end()); - if (params.objects_cut_predicted_paths_beyond_red_lights) - for (auto & predicted_path : predicted_paths) - cut_predicted_path_beyond_red_lights( - predicted_path, ego_data, filtered_object.shape.dimensions.x); - predicted_paths.erase( - std::remove_if( - predicted_paths.begin(), predicted_paths.end(), - [](const auto & p) { return p.path.empty(); }), - predicted_paths.end()); - } + auto & predicted_paths = filtered_object.kinematics.predicted_paths; + const auto new_end = + std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); + predicted_paths.erase(new_end, predicted_paths.end()); + if (params.objects_cut_predicted_paths_beyond_red_lights) + for (auto & predicted_path : predicted_paths) + cut_predicted_path_beyond_red_lights( + predicted_path, ego_data, filtered_object.shape.dimensions.x); + predicted_paths.erase( + std::remove_if( + predicted_paths.begin(), predicted_paths.end(), + [](const auto & p) { return p.path.empty(); }), + predicted_paths.end()); - if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty()) + if (!filtered_object.kinematics.predicted_paths.empty()) filtered_objects.objects.push_back(filtered_object); } return filtered_objects; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp index baf07e4b06ea5..3b2ae11718810 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -19,7 +19,6 @@ #include -#include #include namespace autoware::motion_velocity_planner::out_of_lane @@ -52,8 +51,7 @@ void cut_predicted_path_beyond_red_lights( /// @param [in] params parameters /// @return filtered predicted objects autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const std::shared_ptr planner_data, const EgoData & ego_data, - const PlannerParam & params); + const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // FILTER_PREDICTED_OBJECTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp index f5d68c4fa9bba..564bf5de7ef2e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp @@ -21,15 +21,13 @@ #include #include -#include #include namespace autoware::motion_velocity_planner::out_of_lane { -autoware::universe_utils::Polygon2d make_base_footprint( - const PlannerParam & p, const bool ignore_offset) +universe_utils::Polygon2d make_base_footprint(const PlannerParam & p, const bool ignore_offset) { - autoware::universe_utils::Polygon2d base_footprint; + universe_utils::Polygon2d base_footprint; const auto front_offset = ignore_offset ? 0.0 : p.extra_front_offset; const auto rear_offset = ignore_offset ? 0.0 : p.extra_rear_offset; const auto right_offset = ignore_offset ? 0.0 : p.extra_right_offset; @@ -43,10 +41,10 @@ autoware::universe_utils::Polygon2d make_base_footprint( } lanelet::BasicPolygon2d project_to_pose( - const autoware::universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) + const universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) { const auto angle = tf2::getYaw(pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); @@ -59,22 +57,15 @@ std::vector calculate_trajectory_footprints( const auto base_footprint = make_base_footprint(params); std::vector trajectory_footprints; trajectory_footprints.reserve(ego_data.trajectory_points.size()); - double length = 0.0; - const auto range = std::max(params.slow_dist_threshold, params.stop_dist_threshold) + - params.front_offset + params.extra_front_offset; - for (auto i = ego_data.first_trajectory_idx; - i < ego_data.trajectory_points.size() && length < range; ++i) { + for (auto i = ego_data.first_trajectory_idx; i < ego_data.trajectory_points.size(); ++i) { const auto & trajectory_pose = ego_data.trajectory_points[i].pose; const auto angle = tf2::getYaw(trajectory_pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back( p.x() + trajectory_pose.position.x, p.y() + trajectory_pose.position.y); trajectory_footprints.push_back(footprint); - if (i + 1 < ego_data.trajectory_points.size()) - length += autoware::universe_utils::calcDistance2d( - trajectory_pose, ego_data.trajectory_points[i + 1].pose); } return trajectory_footprints; } @@ -84,7 +75,7 @@ lanelet::BasicPolygon2d calculate_current_ego_footprint( { const auto base_footprint = make_base_footprint(params, ignore_offset); const auto angle = tf2::getYaw(ego_data.pose.orientation); - const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + ego_data.pose.position.x, p.y() + ego_data.pose.position.y); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp index ebe7ab0fa9d7f..88baeefba6f40 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp @@ -21,24 +21,21 @@ #include -namespace autoware::motion_velocity_planner -{ -namespace out_of_lane +namespace autoware::motion_velocity_planner::out_of_lane { /// @brief create the base footprint of ego /// @param [in] p parameters used to create the footprint /// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the /// footprint /// @return base ego footprint -autoware::universe_utils::Polygon2d make_base_footprint( +universe_utils::Polygon2d make_base_footprint( const PlannerParam & p, const bool ignore_offset = false); /// @brief project a footprint to the given pose /// @param [in] base_footprint footprint to project /// @param [in] pose projection pose /// @return footprint projected to the given pose lanelet::BasicPolygon2d project_to_pose( - const autoware::universe_utils::Polygon2d & base_footprint, - const geometry_msgs::msg::Pose & pose); + const universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); /// @brief calculate the trajectory footprints /// @details the resulting polygon follows the format used by the lanelet library: clockwise order /// and implicit closing edge @@ -54,7 +51,6 @@ std::vector calculate_trajectory_footprints( /// footprint lanelet::BasicPolygon2d calculate_current_ego_footprint( const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset = false); -} // namespace out_of_lane -} // namespace autoware::motion_velocity_planner +} // namespace autoware::motion_velocity_planner::out_of_lane #endif // FOOTPRINT_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp index bca849f806f63..f520a564519f0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -14,36 +14,46 @@ #include "lanelets_selection.hpp" +#include "types.hpp" + #include #include +#include +#include #include -#include #include #include -#include namespace autoware::motion_velocity_planner::out_of_lane { +namespace +{ +bool is_road_lanelet(const lanelet::ConstLanelet & lanelet) +{ + return lanelet.hasAttribute(lanelet::AttributeName::Subtype) && + lanelet.attribute(lanelet::AttributeName::Subtype) == lanelet::AttributeValueString::Road; +} +} // namespace + lanelet::ConstLanelets consecutive_lanelets( - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lanelet) + const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet) { - lanelet::ConstLanelets consecutives = route_handler->getRoutingGraphPtr()->following(lanelet); - const auto previous = route_handler->getRoutingGraphPtr()->previous(lanelet); + lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet); + const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet); consecutives.insert(consecutives.end(), previous.begin(), previous.end()); return consecutives; } lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler) + const lanelet::ConstLanelets & trajectory_lanelets, + const route_handler::RouteHandler & route_handler) { lanelet::ConstLanelets missing_lane_change_lanelets; - const auto & routing_graph = *route_handler->getRoutingGraphPtr(); + const auto & routing_graph = *route_handler.getRoutingGraphPtr(); lanelet::ConstLanelets adjacents; lanelet::ConstLanelets consecutives; for (const auto & ll : trajectory_lanelets) { @@ -67,9 +77,9 @@ lanelet::ConstLanelets get_missing_lane_change_lanelets( } lanelet::ConstLanelets calculate_trajectory_lanelets( - const EgoData & ego_data, const std::shared_ptr route_handler) + const EgoData & ego_data, const route_handler::RouteHandler & route_handler) { - const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + const auto lanelet_map_ptr = route_handler.getLaneletMapPtr(); lanelet::ConstLanelets trajectory_lanelets; lanelet::BasicLineString2d trajectory_ls; for (const auto & p : ego_data.trajectory_points) @@ -77,7 +87,9 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( const auto candidates = lanelet_map_ptr->laneletLayer.search(lanelet::geometry::boundingBox2d(trajectory_ls)); for (const auto & ll : candidates) { - if (!boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { + if ( + is_road_lanelet(ll) && + !boost::geometry::disjoint(trajectory_ls, ll.polygon2d().basicPolygon())) { trajectory_lanelets.push_back(ll); } } @@ -89,43 +101,65 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( } lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params) + const lanelet::ConstLanelets & trajectory_lanelets, + const route_handler::RouteHandler & route_handler) { lanelet::ConstLanelets ignored_lanelets; - // ignore lanelets directly behind ego - const auto behind = - autoware::universe_utils::calcOffsetPose(ego_data.pose, params.rear_offset, 0.0, 0.0); - const lanelet::BasicPoint2d behind_point(behind.position.x, behind.position.y); - const auto behind_lanelets = lanelet::geometry::findWithin2d( - route_handler->getLaneletMapPtr()->laneletLayer, behind_point, 0.0); - for (const auto & l : behind_lanelets) { - const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, l.second.id()); - if (!is_trajectory_lanelet) ignored_lanelets.push_back(l.second); + // ignore lanelets directly preceding a trajectory lanelet + for (const auto & trajectory_lanelet : trajectory_lanelets) { + for (const auto & ll : route_handler.getPreviousLanelets(trajectory_lanelet)) { + const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.id()); + if (!is_trajectory_lanelet) ignored_lanelets.push_back(ll); + } } return ignored_lanelets; } -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params) +void calculate_drivable_lane_polygons( + EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + const auto route_lanelets = calculate_trajectory_lanelets(ego_data, route_handler); + const auto ignored_lanelets = + out_of_lane::calculate_ignored_lanelets(route_lanelets, route_handler); + for (const auto & ll : route_lanelets) { + out_of_lane::Polygons tmp; + boost::geometry::union_(ego_data.drivable_lane_polygons, ll.polygon2d().basicPolygon(), tmp); + ego_data.drivable_lane_polygons = tmp; + } + for (const auto & ll : ignored_lanelets) { + out_of_lane::Polygons tmp; + boost::geometry::union_(ego_data.drivable_lane_polygons, ll.polygon2d().basicPolygon(), tmp); + ego_data.drivable_lane_polygons = tmp; + } +} + +void calculate_overlapped_lanelets( + OutOfLanePoint & out_of_lane_point, const route_handler::RouteHandler & route_handler) { - lanelet::ConstLanelets other_lanelets; - const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y); - const auto lanelets_within_range = lanelet::geometry::findWithin2d( - route_handler->getLaneletMapPtr()->laneletLayer, ego_point, - std::max(params.slow_dist_threshold, params.stop_dist_threshold) + params.front_offset + - params.extra_front_offset); - for (const auto & ll : lanelets_within_range) { - if (std::string(ll.second.attributeOr(lanelet::AttributeName::Subtype, "none")) != "road") - continue; - const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.second.id()); - const auto is_ignored_lanelet = contains_lanelet(ignored_lanelets, ll.second.id()); - if (!is_trajectory_lanelet && !is_ignored_lanelet) other_lanelets.push_back(ll.second); + out_of_lane_point.overlapped_lanelets = lanelet::ConstLanelets(); + const auto candidates = route_handler.getLaneletMapPtr()->laneletLayer.search( + lanelet::geometry::boundingBox2d(out_of_lane_point.outside_ring)); + for (const auto & ll : candidates) { + if ( + is_road_lanelet(ll) && !contains_lanelet(out_of_lane_point.overlapped_lanelets, ll.id()) && + boost::geometry::within(out_of_lane_point.outside_ring, ll.polygon2d().basicPolygon())) { + out_of_lane_point.overlapped_lanelets.push_back(ll); + } + } +} + +void calculate_overlapped_lanelets( + OutOfLaneData & out_of_lane_data, const route_handler::RouteHandler & route_handler) +{ + for (auto it = out_of_lane_data.outside_points.begin(); + it != out_of_lane_data.outside_points.end();) { + calculate_overlapped_lanelets(*it, route_handler); + if (it->overlapped_lanelets.empty()) { + // do not keep out of lane points that do not overlap any lanelet + out_of_lane_data.outside_points.erase(it); + } else { + ++it; + } } - return other_lanelets; } } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp index 8618d808d7d40..a7729deb539b6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -44,6 +44,7 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane /// @return lanelets crossed by the ego vehicle lanelet::ConstLanelets calculate_trajectory_lanelets( const EgoData & ego_data, const std::shared_ptr route_handler); + /// @brief calculate lanelets that may not be crossed by the trajectory but may be overlapped during /// a lane change /// @param [in] trajectory_lanelets lanelets driven by the ego vehicle @@ -51,30 +52,28 @@ lanelet::ConstLanelets calculate_trajectory_lanelets( /// @return lanelets that may be overlapped by a lane change (and are not already in /// trajectory_lanelets) lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler); + const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr & route_handler); + /// @brief calculate lanelets that should be ignored -/// @param [in] ego_data data about the ego vehicle -/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle +/// @param [in] trajectory_lanelets lanelets followed by the ego vehicle /// @param [in] route_handler route handler -/// @param [in] params parameters /// @return lanelets to ignore lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params); -/// @brief calculate lanelets that should be checked by the module -/// @param [in] ego_data data about the ego vehicle -/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle -/// @param [in] ignored_lanelets lanelets to ignore -/// @param [in] route_handler route handler -/// @param [in] params parameters -/// @return lanelets to check for overlaps -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const std::shared_ptr route_handler, - const PlannerParam & params); + const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr & route_handler); + +/// @brief calculate the polygons representing the ego lane and add it to the ego data +/// @param [inout] ego_data ego data +/// @param [in] route_handler route handler with map information +void calculate_drivable_lane_polygons( + EgoData & ego_data, const route_handler::RouteHandler & route_handler); + +/// @brief calculate the lanelets overlapped at each out of lane point +/// @param [out] out_of_lane_data data with the out of lane points +/// @param [in] route_handler route handler with the lanelet map +void calculate_overlapped_lanelets( + OutOfLaneData & out_of_lane_data, const route_handler::RouteHandler & route_handler); } // namespace autoware::motion_velocity_planner::out_of_lane #endif // LANELETS_SELECTION_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp new file mode 100644 index 0000000000000..aef035200b6cc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.cpp @@ -0,0 +1,164 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "out_of_lane_collisions.hpp" + +#include "types.hpp" + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +void update_collision_times( + OutOfLaneData & out_of_lane_data, const std::unordered_set & potential_collision_indexes, + const universe_utils::Polygon2d & object_footprint, const double time) +{ + for (const auto index : potential_collision_indexes) { + auto & out_of_lane_point = out_of_lane_data.outside_points[index]; + if (out_of_lane_point.collision_times.count(time) == 0UL) { + const auto has_collision = + !boost::geometry::disjoint(out_of_lane_point.outside_ring, object_footprint.outer()); + if (has_collision) { + out_of_lane_point.collision_times.insert(time); + } + } + } +} + +void calculate_object_path_time_collisions( + OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedPath & object_path, + const autoware_perception_msgs::msg::Shape & object_shape) +{ + const auto time_step = rclcpp::Duration(object_path.time_step).seconds(); + auto time = time_step; + for (const auto & object_pose : object_path.path) { + time += time_step; + const auto object_footprint = universe_utils::toPolygon2d(object_pose, object_shape); + std::vector query_results; + out_of_lane_data.outside_areas_rtree.query( + boost::geometry::index::intersects(object_footprint.outer()), + std::back_inserter(query_results)); + std::unordered_set potential_collision_indexes; + for (const auto & [_, index] : query_results) { + potential_collision_indexes.insert(index); + } + update_collision_times(out_of_lane_data, potential_collision_indexes, object_footprint, time); + } +} + +void calculate_objects_time_collisions( + OutOfLaneData & out_of_lane_data, + const std::vector & objects) +{ + for (const auto & object : objects) { + for (const auto & path : object.kinematics.predicted_paths) { + calculate_object_path_time_collisions(out_of_lane_data, path, object.shape); + } + } +} + +void calculate_min_max_arrival_times( + OutOfLanePoint & out_of_lane_point, + const std::vector & trajectory) +{ + auto min_time = std::numeric_limits::infinity(); + auto max_time = -std::numeric_limits::infinity(); + for (const auto & t : out_of_lane_point.collision_times) { + min_time = std::min(t, min_time); + max_time = std::max(t, max_time); + } + if (min_time <= max_time) { + out_of_lane_point.min_object_arrival_time = min_time; + out_of_lane_point.max_object_arrival_time = max_time; + const auto & ego_time = + rclcpp::Duration(trajectory[out_of_lane_point.trajectory_index].time_from_start).seconds(); + if (ego_time >= min_time && ego_time <= max_time) { + out_of_lane_point.ttc = 0.0; + } else { + out_of_lane_point.ttc = + std::min(std::abs(ego_time - min_time), std::abs(ego_time - max_time)); + } + } +}; + +void calculate_collisions_to_avoid( + OutOfLaneData & out_of_lane_data, + const std::vector & trajectory, + const PlannerParam & params) +{ + for (auto & out_of_lane_point : out_of_lane_data.outside_points) { + calculate_min_max_arrival_times(out_of_lane_point, trajectory); + } + for (auto & p : out_of_lane_data.outside_points) { + if (params.mode == "ttc") { + p.to_avoid = p.ttc && p.ttc <= params.ttc_threshold; + } else { + p.to_avoid = p.min_object_arrival_time && p.min_object_arrival_time <= params.time_threshold; + } + } +} + +std::vector calculate_out_of_lane_points(const EgoData & ego_data) +{ + std::vector out_of_lane_points; + OutOfLanePoint p; + for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { + p.trajectory_index = i + ego_data.first_trajectory_idx; + const auto & footprint = ego_data.trajectory_footprints[i]; + Polygons out_of_lane_polygons; + boost::geometry::difference(footprint, ego_data.drivable_lane_polygons, out_of_lane_polygons); + for (const auto & area : out_of_lane_polygons) { + if (!area.outer.empty()) { + p.outside_ring = area.outer; + out_of_lane_points.push_back(p); + } + } + } + return out_of_lane_points; +} + +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data) +{ + std::vector rtree_nodes; + for (auto i = 0UL; i < out_of_lane_data.outside_points.size(); ++i) { + OutAreaNode n; + n.first = boost::geometry::return_envelope( + out_of_lane_data.outside_points[i].outside_ring); + n.second = i; + rtree_nodes.push_back(n); + } + out_of_lane_data.outside_areas_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; +} + +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp new file mode 100644 index 0000000000000..33f0842c56d36 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef OUT_OF_LANE_COLLISIONS_HPP_ +#define OUT_OF_LANE_COLLISIONS_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +/// @brief calculate the times and points where ego collides with an object's path outside of its +/// lane +void calculate_object_path_time_collisions( + OutOfLaneData & out_of_lane_data, + const autoware_perception_msgs::msg::PredictedPath & object_path, + const autoware_perception_msgs::msg::Shape & object_shape); + +/// @brief calculate the times and points where ego collides with an object outside of its lane +void calculate_objects_time_collisions( + OutOfLaneData & out_of_lane_data, + const std::vector & objects); + +/// @brief calculate the collisions to avoid +/// @details either uses the time to collision or just the time when the object will arrive at the +/// point +void calculate_collisions_to_avoid( + OutOfLaneData & out_of_lane_data, + const std::vector & trajectory, + const PlannerParam & params); + +/// @brief calculate the out of lane points +std::vector calculate_out_of_lane_points(const EgoData & ego_data); + +/// @brief prepare the rtree of out of lane points for the given data +void prepare_out_of_lane_areas_rtree(OutOfLaneData & out_of_lane_data); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // OUT_OF_LANE_COLLISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index a6b34a1566e19..c97e10cc8706e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -16,16 +16,16 @@ #include "calculate_slowdown_points.hpp" #include "debug.hpp" -#include "decisions.hpp" #include "filter_predicted_objects.hpp" #include "footprint.hpp" #include "lanelets_selection.hpp" -#include "overlapping_range.hpp" +#include "out_of_lane_collisions.hpp" #include "types.hpp" #include #include #include +#include #include #include #include @@ -34,11 +34,13 @@ #include #include +#include #include #include #include +#include #include #include #include @@ -56,65 +58,52 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) logger_ = node.get_logger(); clock_ = node.get_clock(); init_parameters(node); - velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_interface_.init(motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - processing_diag_publisher_ = std::make_shared( + processing_diag_publisher_ = std::make_shared( &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); processing_time_publisher_ = node.create_publisher( "~/debug/" + ns_ + "/processing_time_ms", 1); } void OutOfLaneModule::init_parameters(rclcpp::Node & node) { - using autoware::universe_utils::getOrDeclareParameter; + using universe_utils::getOrDeclareParameter; auto & pp = params_; pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); pp.skip_if_already_overlapping = getOrDeclareParameter(node, ns_ + ".skip_if_already_overlapping"); + pp.max_arc_length = getOrDeclareParameter(node, ns_ + ".max_arc_length"); pp.time_threshold = getOrDeclareParameter(node, ns_ + ".threshold.time_threshold"); - pp.intervals_ego_buffer = getOrDeclareParameter(node, ns_ + ".intervals.ego_time_buffer"); - pp.intervals_obj_buffer = - getOrDeclareParameter(node, ns_ + ".intervals.objects_time_buffer"); pp.ttc_threshold = getOrDeclareParameter(node, ns_ + ".ttc.threshold"); pp.objects_min_vel = getOrDeclareParameter(node, ns_ + ".objects.minimum_velocity"); - pp.objects_use_predicted_paths = - getOrDeclareParameter(node, ns_ + ".objects.use_predicted_paths"); pp.objects_min_confidence = getOrDeclareParameter(node, ns_ + ".objects.predicted_path_min_confidence"); - pp.objects_dist_buffer = getOrDeclareParameter(node, ns_ + ".objects.distance_buffer"); pp.objects_cut_predicted_paths_beyond_red_lights = getOrDeclareParameter(node, ns_ + ".objects.cut_predicted_paths_beyond_red_lights"); pp.objects_ignore_behind_ego = getOrDeclareParameter(node, ns_ + ".objects.ignore_behind_ego"); - pp.overlap_min_dist = getOrDeclareParameter(node, ns_ + ".overlap.minimum_distance"); - pp.overlap_extra_length = getOrDeclareParameter(node, ns_ + ".overlap.extra_length"); - - pp.skip_if_over_max_decel = - getOrDeclareParameter(node, ns_ + ".action.skip_if_over_max_decel"); pp.precision = getOrDeclareParameter(node, ns_ + ".action.precision"); pp.min_decision_duration = getOrDeclareParameter(node, ns_ + ".action.min_duration"); pp.lon_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.longitudinal_distance_buffer"); pp.lat_dist_buffer = getOrDeclareParameter(node, ns_ + ".action.lateral_distance_buffer"); pp.slow_velocity = getOrDeclareParameter(node, ns_ + ".action.slowdown.velocity"); - pp.slow_dist_threshold = - getOrDeclareParameter(node, ns_ + ".action.slowdown.distance_threshold"); pp.stop_dist_threshold = getOrDeclareParameter(node, ns_ + ".action.stop.distance_threshold"); - pp.ego_min_velocity = getOrDeclareParameter(node, ns_ + ".ego.min_assumed_velocity"); pp.extra_front_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_front_offset"); pp.extra_rear_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_rear_offset"); pp.extra_left_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_left_offset"); pp.extra_right_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_right_offset"); - const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); + const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.front_offset = vehicle_info.max_longitudinal_offset_m; pp.rear_offset = vehicle_info.min_longitudinal_offset_m; pp.left_offset = vehicle_info.max_lateral_offset_m; @@ -123,44 +112,79 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) void OutOfLaneModule::update_parameters(const std::vector & parameters) { - using autoware::universe_utils::updateParam; + using universe_utils::updateParam; auto & pp = params_; updateParam(parameters, ns_ + ".mode", pp.mode); updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); + updateParam(parameters, ns_ + ".max_arc_length", pp.max_arc_length); updateParam(parameters, ns_ + ".threshold.time_threshold", pp.time_threshold); - updateParam(parameters, ns_ + ".intervals.ego_time_buffer", pp.intervals_ego_buffer); - updateParam(parameters, ns_ + ".intervals.objects_time_buffer", pp.intervals_obj_buffer); updateParam(parameters, ns_ + ".ttc.threshold", pp.ttc_threshold); updateParam(parameters, ns_ + ".objects.minimum_velocity", pp.objects_min_vel); - updateParam(parameters, ns_ + ".objects.use_predicted_paths", pp.objects_use_predicted_paths); updateParam( parameters, ns_ + ".objects.predicted_path_min_confidence", pp.objects_min_confidence); - updateParam(parameters, ns_ + ".objects.distance_buffer", pp.objects_dist_buffer); updateParam( parameters, ns_ + ".objects.cut_predicted_paths_beyond_red_lights", pp.objects_cut_predicted_paths_beyond_red_lights); updateParam(parameters, ns_ + ".objects.ignore_behind_ego", pp.objects_ignore_behind_ego); - updateParam(parameters, ns_ + ".overlap.minimum_distance", pp.overlap_min_dist); - updateParam(parameters, ns_ + ".overlap.extra_length", pp.overlap_extra_length); - updateParam(parameters, ns_ + ".action.skip_if_over_max_decel", pp.skip_if_over_max_decel); updateParam(parameters, ns_ + ".action.precision", pp.precision); updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration); updateParam(parameters, ns_ + ".action.longitudinal_distance_buffer", pp.lon_dist_buffer); updateParam(parameters, ns_ + ".action.lateral_distance_buffer", pp.lat_dist_buffer); updateParam(parameters, ns_ + ".action.slowdown.velocity", pp.slow_velocity); - updateParam(parameters, ns_ + ".action.slowdown.distance_threshold", pp.slow_dist_threshold); updateParam(parameters, ns_ + ".action.stop.distance_threshold", pp.stop_dist_threshold); - updateParam(parameters, ns_ + ".ego.min_assumed_velocity", pp.ego_min_velocity); updateParam(parameters, ns_ + ".ego.extra_front_offset", pp.extra_front_offset); updateParam(parameters, ns_ + ".ego.extra_rear_offset", pp.extra_rear_offset); updateParam(parameters, ns_ + ".ego.extra_left_offset", pp.extra_left_offset); updateParam(parameters, ns_ + ".ego.extra_right_offset", pp.extra_right_offset); } +void OutOfLaneModule::limit_trajectory_size( + out_of_lane::EgoData & ego_data, + const std::vector & ego_trajectory_points, + const double max_arc_length) +{ + ego_data.first_trajectory_idx = + motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); + ego_data.longitudinal_offset_to_first_trajectory_index = + motion_utils::calcLongitudinalOffsetToSegment( + ego_trajectory_points, ego_data.first_trajectory_idx, ego_data.pose.position); + auto l = -ego_data.longitudinal_offset_to_first_trajectory_index; + ego_data.trajectory_points.push_back(ego_trajectory_points[ego_data.first_trajectory_idx]); + for (auto i = ego_data.first_trajectory_idx + 1; i < ego_trajectory_points.size(); ++i) { + l += universe_utils::calcDistance2d(ego_trajectory_points[i - 1], ego_trajectory_points[i]); + if (l >= max_arc_length) { + break; + } + ego_data.trajectory_points.push_back(ego_trajectory_points[i]); + } +} + +void OutOfLaneModule::calculate_min_stop_and_slowdown_distances( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, + std::optional & previous_slowdown_pose_, const double slow_velocity) +{ + ego_data.min_stop_distance = planner_data.calculate_min_deceleration_distance(0.0).value_or(0.0); + ego_data.min_slowdown_distance = + planner_data.calculate_min_deceleration_distance(slow_velocity).value_or(0.0); + if (previous_slowdown_pose_) { + // Ensure we do not remove the previous slowdown point due to the min distance limit + const auto previous_slowdown_pose_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, ego_data.first_trajectory_idx, previous_slowdown_pose_->position); + ego_data.min_stop_distance = + std::min(previous_slowdown_pose_arc_length, ego_data.min_stop_distance); + ego_data.min_slowdown_distance = + std::min(previous_slowdown_pose_arc_length, ego_data.min_slowdown_distance); + } + ego_data.min_stop_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0UL, ego_data.first_trajectory_idx) + + ego_data.longitudinal_offset_to_first_trajectory_index + + ego_data.min_stop_distance; +} + void prepare_stop_lines_rtree( out_of_lane::EgoData & ego_data, const PlannerData & planner_data, const double search_distance) { @@ -197,168 +221,154 @@ void prepare_stop_lines_rtree( ego_data.stop_lines_rtree = {rtree_nodes.begin(), rtree_nodes.end()}; } +out_of_lane::OutOfLaneData prepare_out_of_lane_data( + const out_of_lane::EgoData & ego_data, const route_handler::RouteHandler & route_handler) +{ + out_of_lane::OutOfLaneData out_of_lane_data; + out_of_lane_data.outside_points = out_of_lane::calculate_out_of_lane_points(ego_data); + out_of_lane::calculate_overlapped_lanelets(out_of_lane_data, route_handler); + out_of_lane::prepare_out_of_lane_areas_rtree(out_of_lane_data); + return out_of_lane_data; +} + VelocityPlanningResult OutOfLaneModule::plan( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) { VelocityPlanningResult result; - autoware::universe_utils::StopWatch stopwatch; + universe_utils::StopWatch stopwatch; stopwatch.tic(); + + stopwatch.tic("preprocessing"); out_of_lane::EgoData ego_data; ego_data.pose = planner_data->current_odometry.pose.pose; - ego_data.trajectory_points = ego_trajectory_points; - ego_data.first_trajectory_idx = - autoware::motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); - ego_data.velocity = planner_data->current_odometry.twist.twist.linear.x; - ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel(); - stopwatch.tic("preprocessing"); - prepare_stop_lines_rtree(ego_data, *planner_data, 100.0); + limit_trajectory_size(ego_data, ego_trajectory_points, params_.max_arc_length); + calculate_min_stop_and_slowdown_distances( + ego_data, *planner_data, previous_slowdown_pose_, params_.slow_velocity); + prepare_stop_lines_rtree(ego_data, *planner_data, params_.max_arc_length); const auto preprocessing_us = stopwatch.toc("preprocessing"); stopwatch.tic("calculate_trajectory_footprints"); - const auto current_ego_footprint = + ego_data.current_footprint = out_of_lane::calculate_current_ego_footprint(ego_data, params_, true); - const auto trajectory_footprints = - out_of_lane::calculate_trajectory_footprints(ego_data, params_); + ego_data.trajectory_footprints = out_of_lane::calculate_trajectory_footprints(ego_data, params_); const auto calculate_trajectory_footprints_us = stopwatch.toc("calculate_trajectory_footprints"); - // Calculate lanelets to ignore and consider + stopwatch.tic("calculate_lanelets"); - const auto trajectory_lanelets = - out_of_lane::calculate_trajectory_lanelets(ego_data, planner_data->route_handler); - const auto ignored_lanelets = out_of_lane::calculate_ignored_lanelets( - ego_data, trajectory_lanelets, planner_data->route_handler, params_); - const auto other_lanelets = out_of_lane::calculate_other_lanelets( - ego_data, trajectory_lanelets, ignored_lanelets, planner_data->route_handler, params_); + out_of_lane::calculate_drivable_lane_polygons(ego_data, *planner_data->route_handler); const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); - debug_data_.reset_data(); - debug_data_.trajectory_points = ego_trajectory_points; - debug_data_.footprints = trajectory_footprints; - debug_data_.trajectory_lanelets = trajectory_lanelets; - debug_data_.ignored_lanelets = ignored_lanelets; - debug_data_.other_lanelets = other_lanelets; - debug_data_.first_trajectory_idx = ego_data.first_trajectory_idx; - - if (params_.skip_if_already_overlapping) { - debug_data_.current_footprint = current_ego_footprint; - const auto overlapped_lanelet_it = - std::find_if(other_lanelets.begin(), other_lanelets.end(), [&](const auto & ll) { - return boost::geometry::intersects(ll.polygon2d().basicPolygon(), current_ego_footprint); - }); - if (overlapped_lanelet_it != other_lanelets.end()) { - debug_data_.current_overlapped_lanelets.push_back(*overlapped_lanelet_it); - RCLCPP_DEBUG(logger_, "Ego is already overlapping a lane, skipping the module\n"); - return result; - } - } - // Calculate overlapping ranges - stopwatch.tic("calculate_overlapping_ranges"); - const auto ranges = out_of_lane::calculate_overlapping_ranges( - trajectory_footprints, trajectory_lanelets, other_lanelets, params_); - const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); - // Calculate stop and slowdown points - out_of_lane::DecisionInputs inputs; - inputs.ranges = ranges; - inputs.ego_data = ego_data; + stopwatch.tic("calculate_out_of_lane_areas"); + auto out_of_lane_data = prepare_out_of_lane_data(ego_data, *planner_data->route_handler); + const auto calculate_out_of_lane_areas_us = stopwatch.toc("calculate_out_of_lane_areas"); + stopwatch.tic("filter_predicted_objects"); - inputs.objects = out_of_lane::filter_predicted_objects(planner_data, ego_data, params_); + const auto objects = out_of_lane::filter_predicted_objects(*planner_data, ego_data, params_); const auto filter_predicted_objects_us = stopwatch.toc("filter_predicted_objects"); - inputs.route_handler = planner_data->route_handler; - inputs.lanelets = other_lanelets; - stopwatch.tic("calculate_decisions"); - const auto decisions = out_of_lane::calculate_decisions(inputs, params_, logger_); - const auto calculate_decisions_us = stopwatch.toc("calculate_decisions"); - stopwatch.tic("calc_slowdown_points"); + + stopwatch.tic("calculate_time_collisions"); + out_of_lane::calculate_objects_time_collisions(out_of_lane_data, objects.objects); + const auto calculate_time_collisions_us = stopwatch.toc("calculate_time_collisions"); + + stopwatch.tic("calculate_times"); + // calculate times + out_of_lane::calculate_collisions_to_avoid(out_of_lane_data, ego_data.trajectory_points, params_); + const auto calculate_times_us = stopwatch.toc("calculate_times"); + + if ( + params_.skip_if_already_overlapping && !ego_data.drivable_lane_polygons.empty() && + !lanelet::geometry::within(ego_data.current_footprint, ego_data.drivable_lane_polygons)) { + RCLCPP_WARN(logger_, "Ego is already out of lane, skipping the module\n"); + debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array( + ego_data, out_of_lane_data, objects, debug_data_)); + return result; + } + if ( // reset the previous inserted point if the timer expired - prev_inserted_point_ && - (clock_->now() - prev_inserted_point_time_).seconds() > params_.min_decision_duration) - prev_inserted_point_.reset(); - auto point_to_insert = - out_of_lane::calculate_slowdown_point(ego_data, decisions, prev_inserted_point_, params_); - const auto calc_slowdown_points_us = stopwatch.toc("calc_slowdown_points"); - stopwatch.tic("insert_slowdown_points"); - debug_data_.slowdowns.clear(); - if ( // reset the timer if there is no previous inserted point or if we avoid the same lane - point_to_insert && - (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == - point_to_insert->slowdown.lane_to_avoid.id())) - prev_inserted_point_time_ = clock_->now(); - // reuse previous stop point if there is no new one or if its velocity is not higher than the new + previous_slowdown_pose_ && + (clock_->now() - previous_slowdown_time_).seconds() > params_.min_decision_duration) { + previous_slowdown_pose_.reset(); + } + + stopwatch.tic("calculate_slowdown_point"); + auto slowdown_pose = out_of_lane::calculate_slowdown_point(ego_data, out_of_lane_data, params_); + const auto calculate_slowdown_point_us = stopwatch.toc("calculate_slowdown_point"); + + if ( // reset the timer if there is no previous inserted point + slowdown_pose && (!previous_slowdown_pose_)) { + previous_slowdown_time_ = clock_->now(); + } + // reuse previous stop pose if there is no new one or if its velocity is not higher than the new // one and its arc length is lower - const auto should_use_prev_inserted_point = [&]() { - if ( - point_to_insert && prev_inserted_point_ && - prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { - const auto arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, point_to_insert->point.pose.position); - const auto prev_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); + const auto should_use_previous_pose = [&]() { + if (slowdown_pose && previous_slowdown_pose_) { + const auto arc_length = + motion_utils::calcSignedArcLength(ego_trajectory_points, 0LU, slowdown_pose->position); + const auto prev_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); return prev_arc_length < arc_length; } - return !point_to_insert && prev_inserted_point_; + return !slowdown_pose && previous_slowdown_pose_; }(); - if (should_use_prev_inserted_point) { + if (should_use_previous_pose) { // if the trajectory changed the prev point is no longer on the trajectory so we project it - const auto insert_arc_length = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); - prev_inserted_point_->point.pose = - autoware::motion_utils::calcInterpolatedPose(ego_trajectory_points, insert_arc_length); - point_to_insert = prev_inserted_point_; + const auto new_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, previous_slowdown_pose_->position); + slowdown_pose = motion_utils::calcInterpolatedPose(ego_trajectory_points, new_arc_length); } - if (point_to_insert) { - prev_inserted_point_ = point_to_insert; - RCLCPP_DEBUG(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); - debug_data_.slowdowns = {*point_to_insert}; - if (point_to_insert->slowdown.velocity == 0.0) - result.stop_points.push_back(point_to_insert->point.pose.position); - else + if (slowdown_pose) { + const auto arc_length = + motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.first_trajectory_idx, slowdown_pose->position) - + ego_data.longitudinal_offset_to_first_trajectory_index; + const auto slowdown_velocity = + arc_length <= params_.stop_dist_threshold ? 0.0 : params_.slow_velocity; + previous_slowdown_pose_ = slowdown_pose; + if (slowdown_velocity == 0.0) { + result.stop_points.push_back(slowdown_pose->position); + } else { result.slowdown_intervals.emplace_back( - point_to_insert->point.pose.position, point_to_insert->point.pose.position, - point_to_insert->slowdown.velocity); - - const auto is_approaching = autoware::motion_utils::calcSignedArcLength( - ego_trajectory_points, ego_data.pose.position, - point_to_insert->point.pose.position) > 0.1 && - ego_data.velocity > 0.1; - const auto status = is_approaching ? autoware::motion_utils::VelocityFactor::APPROACHING - : autoware::motion_utils::VelocityFactor::STOPPED; + slowdown_pose->position, slowdown_pose->position, slowdown_velocity); + } + + const auto is_approaching = + motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.pose.position, slowdown_pose->position) > 0.1 && + planner_data->current_odometry.twist.twist.linear.x > 0.1; + const auto status = is_approaching ? motion_utils::VelocityFactor::APPROACHING + : motion_utils::VelocityFactor::STOPPED; velocity_factor_interface_.set( - ego_trajectory_points, ego_data.pose, point_to_insert->point.pose, status, "out_of_lane"); + ego_trajectory_points, ego_data.pose, *slowdown_pose, status, "out_of_lane"); result.velocity_factor = velocity_factor_interface_.get(); - } else if (!decisions.empty()) { - RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); + virtual_wall_marker_creator.add_virtual_walls( + out_of_lane::debug::create_virtual_walls(*slowdown_pose, slowdown_velocity == 0.0, params_)); + virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); + } else if (std::any_of( + out_of_lane_data.outside_points.begin(), out_of_lane_data.outside_points.end(), + [](const auto & p) { return p.to_avoid; })) { + RCLCPP_WARN( + logger_, "[out_of_lane] Could not insert slowdown point because of deceleration limits"); } - const auto insert_slowdown_points_us = stopwatch.toc("insert_slowdown_points"); - debug_data_.ranges = inputs.ranges; + stopwatch.tic("gen_debug"); + const auto markers = + out_of_lane::debug::create_debug_marker_array(ego_data, out_of_lane_data, objects, debug_data_); + const auto markers_us = stopwatch.toc("gen_debug"); + stopwatch.tic("pub"); + debug_publisher_->publish(markers); + const auto pub_markers_us = stopwatch.toc("pub"); const auto total_time_us = stopwatch.toc(); - RCLCPP_DEBUG( - logger_, - "Total time = %2.2fus\n" - "\tpreprocessing = %2.0fus\n" - "\tcalculate_lanelets = %2.0fus\n" - "\tcalculate_trajectory_footprints = %2.0fus\n" - "\tcalculate_overlapping_ranges = %2.0fus\n" - "\tfilter_pred_objects = %2.0fus\n" - "\tcalculate_decisions = %2.0fus\n" - "\tcalc_slowdown_points = %2.0fus\n" - "\tinsert_slowdown_points = %2.0fus\n", - preprocessing_us, total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_us, - calculate_overlapping_ranges_us, filter_predicted_objects_us, calculate_decisions_us, - calc_slowdown_points_us, insert_slowdown_points_us); - debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array(debug_data_)); - virtual_wall_marker_creator.add_virtual_walls( - out_of_lane::debug::create_virtual_walls(debug_data_, params_)); - virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); std::map processing_times; processing_times["preprocessing"] = preprocessing_us / 1000; processing_times["calculate_lanelets"] = calculate_lanelets_us / 1000; processing_times["calculate_trajectory_footprints"] = calculate_trajectory_footprints_us / 1000; - processing_times["calculate_overlapping_ranges"] = calculate_overlapping_ranges_us / 1000; + processing_times["calculate_out_of_lane_areas"] = calculate_out_of_lane_areas_us / 1000; processing_times["filter_pred_objects"] = filter_predicted_objects_us / 1000; - processing_times["calculate_decision"] = calculate_decisions_us / 1000; - processing_times["calc_slowdown_points"] = calc_slowdown_points_us / 1000; - processing_times["insert_slowdown_points"] = insert_slowdown_points_us / 1000; + processing_times["calculate_time_collisions"] = calculate_time_collisions_us / 1000; + processing_times["calculate_times"] = calculate_times_us / 1000; + processing_times["calculate_slowdown_point"] = calculate_slowdown_point_us / 1000; + processing_times["generate_markers"] = markers_us / 1000; + processing_times["publish_markers"] = pub_markers_us / 1000; processing_times["Total"] = total_time_us / 1000; processing_diag_publisher_->publish(processing_times); tier4_debug_msgs::msg::Float64Stamped processing_time_msg; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 310a73c04d643..fc0cd4ac539ca 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -23,12 +23,14 @@ #include #include +#include #include #include #include #include +#include #include #include @@ -46,17 +48,28 @@ class OutOfLaneModule : public PluginModuleInterface private: void init_parameters(rclcpp::Node & node); - out_of_lane::PlannerParam params_; + /// @brief resize the trajectory to start from the segment closest to ego and to have at most the + /// given length + static void limit_trajectory_size( + out_of_lane::EgoData & ego_data, + const std::vector & ego_trajectory_points, + const double max_arc_length); + /// @brief calculate the minimum stop and slowdown distances of ego + static void calculate_min_stop_and_slowdown_distances( + out_of_lane::EgoData & ego_data, const PlannerData & planner_data, + std::optional & previous_slowdown_pose_, const double slow_velocity); + + out_of_lane::PlannerParam params_{}; inline static const std::string ns_ = "out_of_lane"; - std::string module_name_; - std::optional prev_inserted_point_{}; - rclcpp::Clock::SharedPtr clock_{}; - rclcpp::Time prev_inserted_point_time_{}; + std::string module_name_{"uninitialized"}; + rclcpp::Clock::SharedPtr clock_{nullptr}; + std::optional previous_slowdown_pose_{std::nullopt}; + rclcpp::Time previous_slowdown_time_{0}; protected: // Debug - mutable out_of_lane::DebugData debug_data_; + mutable out_of_lane::DebugData debug_data_{}; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp deleted file mode 100644 index a1a722bb07f14..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp +++ /dev/null @@ -1,127 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "overlapping_range.hpp" - -#include -#include - -#include - -#include -#include - -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ - -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & trajectory_footprint, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet) -{ - Overlap overlap; - const auto & left_bound = lanelet.leftBound2d().basicLineString(); - const auto & right_bound = lanelet.rightBound2d().basicLineString(); - // TODO(Maxime): these intersects (for each trajectory footprint, for each lanelet) are too - // expensive - const auto overlap_left = boost::geometry::intersects(trajectory_footprint, left_bound); - const auto overlap_right = boost::geometry::intersects(trajectory_footprint, right_bound); - - lanelet::BasicPolygons2d overlapping_polygons; - if (overlap_left || overlap_right) - boost::geometry::intersection( - trajectory_footprint, lanelet.polygon2d().basicPolygon(), overlapping_polygons); - for (const auto & overlapping_polygon : overlapping_polygons) { - for (const auto & point : overlapping_polygon) { - if (overlap_left && overlap_right) - overlap.inside_distance = boost::geometry::distance(left_bound, right_bound); - else if (overlap_left) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, left_bound)); - else if (overlap_right) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, right_bound)); - geometry_msgs::msg::Pose p; - p.position.x = point.x(); - p.position.y = point.y(); - const auto length = lanelet::utils::getArcCoordinates(trajectory_lanelets, p).length; - if (length > overlap.max_arc_length) { - overlap.max_arc_length = length; - overlap.max_overlap_point = point; - } - if (length < overlap.min_arc_length) { - overlap.min_arc_length = length; - overlap.min_overlap_point = point; - } - } - } - return overlap; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params) -{ - OverlapRanges ranges; - OtherLane other_lane(lanelet); - std::vector overlaps; - for (auto i = 0UL; i < trajectory_footprints.size(); ++i) { - const auto overlap = calculate_overlap(trajectory_footprints[i], trajectory_lanelets, lanelet); - const auto has_overlap = overlap.inside_distance > params.overlap_min_dist; - if (has_overlap) { // open/update the range - overlaps.push_back(overlap); - if (!other_lane.range_is_open) { - other_lane.first_range_bound.index = i; - other_lane.first_range_bound.point = overlap.min_overlap_point; - other_lane.first_range_bound.arc_length = - overlap.min_arc_length - params.overlap_extra_length; - other_lane.first_range_bound.inside_distance = overlap.inside_distance; - other_lane.range_is_open = true; - } - other_lane.last_range_bound.index = i; - other_lane.last_range_bound.point = overlap.max_overlap_point; - other_lane.last_range_bound.arc_length = overlap.max_arc_length + params.overlap_extra_length; - other_lane.last_range_bound.inside_distance = overlap.inside_distance; - } else if (other_lane.range_is_open) { // !has_overlap: close the range if it is open - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - } - // close the range if it is still open - if (other_lane.range_is_open) { - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - return ranges; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params) -{ - OverlapRanges ranges; - for (auto & lanelet : lanelets) { - const auto lanelet_ranges = - calculate_overlapping_ranges(trajectory_footprints, trajectory_lanelets, lanelet, params); - ranges.insert(ranges.end(), lanelet_ranges.begin(), lanelet_ranges.end()); - } - return ranges; -} - -} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp deleted file mode 100644 index bc5872db16e03..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef OVERLAPPING_RANGE_HPP_ -#define OVERLAPPING_RANGE_HPP_ - -#include "types.hpp" - -#include - -#include - -#include - -namespace autoware::motion_velocity_planner::out_of_lane -{ - -/// @brief calculate the overlap between the given footprint and lanelet -/// @param [in] path_footprint footprint used to calculate the overlap -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelet lanelet used to calculate the overlap -/// @return the found overlap between the footprint and the lanelet -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & trajectory_footprint, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet); -/// @brief calculate the overlapping ranges between the trajectory footprints and a lanelet -/// @param [in] trajectory_footprints footprints used to calculate the overlaps -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelet lanelet used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelet -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params); -/// @brief calculate the overlapping ranges between the trajectory footprints and some lanelets -/// @param [in] trajectory_footprints footprints used to calculate the overlaps -/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego -/// trajectory -/// @param [in] lanelets lanelets used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelets, sorted by -/// increasing arc length along the trajectory -OverlapRanges calculate_overlapping_ranges( - const std::vector & trajectory_footprints, - const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params); -} // namespace autoware::motion_velocity_planner::out_of_lane - -#endif // OVERLAPPING_RANGE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp index 96c54064e296c..c3714c5609135 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -28,52 +28,45 @@ #include #include +#include -#include -#include -#include #include +#include #include #include #include namespace autoware::motion_velocity_planner::out_of_lane { -using autoware_planning_msgs::msg::TrajectoryPoint; +using Polygons = boost::geometry::model::multi_polygon; -/// @brief parameters for the "out of lane" module +/// @brief parameters for the out_of_lane module struct PlannerParam { std::string mode; // mode used to consider a conflict with an object bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps // another lane + double max_arc_length; // [m] maximum arc length along the trajectory to check for collision - double time_threshold; // [s](mode="threshold") objects time threshold - double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range - double intervals_obj_buffer; // [s](mode="intervals") buffer to extend the objects time range + double time_threshold; // [s](mode="threshold") objects time threshold double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object - double ego_min_velocity; // [m/s] minimum velocity of ego used to calculate its ttc or time range - bool objects_use_predicted_paths; // whether to use the objects' predicted paths bool objects_cut_predicted_paths_beyond_red_lights; // whether to cut predicted paths beyond red // lights' stop lines - double objects_min_vel; // [m/s] objects lower than this velocity will be ignored - double objects_min_confidence; // minimum confidence to consider a predicted path - double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in - // the other lane + double objects_min_vel; // [m/s] objects lower than this velocity will be ignored + double objects_min_confidence; // minimum confidence to consider a predicted path bool objects_ignore_behind_ego; // if true, objects behind the ego vehicle are ignored - double overlap_extra_length; // [m] extra length to add around an overlap range - double overlap_min_dist; // [m] min distance inside another lane to consider an overlap - // action to insert in the trajectory if an object causes a conflict at an overlap - bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel - double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle - double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle - double slow_velocity; - double slow_dist_threshold; - double stop_dist_threshold; - double precision; // [m] precision when inserting a stop pose in the trajectory - double min_decision_duration; // [s] minimum duration needed a decision can be canceled + // action to insert in the trajectory if an object causes a collision at an overlap + double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle + double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle + double slow_velocity; // [m/s] slowdown velocity + double stop_dist_threshold; // [m] if a collision is detected bellow this distance ahead of ego, + // try to insert a stop point + double precision; // [m] precision when inserting a stop pose in the trajectory + double + min_decision_duration; // [s] duration needed before a stop or slowdown point can be removed + // ego dimensions used to create its polygon footprint double front_offset; // [m] front offset (from vehicle info) double rear_offset; // [m] rear offset (from vehicle info) @@ -85,98 +78,6 @@ struct PlannerParam double extra_left_offset; // [m] extra left distance }; -struct EnterExitTimes -{ - double enter_time{}; - double exit_time{}; -}; -struct RangeTimes -{ - EnterExitTimes ego{}; - EnterExitTimes object{}; -}; - -/// @brief action taken by the "out of lane" module -struct Slowdown -{ - size_t target_trajectory_idx{}; // we want to slowdown before this trajectory index - double velocity{}; // desired slow down velocity - lanelet::ConstLanelet lane_to_avoid{}; // we want to slowdown before entering this lane -}; -/// @brief slowdown to insert in a trajectory -struct SlowdownToInsert -{ - Slowdown slowdown{}; - autoware_planning_msgs::msg::TrajectoryPoint point{}; -}; - -/// @brief bound of an overlap range (either the first, or last bound) -struct RangeBound -{ - size_t index{}; - lanelet::BasicPoint2d point{}; - double arc_length{}; - double inside_distance{}; -}; - -/// @brief representation of an overlap between the ego footprint and some other lane -struct Overlap -{ - double inside_distance = 0.0; ///!< distance inside the overlap - double min_arc_length = std::numeric_limits::infinity(); - double max_arc_length = 0.0; - lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length - lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length -}; - -/// @brief range along the trajectory where ego overlaps another lane -struct OverlapRange -{ - lanelet::ConstLanelet lane{}; - size_t entering_trajectory_idx{}; - size_t exiting_trajectory_idx{}; - lanelet::BasicPoint2d entering_point{}; // pose of the overlapping point closest along the lane - lanelet::BasicPoint2d exiting_point{}; // pose of the overlapping point furthest along the lane - double inside_distance{}; // [m] how much ego footprint enters the lane - mutable struct - { - std::vector overlaps{}; - std::optional decision{}; - RangeTimes times{}; - std::optional object{}; - } debug; -}; -using OverlapRanges = std::vector; -/// @brief representation of a lane and its current overlap range -struct OtherLane -{ - bool range_is_open = false; - RangeBound first_range_bound{}; - RangeBound last_range_bound{}; - lanelet::ConstLanelet lanelet{}; - lanelet::BasicPolygon2d polygon{}; - - explicit OtherLane(lanelet::ConstLanelet ll) : lanelet(std::move(ll)) - { - polygon = lanelet.polygon2d().basicPolygon(); - } - - [[nodiscard]] OverlapRange close_range() - { - OverlapRange range; - range.lane = lanelet; - range.entering_trajectory_idx = first_range_bound.index; - range.entering_point = first_range_bound.point; - range.exiting_trajectory_idx = last_range_bound.index; - range.exiting_point = last_range_bound.point; - range.inside_distance = - std::max(first_range_bound.inside_distance, last_range_bound.inside_distance); - range_is_open = false; - last_range_bound = {}; - return range; - } -}; - namespace bgi = boost::geometry::index; struct StopLine { @@ -185,68 +86,52 @@ struct StopLine }; using StopLineNode = std::pair; using StopLinesRtree = bgi::rtree>; -using OutAreaRtree = bgi::rtree, bgi::rstar<16>>; +using OutAreaNode = std::pair; +using OutAreaRtree = bgi::rtree>; /// @brief data related to the ego vehicle struct EgoData { - std::vector trajectory_points{}; + std::vector trajectory_points; + geometry_msgs::msg::Pose pose; size_t first_trajectory_idx{}; - double velocity{}; // [m/s] - double max_decel{}; // [m/s²] - geometry_msgs::msg::Pose pose{}; + double longitudinal_offset_to_first_trajectory_index{}; + double min_stop_distance{}; + double min_slowdown_distance{}; + double min_stop_arc_length{}; + + Polygons drivable_lane_polygons; + + lanelet::BasicPolygon2d current_footprint; + std::vector trajectory_footprints; + StopLinesRtree stop_lines_rtree; }; -/// @brief data needed to make decisions -struct DecisionInputs +struct OutOfLanePoint { - OverlapRanges ranges; - EgoData ego_data; - autoware_perception_msgs::msg::PredictedObjects objects; - std::shared_ptr route_handler; - lanelet::ConstLanelets lanelets; + size_t trajectory_index; + lanelet::BasicPolygon2d outside_ring; + std::set collision_times; + std::optional min_object_arrival_time; + std::optional max_object_arrival_time; + std::optional ttc; + lanelet::ConstLanelets overlapped_lanelets; + bool to_avoid = false; +}; +struct OutOfLaneData +{ + std::vector outside_points; + OutAreaRtree outside_areas_rtree; }; /// @brief debug data struct DebugData { - std::vector footprints; - std::vector slowdowns; - geometry_msgs::msg::Pose ego_pose; - OverlapRanges ranges; - lanelet::BasicPolygon2d current_footprint; - lanelet::ConstLanelets current_overlapped_lanelets; - lanelet::ConstLanelets trajectory_lanelets; - lanelet::ConstLanelets ignored_lanelets; - lanelet::ConstLanelets other_lanelets; - std::vector trajectory_points; - size_t first_trajectory_idx; - - size_t prev_footprints = 0; - size_t prev_slowdowns = 0; - size_t prev_ranges = 0; - size_t prev_current_overlapped_lanelets = 0; - size_t prev_ignored_lanelets = 0; - size_t prev_trajectory_lanelets = 0; - size_t prev_other_lanelets = 0; - void reset_data() - { - prev_footprints = footprints.size(); - footprints.clear(); - prev_slowdowns = slowdowns.size(); - slowdowns.clear(); - prev_ranges = ranges.size(); - ranges.clear(); - prev_current_overlapped_lanelets = current_overlapped_lanelets.size(); - current_overlapped_lanelets.clear(); - prev_ignored_lanelets = ignored_lanelets.size(); - ignored_lanelets.clear(); - prev_trajectory_lanelets = trajectory_lanelets.size(); - trajectory_lanelets.clear(); - prev_other_lanelets = other_lanelets.size(); - other_lanelets.clear(); - } + size_t prev_out_of_lane_areas = 0; + size_t prev_ttcs = 0; + size_t prev_objects = 0; + size_t prev_stop_line = 0; }; } // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt index f1eb7ff047fdc..ffc06aa8cc2f8 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt @@ -5,9 +5,20 @@ find_package(autoware_cmake REQUIRED) autoware_package() -# ament_auto_add_library(${PROJECT_NAME}_lib SHARED -# DIRECTORY src -# ) +ament_auto_add_library(${PROJECT_NAME}_lib SHARED + DIRECTORY src +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_collision_checker.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + gtest_main + ${PROJECT_NAME}_lib + ) + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() ament_auto_package(INSTALL_TO_SHARE include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp new file mode 100644 index 0000000000000..bf471c62af969 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp @@ -0,0 +1,69 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +namespace bgi = boost::geometry::index; +using RtreeNode = std::pair; +using Rtree = bgi::rtree>; + +/// @brief collision as a trajectory index and corresponding collision points +struct Collision +{ + size_t trajectory_index{}; + autoware::universe_utils::MultiPoint2d collision_points; +}; + +/// @brief collision checker for a trajectory as a sequence of 2D footprints +class CollisionChecker +{ + const autoware::universe_utils::MultiPolygon2d trajectory_footprints_; + std::shared_ptr rtree_; + +public: + /// @brief construct the collisions checker + /// @param trajectory_footprints footprints of the trajectory to be used for collision checking + /// @details internally, the rtree is built with the packing algorithm + explicit CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints); + + /// @brief efficiently calculate collisions with a geometry + /// @tparam Geometry boost geometry type + /// @param geometry geometry to check for collisions + /// @return collisions between the trajectory footprints and the input geometry + template + [[nodiscard]] std::vector get_collisions(const Geometry & geometry) const; + + /// @brief direct access to the rtree storing the polygon footprints + /// @return rtree of the polygon footprints + [[nodiscard]] std::shared_ptr get_rtree() const { return rtree_; } + + /// @brief get the size of the trajectory used by this collision checker + [[nodiscard]] size_t trajectory_size() const { return trajectory_footprints_.size(); } +}; +} // namespace autoware::motion_velocity_planner + +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index 5dbb872d99ca9..a96587c4465d6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -15,7 +15,10 @@ #ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#include +#include #include +#include #include #include @@ -37,12 +40,9 @@ #include #include -#include -#include #include #include #include -#include namespace autoware::motion_velocity_planner { @@ -59,11 +59,11 @@ struct PlannerData } // msgs from callbacks that are used for data-ready - nav_msgs::msg::Odometry current_odometry{}; - geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration{}; - autoware_perception_msgs::msg::PredictedObjects predicted_objects{}; - pcl::PointCloud no_ground_pointcloud{}; - nav_msgs::msg::OccupancyGrid occupancy_grid{}; + nav_msgs::msg::Odometry current_odometry; + geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration; + autoware_perception_msgs::msg::PredictedObjects predicted_objects; + pcl::PointCloud no_ground_pointcloud; + nav_msgs::msg::OccupancyGrid occupancy_grid; std::shared_ptr route_handler; // nearest search @@ -79,7 +79,7 @@ struct PlannerData tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states; // velocity smoother - std::shared_ptr velocity_smoother_{}; + std::shared_ptr velocity_smoother_; // parameters autoware::vehicle_info_utils::VehicleInfo vehicle_info_; @@ -88,7 +88,7 @@ struct PlannerData *@brief queries the traffic signal information of given Id. if keep_last_observation = true, *recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation */ - std::optional get_traffic_signal( + [[nodiscard]] std::optional get_traffic_signal( const lanelet::Id id, const bool keep_last_observation = false) const { const auto & traffic_light_id_map = @@ -98,6 +98,15 @@ struct PlannerData } return std::make_optional(traffic_light_id_map.at(id)); } + + [[nodiscard]] std::optional calculate_min_deceleration_distance( + const double target_velocity) const + { + return motion_utils::calcDecelDistWithJerkAndAccConstraints( + current_odometry.twist.twist.linear.x, target_velocity, + current_acceleration.accel.accel.linear.x, velocity_smoother_->getMinDecel(), + std::abs(velocity_smoother_->getMinJerk()), velocity_smoother_->getMinJerk()); + } }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp new file mode 100644 index 0000000000000..6e84b63a3c7fc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp @@ -0,0 +1,70 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/motion_velocity_planner_common/collision_checker.hpp" + +namespace autoware::motion_velocity_planner +{ +CollisionChecker::CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints) +: trajectory_footprints_(std::move(trajectory_footprints)) +{ + std::vector nodes; + nodes.reserve(trajectory_footprints_.size()); + for (auto i = 0UL; i < trajectory_footprints_.size(); ++i) { + nodes.emplace_back( + boost::geometry::return_envelope(trajectory_footprints_[i]), + i); + } + rtree_ = std::make_shared(nodes.begin(), nodes.end()); +} + +template +std::vector CollisionChecker::get_collisions(const Geometry & geometry) const +{ + std::vector collisions; + std::vector approximate_results; + autoware::universe_utils::MultiPoint2d intersections; + ; + rtree_->query(bgi::intersects(geometry), std::back_inserter(approximate_results)); + for (const auto & result : approximate_results) { + intersections.clear(); + boost::geometry::intersection(trajectory_footprints_[result.second], geometry, intersections); + if (!intersections.empty()) { + Collision c; + c.trajectory_index = result.second; + c.collision_points = intersections; + collisions.push_back(c); + } + } + return collisions; +} + +template std::vector CollisionChecker::get_collisions( + const autoware::universe_utils::Point2d & geometry) const; +template std::vector CollisionChecker::get_collisions( + const autoware::universe_utils::Line2d & geometry) const; +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiPolygon2d & geometry) const; + +// @warn Multi geometries usually lead to very inefficient queries +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiPoint2d & geometry) const; +template std::vector +CollisionChecker::get_collisions( + const autoware::universe_utils::MultiLineString2d & geometry) const; +template std::vector CollisionChecker::get_collisions< + autoware::universe_utils::Polygon2d>(const autoware::universe_utils::Polygon2d & geometry) const; +} // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp new file mode 100644 index 0000000000000..df813db336a9d --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp @@ -0,0 +1,176 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/motion_velocity_planner_common/collision_checker.hpp" + +#include + +#include + +#include +#include + +using autoware::motion_velocity_planner::CollisionChecker; +using autoware::universe_utils::Line2d; +using autoware::universe_utils::MultiLineString2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; + +Point2d random_point() +{ + static std::random_device r; + static std::default_random_engine e1(r()); + static std::uniform_real_distribution uniform_dist(-100, 100); + return {uniform_dist(e1), uniform_dist(e1)}; +} + +Line2d random_line() +{ + const auto point = random_point(); + const auto point2 = Point2d{point.x() + 1, point.y() + 1}; + const auto point3 = Point2d{point2.x() - 1, point2.y() + 1}; + const auto point4 = Point2d{point3.x() + 1, point3.y() + 1}; + return {point, point2, point3, point4}; +} + +Polygon2d random_polygon() +{ + Polygon2d polygon; + const auto point = random_point(); + const auto point2 = Point2d{point.x() + 1, point.y() + 4}; + const auto point3 = Point2d{point.x() + 4, point.y() + 4}; + const auto point4 = Point2d{point.x() + 3, point.y() + 1}; + polygon.outer() = {point, point2, point3, point4, point}; + return polygon; +} + +bool all_within(const MultiPoint2d & pts1, const MultiPoint2d & pts2) +{ + // results from the collision checker and the direct checks can have some small precision errors + constexpr auto eps = 1e-3; + for (const auto & p1 : pts1) { + bool found = false; + for (const auto & p2 : pts2) { + if (boost::geometry::comparable_distance(p1, p2) < eps) { + found = true; + break; + } + } + if (!found) return false; + } + return true; +} + +TEST(TestCollisionChecker, Benchmark) +{ + constexpr auto nb_ego_footprints = 1000; + constexpr auto nb_obstacles = 1000; + MultiPolygon2d ego_footprints; + ego_footprints.reserve(nb_ego_footprints); + for (auto i = 0; i < nb_ego_footprints; ++i) { + ego_footprints.push_back(random_polygon()); + } + const auto cc_constr_start = std::chrono::system_clock::now(); + CollisionChecker collision_checker(ego_footprints); + const auto cc_constr_end = std::chrono::system_clock::now(); + const auto cc_constr_ns = + std::chrono::duration_cast(cc_constr_end - cc_constr_start).count(); + std::printf( + "Collision checker construction (with %d footprints): %ld ns\n", nb_ego_footprints, + cc_constr_ns); + MultiPolygon2d poly_obstacles; + MultiPoint2d point_obstacles; + MultiLineString2d line_obstacles; + for (auto i = 0; i < nb_obstacles; ++i) { + poly_obstacles.push_back(random_polygon()); + point_obstacles.push_back(random_point()); + line_obstacles.push_back(random_line()); + } + const auto check_obstacles_one_by_one = [&](const auto & obstacles) { + std::chrono::nanoseconds collision_checker_ns{}; + std::chrono::nanoseconds naive_ns{}; + for (const auto & obs : obstacles) { + const auto cc_start = std::chrono::system_clock::now(); + const auto collisions = collision_checker.get_collisions(obs); + MultiPoint2d cc_collision_points; + for (const auto & c : collisions) + cc_collision_points.insert( + cc_collision_points.end(), c.collision_points.begin(), c.collision_points.end()); + const auto cc_end = std::chrono::system_clock::now(); + const auto naive_start = std::chrono::system_clock::now(); + MultiPoint2d naive_collision_points; + for (const auto & ego_footprint : ego_footprints) { + MultiPoint2d points; + boost::geometry::intersection(ego_footprint, obs, points); + naive_collision_points.insert(naive_collision_points.end(), points.begin(), points.end()); + } + const auto naive_end = std::chrono::system_clock::now(); + const auto equal = all_within(cc_collision_points, naive_collision_points) && + all_within(naive_collision_points, cc_collision_points); + EXPECT_TRUE(equal); + if (!equal) { + std::cout << "cc: " << boost::geometry::wkt(cc_collision_points) << std::endl; + std::cout << "naive: " << boost::geometry::wkt(naive_collision_points) << std::endl; + } + collision_checker_ns += + std::chrono::duration_cast(cc_end - cc_start); + naive_ns += std::chrono::duration_cast(naive_end - naive_start); + } + std::printf("%20s%10ld ns\n", "collision checker : ", collision_checker_ns.count()); + std::printf("%20s%10ld ns\n", "naive : ", naive_ns.count()); + }; + const auto check_obstacles = [&](const auto & obstacles) { + std::chrono::nanoseconds collision_checker_ns{}; + std::chrono::nanoseconds naive_ns{}; + const auto cc_start = std::chrono::system_clock::now(); + const auto collisions = collision_checker.get_collisions(obstacles); + MultiPoint2d cc_collision_points; + for (const auto & c : collisions) + cc_collision_points.insert( + cc_collision_points.end(), c.collision_points.begin(), c.collision_points.end()); + const auto cc_end = std::chrono::system_clock::now(); + const auto naive_start = std::chrono::system_clock::now(); + MultiPoint2d naive_collision_points; + boost::geometry::intersection(ego_footprints, obstacles, naive_collision_points); + const auto naive_end = std::chrono::system_clock::now(); + const auto equal = all_within(cc_collision_points, naive_collision_points) && + all_within(naive_collision_points, cc_collision_points); + EXPECT_TRUE(equal); + if (!equal) { + std::cout << "cc: " << boost::geometry::wkt(cc_collision_points) << std::endl; + std::cout << "naive: " << boost::geometry::wkt(naive_collision_points) << std::endl; + } + collision_checker_ns += std::chrono::duration_cast(cc_end - cc_start); + naive_ns += std::chrono::duration_cast(naive_end - naive_start); + std::printf("%20s%10ld ns\n", "collision checker : ", collision_checker_ns.count()); + std::printf("%20s%10ld ns\n", "naive : ", naive_ns.count()); + }; + + std::cout << "* check one by one\n"; + std::printf("%d Polygons:\n", nb_obstacles); + check_obstacles_one_by_one(poly_obstacles); + std::printf("%d Lines:\n", nb_obstacles); + check_obstacles_one_by_one(line_obstacles); + std::printf("%d Points:\n", nb_obstacles); + check_obstacles_one_by_one(point_obstacles); + std::cout << "* check all at once\n"; + std::printf("%d Polygons:\n", nb_obstacles); + check_obstacles(poly_obstacles); + std::printf("%d Lines:\n", nb_obstacles); + check_obstacles(line_obstacles); + std::printf("%d Points:\n", nb_obstacles); + check_obstacles(point_obstacles); +} diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 76b64c0a4d5e2..9a08616b8fe7b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -83,8 +82,11 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & velocity_factor_publisher_ = this->create_publisher( "~/output/velocity_factors", 1); - processing_time_publisher_ = this->create_publisher( - "~/debug/total_time/processing_time_ms", 1); + processing_time_publisher_ = + this->create_publisher("~/debug/processing_time_ms", 1); + debug_viz_pub_ = + this->create_publisher("~/debug/markers", 1); + diagnostics_pub_ = this->create_publisher("/diagnostics", 10); // Parameters smooth_velocity_before_planning_ = declare_parameter("smooth_velocity_before_planning"); @@ -98,7 +100,7 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & // Initialize PlannerManager for (const auto & name : declare_parameter>("launch_modules")) { // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter. - if (name == "") { + if (name.empty()) { break; } planner_manager_.load_module_plugin(*this, name); @@ -134,7 +136,7 @@ bool MotionVelocityPlannerNode::update_planner_data() const auto check_with_log = [&](const auto ptr, const auto & log) { constexpr auto throttle_duration = 3000; // [ms] if (!ptr) { - RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, log); + RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, "%s", log); is_ready = false; return false; } @@ -277,7 +279,6 @@ void MotionVelocityPlannerNode::on_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points{ input_trajectory_msg->points.begin(), input_trajectory_msg->points.end()}; - auto output_trajectory_msg = generate_trajectory(input_trajectory_points); output_trajectory_msg.header = input_trajectory_msg->header; processing_times["generate_trajectory"] = stop_watch.toc(true); @@ -293,6 +294,13 @@ void MotionVelocityPlannerNode::on_trajectory( processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); + + std::shared_ptr diagnostics = + planner_manager_.get_diagnostics(get_clock()->now()); + if (!diagnostics->status.empty()) { + diagnostics_pub_->publish(*diagnostics); + } + planner_manager_.clear_diagnostics(); } void MotionVelocityPlannerNode::insert_stop( @@ -325,7 +333,8 @@ void MotionVelocityPlannerNode::insert_slowdown( autoware::motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); if (from_insert_idx && to_insert_idx) { for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) - trajectory.points[idx].longitudinal_velocity_mps = slowdown_interval.velocity; + trajectory.points[idx].longitudinal_velocity_mps = + static_cast(slowdown_interval.velocity); } else { RCLCPP_WARN(get_logger(), "Failed to insert slowdown point"); } @@ -360,16 +369,14 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware::motion_velocity_planner::TrajectoryPoints clipped; autoware::motion_velocity_planner::TrajectoryPoints traj_smoothed; clipped.insert( - clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); + clipped.end(), std::next(traj_resampled.begin(), static_cast(traj_resampled_closest)), + traj_resampled.end()); if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { RCLCPP_ERROR(get_logger(), "failed to smooth"); } - traj_smoothed.insert( - traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); - if (external_v_limit) { autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( - traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); + 0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } return traj_smoothed; } @@ -377,13 +384,21 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points) { + universe_utils::StopWatch stop_watch; autoware_planning_msgs::msg::Trajectory output_trajectory_msg; output_trajectory_msg.points = {input_trajectory_points.begin(), input_trajectory_points.end()}; - if (smooth_velocity_before_planning_) + if (smooth_velocity_before_planning_) { + stop_watch.tic("smooth"); input_trajectory_points = smooth_trajectory(input_trajectory_points, planner_data_); - const auto resampled_trajectory = - autoware::motion_utils::resampleTrajectory(output_trajectory_msg, 0.5); - + RCLCPP_DEBUG(get_logger(), "smooth: %2.2f us", stop_watch.toc("smooth")); + } + autoware_planning_msgs::msg::Trajectory smooth_velocity_trajectory; + smooth_velocity_trajectory.points = { + input_trajectory_points.begin(), input_trajectory_points.end()}; + auto resampled_trajectory = + autoware::motion_utils::resampleTrajectory(smooth_velocity_trajectory, 0.5); + motion_utils::calculate_time_from_start( + resampled_trajectory.points, planner_data_.current_odometry.pose.pose.position); const auto planning_results = planner_manager_.plan_velocities( resampled_trajectory.points, std::make_shared(planner_data_)); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 8debb9cbedf00..b143018bb0e1e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -43,6 +43,8 @@ #include #include +using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + namespace autoware::motion_velocity_planner { using autoware_map_msgs::msg::LaneletMapBin; @@ -100,6 +102,7 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this}; rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; + rclcpp::Publisher::SharedPtr diagnostics_pub_; // parameters rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr set_param_callback_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp index 66063fcbaebca..04641e0cea6bb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp @@ -71,13 +71,60 @@ void MotionVelocityPlannerManager::update_module_parameters( for (auto & plugin : loaded_plugins_) plugin->update_parameters(parameters); } +std::shared_ptr MotionVelocityPlannerManager::make_diagnostic( + const std::string & module_name, const std::string & reason, const bool is_decided) +{ + auto status = std::make_shared(); + status->level = status->OK; + status->name = module_name + '.' + reason; + diagnostic_msgs::msg::KeyValue key_value; + { + // Decision + key_value.key = "decision"; + if (is_decided) + key_value.value = reason; + else + key_value.value = "none"; + status->values.push_back(key_value); + } + // Add other information to the status if necessary in the future. + return status; +} + +std::shared_ptr MotionVelocityPlannerManager::get_diagnostics( + const rclcpp::Time & current_time) const +{ + auto diagnostics = std::make_shared(); + + for (const auto & ds_ptr : diagnostics_) { + if ( + !ds_ptr->values.empty() && ds_ptr->values[0].key == "decision" && + ds_ptr->values[0].value != "none") { + diagnostics->status.push_back(*ds_ptr); + } + } + diagnostics->header.stamp = current_time; + diagnostics->header.frame_id = "map"; + return diagnostics; +} + std::vector MotionVelocityPlannerManager::plan_velocities( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) { std::vector results; - for (auto & plugin : loaded_plugins_) - results.push_back(plugin->plan(ego_trajectory_points, planner_data)); + for (auto & plugin : loaded_plugins_) { + VelocityPlanningResult res = plugin->plan(ego_trajectory_points, planner_data); + results.push_back(res); + + const auto stop_reason_diag = + make_diagnostic(plugin->get_module_name(), "stop", res.stop_points.size() > 0); + diagnostics_.push_back(stop_reason_diag); + + const auto slow_down_reason_diag = + make_diagnostic(plugin->get_module_name(), "slow_down", res.slowdown_intervals.size() > 0); + diagnostics_.push_back(slow_down_reason_diag); + } return results; } } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp index 20165d359f669..ac2e421d30cb6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -35,6 +36,9 @@ #include #include +using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; +using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + namespace autoware::motion_velocity_planner { class MotionVelocityPlannerManager @@ -48,7 +52,14 @@ class MotionVelocityPlannerManager const std::vector & ego_trajectory_points, const std::shared_ptr planner_data); + // Diagnostic + std::shared_ptr make_diagnostic( + const std::string & module_name, const std::string & reason, const bool is_decided = true); + std::shared_ptr get_diagnostics(const rclcpp::Time & current_time) const; + void clear_diagnostics() { diagnostics_.clear(); } + private: + std::vector> diagnostics_; pluginlib::ClassLoader plugin_loader_; std::vector> loaded_plugins_; }; From c1011857f1f31ccdff9ede41b51f004889c51786 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 5 Sep 2024 11:56:43 +0900 Subject: [PATCH 132/151] fix(mission_planner): improve condition to check if the goal is within the lane (#1506) fix(mission_planner): improve condition to check if the goal is within the lane (#8710) Signed-off-by: Maxime CLEMENT --- .../src/lanelet2_plugins/default_planner.cpp | 108 +++++++++--------- .../src/lanelet2_plugins/default_planner.hpp | 22 ++-- .../lanelet2_plugins/utility_functions.cpp | 60 ---------- .../lanelet2_plugins/utility_functions.hpp | 12 -- 4 files changed, 65 insertions(+), 137 deletions(-) diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp index 69c52b9c2eafb..2097c0576c545 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -17,6 +17,7 @@ #include "utility_functions.hpp" #include +#include #include #include #include @@ -27,10 +28,13 @@ #include #include +#include +#include + +#include #include +#include #include -#include -#include #include #include @@ -216,7 +220,7 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route) } visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint( - autoware::universe_utils::LinearRing2d goal_footprint) const + autoware::universe_utils::LinearRing2d goal_footprint) { visualization_msgs::msg::MarkerArray msg; auto marker = autoware::universe_utils::createDefaultMarker( @@ -244,52 +248,58 @@ visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint( return msg; } -bool DefaultPlanner::check_goal_footprint_inside_lanes( - const lanelet::ConstLanelet & current_lanelet, - const lanelet::ConstLanelet & combined_prev_lanelet, - const autoware::universe_utils::Polygon2d & goal_footprint, double & next_lane_length, - const double search_margin) +lanelet::ConstLanelets next_lanelets_up_to( + const lanelet::ConstLanelet & start_lanelet, const double up_to_distance, + const route_handler::RouteHandler & route_handler) { - // check if goal footprint is in current lane - if (boost::geometry::within(goal_footprint, combined_prev_lanelet.polygon2d().basicPolygon())) { - return true; + lanelet::ConstLanelets lanelets; + if (up_to_distance <= 0.0) { + return lanelets; } - const auto following = route_handler_.getNextLanelets(current_lanelet); - // check if goal footprint is in between many lanelets in depth-first search manner - for (const auto & next_lane : following) { - next_lane_length += lanelet::utils::getLaneletLength2d(next_lane); - lanelet::ConstLanelets lanelets; - lanelets.push_back(combined_prev_lanelet); + for (const auto & next_lane : route_handler.getNextLanelets(start_lanelet)) { lanelets.push_back(next_lane); - lanelet::ConstLanelet combined_lanelets = - combine_lanelets_with_shoulder(lanelets, route_handler_); - - // if next lanelet length is longer than vehicle longitudinal offset - if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { - next_lane_length -= lanelet::utils::getLaneletLength2d(next_lane); - // and if the goal_footprint is within the (accumulated) combined_lanelets, terminate the - // query - if (boost::geometry::within(goal_footprint, combined_lanelets.polygon2d().basicPolygon())) { - return true; - } - // if not, iteration continues to next next_lane, and this subtree is terminated - } else { // if next lanelet length is shorter than vehicle longitudinal offset, check the - // overlap with the polygon including the next_lane(s) until the additional lanes get - // longer than ego vehicle length - if (!check_goal_footprint_inside_lanes( - next_lane, combined_lanelets, goal_footprint, next_lane_length)) { - next_lane_length -= lanelet::utils::getLaneletLength2d(next_lane); - continue; - } else { - return true; - } + const auto next_lanelets = next_lanelets_up_to( + next_lane, up_to_distance - lanelet::geometry::length2d(next_lane), route_handler); + lanelets.insert(lanelets.end(), next_lanelets.begin(), next_lanelets.end()); + } + return lanelets; +} + +bool DefaultPlanner::check_goal_footprint_inside_lanes( + const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelets & path_lanelets, + const universe_utils::Polygon2d & goal_footprint) const +{ + universe_utils::MultiPolygon2d ego_lanes; + universe_utils::Polygon2d poly; + for (const auto & ll : path_lanelets) { + const auto left_shoulder = route_handler_.getLeftShoulderLanelet(ll); + if (left_shoulder) { + boost::geometry::convert(left_shoulder->polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); + } + const auto right_shoulder = route_handler_.getRightShoulderLanelet(ll); + if (right_shoulder) { + boost::geometry::convert(right_shoulder->polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); } + boost::geometry::convert(ll.polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); } - return false; + const auto next_lanelets = + next_lanelets_up_to(current_lanelet, vehicle_info_.max_longitudinal_offset_m, route_handler_); + for (const auto & ll : next_lanelets) { + boost::geometry::convert(ll.polygon2d().basicPolygon(), poly); + ego_lanes.push_back(poly); + } + + // check if goal footprint is in the ego lane + universe_utils::MultiPolygon2d difference; + boost::geometry::difference(goal_footprint, ego_lanes, difference); + return boost::geometry::is_empty(difference); } bool DefaultPlanner::is_goal_valid( - const geometry_msgs::msg::Pose & goal, lanelet::ConstLanelets path_lanelets) + const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelets & path_lanelets) { const auto logger = node_->get_logger(); @@ -337,16 +347,10 @@ bool DefaultPlanner::is_goal_valid( pub_goal_footprint_marker_->publish(visualize_debug_footprint(goal_footprint)); const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint); - double next_lane_length = 0.0; - // combine calculated route lanelets - const lanelet::ConstLanelet combined_prev_lanelet = - combine_lanelets_with_shoulder(path_lanelets, route_handler_); - // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( param_.check_footprint_inside_lanes && - !check_goal_footprint_inside_lanes( - closest_lanelet, combined_prev_lanelet, polygon_footprint, next_lane_length) && + !check_goal_footprint_inside_lanes(closest_lanelet, path_lanelets, polygon_footprint) && !is_in_parking_lot( lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()), lanelet::utils::conversion::toLaneletPoint(goal.position))) { @@ -375,11 +379,7 @@ bool DefaultPlanner::is_goal_valid( // check if goal is in parking lot const auto parking_lots = lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()); - if (is_in_parking_lot(parking_lots, goal_lanelet_pt)) { - return true; - } - - return false; + return is_in_parking_lot(parking_lots, goal_lanelet_pt); } PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) @@ -429,7 +429,7 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) return route_msg; } - if (route_handler_.isRouteLooped(route_sections)) { + if (route_handler::RouteHandler::isRouteLooped(route_sections)) { RCLCPP_WARN(logger, "Loop detected within route!"); return route_msg; } diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp index 60c2a53b82123..39b7fa8909a6a 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -27,7 +27,6 @@ #include #include -#include #include namespace autoware::mission_planner::lanelet2 @@ -44,15 +43,17 @@ struct DefaultPlannerParameters class DefaultPlanner : public mission_planner::PlannerPlugin { public: + DefaultPlanner() : vehicle_info_(), is_graph_ready_(false), param_(), node_(nullptr) {} + void initialize(rclcpp::Node * node) override; void initialize(rclcpp::Node * node, const LaneletMapBin::ConstSharedPtr msg) override; - bool ready() const override; + [[nodiscard]] bool ready() const override; LaneletRoute plan(const RoutePoints & points) override; void updateRoute(const PlannerPlugin::LaneletRoute & route) override; void clearRoute() override; - MarkerArray visualize(const LaneletRoute & route) const override; - MarkerArray visualize_debug_footprint( - autoware::universe_utils::LinearRing2d goal_footprint_) const; + [[nodiscard]] MarkerArray visualize(const LaneletRoute & route) const override; + [[nodiscard]] static MarkerArray visualize_debug_footprint( + autoware::universe_utils::LinearRing2d goal_footprint); autoware::vehicle_info_utils::VehicleInfo vehicle_info_; private: @@ -83,17 +84,16 @@ class DefaultPlanner : public mission_planner::PlannerPlugin * @param next_lane_length the accumulated total length from the start lanelet of the search to * the lanelet of current goal query */ - bool check_goal_footprint_inside_lanes( - const lanelet::ConstLanelet & current_lanelet, - const lanelet::ConstLanelet & combined_prev_lanelet, - const autoware::universe_utils::Polygon2d & goal_footprint, double & next_lane_length, - const double search_margin = 2.0); + [[nodiscard]] bool check_goal_footprint_inside_lanes( + const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelets & path_lanelets, + const universe_utils::Polygon2d & goal_footprint) const; /** * @brief return true if (1)the goal is in parking area or (2)the goal is on the lanes and the * footprint around the goal does not overlap the lanes */ - bool is_goal_valid(const geometry_msgs::msg::Pose & goal, lanelet::ConstLanelets path_lanelets); + bool is_goal_valid( + const geometry_msgs::msg::Pose & goal, const lanelet::ConstLanelets & path_lanelets); /** * @brief project the specified goal pose onto the goal lanelet(the last preferred lanelet of diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp index 5046b81c72b96..34b16ef35f603 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -18,9 +18,6 @@ #include -#include -#include - autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( autoware::universe_utils::LinearRing2d footprint) { @@ -41,63 +38,6 @@ void insert_marker_array( a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end()); } -lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, - const autoware::route_handler::RouteHandler & route_handler) -{ - lanelet::Points3d lefts; - lanelet::Points3d rights; - lanelet::Points3d centers; - std::vector left_bound_ids; - std::vector right_bound_ids; - - for (const auto & llt : lanelets) { - if (llt.id() != lanelet::InvalId) { - left_bound_ids.push_back(llt.leftBound().id()); - right_bound_ids.push_back(llt.rightBound().id()); - } - } - - // lambda to add bound to target_bound - const auto add_bound = [](const auto & bound, auto & target_bound) { - std::transform( - bound.begin(), bound.end(), std::back_inserter(target_bound), - [](const auto & pt) { return lanelet::Point3d(pt); }); - }; - for (const auto & llt : lanelets) { - // check if shoulder lanelets which has RIGHT bound same to LEFT bound of lanelet exist - const auto left_shared_shoulder = route_handler.getLeftShoulderLanelet(llt); - if (left_shared_shoulder) { - // if exist, add left bound of SHOULDER lanelet to lefts - add_bound(left_shared_shoulder->leftBound(), lefts); - } else if ( - // if not exist, add left bound of lanelet to lefts - // if the **left** of this lanelet does not match any of the **right** bounds of `lanelets`, - // then its left bound constitutes the left boundary of the entire merged lanelet - std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) { - add_bound(llt.leftBound(), lefts); - } - - // check if shoulder lanelets which has LEFT bound same to RIGHT bound of lanelet exist - const auto right_shared_shoulder = route_handler.getRightShoulderLanelet(llt); - if (right_shared_shoulder) { - // if exist, add right bound of SHOULDER lanelet to rights - add_bound(right_shared_shoulder->rightBound(), rights); - } else if ( - // if not exist, add right bound of lanelet to rights - // if the **right** of this lanelet does not match any of the **left** bounds of `lanelets`, - // then its right bound constitutes the right boundary of the entire merged lanelet - std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) { - add_bound(llt.rightBound(), rights); - } - } - - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, lefts); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, rights); - auto combined_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - return std::move(combined_lanelet); -} - std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet) { std::vector centerline_points; diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp index c8812e2c76dd6..6e3d2a0e88941 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -27,8 +27,6 @@ #include #include -#include -#include #include template @@ -47,16 +45,6 @@ autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); -/** - * @brief create a single merged lanelet whose left/right bounds consist of the leftmost/rightmost - * bound of the original lanelets or the left/right bound of its adjacent road_shoulder respectively - * @param lanelets topologically sorted sequence of lanelets - * @param route_handler route handler to query the lanelet map - */ -lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, - const autoware::route_handler::RouteHandler & route_handler); - std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( const lanelet::BasicPoint3d & point, const double lane_yaw); From a53dbea31f103dfe60cac6c65b921891634b1551 Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Fri, 6 Sep 2024 08:56:42 +0900 Subject: [PATCH 133/151] fix(motion_velocity_planner): fix duplicated topic name (#1517) * # This is a combination of 3 commits. # This is the 1st commit message: change processing_time_ms topic name Signed-off-by: Autumn60 # This is the commit message #2: style(pre-commit): autofix # This is the commit message #3: Revert "style(pre-commit): autofix" This reverts commit 1dc1351c09f978307bfecae459fee363d07db4f5. * change processing_time_ms topic name Signed-off-by: Autumn60 style(pre-commit): autofix Revert "style(pre-commit): autofix" This reverts commit 1dc1351c09f978307bfecae459fee363d07db4f5. Revert "change processing_time_ms topic name" This reverts commit 6f026f8a6300020a3e22e5acdcb25790bb2b0a91. change processing_time_ms diag topic name Signed-off-by: Autumn60 --------- Signed-off-by: Autumn60 --- .../autoware_motion_velocity_planner_node/src/node.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index b143018bb0e1e..7a7fb5790ace1 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -99,7 +99,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_viz_pub_; rclcpp::Publisher::SharedPtr velocity_factor_publisher_; - autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{this}; + autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ + this, "~/debug/processing_time_ms_diag"}; rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; rclcpp::Publisher::SharedPtr diagnostics_pub_; From c46506269692d9e49714fcad9f00084925e306f3 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 29 Aug 2024 10:18:25 +0900 Subject: [PATCH 134/151] fix(reaction_analyzer): fix include hierarchy of tf2_eigen (#8663) Fixed include hierarchy of tf2_eigen Signed-off-by: Shintaro Sakoda --- tools/reaction_analyzer/include/subscriber.hpp | 2 +- tools/reaction_analyzer/include/topic_publisher.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/reaction_analyzer/include/subscriber.hpp b/tools/reaction_analyzer/include/subscriber.hpp index ff251251373e2..d2a8363e15bf3 100644 --- a/tools/reaction_analyzer/include/subscriber.hpp +++ b/tools/reaction_analyzer/include/subscriber.hpp @@ -16,7 +16,7 @@ #define SUBSCRIBER_HPP_ #include #include -#include +#include #include #include diff --git a/tools/reaction_analyzer/include/topic_publisher.hpp b/tools/reaction_analyzer/include/topic_publisher.hpp index 0c01561fec508..4517b1f793e6c 100644 --- a/tools/reaction_analyzer/include/topic_publisher.hpp +++ b/tools/reaction_analyzer/include/topic_publisher.hpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include From 61ec77c3f9705d5e3c907e9e127aa996473b330e Mon Sep 17 00:00:00 2001 From: ralwing <58466562+ralwing@users.noreply.github.com> Date: Wed, 3 Jul 2024 08:46:48 +0200 Subject: [PATCH 135/151] feat(pointcloud_preprocessor): runtime configurable output topic qos (#6658) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat(pointcloud_preprocessor): runtime configurable output topic qos Signed-off-by: Grzegorz GÅ‚owacki * configurable qos in livox_tag_filter_node Signed-off-by: Grzegorz GÅ‚owacki * configurable qos in radar_scan_to_pointcloud2 Signed-off-by: Grzegorz GÅ‚owacki --------- Signed-off-by: Grzegorz GÅ‚owacki --- .../livox_tag_filter_node/livox_tag_filter_node.cpp | 10 +++++++--- .../concatenate_and_time_sync_nodelet.cpp | 9 +++++++-- .../src/concatenate_data/concatenate_pointclouds.cpp | 4 +++- .../src/crop_box_filter/crop_box_filter_nodelet.cpp | 6 ++++-- .../distortion_corrector/distortion_corrector.cpp | 11 +++++++---- sensing/pointcloud_preprocessor/src/filter.cpp | 4 +++- .../dual_return_outlier_filter_nodelet.cpp | 9 ++++++--- .../outlier_filter/ring_outlier_filter_nodelet.cpp | 8 ++++++-- .../time_synchronizer/time_synchronizer_nodelet.cpp | 4 +++- .../lanelet2_map_filter_nodelet.cpp | 4 +++- .../radar_scan_to_pointcloud2_node.cpp | 12 +++++++++--- 11 files changed, 58 insertions(+), 23 deletions(-) diff --git a/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp b/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp index f3216fdcd9b6a..0cff38a5f7217 100644 --- a/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp +++ b/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp @@ -47,9 +47,13 @@ LivoxTagFilterNode::LivoxTagFilterNode(const rclcpp::NodeOptions & node_options) sub_pointcloud_ = this->create_subscription( "input", rclcpp::SensorDataQoS(), std::bind(&LivoxTagFilterNode::onPointCloud, this, _1)); - // Publisher - pub_pointcloud_ = - this->create_publisher("output", rclcpp::SensorDataQoS()); + { + // Publisher + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_pointcloud_ = this->create_publisher( + "output", rclcpp::SensorDataQoS(), pub_options); + } } void LivoxTagFilterNode::onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index e998a79b27f77..17f650fcb8e54 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -141,8 +141,10 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Output Publishers { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_output_ = this->create_publisher( - "output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_)); + "output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); } // Subscribers @@ -192,10 +194,13 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud if (publish_synchronized_pointcloud_) { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + for (auto & topic : input_topics_) { std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_); auto publisher = this->create_publisher( - new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_)); + new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); transformed_raw_pc_publisher_map_.insert({topic, publisher}); } } diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index 3586b7c999776..0ecaa5588bf65 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -97,8 +97,10 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent( // Output Publishers { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_output_ = this->create_publisher( - "output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_)); + "output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); } // Subscribers diff --git a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp index 620e9e42a6864..a56d8f1570234 100644 --- a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -87,8 +87,10 @@ CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & optio // set additional publishers { - crop_box_polygon_pub_ = - this->create_publisher("~/crop_box_polygon", 10); + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + crop_box_polygon_pub_ = this->create_publisher( + "~/crop_box_polygon", 10, pub_options); } // set parameter service callback diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index e7aa1f24409e6..8bf511637371a 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -40,10 +40,13 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt time_stamp_field_name_ = declare_parameter("time_stamp_field_name", "time_stamp"); use_imu_ = declare_parameter("use_imu", true); - // Publisher - undistorted_points_pub_ = - this->create_publisher("~/output/pointcloud", rclcpp::SensorDataQoS()); - + { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + // Publisher + undistorted_points_pub_ = this->create_publisher( + "~/output/pointcloud", rclcpp::SensorDataQoS(), pub_options); + } // Subscriber twist_sub_ = this->create_subscription( "~/input/twist", 10, diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/pointcloud_preprocessor/src/filter.cpp index c9bb6dfc0fc66..035be38f4c342 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/pointcloud_preprocessor/src/filter.cpp @@ -89,8 +89,10 @@ pointcloud_preprocessor::Filter::Filter( // Set publisher { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_output_ = this->create_publisher( - "output", rclcpp::SensorDataQoS().keep_last(max_queue_size_)); + "output", rclcpp::SensorDataQoS().keep_last(max_queue_size_), pub_options); } subscribe(filter_name); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index ccceae9ab5186..d8f5c78ab1e73 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -72,9 +72,12 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( image_transport::create_publisher(this, "dual_return_outlier_filter/debug/frequency_image"); visibility_pub_ = create_publisher( "dual_return_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); - noise_cloud_pub_ = create_publisher( - "dual_return_outlier_filter/debug/pointcloud_noise", rclcpp::SensorDataQoS()); - + { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + noise_cloud_pub_ = create_publisher( + "dual_return_outlier_filter/debug/pointcloud_noise", rclcpp::SensorDataQoS(), pub_options); + } using std::placeholders::_1; set_param_res_ = this->add_on_set_parameters_callback( std::bind(&DualReturnOutlierFilterComponent::paramCallback, this, _1)); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index 127c0c65b9915..a9722d041c42c 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -33,8 +33,12 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "ring_outlier_filter"); - outlier_pointcloud_publisher_ = - this->create_publisher("debug/ring_outlier_filter", 1); + { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + outlier_pointcloud_publisher_ = + this->create_publisher("debug/ring_outlier_filter", 1, pub_options); + } visibility_pub_ = create_publisher( "ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); stop_watch_ptr_->tic("cyclic_time"); diff --git a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp index 099e5757ffc0a..35c35471bf30e 100644 --- a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -160,10 +160,12 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( // Transformed Raw PointCloud2 Publisher { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); for (auto & topic : input_topics_) { std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix); auto publisher = this->create_publisher( - new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_)); + new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); transformed_raw_pc_publisher_map_.insert({topic, publisher}); } } diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp index 8f7cb2abec6a4..9049f2964a850 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp @@ -45,8 +45,10 @@ Lanelet2MapFilterComponent::Lanelet2MapFilterComponent(const rclcpp::NodeOptions // Set publisher { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); filtered_pointcloud_pub_ = - this->create_publisher("output", rclcpp::SensorDataQoS()); + this->create_publisher("output", rclcpp::SensorDataQoS(), pub_options); } // Set subscriber diff --git a/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp b/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp index b182147468262..8874b744bced6 100644 --- a/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp +++ b/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp @@ -111,9 +111,15 @@ RadarScanToPointcloud2Node::RadarScanToPointcloud2Node(const rclcpp::NodeOptions sub_radar_ = create_subscription( "~/input/radar", rclcpp::QoS{1}, std::bind(&RadarScanToPointcloud2Node::onData, this, _1)); - // Publisher - pub_amplitude_pointcloud_ = create_publisher("~/output/amplitude_pointcloud", 1); - pub_doppler_pointcloud_ = create_publisher("~/output/doppler_pointcloud", 1); + { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + // Publisher + pub_amplitude_pointcloud_ = + create_publisher("~/output/amplitude_pointcloud", 1, pub_options); + pub_doppler_pointcloud_ = + create_publisher("~/output/doppler_pointcloud", 1, pub_options); + } } rcl_interfaces::msg::SetParametersResult RadarScanToPointcloud2Node::onSetParam( From efc550c53149553a709de2e3c0d631e2276080f3 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 3 Jul 2024 16:42:25 +0900 Subject: [PATCH 136/151] feat(pointcloud_preprocessor): support for 3d distortion correction algorithm and refactor distortion correction node (#7137) * add support for 3d distortion correction Signed-off-by: vividf * change parameter back to default and do small refactor Signed-off-by: vividf * init version, need to double check Signed-off-by: vividf * fix the logic error Signed-off-by: vividf * temporary save, need to delete some code * init done, need to check for 3d as time is high Signed-off-by: vividf * fix error Signed-off-by: vividf * temporaily save * clean code Signed-off-by: vividf * remove unused parameters Signed-off-by: vividf * fix constructor error Signed-off-by: vividf * fix spell errors Signed-off-by: vividf * fix more spell errors Signed-off-by: vividf * add undistorter to library Signed-off-by: vividf * fix: fix cmake and change class name Signed-off-by: vividf * Update sensing/pointcloud_preprocessor/docs/distortion-corrector.md Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: update sensing/pointcloud_preprocessor/docs/distortion-corrector.md Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: update sensing/pointcloud_preprocessor/docs/distortion-corrector.md Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: fix company name Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: fix company name Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: fix company name Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: fix imu to IMU Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: fix company name Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: remove old naming Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: change boolean variable naming Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: change boolean variable naming Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * chore: change boolean variable naming Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> Signed-off-by: vividf * fix: fix file name and variable name Signed-off-by: vividf * chore: fix invlaid virtual function definitions Signed-off-by: vividf * fix: add sophus in package dependency Signed-off-by: vividf * chore: remove brackets Signed-off-by: vividf * chore: fix algorithm Signed-off-by: vividf * chore: remove timestamp_field_name and add default parameter for 3d distortion Signed-off-by: vividf * chore: fix known limits explanation Signed-off-by: vividf * feat: add parameter schema and launch file for distortion correction node Signed-off-by: vividf * chore: fix function name Signed-off-by: vividf * chore: fix IMU function name Signed-off-by: vividf * chore: fix twist and imu iterator function name Signed-off-by: vividf * fix: add inline for undistortPointcloud function Signed-off-by: vividf * chore: move varialbe to const Signed-off-by: vividf * chore: fix grammar error Signed-off-by: vividf * fix: fix inline function Signed-off-by: vividf * chore: solve conflicts Signed-off-by: vividf * fix: fix bug in previous code Signed-off-by: vividf * fix: fix the template naming Signed-off-by: vividf * fix: fix the component test Signed-off-by: vividf * fix: solve conflicts Signed-off-by: vividf --------- Signed-off-by: vividf Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> --- .../pointcloud_preprocessor/CMakeLists.txt | 4 + .../distortion_corrector_node.param.yaml | 5 + .../docs/distortion-corrector.md | 43 +- .../distortion_corrector.hpp | 142 +++-- .../distortion_corrector_node.hpp | 65 +++ .../distortion_corrector_node.launch.xml | 16 + sensing/pointcloud_preprocessor/package.xml | 1 + .../distortion_corrector_node.schema.json | 40 ++ .../distortion_corrector.cpp | 515 ++++++++++-------- .../distortion_corrector_node.cpp | 124 +++++ .../test/test_distortion_corrector.py | 2 +- ...test_distortion_corrector_use_imu_false.py | 6 +- 12 files changed, 694 insertions(+), 269 deletions(-) create mode 100644 sensing/pointcloud_preprocessor/config/distortion_corrector_node.param.yaml create mode 100644 sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp create mode 100644 sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml create mode 100644 sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json create mode 100644 sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index df62f538e9964..dd73f28a41f3c 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -9,6 +9,7 @@ set(CGAL_DATA_DIR ".") find_package(OpenCV REQUIRED) find_package(Eigen3 REQUIRED) +find_package(Sophus REQUIRED) find_package(Boost REQUIRED) find_package(PCL REQUIRED) find_package(CGAL REQUIRED COMPONENTS Core) @@ -19,6 +20,7 @@ include_directories( ${Boost_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} + ${Sophus_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS} ) @@ -76,6 +78,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp src/vector_map_filter/lanelet2_map_filter_nodelet.cpp src/distortion_corrector/distortion_corrector.cpp + src/distortion_corrector/distortion_corrector_node.cpp src/blockage_diag/blockage_diag_nodelet.cpp src/polygon_remover/polygon_remover.cpp src/vector_map_filter/vector_map_inside_area_filter.cpp @@ -86,6 +89,7 @@ target_link_libraries(pointcloud_preprocessor_filter faster_voxel_grid_downsample_filter ${Boost_LIBRARIES} ${OpenCV_LIBRARIES} + ${Sophus_LIBRARIES} ${PCL_LIBRARIES} ) diff --git a/sensing/pointcloud_preprocessor/config/distortion_corrector_node.param.yaml b/sensing/pointcloud_preprocessor/config/distortion_corrector_node.param.yaml new file mode 100644 index 0000000000000..3afa4816271cb --- /dev/null +++ b/sensing/pointcloud_preprocessor/config/distortion_corrector_node.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + base_frame: base_link + use_imu: true + use_3d_distortion_correction: false diff --git a/sensing/pointcloud_preprocessor/docs/distortion-corrector.md b/sensing/pointcloud_preprocessor/docs/distortion-corrector.md index dcb03cc792cae..96124f473f825 100644 --- a/sensing/pointcloud_preprocessor/docs/distortion-corrector.md +++ b/sensing/pointcloud_preprocessor/docs/distortion-corrector.md @@ -2,20 +2,17 @@ ## Purpose -The `distortion_corrector` is a node that compensates pointcloud distortion caused by ego vehicle's movement during 1 scan. +The `distortion_corrector` is a node that compensates for pointcloud distortion caused by the ego-vehicle's movement during one scan. -Since the LiDAR sensor scans by rotating an internal laser, the resulting point cloud will be distorted if the ego-vehicle moves during a single scan (as shown by the figure below). The node corrects this by interpolating sensor data using odometry of ego-vehicle. +Since the LiDAR sensor scans by rotating an internal laser, the resulting point cloud will be distorted if the ego-vehicle moves during a single scan (as shown by the figure below). The node corrects this by interpolating sensor data using the odometry of the ego-vehicle. ## Inner-workings / Algorithms -- Use the equations below (specific to the Velodyne 32C sensor) to obtain an accurate timestamp for each scan data point. -- Use twist information to determine the distance the ego-vehicle has traveled between the time that the scan started and the corrected timestamp of each point, and then correct the position of the point. +The node uses twist information (linear and angular velocity) from the `~/input/twist` topic to correct each point in the point cloud. If the user sets `use_imu` to true, the node will replace the twist's angular velocity with the angular velocity from IMU. -The offset equation is given by -$ TimeOffset = (55.296 \mu s _SequenceIndex) + (2.304 \mu s_ DataPointIndex) $ +The node supports two different modes of distortion correction: 2D distortion correction and 3D distortion correction. The main difference is that the 2D distortion corrector only utilizes the x-axis of linear velocity and the z-axis of angular velocity to correct the point positions. On the other hand, the 3D distortion corrector utilizes all linear and angular velocity components to correct the point positions. -To calculate the exact point time, add the TimeOffset to the timestamp. -$ ExactPointTime = TimeStamp + TimeOffset $ +Please note that the processing time difference between the two distortion methods is significant; the 3D corrector takes 50% more time than the 2D corrector. Therefore, it is recommended that in general cases, users should set `use_3d_distortion_correction` to `false`. However, in scenarios such as a vehicle going over speed bumps, using the 3D corrector can be beneficial. ![distortion corrector figure](./image/distortion_corrector.jpg) @@ -23,25 +20,31 @@ $ ExactPointTime = TimeStamp + TimeOffset $ ### Input -| Name | Type | Description | -| ---------------- | ------------------------------------------------ | ---------------- | -| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points | -| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | twist | -| `~/input/imu` | `sensor_msgs::msg::Imu` | imu data | +| Name | Type | Description | +| -------------------- | ------------------------------------------------ | ---------------------------------- | +| `~/input/pointcloud` | `sensor_msgs::msg::PointCloud2` | Topic of the distorted pointcloud. | +| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Topic of the twist information. | +| `~/input/imu` | `sensor_msgs::msg::Imu` | Topic of the IMU data. | ### Output -| Name | Type | Description | -| ----------------- | ------------------------------- | --------------- | -| `~/output/points` | `sensor_msgs::msg::PointCloud2` | filtered points | +| Name | Type | Description | +| --------------------- | ------------------------------- | ----------------------------------- | +| `~/output/pointcloud` | `sensor_msgs::msg::PointCloud2` | Topic of the undistorted pointcloud | ## Parameters ### Core Parameters -| Name | Type | Default Value | Description | -| ---------------------- | ------ | ------------- | ----------------------------------------------------------- | -| `timestamp_field_name` | string | "time_stamp" | time stamp field name | -| `use_imu` | bool | true | use gyroscope for yaw rate if true, else use vehicle status | +{{ json_to_markdown("sensing/pointcloud_preprocessor/schema/distortion_corrector.schema.json") }} + +## Launch + +```bash +ros2 launch pointcloud_preprocessor distortion_corrector.launch.xml +``` ## Assumptions / Known limits + +- The node requires time synchronization between the topics from lidars, twist, and IMU. +- If you want to use a 3D distortion corrector without IMU, please check that the linear and angular velocity fields of your twist message are not empty. diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 80abba9b5d1a5..6f372f0e74646 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,7 +15,9 @@ #ifndef POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ #define POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_HPP_ +#include #include +#include #include #include @@ -33,54 +35,132 @@ #endif #include +#include #include -// Include tier4 autoware utils -#include -#include - #include #include #include namespace pointcloud_preprocessor { -using rcl_interfaces::msg::SetParametersResult; -using sensor_msgs::msg::PointCloud2; -class DistortionCorrectorComponent : public rclcpp::Node +class DistortionCorrectorBase { public: - explicit DistortionCorrectorComponent(const rclcpp::NodeOptions & options); + virtual void processTwistMessage( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) = 0; + virtual void processIMUMessage( + const std::string & base_frame, const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) = 0; + virtual void setPointCloudTransform( + const std::string & base_frame, const std::string & lidar_frame) = 0; + virtual void initialize() = 0; + virtual void undistortPointCloud(bool use_imu, sensor_msgs::msg::PointCloud2 & pointcloud) = 0; +}; -private: - void onPointCloud(PointCloud2::UniquePtr points_msg); - void onTwistWithCovarianceStamped( - const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg); - void onImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg); - bool getTransform( - const std::string & target_frame, const std::string & source_frame, - tf2::Transform * tf2_transform_ptr); +template +class DistortionCorrector : public DistortionCorrectorBase +{ +public: + bool pointcloud_transform_needed_{false}; + bool pointcloud_transform_exists_{false}; + bool imu_transform_exists_{false}; + rclcpp::Node * node_; + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; - bool undistortPointCloud(const tf2::Transform & tf2_base_link_to_sensor, PointCloud2 & points); + std::deque twist_queue_; + std::deque angular_velocity_queue_; + + explicit DistortionCorrector(rclcpp::Node * node) + : node_(node), tf_buffer_(node_->get_clock()), tf_listener_(tf_buffer_) + { + } + void processTwistMessage( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) override; + + void processIMUMessage( + const std::string & base_frame, const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) override; + void getIMUTransformation( + const std::string & base_frame, const std::string & imu_frame, + geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr); + void enqueueIMU( + const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg, + geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr); + + bool isInputValid(sensor_msgs::msg::PointCloud2 & pointcloud); + void getTwistAndIMUIterator( + bool use_imu, double first_point_time_stamp_sec, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu); + void undistortPointCloud(bool use_imu, sensor_msgs::msg::PointCloud2 & pointcloud) override; + void warnIfTimestampIsTooLate(bool is_twist_time_stamp_too_late, bool is_imu_time_stamp_too_late); + void undistortPoint( + sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, + sensor_msgs::PointCloud2Iterator & it_z, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu, float const & time_offset, + const bool & is_twist_valid, const bool & is_imu_valid) + { + static_cast(this)->undistortPointImplementation( + it_x, it_y, it_z, it_twist, it_imu, time_offset, is_twist_valid, is_imu_valid); + }; +}; - rclcpp::Subscription::SharedPtr input_points_sub_; - rclcpp::Subscription::SharedPtr imu_sub_; - rclcpp::Subscription::SharedPtr twist_sub_; - rclcpp::Publisher::SharedPtr undistorted_points_pub_; +class DistortionCorrector2D : public DistortionCorrector +{ +private: + // defined outside of for loop for performance reasons. + tf2::Quaternion baselink_quat_; + tf2::Transform baselink_tf_odom_; + tf2::Vector3 point_tf_; + tf2::Vector3 undistorted_point_tf_; + float theta_; + float x_; + float y_; + + // TF + tf2::Transform tf2_lidar_to_base_link_; + tf2::Transform tf2_base_link_to_lidar_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; +public: + explicit DistortionCorrector2D(rclcpp::Node * node) : DistortionCorrector(node) {} + void initialize() override; + void undistortPointImplementation( + sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, + sensor_msgs::PointCloud2Iterator & it_z, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu, const float & time_offset, + const bool & is_twist_valid, const bool & is_imu_valid); + + void setPointCloudTransform( + const std::string & base_frame, const std::string & lidar_frame) override; +}; - tf2_ros::Buffer tf2_buffer_{get_clock()}; - tf2_ros::TransformListener tf2_listener_{tf2_buffer_}; +class DistortionCorrector3D : public DistortionCorrector +{ +private: + // defined outside of for loop for performance reasons. + Eigen::Vector4f point_eigen_; + Eigen::Vector4f undistorted_point_eigen_; + Eigen::Matrix4f transformation_matrix_; + Eigen::Matrix4f prev_transformation_matrix_; - std::deque twist_queue_; - std::deque angular_velocity_queue_; + // TF + Eigen::Matrix4f eigen_lidar_to_base_link_; + Eigen::Matrix4f eigen_base_link_to_lidar_; - std::string base_link_frame_ = "base_link"; - std::string time_stamp_field_name_; - bool use_imu_; +public: + explicit DistortionCorrector3D(rclcpp::Node * node) : DistortionCorrector(node) {} + void initialize() override; + void undistortPointImplementation( + sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, + sensor_msgs::PointCloud2Iterator & it_z, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu, const float & time_offset, + const bool & is_twist_valid, const bool & is_imu_valid); + void setPointCloudTransform( + const std::string & base_frame, const std::string & lidar_frame) override; }; } // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp new file mode 100644 index 0000000000000..162170b193827 --- /dev/null +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp @@ -0,0 +1,65 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ +#define POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ + +#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace pointcloud_preprocessor +{ +using rcl_interfaces::msg::SetParametersResult; +using sensor_msgs::msg::PointCloud2; + +class DistortionCorrectorComponent : public rclcpp::Node +{ +public: + explicit DistortionCorrectorComponent(const rclcpp::NodeOptions & options); + +private: + rclcpp::Subscription::SharedPtr twist_sub_; + rclcpp::Subscription::SharedPtr imu_sub_; + rclcpp::Subscription::SharedPtr pointcloud_sub_; + + rclcpp::Publisher::SharedPtr undistorted_pointcloud_pub_; + + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; + + std::string base_frame_; + bool use_imu_; + bool use_3d_distortion_correction_; + + std::unique_ptr distortion_corrector_; + + void onPointCloud(PointCloud2::UniquePtr points_msg); + void onTwist(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg); + void onImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg); +}; + +} // namespace pointcloud_preprocessor + +#endif // POINTCLOUD_PREPROCESSOR__DISTORTION_CORRECTOR__DISTORTION_CORRECTOR_NODE_HPP_ diff --git a/sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml b/sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml new file mode 100644 index 0000000000000..d970aae102264 --- /dev/null +++ b/sensing/pointcloud_preprocessor/launch/distortion_corrector_node.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/sensing/pointcloud_preprocessor/package.xml b/sensing/pointcloud_preprocessor/package.xml index a669e94ee8aae..7ed22714a0c12 100644 --- a/sensing/pointcloud_preprocessor/package.xml +++ b/sensing/pointcloud_preprocessor/package.xml @@ -42,6 +42,7 @@ rclcpp rclcpp_components sensor_msgs + sophus std_msgs tf2 tf2_eigen diff --git a/sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json b/sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json new file mode 100644 index 0000000000000..acf67fd2746c4 --- /dev/null +++ b/sensing/pointcloud_preprocessor/schema/distortion_corrector_node.schema.json @@ -0,0 +1,40 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Distortion Corrector Node", + "type": "object", + "definitions": { + "distortion_corrector": { + "type": "object", + "properties": { + "base_frame": { + "type": "string", + "description": "The undistortion algorithm is based on a base frame, which must be the same as the twist frame.", + "default": "base_link" + }, + "use_imu": { + "type": "boolean", + "description": "Use IMU angular velocity, otherwise, use twist angular velocity.", + "default": "true" + }, + "use_3d_distortion_correction": { + "type": "boolean", + "description": "Use 3d distortion correction algorithm, otherwise, use 2d distortion correction algorithm.", + "default": "false" + } + }, + "required": ["base_frame", "use_imu", "use_3d_distortion_correction"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/distortion_corrector" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 8bf511637371a..81c29a9f6202a 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -16,51 +16,12 @@ #include "autoware/universe_utils/math/trigonometry.hpp" -#include -#include -#include +#include namespace pointcloud_preprocessor { -/** @brief Constructor. */ -DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOptions & options) -: Node("distortion_corrector_node", options) -{ - // initialize debug tool - { - using autoware::universe_utils::DebugPublisher; - using autoware::universe_utils::StopWatch; - stop_watch_ptr_ = std::make_unique>(); - debug_publisher_ = std::make_unique(this, "distortion_corrector"); - stop_watch_ptr_->tic("cyclic_time"); - stop_watch_ptr_->tic("processing_time"); - } - - // Parameter - time_stamp_field_name_ = declare_parameter("time_stamp_field_name", "time_stamp"); - use_imu_ = declare_parameter("use_imu", true); - - { - rclcpp::PublisherOptions pub_options; - pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - // Publisher - undistorted_points_pub_ = this->create_publisher( - "~/output/pointcloud", rclcpp::SensorDataQoS(), pub_options); - } - // Subscriber - twist_sub_ = this->create_subscription( - "~/input/twist", 10, - std::bind( - &DistortionCorrectorComponent::onTwistWithCovarianceStamped, this, std::placeholders::_1)); - imu_sub_ = this->create_subscription( - "~/input/imu", 10, - std::bind(&DistortionCorrectorComponent::onImu, this, std::placeholders::_1)); - input_points_sub_ = this->create_subscription( - "~/input/pointcloud", rclcpp::SensorDataQoS(), - std::bind(&DistortionCorrectorComponent::onPointCloud, this, std::placeholders::_1)); -} - -void DistortionCorrectorComponent::onTwistWithCovarianceStamped( +template +void DistortionCorrector::processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) { geometry_msgs::msg::TwistStamped msg; @@ -76,28 +37,66 @@ void DistortionCorrectorComponent::onTwistWithCovarianceStamped( rclcpp::Time(twist_queue_.front().header.stamp) < rclcpp::Time(twist_msg->header.stamp) - rclcpp::Duration::from_seconds(1.0)) { twist_queue_.pop_front(); + } else { + break; } - break; } } -void DistortionCorrectorComponent::onImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) +template +void DistortionCorrector::processIMUMessage( + const std::string & base_frame, const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) +{ + geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr = + std::make_shared(); + getIMUTransformation(base_frame, imu_msg->header.frame_id, geometry_imu_to_base_link_ptr); + enqueueIMU(imu_msg, geometry_imu_to_base_link_ptr); +} + +template +void DistortionCorrector::getIMUTransformation( + const std::string & base_frame, const std::string & imu_frame, + geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr) { - if (!use_imu_) { + if (imu_transform_exists_) { return; } - tf2::Transform tf2_imu_link_to_base_link{}; - getTransform(base_link_frame_, imu_msg->header.frame_id, &tf2_imu_link_to_base_link); - geometry_msgs::msg::TransformStamped::SharedPtr tf_base2imu_ptr = - std::make_shared(); - tf_base2imu_ptr->transform.rotation = tf2::toMsg(tf2_imu_link_to_base_link.getRotation()); + tf2::Transform tf2_imu_to_base_link; + if (base_frame == imu_frame) { + tf2_imu_to_base_link.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); + tf2_imu_to_base_link.setRotation(tf2::Quaternion(0.0, 0.0, 0.0, 1.0)); + imu_transform_exists_ = true; + } else { + try { + const auto transform_msg = + tf_buffer_.lookupTransform(base_frame, imu_frame, tf2::TimePointZero); + tf2::convert(transform_msg.transform, tf2_imu_to_base_link); + imu_transform_exists_ = true; + } catch (const tf2::TransformException & ex) { + RCLCPP_WARN(node_->get_logger(), "%s", ex.what()); + RCLCPP_ERROR( + node_->get_logger(), "Please publish TF %s to %s", base_frame.c_str(), imu_frame.c_str()); + + tf2_imu_to_base_link.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); + tf2_imu_to_base_link.setRotation(tf2::Quaternion(0.0, 0.0, 0.0, 1.0)); + } + } + + geometry_imu_to_base_link_ptr->transform.rotation = + tf2::toMsg(tf2_imu_to_base_link.getRotation()); +} +template +void DistortionCorrector::enqueueIMU( + const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg, + geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr) +{ geometry_msgs::msg::Vector3Stamped angular_velocity; angular_velocity.vector = imu_msg->angular_velocity; geometry_msgs::msg::Vector3Stamped transformed_angular_velocity; - tf2::doTransform(angular_velocity, transformed_angular_velocity, *tf_base2imu_ptr); + tf2::doTransform(angular_velocity, transformed_angular_velocity, *geometry_imu_to_base_link_ptr); transformed_angular_velocity.header = imu_msg->header; angular_velocity_queue_.push_back(transformed_angular_velocity); @@ -111,226 +110,310 @@ void DistortionCorrectorComponent::onImu(const sensor_msgs::msg::Imu::ConstShare rclcpp::Time(angular_velocity_queue_.front().header.stamp) < rclcpp::Time(imu_msg->header.stamp) - rclcpp::Duration::from_seconds(1.0)) { angular_velocity_queue_.pop_front(); + } else { + break; } - break; - } -} - -void DistortionCorrectorComponent::onPointCloud(PointCloud2::UniquePtr points_msg) -{ - stop_watch_ptr_->toc("processing_time", true); - const auto points_sub_count = undistorted_points_pub_->get_subscription_count() + - undistorted_points_pub_->get_intra_process_subscription_count(); - - if (points_sub_count < 1) { - return; - } - - tf2::Transform tf2_base_link_to_sensor{}; - getTransform(points_msg->header.frame_id, base_link_frame_, &tf2_base_link_to_sensor); - - undistortPointCloud(tf2_base_link_to_sensor, *points_msg); - - if (debug_publisher_) { - auto pipeline_latency_ms = - std::chrono::duration( - std::chrono::nanoseconds( - (this->get_clock()->now() - points_msg->header.stamp).nanoseconds())) - .count(); - debug_publisher_->publish( - "debug/pipeline_latency_ms", pipeline_latency_ms); - } - - undistorted_points_pub_->publish(std::move(points_msg)); - - // add processing time for debug - if (debug_publisher_) { - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); } } -bool DistortionCorrectorComponent::getTransform( - const std::string & target_frame, const std::string & source_frame, - tf2::Transform * tf2_transform_ptr) +template +void DistortionCorrector::getTwistAndIMUIterator( + bool use_imu, double first_point_time_stamp_sec, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu) { - if (target_frame == source_frame) { - tf2_transform_ptr->setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); - tf2_transform_ptr->setRotation(tf2::Quaternion(0.0, 0.0, 0.0, 1.0)); - return true; - } - - try { - const auto transform_msg = - tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); - tf2::convert(transform_msg.transform, *tf2_transform_ptr); - } catch (const tf2::TransformException & ex) { - RCLCPP_WARN(get_logger(), "%s", ex.what()); - RCLCPP_ERROR( - get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); + it_twist = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), first_point_time_stamp_sec, + [](const geometry_msgs::msg::TwistStamped & x, const double t) { + return rclcpp::Time(x.header.stamp).seconds() < t; + }); + it_twist = it_twist == std::end(twist_queue_) ? std::end(twist_queue_) - 1 : it_twist; - tf2_transform_ptr->setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); - tf2_transform_ptr->setRotation(tf2::Quaternion(0.0, 0.0, 0.0, 1.0)); - return false; + if (use_imu && !angular_velocity_queue_.empty()) { + it_imu = std::lower_bound( + std::begin(angular_velocity_queue_), std::end(angular_velocity_queue_), + first_point_time_stamp_sec, [](const geometry_msgs::msg::Vector3Stamped & x, const double t) { + return rclcpp::Time(x.header.stamp).seconds() < t; + }); + it_imu = + it_imu == std::end(angular_velocity_queue_) ? std::end(angular_velocity_queue_) - 1 : it_imu; } - return true; } -bool DistortionCorrectorComponent::undistortPointCloud( - const tf2::Transform & tf2_base_link_to_sensor, PointCloud2 & points) +template +bool DistortionCorrector::isInputValid(sensor_msgs::msg::PointCloud2 & pointcloud) { - if (points.data.empty() || twist_queue_.empty()) { + if (pointcloud.data.empty() || twist_queue_.empty()) { RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), 10000 /* ms */, - "input_pointcloud->points or twist_queue_ is empty."); + node_->get_logger(), *node_->get_clock(), 10000 /* ms */, + "input pointcloud or twist_queue_ is empty."); return false; } auto time_stamp_field_it = std::find_if( - std::cbegin(points.fields), std::cend(points.fields), - [this](const sensor_msgs::msg::PointField & field) { - return field.name == time_stamp_field_name_; - }); - if (time_stamp_field_it == points.fields.cend()) { + std::cbegin(pointcloud.fields), std::cend(pointcloud.fields), + [](const sensor_msgs::msg::PointField & field) { return field.name == "time_stamp"; }); + if (time_stamp_field_it == pointcloud.fields.cend()) { RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), 10000 /* ms */, + node_->get_logger(), *node_->get_clock(), 10000 /* ms */, "Required field time stamp doesn't exist in the point cloud."); return false; } + return true; +} + +template +void DistortionCorrector::undistortPointCloud( + bool use_imu, sensor_msgs::msg::PointCloud2 & pointcloud) +{ + if (!isInputValid(pointcloud)) return; - sensor_msgs::PointCloud2Iterator it_x(points, "x"); - sensor_msgs::PointCloud2Iterator it_y(points, "y"); - sensor_msgs::PointCloud2Iterator it_z(points, "z"); - sensor_msgs::PointCloud2ConstIterator it_time_stamp(points, time_stamp_field_name_); + sensor_msgs::PointCloud2Iterator it_x(pointcloud, "x"); + sensor_msgs::PointCloud2Iterator it_y(pointcloud, "y"); + sensor_msgs::PointCloud2Iterator it_z(pointcloud, "z"); + sensor_msgs::PointCloud2ConstIterator it_time_stamp(pointcloud, "time_stamp"); - float theta{0.0f}; - float x{0.0f}; - float y{0.0f}; double prev_time_stamp_sec{*it_time_stamp}; const double first_point_time_stamp_sec{*it_time_stamp}; - auto twist_it = std::lower_bound( - std::begin(twist_queue_), std::end(twist_queue_), first_point_time_stamp_sec, - [](const geometry_msgs::msg::TwistStamped & x, const double t) { - return rclcpp::Time(x.header.stamp).seconds() < t; - }); - twist_it = twist_it == std::end(twist_queue_) ? std::end(twist_queue_) - 1 : twist_it; - - decltype(angular_velocity_queue_)::iterator imu_it; - if (use_imu_ && !angular_velocity_queue_.empty()) { - imu_it = std::lower_bound( - std::begin(angular_velocity_queue_), std::end(angular_velocity_queue_), - first_point_time_stamp_sec, [](const geometry_msgs::msg::Vector3Stamped & x, const double t) { - return rclcpp::Time(x.header.stamp).seconds() < t; - }); - imu_it = - imu_it == std::end(angular_velocity_queue_) ? std::end(angular_velocity_queue_) - 1 : imu_it; - } - - const tf2::Transform tf2_base_link_to_sensor_inv{tf2_base_link_to_sensor.inverse()}; - - // For performance, do not instantiate `rclcpp::Time` inside of the for-loop - double twist_stamp = rclcpp::Time(twist_it->header.stamp).seconds(); - - // For performance, instantiate outside of the for-loop - tf2::Quaternion baselink_quat{}; - tf2::Transform baselink_tf_odom{}; - tf2::Vector3 point{}; - tf2::Vector3 undistorted_point{}; - - // For performance, avoid transform computation if unnecessary - bool need_transform = points.header.frame_id != base_link_frame_; + std::deque::iterator it_twist; + std::deque::iterator it_imu; + getTwistAndIMUIterator(use_imu, first_point_time_stamp_sec, it_twist, it_imu); // For performance, do not instantiate `rclcpp::Time` inside of the for-loop + double twist_stamp = rclcpp::Time(it_twist->header.stamp).seconds(); double imu_stamp{0.0}; - if (use_imu_ && !angular_velocity_queue_.empty()) { - imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds(); + if (use_imu && !angular_velocity_queue_.empty()) { + imu_stamp = rclcpp::Time(it_imu->header.stamp).seconds(); } - // If there is a point that cannot be associated, record it to issue a warning - bool twist_time_stamp_is_too_late = false; - bool imu_time_stamp_is_too_late = false; + // If there is a point in a pointcloud that cannot be associated, record it to issue a warning + bool is_twist_time_stamp_too_late = false; + bool is_imu_time_stamp_too_late = false; + bool is_twist_valid = true; + bool is_imu_valid = true; for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_time_stamp) { - while (twist_it != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) { - ++twist_it; - twist_stamp = rclcpp::Time(twist_it->header.stamp).seconds(); - } - - float v{static_cast(twist_it->twist.linear.x)}; - float w{static_cast(twist_it->twist.angular.z)}; + is_twist_valid = true; + is_imu_valid = true; + // Get closest twist information + while (it_twist != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) { + ++it_twist; + twist_stamp = rclcpp::Time(it_twist->header.stamp).seconds(); + } if (std::abs(*it_time_stamp - twist_stamp) > 0.1) { - twist_time_stamp_is_too_late = true; - v = 0.0f; - w = 0.0f; + is_twist_time_stamp_too_late = true; + is_twist_valid = false; } - if (use_imu_ && !angular_velocity_queue_.empty()) { - while (imu_it != std::end(angular_velocity_queue_) - 1 && *it_time_stamp > imu_stamp) { - ++imu_it; - imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds(); + // Get closest IMU information + if (use_imu && !angular_velocity_queue_.empty()) { + while (it_imu != std::end(angular_velocity_queue_) - 1 && *it_time_stamp > imu_stamp) { + ++it_imu; + imu_stamp = rclcpp::Time(it_imu->header.stamp).seconds(); } if (std::abs(*it_time_stamp - imu_stamp) > 0.1) { - imu_time_stamp_is_too_late = true; - } else { - w = static_cast(imu_it->vector.z); + is_imu_time_stamp_too_late = true; + is_imu_valid = false; } + } else { + is_imu_valid = false; } - const auto time_offset = static_cast(*it_time_stamp - prev_time_stamp_sec); + float time_offset = static_cast(*it_time_stamp - prev_time_stamp_sec); - point.setValue(*it_x, *it_y, *it_z); + // Undistort a single point based on the strategy + undistortPoint(it_x, it_y, it_z, it_twist, it_imu, time_offset, is_twist_valid, is_imu_valid); - if (need_transform) { - point = tf2_base_link_to_sensor_inv * point; - } + prev_time_stamp_sec = *it_time_stamp; + } - theta += w * time_offset; - baselink_quat.setValue( - 0, 0, autoware::universe_utils::sin(theta * 0.5f), - autoware::universe_utils::cos(theta * 0.5f)); // baselink_quat.setRPY(0.0, 0.0, theta); - const float dis = v * time_offset; - x += dis * autoware::universe_utils::cos(theta); - y += dis * autoware::universe_utils::sin(theta); + warnIfTimestampIsTooLate(is_twist_time_stamp_too_late, is_imu_time_stamp_too_late); +} - baselink_tf_odom.setOrigin(tf2::Vector3(x, y, 0.0)); - baselink_tf_odom.setRotation(baselink_quat); +template +void DistortionCorrector::warnIfTimestampIsTooLate( + bool is_twist_time_stamp_too_late, bool is_imu_time_stamp_too_late) +{ + if (is_twist_time_stamp_too_late) { + RCLCPP_WARN_STREAM_THROTTLE( + node_->get_logger(), *node_->get_clock(), 10000 /* ms */, + "Twist time_stamp is too late. Could not interpolate."); + } - undistorted_point = baselink_tf_odom * point; + if (is_imu_time_stamp_too_late) { + RCLCPP_WARN_STREAM_THROTTLE( + node_->get_logger(), *node_->get_clock(), 10000 /* ms */, + "IMU time_stamp is too late. Could not interpolate."); + } +} - if (need_transform) { - undistorted_point = tf2_base_link_to_sensor * undistorted_point; +///////////////////////// Functions for different undistortion strategies ///////////////////////// + +void DistortionCorrector2D::initialize() +{ + x_ = 0.0f; + y_ = 0.0f; + theta_ = 0.0f; +} + +void DistortionCorrector3D::initialize() +{ + prev_transformation_matrix_ = Eigen::Matrix4f::Identity(); +} + +void DistortionCorrector2D::setPointCloudTransform( + const std::string & base_frame, const std::string & lidar_frame) +{ + if (pointcloud_transform_exists_) { + return; + } + + if (base_frame == lidar_frame) { + tf2_lidar_to_base_link_.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); + tf2_lidar_to_base_link_.setRotation(tf2::Quaternion(0.0, 0.0, 0.0, 1.0)); + tf2_base_link_to_lidar_ = tf2_lidar_to_base_link_; + pointcloud_transform_exists_ = true; + } else { + try { + const auto transform_msg = + tf_buffer_.lookupTransform(base_frame, lidar_frame, tf2::TimePointZero); + tf2::convert(transform_msg.transform, tf2_lidar_to_base_link_); + tf2_base_link_to_lidar_ = tf2_lidar_to_base_link_.inverse(); + pointcloud_transform_exists_ = true; + pointcloud_transform_needed_ = true; + } catch (const tf2::TransformException & ex) { + RCLCPP_WARN(node_->get_logger(), "%s", ex.what()); + RCLCPP_ERROR( + node_->get_logger(), "Please publish TF %s to %s", base_frame.c_str(), lidar_frame.c_str()); + + tf2_lidar_to_base_link_.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); + tf2_lidar_to_base_link_.setRotation(tf2::Quaternion(0.0, 0.0, 0.0, 1.0)); + tf2_base_link_to_lidar_ = tf2_lidar_to_base_link_; } + } +} + +void DistortionCorrector3D::setPointCloudTransform( + const std::string & base_frame, const std::string & lidar_frame) +{ + if (pointcloud_transform_exists_) { + return; + } - *it_x = static_cast(undistorted_point.getX()); - *it_y = static_cast(undistorted_point.getY()); - *it_z = static_cast(undistorted_point.getZ()); + if (base_frame == lidar_frame) { + eigen_lidar_to_base_link_ = Eigen::Matrix4f::Identity(); + eigen_base_link_to_lidar_ = Eigen::Matrix4f::Identity(); + pointcloud_transform_exists_ = true; + } - prev_time_stamp_sec = *it_time_stamp; + try { + const auto transform_msg = + tf_buffer_.lookupTransform(base_frame, lidar_frame, tf2::TimePointZero); + eigen_lidar_to_base_link_ = + tf2::transformToEigen(transform_msg.transform).matrix().cast(); + eigen_base_link_to_lidar_ = eigen_lidar_to_base_link_.inverse(); + pointcloud_transform_exists_ = true; + pointcloud_transform_needed_ = true; + } catch (const tf2::TransformException & ex) { + RCLCPP_WARN(node_->get_logger(), "%s", ex.what()); + RCLCPP_ERROR( + node_->get_logger(), "Please publish TF %s to %s", base_frame.c_str(), lidar_frame.c_str()); + eigen_lidar_to_base_link_ = Eigen::Matrix4f::Identity(); + eigen_base_link_to_lidar_ = Eigen::Matrix4f::Identity(); } +} - if (twist_time_stamp_is_too_late) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), 10000 /* ms */, - "twist time_stamp is too late. Could not interpolate."); +inline void DistortionCorrector2D::undistortPointImplementation( + sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, + sensor_msgs::PointCloud2Iterator & it_z, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu, const float & time_offset, + const bool & is_twist_valid, const bool & is_imu_valid) +{ + // Initialize linear velocity and angular velocity + float v{0.0f}, w{0.0f}; + if (is_twist_valid) { + v = static_cast(it_twist->twist.linear.x); + w = static_cast(it_twist->twist.angular.z); + } + if (is_imu_valid) { + w = static_cast(it_imu->vector.z); } - if (imu_time_stamp_is_too_late) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), 10000 /* ms */, - "imu time_stamp is too late. Could not interpolate."); + // Undistort point + point_tf_.setValue(*it_x, *it_y, *it_z); + + if (pointcloud_transform_needed_) { + point_tf_ = tf2_lidar_to_base_link_ * point_tf_; } + theta_ += w * time_offset; + baselink_quat_.setValue( + 0, 0, autoware::universe_utils::sin(theta_ * 0.5f), + autoware::universe_utils::cos(theta_ * 0.5f)); // baselink_quat.setRPY(0.0, 0.0, theta); + const float dis = v * time_offset; + x_ += dis * autoware::universe_utils::cos(theta_); + y_ += dis * autoware::universe_utils::sin(theta_); - return true; + baselink_tf_odom_.setOrigin(tf2::Vector3(x_, y_, 0.0)); + baselink_tf_odom_.setRotation(baselink_quat_); + + undistorted_point_tf_ = baselink_tf_odom_ * point_tf_; + + if (pointcloud_transform_needed_) { + undistorted_point_tf_ = tf2_base_link_to_lidar_ * undistorted_point_tf_; + } + + *it_x = static_cast(undistorted_point_tf_.getX()); + *it_y = static_cast(undistorted_point_tf_.getY()); + *it_z = static_cast(undistorted_point_tf_.getZ()); } -} // namespace pointcloud_preprocessor +inline void DistortionCorrector3D::undistortPointImplementation( + sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, + sensor_msgs::PointCloud2Iterator & it_z, + std::deque::iterator & it_twist, + std::deque::iterator & it_imu, const float & time_offset, + const bool & is_twist_valid, const bool & is_imu_valid) +{ + // Initialize linear velocity and angular velocity + float v_x_{0.0f}, v_y_{0.0f}, v_z_{0.0f}, w_x_{0.0f}, w_y_{0.0f}, w_z_{0.0f}; + if (is_twist_valid) { + v_x_ = static_cast(it_twist->twist.linear.x); + v_y_ = static_cast(it_twist->twist.linear.y); + v_z_ = static_cast(it_twist->twist.linear.z); + w_x_ = static_cast(it_twist->twist.angular.x); + w_y_ = static_cast(it_twist->twist.angular.y); + w_z_ = static_cast(it_twist->twist.angular.z); + } + if (is_imu_valid) { + w_x_ = static_cast(it_imu->vector.x); + w_y_ = static_cast(it_imu->vector.y); + w_z_ = static_cast(it_imu->vector.z); + } -#include -RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent) + // Undistort point + point_eigen_ << *it_x, *it_y, *it_z, 1.0; + if (pointcloud_transform_needed_) { + point_eigen_ = eigen_lidar_to_base_link_ * point_eigen_; + } + + Sophus::SE3f::Tangent twist(v_x_, v_y_, v_z_, w_x_, w_y_, w_z_); + twist = twist * time_offset; + transformation_matrix_ = Sophus::SE3f::exp(twist).matrix(); + transformation_matrix_ = transformation_matrix_ * prev_transformation_matrix_; + undistorted_point_eigen_ = transformation_matrix_ * point_eigen_; + + if (pointcloud_transform_needed_) { + undistorted_point_eigen_ = eigen_base_link_to_lidar_ * undistorted_point_eigen_; + } + *it_x = undistorted_point_eigen_[0]; + *it_y = undistorted_point_eigen_[1]; + *it_z = undistorted_point_eigen_[2]; + + prev_transformation_matrix_ = transformation_matrix_; +} + +} // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp new file mode 100644 index 0000000000000..b5cf581301a23 --- /dev/null +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp @@ -0,0 +1,124 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector_node.hpp" + +#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" + +namespace pointcloud_preprocessor +{ +/** @brief Constructor. */ +DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOptions & options) +: Node("distortion_corrector_node", options) +{ + // initialize debug tool + + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ = std::make_unique(this, "distortion_corrector"); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + + // Parameter + base_frame_ = declare_parameter("base_frame"); + use_imu_ = declare_parameter("use_imu"); + use_3d_distortion_correction_ = declare_parameter("use_3d_distortion_correction"); + + // Publisher + { + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + // Publisher + undistorted_pointcloud_pub_ = this->create_publisher( + "~/output/pointcloud", rclcpp::SensorDataQoS(), pub_options); + } + + // Subscriber + twist_sub_ = this->create_subscription( + "~/input/twist", 10, + std::bind(&DistortionCorrectorComponent::onTwist, this, std::placeholders::_1)); + imu_sub_ = this->create_subscription( + "~/input/imu", 10, + std::bind(&DistortionCorrectorComponent::onImu, this, std::placeholders::_1)); + pointcloud_sub_ = this->create_subscription( + "~/input/pointcloud", rclcpp::SensorDataQoS(), + std::bind(&DistortionCorrectorComponent::onPointCloud, this, std::placeholders::_1)); + + // Setup the distortion corrector + + if (use_3d_distortion_correction_) { + distortion_corrector_ = std::make_unique(this); + } else { + distortion_corrector_ = std::make_unique(this); + } +} + +void DistortionCorrectorComponent::onTwist( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) +{ + distortion_corrector_->processTwistMessage(twist_msg); +} + +void DistortionCorrectorComponent::onImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) +{ + if (!use_imu_) { + return; + } + + distortion_corrector_->processIMUMessage(base_frame_, imu_msg); +} + +void DistortionCorrectorComponent::onPointCloud(PointCloud2::UniquePtr pointcloud_msg) +{ + stop_watch_ptr_->toc("processing_time", true); + const auto points_sub_count = undistorted_pointcloud_pub_->get_subscription_count() + + undistorted_pointcloud_pub_->get_intra_process_subscription_count(); + + if (points_sub_count < 1) { + return; + } + + distortion_corrector_->setPointCloudTransform(base_frame_, pointcloud_msg->header.frame_id); + + distortion_corrector_->initialize(); + distortion_corrector_->undistortPointCloud(use_imu_, *pointcloud_msg); + + if (debug_publisher_) { + auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds( + (this->get_clock()->now() - pointcloud_msg->header.stamp).nanoseconds())) + .count(); + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); + } + + undistorted_pointcloud_pub_->publish(std::move(pointcloud_msg)); + + // add processing time for debug + if (debug_publisher_) { + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); + debug_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + } +} + +} // namespace pointcloud_preprocessor + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(pointcloud_preprocessor::DistortionCorrectorComponent) diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py b/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py index 5fdf434123c36..cc80da29e3c13 100644 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py +++ b/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py @@ -47,7 +47,7 @@ def generate_test_description(): plugin="pointcloud_preprocessor::DistortionCorrectorComponent", name="distortion_corrector_node", parameters=[ - {"use_imu": True}, + {"base_frame": "base_link", "use_imu": True, "use_3d_distortion_correction": False}, ], remappings=[ ("~/input/twist", "/test/sensing/vehicle_velocity_converter/twist_with_covariance"), diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py index 5943aec13bca6..35eb41f9dbc17 100644 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py +++ b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py @@ -46,7 +46,11 @@ def generate_test_description(): plugin="pointcloud_preprocessor::DistortionCorrectorComponent", name="distortion_corrector_node", parameters=[ - {"use_imu": False}, + { + "base_frame": "base_link", + "use_imu": False, + "use_3d_distortion_correction": False, + }, ], remappings=[ ("~/input/twist", "/test/sensing/vehicle_velocity_converter/twist_with_covariance"), From c7302afd0374a09e42b3c37e6d6f9ae4ee4bfa97 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Mon, 8 Jul 2024 16:22:41 +0900 Subject: [PATCH 137/151] fix(pointcloud_preprocessor): fix the bug where the geometry message was not saved correctly. (#7886) * fix: fix bug that geometry message didn't save correctly Signed-off-by: vividf * chore: change some functions from public to protected Signed-off-by: vividf --------- Signed-off-by: vividf Co-authored-by: Kenzo Lobos Tsunekawa --- .../distortion_corrector.hpp | 36 +++++++++---------- .../distortion_corrector.cpp | 19 +++++----- 2 files changed, 25 insertions(+), 30 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 6f372f0e74646..8a7b7c90113da 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -61,7 +61,8 @@ class DistortionCorrectorBase template class DistortionCorrector : public DistortionCorrectorBase { -public: +protected: + geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr_; bool pointcloud_transform_needed_{false}; bool pointcloud_transform_exists_{false}; bool imu_transform_exists_{false}; @@ -72,28 +73,12 @@ class DistortionCorrector : public DistortionCorrectorBase std::deque twist_queue_; std::deque angular_velocity_queue_; - explicit DistortionCorrector(rclcpp::Node * node) - : node_(node), tf_buffer_(node_->get_clock()), tf_listener_(tf_buffer_) - { - } - void processTwistMessage( - const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) override; - - void processIMUMessage( - const std::string & base_frame, const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) override; - void getIMUTransformation( - const std::string & base_frame, const std::string & imu_frame, - geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr); - void enqueueIMU( - const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg, - geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr); - - bool isInputValid(sensor_msgs::msg::PointCloud2 & pointcloud); + void getIMUTransformation(const std::string & base_frame, const std::string & imu_frame); + void enqueueIMU(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg); void getTwistAndIMUIterator( bool use_imu, double first_point_time_stamp_sec, std::deque::iterator & it_twist, std::deque::iterator & it_imu); - void undistortPointCloud(bool use_imu, sensor_msgs::msg::PointCloud2 & pointcloud) override; void warnIfTimestampIsTooLate(bool is_twist_time_stamp_too_late, bool is_imu_time_stamp_too_late); void undistortPoint( sensor_msgs::PointCloud2Iterator & it_x, sensor_msgs::PointCloud2Iterator & it_y, @@ -105,6 +90,19 @@ class DistortionCorrector : public DistortionCorrectorBase static_cast(this)->undistortPointImplementation( it_x, it_y, it_z, it_twist, it_imu, time_offset, is_twist_valid, is_imu_valid); }; + +public: + explicit DistortionCorrector(rclcpp::Node * node) + : node_(node), tf_buffer_(node_->get_clock()), tf_listener_(tf_buffer_) + { + } + void processTwistMessage( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) override; + + void processIMUMessage( + const std::string & base_frame, const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) override; + void undistortPointCloud(bool use_imu, sensor_msgs::msg::PointCloud2 & pointcloud) override; + bool isInputValid(sensor_msgs::msg::PointCloud2 & pointcloud); }; class DistortionCorrector2D : public DistortionCorrector diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 81c29a9f6202a..8c8752c7e278e 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -47,21 +47,20 @@ template void DistortionCorrector::processIMUMessage( const std::string & base_frame, const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) { - geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr = - std::make_shared(); - getIMUTransformation(base_frame, imu_msg->header.frame_id, geometry_imu_to_base_link_ptr); - enqueueIMU(imu_msg, geometry_imu_to_base_link_ptr); + getIMUTransformation(base_frame, imu_msg->header.frame_id); + enqueueIMU(imu_msg); } template void DistortionCorrector::getIMUTransformation( - const std::string & base_frame, const std::string & imu_frame, - geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr) + const std::string & base_frame, const std::string & imu_frame) { if (imu_transform_exists_) { return; } + geometry_imu_to_base_link_ptr_ = std::make_shared(); + tf2::Transform tf2_imu_to_base_link; if (base_frame == imu_frame) { tf2_imu_to_base_link.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); @@ -83,20 +82,18 @@ void DistortionCorrector::getIMUTransformation( } } - geometry_imu_to_base_link_ptr->transform.rotation = + geometry_imu_to_base_link_ptr_->transform.rotation = tf2::toMsg(tf2_imu_to_base_link.getRotation()); } template -void DistortionCorrector::enqueueIMU( - const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg, - geometry_msgs::msg::TransformStamped::SharedPtr geometry_imu_to_base_link_ptr) +void DistortionCorrector::enqueueIMU(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg) { geometry_msgs::msg::Vector3Stamped angular_velocity; angular_velocity.vector = imu_msg->angular_velocity; geometry_msgs::msg::Vector3Stamped transformed_angular_velocity; - tf2::doTransform(angular_velocity, transformed_angular_velocity, *geometry_imu_to_base_link_ptr); + tf2::doTransform(angular_velocity, transformed_angular_velocity, *geometry_imu_to_base_link_ptr_); transformed_angular_velocity.header = imu_msg->header; angular_velocity_queue_.push_back(transformed_angular_velocity); From da1a0429018e46a85851c69c1afba0d733f102cb Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 4 Jul 2024 00:34:15 +0900 Subject: [PATCH 138/151] feat(pointcloud_preprocessor): add unit test for distortion corrector node (#7801) feat: add unit test for distoriton corrector node Signed-off-by: vividf --- .../pointcloud_preprocessor/CMakeLists.txt | 14 +- .../test/test_distortion_corrector.py | 241 ------- .../test/test_distortion_corrector_node.cpp | 600 ++++++++++++++++++ ...test_distortion_corrector_use_imu_false.py | 240 ------- 4 files changed, 606 insertions(+), 489 deletions(-) delete mode 100644 sensing/pointcloud_preprocessor/test/test_distortion_corrector.py create mode 100644 sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp delete mode 100644 sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index dd73f28a41f3c..2d0649fe43954 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -231,14 +231,12 @@ if(BUILD_TESTING) ament_add_gtest(test_utilities test/test_utilities.cpp ) + ament_add_gtest(distortion_corrector_node_tests + test/test_distortion_corrector_node.cpp + ) + target_link_libraries(test_utilities pointcloud_preprocessor_filter) + target_link_libraries(distortion_corrector_node_tests pointcloud_preprocessor_filter) + - add_ros_test( - test/test_distortion_corrector.py - TIMEOUT "30" - ) - add_ros_test( - test/test_distortion_corrector_use_imu_false.py - TIMEOUT "30" - ) endif() diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py b/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py deleted file mode 100644 index cc80da29e3c13..0000000000000 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector.py +++ /dev/null @@ -1,241 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import unittest - -from geometry_msgs.msg import TwistWithCovarianceStamped -import launch -from launch.logging import get_logger -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode -import launch_testing -import numpy as np -import pytest -import rclpy -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSHistoryPolicy -from rclpy.qos import QoSProfile -from rclpy.qos import QoSReliabilityPolicy -from sensor_msgs.msg import Imu -from sensor_msgs.msg import PointCloud2 -from sensor_msgs.msg import PointField -from std_msgs.msg import Header - -logger = get_logger(__name__) - - -@pytest.mark.launch_test -def generate_test_description(): - nodes = [] - - nodes.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DistortionCorrectorComponent", - name="distortion_corrector_node", - parameters=[ - {"base_frame": "base_link", "use_imu": True, "use_3d_distortion_correction": False}, - ], - remappings=[ - ("~/input/twist", "/test/sensing/vehicle_velocity_converter/twist_with_covariance"), - ("~/input/imu", "/test/sensing/imu/imu_data"), - ("~/input/pointcloud", "/test/sensing/lidar/top/mirror_cropped/pointcloud_ex"), - ("~/output/pointcloud", "/test/sensing/lidar/top/rectified/pointcloud_ex"), - ], - extra_arguments=[{"use_intra_process_comms": True}], - ) - ) - - container = ComposableNodeContainer( - name="test_distortion_corrector_container", - namespace="pointcloud_preprocessor", - package="rclcpp_components", - executable="component_container", - composable_node_descriptions=nodes, - output="screen", - ) - - return launch.LaunchDescription( - [ - container, - # Start tests right away - no need to wait for anything - launch_testing.actions.ReadyToTest(), - ] - ) - - -class TestDistortionCorrector(unittest.TestCase): - @classmethod - def setUpClass(cls): - # Initialize the ROS context for the test node - rclpy.init() - - @classmethod - def tearDownClass(cls): - # Shutdown the ROS context - rclpy.shutdown() - - def setUp(self): - # Create a ROS node for tests - self.test_node = rclpy.create_node("test_node") - self.evaluation_time = 2 # 200ms - - def tearDown(self): - self.test_node.destroy_node() - - @staticmethod - def print_message(stat): - logger.debug("===========================") - logger.debug(stat) - - @staticmethod - def pointcloud2_to_xyz_array(cloud_msg): - cloud_arr = np.frombuffer(cloud_msg.data, dtype=np.float32) - cloud_arr = np.reshape(cloud_arr, (cloud_msg.width, int(cloud_msg.point_step / 4))) - return cloud_arr[:, :3] - - @staticmethod - def generate_pointcloud(num_points, header, timestamp_offset_per_point=0.01): - points_xyz = np.random.rand(num_points, 3).astype(np.float32) - timestamps = np.array( - [ - header.stamp.sec + header.stamp.nanosec * 1e-9 + timestamp_offset_per_point * i - for i in range(num_points) - ] - ).astype(np.float64) - xyz_data = points_xyz.tobytes() - timestamp_data = timestamps.tobytes() - pointcloud_data = b"".join( - xyz_data[i * 12 : i * 12 + 12] + timestamp_data[i * 8 : i * 8 + 8] - for i in range(len(xyz_data)) - ) - fields = [ - PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), - PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), - PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), - PointField(name="time_stamp", offset=12, datatype=PointField.FLOAT64, count=1), - ] - pointcloud_msg = PointCloud2( - header=header, - height=1, - width=10, - is_dense=True, - is_bigendian=False, - point_step=20, # 4 float32 fields * 4 bytes/field - row_step=20 * num_points, # point_step * width - fields=fields, - data=pointcloud_data, - ) - return pointcloud_msg - - def test_node_link(self): - # QoS profile for sensor data - sensor_qos = QoSProfile( - history=QoSHistoryPolicy.KEEP_LAST, - depth=10, - reliability=QoSReliabilityPolicy.BEST_EFFORT, - durability=QoSDurabilityPolicy.VOLATILE, - ) - - # Publishers - imu_pub = self.test_node.create_publisher(Imu, "/test/sensing/imu/imu_data", 10) - velocity_pub = self.test_node.create_publisher( - TwistWithCovarianceStamped, - "/test/sensing/vehicle_velocity_converter/twist_with_covariance", - 10, - ) - pointcloud_pub = self.test_node.create_publisher( - PointCloud2, - "/test/sensing/lidar/top/mirror_cropped/pointcloud_ex", - qos_profile=sensor_qos, - ) - - # Subscribers - received_data = {"msg": None} - - def pointcloud_callback(msg): - received_data["msg"] = msg - - self.test_node.create_subscription( - PointCloud2, - "/test/sensing/lidar/top/rectified/pointcloud_ex", - pointcloud_callback, - qos_profile=sensor_qos, - ) - - # Wait for composable node launches - rclpy.spin_once(self.test_node, timeout_sec=1.0) - - # Prepare header - header = Header() - header.stamp = self.test_node.get_clock().now().to_msg() - header.frame_id = "base_link" - - # Publish IMU and velocity data - for i in range(50): - header_tmp = Header() - header_tmp.stamp = self.test_node.get_clock().now().to_msg() - header_tmp.frame_id = "base_link" - - imu_msg = Imu() - imu_msg.header = header_tmp - velocity_msg = TwistWithCovarianceStamped() - velocity_msg.header = header_tmp - velocity_msg.twist.twist.linear.x = 1.0 - - imu_pub.publish(imu_msg) - velocity_pub.publish(velocity_msg) - rclpy.spin_once(self.test_node, timeout_sec=0.01) - - # Publish pointcloud data - num_points = 10 - pointcloud_msg = self.generate_pointcloud(num_points, header) - pointcloud_pub.publish(pointcloud_msg) - - # Wait for output with a timeout - start_time = self.test_node.get_clock().now() - while self.test_node.get_clock().now() - start_time < rclpy.duration.Duration( - seconds=self.evaluation_time - ): - rclpy.spin_once(self.test_node, timeout_sec=0.1) - if received_data["msg"] is not None: - break - - # Check if the output was received - self.assertIsNotNone(received_data["msg"], "Did not receive output pointcloud data") - - # Check that the received pointcloud data has same length as num_points - received_pointcloud = received_data["msg"] - self.assertEqual( - received_pointcloud.width, - num_points, - "The received pointcloud data has a different length than expected", - ) - - # Check that the received pointcloud data is different from the original one - original_pointcloud_arr = self.pointcloud2_to_xyz_array(pointcloud_msg) - received_pointcloud_arr = self.pointcloud2_to_xyz_array(received_pointcloud) - self.assertFalse( - np.allclose(original_pointcloud_arr, received_pointcloud_arr, atol=1e-6), - "The received pointcloud data is not different from the original one", - ) - - -@launch_testing.post_shutdown_test() -class TestProcessOutput(unittest.TestCase): - def test_exit_code(self, proc_info): - # Check that process exits with code 0: no error - launch_testing.asserts.assertExitCodes(proc_info) diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp new file mode 100644 index 0000000000000..9e5d068be52f5 --- /dev/null +++ b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -0,0 +1,600 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" + +#include + +#include +#include +#include +#include + +#include +#include + +class DistortionCorrectorTest : public ::testing::Test +{ +protected: + void SetUp() override + { + node_ = std::make_shared("test_node"); + distortion_corrector_2d_ = + std::make_shared(node_.get()); + distortion_corrector_3d_ = + std::make_shared(node_.get()); + + // Setup TF + tf_broadcaster_ = std::make_shared(node_); + tf_broadcaster_->sendTransform(generateStaticTransformMsg()); + + // Spin the node for a while to ensure transforms are published + auto start = std::chrono::steady_clock::now(); + auto timeout = std::chrono::seconds(1); + while (std::chrono::steady_clock::now() - start < timeout) { + rclcpp::spin_some(node_); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + + void TearDown() override {} + + rclcpp::Time addMilliseconds(rclcpp::Time stamp, int ms) + { + auto ms_in_ns = rclcpp::Duration(0, ms * 1000000); + return stamp + ms_in_ns; + } + + rclcpp::Time subtractMilliseconds(rclcpp::Time stamp, int ms) + { + auto ms_in_ns = rclcpp::Duration(0, ms * 1000000); + return stamp - ms_in_ns; + } + + geometry_msgs::msg::TransformStamped generateTransformMsg( + const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, + double qx, double qy, double qz, double qw) + { + geometry_msgs::msg::TransformStamped tf_msg; + tf_msg.header.stamp = node_->get_clock()->now(); + tf_msg.header.frame_id = parent_frame; + tf_msg.child_frame_id = child_frame; + tf_msg.transform.translation.x = x; + tf_msg.transform.translation.y = y; + tf_msg.transform.translation.z = z; + tf_msg.transform.rotation.x = qx; + tf_msg.transform.rotation.y = qy; + tf_msg.transform.rotation.z = qz; + tf_msg.transform.rotation.w = qw; + return tf_msg; + } + + std::vector generateStaticTransformMsg() + { + return { + generateTransformMsg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), + generateTransformMsg("base_link", "imu_link", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; + } + + std::shared_ptr generateTwistMsg( + double linear_x, double angular_z, rclcpp::Time stamp) + { + auto twist_msg = std::make_shared(); + twist_msg->header.stamp = stamp; + twist_msg->header.frame_id = "base_link"; + twist_msg->twist.twist.linear.x = linear_x; + twist_msg->twist.twist.angular.z = angular_z; + return twist_msg; + } + + std::shared_ptr generateImuMsg( + double angular_vel_x, double angular_vel_y, double angular_vel_z, rclcpp::Time stamp) + { + auto imu_msg = std::make_shared(); + imu_msg->header.stamp = stamp; + imu_msg->header.frame_id = "imu_link"; + imu_msg->angular_velocity.x = angular_vel_x; + imu_msg->angular_velocity.y = angular_vel_y; + imu_msg->angular_velocity.z = angular_vel_z; + return imu_msg; + } + + std::vector> generateTwistMsgs( + rclcpp::Time pointcloud_timestamp) + { + std::vector> twist_msgs; + rclcpp::Time twist_stamp = subtractMilliseconds(pointcloud_timestamp, 5); + + for (int i = 0; i < 6; ++i) { + auto twist_msg = generateTwistMsg(10.0 + i * 2, 0.02 + i * 0.01, twist_stamp); + twist_msgs.push_back(twist_msg); + // Make sure the twist stamp is not identical to any point stamp, and imu stamp + twist_stamp = addMilliseconds(twist_stamp, 24); + } + + return twist_msgs; + } + + std::vector> generateImuMsgs( + rclcpp::Time pointcloud_timestamp) + { + std::vector> imu_msgs; + rclcpp::Time imu_stamp = subtractMilliseconds(pointcloud_timestamp, 10); + + for (int i = 0; i < 6; ++i) { + auto imu_msg = + generateImuMsg(0.01 + i * 0.005, -0.02 + i * 0.005, 0.05 + i * 0.005, imu_stamp); + imu_msgs.push_back(imu_msg); + // Make sure the imu stamp is not identical to any point stamp, and twist stamp + imu_stamp = addMilliseconds(imu_stamp, 27); + } + + return imu_msgs; + } + + sensor_msgs::msg::PointCloud2 generatePointCloudMsg( + bool is_generate_points, bool is_lidar_frame, rclcpp::Time stamp) + { + sensor_msgs::msg::PointCloud2 pointcloud_msg; + pointcloud_msg.header.stamp = stamp; + pointcloud_msg.header.frame_id = is_lidar_frame ? "lidar_top" : "base_link"; + pointcloud_msg.height = 1; + pointcloud_msg.is_dense = true; + pointcloud_msg.is_bigendian = false; + pointcloud_msg.point_step = + 20; // 3 float32 fields * 4 bytes/field + 1 float64 field * 8 bytes/field + + if (is_generate_points) { + std::vector points = { + 10.0f, 0.0f, 0.0f, // point 1 + 0.0f, 10.0f, 0.0f, // point 2 + 0.0f, 0.0f, 10.0f, // point 3 + 20.0f, 0.0f, 0.0f, // point 4 + 0.0f, 20.0f, 0.0f, // point 5 + 0.0f, 0.0f, 20.0f, // point 6 + 30.0f, 0.0f, 0.0f, // point 7 + 0.0f, 30.0f, 0.0f, // point 8 + 0.0f, 0.0f, 30.0f, // point 9 + 10.0f, 10.0f, 10.0f // point 10 + }; + + size_t number_of_points = points.size() / 3; + std::vector timestamps = + generatePointTimestamps(is_generate_points, stamp, number_of_points); + + std::vector data(number_of_points * pointcloud_msg.point_step); + + for (size_t i = 0; i < number_of_points; ++i) { + std::memcpy(data.data() + i * pointcloud_msg.point_step, &points[i * 3], 3 * sizeof(float)); + std::memcpy( + data.data() + i * pointcloud_msg.point_step + 12, ×tamps[i], sizeof(double)); + } + + pointcloud_msg.width = number_of_points; + pointcloud_msg.row_step = pointcloud_msg.point_step * pointcloud_msg.width; + pointcloud_msg.data = std::move(data); + } else { + pointcloud_msg.width = 0; + pointcloud_msg.row_step = 0; + } + + sensor_msgs::msg::PointField x_field; + x_field.name = "x"; + x_field.offset = 0; + x_field.datatype = sensor_msgs::msg::PointField::FLOAT32; + x_field.count = 1; + + sensor_msgs::msg::PointField y_field; + y_field.name = "y"; + y_field.offset = 4; + y_field.datatype = sensor_msgs::msg::PointField::FLOAT32; + y_field.count = 1; + + sensor_msgs::msg::PointField z_field; + z_field.name = "z"; + z_field.offset = 8; + z_field.datatype = sensor_msgs::msg::PointField::FLOAT32; + z_field.count = 1; + + sensor_msgs::msg::PointField timestamp_field; + timestamp_field.name = "time_stamp"; + timestamp_field.offset = 12; + timestamp_field.datatype = sensor_msgs::msg::PointField::FLOAT64; + timestamp_field.count = 1; + + pointcloud_msg.fields = {x_field, y_field, z_field, timestamp_field}; + + return pointcloud_msg; + } + + std::vector generatePointTimestamps( + bool is_generate_points, rclcpp::Time pointcloud_timestamp, size_t number_of_points) + { + std::vector timestamps; + if (is_generate_points) { + rclcpp::Time point_stamp = pointcloud_timestamp; + for (size_t i = 0; i < number_of_points; ++i) { + double timestamp = point_stamp.seconds(); + timestamps.push_back(timestamp); + if (i > 0) { + point_stamp = point_stamp + rclcpp::Duration::from_seconds( + 0.001); // Assuming 1ms offset for demonstration + } + } + } + return timestamps; + } + + std::shared_ptr node_; + std::shared_ptr distortion_corrector_2d_; + std::shared_ptr distortion_corrector_3d_; + std::shared_ptr tf_broadcaster_; +}; + +TEST_F(DistortionCorrectorTest, TestProcessTwistMessage) +{ + auto twist_msg = generateTwistMsg(1.0, 0.5, node_->get_clock()->now()); + distortion_corrector_2d_->processTwistMessage(twist_msg); + + ASSERT_FALSE(distortion_corrector_2d_->twist_queue_.empty()); + EXPECT_EQ(distortion_corrector_2d_->twist_queue_.front().twist.linear.x, 1.0); + EXPECT_EQ(distortion_corrector_2d_->twist_queue_.front().twist.angular.z, 0.5); +} + +TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) +{ + auto imu_msg = generateImuMsg(0.5, 0.3, 0.1, node_->get_clock()->now()); + distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); + + ASSERT_FALSE(distortion_corrector_2d_->angular_velocity_queue_.empty()); + EXPECT_NEAR(distortion_corrector_2d_->angular_velocity_queue_.front().vector.z, 0.0443032, 1e-5); +} + +TEST_F(DistortionCorrectorTest, TestIsInputValid) +{ + // input normal pointcloud without twist + sensor_msgs::msg::PointCloud2 pointcloud = + generatePointCloudMsg(true, false, node_->get_clock()->now()); + bool result = distortion_corrector_2d_->isInputValid(pointcloud); + EXPECT_FALSE(result); + + // input normal pointcloud with valid twist + auto twist_msg = generateTwistMsg(1.0, 0.5, node_->get_clock()->now()); + distortion_corrector_2d_->processTwistMessage(twist_msg); + + pointcloud = generatePointCloudMsg(true, false, node_->get_clock()->now()); + result = distortion_corrector_2d_->isInputValid(pointcloud); + EXPECT_TRUE(result); + + // input empty pointcloud + pointcloud = generatePointCloudMsg(false, false, node_->get_clock()->now()); + result = distortion_corrector_2d_->isInputValid(pointcloud); + EXPECT_FALSE(result); +} + +TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithBaseLink) +{ + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists_); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed_); +} + +TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithLidarFrame) +{ + distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists_); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_needed_); +} + +TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithMissingFrame) +{ + distortion_corrector_2d_->setPointCloudTransform("base_link", "missing_lidar_frame"); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_exists_); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed_); +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyTwist) +{ + rclcpp::Time timestamp = node_->get_clock()->now(); + // Generate the point cloud message + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Process empty twist queue + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->undistortPointCloud(false, pointcloud); + + // Verify the point cloud is not changed + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + std::vector> expected_pointcloud = { + {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.0f, 0.0f, 10.0f}, {20.0f, 0.0f, 0.0f}, + {0.0f, 20.0f, 0.0f}, {0.0f, 0.0f, 20.0f}, {30.0f, 0.0f, 0.0f}, {0.0f, 30.0f, 0.0f}, + {0.0f, 0.0f, 30.0f}, {10.0f, 10.0f, 10.0f}, + }; + + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 1e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 1e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 1e-5); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyPointCloud) +{ + rclcpp::Time timestamp = node_->get_clock()->now(); + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + // Generate an empty point cloud message + sensor_msgs::msg::PointCloud2 empty_pointcloud = generatePointCloudMsg(false, false, timestamp); + + // Process empty point cloud + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->undistortPointCloud(true, empty_pointcloud); + + // Verify the point cloud is still empty + EXPECT_EQ(empty_pointcloud.width, 0); + EXPECT_EQ(empty_pointcloud.row_step, 0); +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithoutImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp = node_->get_clock()->now(); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + + // Test using only twist + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_2d_->undistortPointCloud(false, pointcloud); + + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + + // Expected undistorted point cloud values + std::vector> expected_pointcloud = { + {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.012002f, 5.75338e-07f, 10.0f}, + {20.024f, 0.00191863f, 0.0f}, {0.0340828f, 20.0f, 0.0f}, {0.0479994f, 4.02654e-06f, 20.0f}, + {30.06f, 0.00575818f, 0.0f}, {0.0662481f, 30.0f, 0.0f}, {0.0839996f, 1.03542e-05f, 30.0f}, + {10.0931f, 10.0029f, 10.0f}, + }; + + // Verify each point in the undistorted point cloud + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp = node_->get_clock()->now(); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_2d_->undistortPointCloud(true, pointcloud); + + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + + // Expected undistorted point cloud values + std::vector> expected_pointcloud = { + {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.0119991f, 5.75201e-07f, 10.0f}, + {20.024f, 0.0019192f, 0.0f}, {0.0321653f, 20.0f, 0.0f}, {0.0479994f, 6.32762e-06f, 20.0f}, + {30.06f, 0.00863842f, 0.0f}, {0.063369f, 30.0f, 0.0f}, {0.0839996f, 1.84079e-05f, 30.0f}, + {10.0912f, 10.0048f, 10.0f}, + }; + + // Verify each point in the undistorted point cloud + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithImuInLidarFrame) +{ + // Generate the point cloud message + rclcpp::Time timestamp = node_->get_clock()->now(); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, true, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); + distortion_corrector_2d_->undistortPointCloud(true, pointcloud); + + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + // Expected undistorted point cloud values + std::vector> expected_pointcloud = { + {10.0f, -1.77636e-15f, -4.44089e-16f}, {-2.66454e-15f, 10.0f, -8.88178e-16f}, + {0.00622853f, 0.00600991f, 10.0084f}, {20.0106f, 0.010948f, 0.0157355f}, + {0.0176543f, 20.0176f, 0.0248379f}, {0.024499f, 0.0245179f, 20.0348f}, + {30.0266f, 0.0255826f, 0.0357166f}, {0.0355204f, 30.0353f, 0.0500275f}, + {0.047132f, 0.0439795f, 30.0606f}, {10.0488f, 10.046f, 10.0636f}, + }; + + // Verify each point in the undistorted point cloud + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithoutImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp = node_->get_clock()->now(); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_3d_->processTwistMessage(twist_msg); + } + + // Test using only twist + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_3d_->undistortPointCloud(false, pointcloud); + + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + + // Expected undistorted point cloud values + std::vector> expected_pointcloud = { + {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.0119991f, 0.0f, 10.0f}, + {20.024f, 0.00120042f, 0.0f}, {0.0342002f, 20.0f, 0.0f}, {0.0479994f, 2.15994e-06f, 20.0f}, + {30.06f, 0.00450349f, 0.0f}, {0.0666005f, 30.0f, 0.0f}, {0.0839996f, 7.55993e-06f, 30.0f}, + {10.0936f, 10.0024f, 10.0f}, + }; + + // Verify each point in the undistorted point cloud + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp = node_->get_clock()->now(); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_3d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_3d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_3d_->undistortPointCloud(true, pointcloud); + + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + + // Expected undistorted point cloud values + std::vector> expected_pointcloud = { + {10.0f, 0.0f, 0.0f}, + {0.0f, 10.0f, 0.0f}, + {0.0118491f, -0.000149993f, 10.0f}, + {20.024f, 0.00220075f, 0.000600241f}, + {0.0327002f, 20.0f, 0.000900472f}, + {0.0468023f, -0.00119623f, 20.0f}, + {30.06f, 0.0082567f, 0.00225216f}, + {0.0621003f, 30.0f, 0.00270227f}, + {0.0808503f, -0.00313673f, 30.0f}, + {10.0904f, 10.0032f, 10.0024f}, + }; + + // Verify each point in the undistorted point cloud + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithImuInLidarFrame) +{ + // Generate the point cloud message + rclcpp::Time timestamp = node_->get_clock()->now(); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, true, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_3d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_3d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "lidar_top"); + distortion_corrector_3d_->undistortPointCloud(true, pointcloud); + + const float * data_ptr = reinterpret_cast(pointcloud.data.data()); + // Expected undistorted point cloud values + std::vector> expected_pointcloud = { + {10.0f, 0.0f, 0.0f}, + {-4.76837e-07f, 10.0f, 4.76837e-07f}, + {0.00572586f, 0.00616837f, 10.0086f}, + {20.0103f, 0.0117249f, 0.0149349f}, + {0.0158343f, 20.0179f, 0.024497f}, + {0.0251098f, 0.0254798f, 20.0343f}, + {30.0259f, 0.0290527f, 0.034577f}, + {0.0319824f, 30.0358f, 0.0477753f}, + {0.0478067f, 0.0460052f, 30.06f}, + {10.0462f, 10.0489f, 10.0625f}, + }; + + // Verify each point in the undistorted point cloud + for (size_t i = 0; i < expected_pointcloud.size(); ++i) { + EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); + EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); + } +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int ret = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return ret; +} diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py deleted file mode 100644 index 35eb41f9dbc17..0000000000000 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_use_imu_false.py +++ /dev/null @@ -1,240 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import unittest - -from geometry_msgs.msg import TwistWithCovarianceStamped -import launch -from launch.logging import get_logger -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode -import launch_testing -import numpy as np -import pytest -import rclpy -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSHistoryPolicy -from rclpy.qos import QoSProfile -from rclpy.qos import QoSReliabilityPolicy -from sensor_msgs.msg import PointCloud2 -from sensor_msgs.msg import PointField -from std_msgs.msg import Header - -logger = get_logger(__name__) - - -@pytest.mark.launch_test -def generate_test_description(): - nodes = [] - - nodes.append( - ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DistortionCorrectorComponent", - name="distortion_corrector_node", - parameters=[ - { - "base_frame": "base_link", - "use_imu": False, - "use_3d_distortion_correction": False, - }, - ], - remappings=[ - ("~/input/twist", "/test/sensing/vehicle_velocity_converter/twist_with_covariance"), - ("~/input/imu", "/test/sensing/imu/imu_data"), - ("~/input/pointcloud", "/test/sensing/lidar/top/mirror_cropped/pointcloud_ex"), - ("~/output/pointcloud", "/test/sensing/lidar/top/rectified/pointcloud_ex"), - ], - extra_arguments=[{"use_intra_process_comms": True}], - ) - ) - - container = ComposableNodeContainer( - name="test_distortion_corrector_container", - namespace="pointcloud_preprocessor", - package="rclcpp_components", - executable="component_container", - composable_node_descriptions=nodes, - output="screen", - ) - - return launch.LaunchDescription( - [ - container, - # Start tests right away - no need to wait for anything - launch_testing.actions.ReadyToTest(), - ] - ) - - -class TestDistortionCorrector(unittest.TestCase): - @classmethod - def setUpClass(cls): - # Initialize the ROS context for the test node - rclpy.init() - - @classmethod - def tearDownClass(cls): - # Shutdown the ROS context - rclpy.shutdown() - - def setUp(self): - # Create a ROS node for tests - self.test_node = rclpy.create_node("test_node") - self.evaluation_time = 2 # 200ms - - def tearDown(self): - self.test_node.destroy_node() - - @staticmethod - def print_message(stat): - logger.debug("===========================") - logger.debug(stat) - - @staticmethod - def pointcloud2_to_xyz_array(cloud_msg): - cloud_arr = np.frombuffer(cloud_msg.data, dtype=np.float32) - cloud_arr = np.reshape(cloud_arr, (cloud_msg.width, int(cloud_msg.point_step / 4))) - return cloud_arr[:, :3] - - @staticmethod - def generate_pointcloud(num_points, header, timestamp_offset_per_point=0.01): - points_xyz = np.random.rand(num_points, 3).astype(np.float32) - timestamps = np.array( - [ - header.stamp.sec + header.stamp.nanosec * 1e-9 + timestamp_offset_per_point * i - for i in range(num_points) - ] - ).astype(np.float64) - xyz_data = points_xyz.tobytes() - timestamp_data = timestamps.tobytes() - pointcloud_data = b"".join( - xyz_data[i * 12 : i * 12 + 12] + timestamp_data[i * 8 : i * 8 + 8] - for i in range(len(xyz_data)) - ) - fields = [ - PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), - PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), - PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), - PointField(name="time_stamp", offset=12, datatype=PointField.FLOAT64, count=1), - ] - pointcloud_msg = PointCloud2( - header=header, - height=1, - width=10, - is_dense=True, - is_bigendian=False, - point_step=20, # 4 float32 fields * 4 bytes/field - row_step=20 * num_points, # point_step * width - fields=fields, - data=pointcloud_data, - ) - return pointcloud_msg - - def test_node_link(self): - # QoS profile for sensor data - sensor_qos = QoSProfile( - history=QoSHistoryPolicy.KEEP_LAST, - depth=10, - reliability=QoSReliabilityPolicy.BEST_EFFORT, - durability=QoSDurabilityPolicy.VOLATILE, - ) - - # Publishers - velocity_pub = self.test_node.create_publisher( - TwistWithCovarianceStamped, - "/test/sensing/vehicle_velocity_converter/twist_with_covariance", - 10, - ) - pointcloud_pub = self.test_node.create_publisher( - PointCloud2, - "/test/sensing/lidar/top/mirror_cropped/pointcloud_ex", - qos_profile=sensor_qos, - ) - - # Subscribers - received_data = {"msg": None} - - def pointcloud_callback(msg): - received_data["msg"] = msg - - self.test_node.create_subscription( - PointCloud2, - "/test/sensing/lidar/top/rectified/pointcloud_ex", - pointcloud_callback, - qos_profile=sensor_qos, - ) - - # Wait for composable node launches - rclpy.spin_once(self.test_node, timeout_sec=1.0) - - # Prepare header - header = Header() - header.stamp = self.test_node.get_clock().now().to_msg() - header.frame_id = "base_link" - - # Publish velocity data - for i in range(50): - header_tmp = Header() - header_tmp.stamp = self.test_node.get_clock().now().to_msg() - header_tmp.frame_id = "base_link" - - velocity_msg = TwistWithCovarianceStamped() - velocity_msg.header = header_tmp - velocity_msg.twist.twist.linear.x = 1.0 - - velocity_pub.publish(velocity_msg) - rclpy.spin_once(self.test_node, timeout_sec=0.01) - - # Publish pointcloud data - num_points = 10 - pointcloud_msg = self.generate_pointcloud(num_points, header) - pointcloud_pub.publish(pointcloud_msg) - - # Wait for output with a timeout - start_time = self.test_node.get_clock().now() - while self.test_node.get_clock().now() - start_time < rclpy.duration.Duration( - seconds=self.evaluation_time - ): - rclpy.spin_once(self.test_node, timeout_sec=0.1) - if received_data["msg"] is not None: - break - - # Check if the output was received - self.assertIsNotNone(received_data["msg"], "Did not receive output pointcloud data") - - # Check that the received pointcloud data has same length as num_points - received_pointcloud = received_data["msg"] - self.assertEqual( - received_pointcloud.width, - num_points, - "The received pointcloud data has a different length than expected", - ) - - # Check that the received pointcloud data is different from the original one - original_pointcloud_arr = self.pointcloud2_to_xyz_array(pointcloud_msg) - received_pointcloud_arr = self.pointcloud2_to_xyz_array(received_pointcloud) - self.assertFalse( - np.allclose(original_pointcloud_arr, received_pointcloud_arr, atol=1e-6), - "The received pointcloud data is not different from the original one", - ) - - -@launch_testing.post_shutdown_test() -class TestProcessOutput(unittest.TestCase): - def test_exit_code(self, proc_info): - # Check that process exits with code 0: no error - launch_testing.asserts.assertExitCodes(proc_info) From 416609f585f73d0eb8acacefc5fbdcd25d030553 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Mon, 8 Jul 2024 08:10:59 +0900 Subject: [PATCH 139/151] fix(pointcloud_preprocessor): temporarily remove distortion corrector unit test (#7879) fix: temporarily remove distortion corretor unit test Signed-off-by: vividf --- .../pointcloud_preprocessor/CMakeLists.txt | 4 - .../test/test_distortion_corrector_node.cpp | 600 ------------------ 2 files changed, 604 deletions(-) delete mode 100644 sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index 2d0649fe43954..53b6aae55d47b 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -231,12 +231,8 @@ if(BUILD_TESTING) ament_add_gtest(test_utilities test/test_utilities.cpp ) - ament_add_gtest(distortion_corrector_node_tests - test/test_distortion_corrector_node.cpp - ) target_link_libraries(test_utilities pointcloud_preprocessor_filter) - target_link_libraries(distortion_corrector_node_tests pointcloud_preprocessor_filter) endif() diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp deleted file mode 100644 index 9e5d068be52f5..0000000000000 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ /dev/null @@ -1,600 +0,0 @@ -// Copyright 2024 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" - -#include - -#include -#include -#include -#include - -#include -#include - -class DistortionCorrectorTest : public ::testing::Test -{ -protected: - void SetUp() override - { - node_ = std::make_shared("test_node"); - distortion_corrector_2d_ = - std::make_shared(node_.get()); - distortion_corrector_3d_ = - std::make_shared(node_.get()); - - // Setup TF - tf_broadcaster_ = std::make_shared(node_); - tf_broadcaster_->sendTransform(generateStaticTransformMsg()); - - // Spin the node for a while to ensure transforms are published - auto start = std::chrono::steady_clock::now(); - auto timeout = std::chrono::seconds(1); - while (std::chrono::steady_clock::now() - start < timeout) { - rclcpp::spin_some(node_); - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - } - - void TearDown() override {} - - rclcpp::Time addMilliseconds(rclcpp::Time stamp, int ms) - { - auto ms_in_ns = rclcpp::Duration(0, ms * 1000000); - return stamp + ms_in_ns; - } - - rclcpp::Time subtractMilliseconds(rclcpp::Time stamp, int ms) - { - auto ms_in_ns = rclcpp::Duration(0, ms * 1000000); - return stamp - ms_in_ns; - } - - geometry_msgs::msg::TransformStamped generateTransformMsg( - const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, - double qx, double qy, double qz, double qw) - { - geometry_msgs::msg::TransformStamped tf_msg; - tf_msg.header.stamp = node_->get_clock()->now(); - tf_msg.header.frame_id = parent_frame; - tf_msg.child_frame_id = child_frame; - tf_msg.transform.translation.x = x; - tf_msg.transform.translation.y = y; - tf_msg.transform.translation.z = z; - tf_msg.transform.rotation.x = qx; - tf_msg.transform.rotation.y = qy; - tf_msg.transform.rotation.z = qz; - tf_msg.transform.rotation.w = qw; - return tf_msg; - } - - std::vector generateStaticTransformMsg() - { - return { - generateTransformMsg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), - generateTransformMsg("base_link", "imu_link", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; - } - - std::shared_ptr generateTwistMsg( - double linear_x, double angular_z, rclcpp::Time stamp) - { - auto twist_msg = std::make_shared(); - twist_msg->header.stamp = stamp; - twist_msg->header.frame_id = "base_link"; - twist_msg->twist.twist.linear.x = linear_x; - twist_msg->twist.twist.angular.z = angular_z; - return twist_msg; - } - - std::shared_ptr generateImuMsg( - double angular_vel_x, double angular_vel_y, double angular_vel_z, rclcpp::Time stamp) - { - auto imu_msg = std::make_shared(); - imu_msg->header.stamp = stamp; - imu_msg->header.frame_id = "imu_link"; - imu_msg->angular_velocity.x = angular_vel_x; - imu_msg->angular_velocity.y = angular_vel_y; - imu_msg->angular_velocity.z = angular_vel_z; - return imu_msg; - } - - std::vector> generateTwistMsgs( - rclcpp::Time pointcloud_timestamp) - { - std::vector> twist_msgs; - rclcpp::Time twist_stamp = subtractMilliseconds(pointcloud_timestamp, 5); - - for (int i = 0; i < 6; ++i) { - auto twist_msg = generateTwistMsg(10.0 + i * 2, 0.02 + i * 0.01, twist_stamp); - twist_msgs.push_back(twist_msg); - // Make sure the twist stamp is not identical to any point stamp, and imu stamp - twist_stamp = addMilliseconds(twist_stamp, 24); - } - - return twist_msgs; - } - - std::vector> generateImuMsgs( - rclcpp::Time pointcloud_timestamp) - { - std::vector> imu_msgs; - rclcpp::Time imu_stamp = subtractMilliseconds(pointcloud_timestamp, 10); - - for (int i = 0; i < 6; ++i) { - auto imu_msg = - generateImuMsg(0.01 + i * 0.005, -0.02 + i * 0.005, 0.05 + i * 0.005, imu_stamp); - imu_msgs.push_back(imu_msg); - // Make sure the imu stamp is not identical to any point stamp, and twist stamp - imu_stamp = addMilliseconds(imu_stamp, 27); - } - - return imu_msgs; - } - - sensor_msgs::msg::PointCloud2 generatePointCloudMsg( - bool is_generate_points, bool is_lidar_frame, rclcpp::Time stamp) - { - sensor_msgs::msg::PointCloud2 pointcloud_msg; - pointcloud_msg.header.stamp = stamp; - pointcloud_msg.header.frame_id = is_lidar_frame ? "lidar_top" : "base_link"; - pointcloud_msg.height = 1; - pointcloud_msg.is_dense = true; - pointcloud_msg.is_bigendian = false; - pointcloud_msg.point_step = - 20; // 3 float32 fields * 4 bytes/field + 1 float64 field * 8 bytes/field - - if (is_generate_points) { - std::vector points = { - 10.0f, 0.0f, 0.0f, // point 1 - 0.0f, 10.0f, 0.0f, // point 2 - 0.0f, 0.0f, 10.0f, // point 3 - 20.0f, 0.0f, 0.0f, // point 4 - 0.0f, 20.0f, 0.0f, // point 5 - 0.0f, 0.0f, 20.0f, // point 6 - 30.0f, 0.0f, 0.0f, // point 7 - 0.0f, 30.0f, 0.0f, // point 8 - 0.0f, 0.0f, 30.0f, // point 9 - 10.0f, 10.0f, 10.0f // point 10 - }; - - size_t number_of_points = points.size() / 3; - std::vector timestamps = - generatePointTimestamps(is_generate_points, stamp, number_of_points); - - std::vector data(number_of_points * pointcloud_msg.point_step); - - for (size_t i = 0; i < number_of_points; ++i) { - std::memcpy(data.data() + i * pointcloud_msg.point_step, &points[i * 3], 3 * sizeof(float)); - std::memcpy( - data.data() + i * pointcloud_msg.point_step + 12, ×tamps[i], sizeof(double)); - } - - pointcloud_msg.width = number_of_points; - pointcloud_msg.row_step = pointcloud_msg.point_step * pointcloud_msg.width; - pointcloud_msg.data = std::move(data); - } else { - pointcloud_msg.width = 0; - pointcloud_msg.row_step = 0; - } - - sensor_msgs::msg::PointField x_field; - x_field.name = "x"; - x_field.offset = 0; - x_field.datatype = sensor_msgs::msg::PointField::FLOAT32; - x_field.count = 1; - - sensor_msgs::msg::PointField y_field; - y_field.name = "y"; - y_field.offset = 4; - y_field.datatype = sensor_msgs::msg::PointField::FLOAT32; - y_field.count = 1; - - sensor_msgs::msg::PointField z_field; - z_field.name = "z"; - z_field.offset = 8; - z_field.datatype = sensor_msgs::msg::PointField::FLOAT32; - z_field.count = 1; - - sensor_msgs::msg::PointField timestamp_field; - timestamp_field.name = "time_stamp"; - timestamp_field.offset = 12; - timestamp_field.datatype = sensor_msgs::msg::PointField::FLOAT64; - timestamp_field.count = 1; - - pointcloud_msg.fields = {x_field, y_field, z_field, timestamp_field}; - - return pointcloud_msg; - } - - std::vector generatePointTimestamps( - bool is_generate_points, rclcpp::Time pointcloud_timestamp, size_t number_of_points) - { - std::vector timestamps; - if (is_generate_points) { - rclcpp::Time point_stamp = pointcloud_timestamp; - for (size_t i = 0; i < number_of_points; ++i) { - double timestamp = point_stamp.seconds(); - timestamps.push_back(timestamp); - if (i > 0) { - point_stamp = point_stamp + rclcpp::Duration::from_seconds( - 0.001); // Assuming 1ms offset for demonstration - } - } - } - return timestamps; - } - - std::shared_ptr node_; - std::shared_ptr distortion_corrector_2d_; - std::shared_ptr distortion_corrector_3d_; - std::shared_ptr tf_broadcaster_; -}; - -TEST_F(DistortionCorrectorTest, TestProcessTwistMessage) -{ - auto twist_msg = generateTwistMsg(1.0, 0.5, node_->get_clock()->now()); - distortion_corrector_2d_->processTwistMessage(twist_msg); - - ASSERT_FALSE(distortion_corrector_2d_->twist_queue_.empty()); - EXPECT_EQ(distortion_corrector_2d_->twist_queue_.front().twist.linear.x, 1.0); - EXPECT_EQ(distortion_corrector_2d_->twist_queue_.front().twist.angular.z, 0.5); -} - -TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) -{ - auto imu_msg = generateImuMsg(0.5, 0.3, 0.1, node_->get_clock()->now()); - distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); - - ASSERT_FALSE(distortion_corrector_2d_->angular_velocity_queue_.empty()); - EXPECT_NEAR(distortion_corrector_2d_->angular_velocity_queue_.front().vector.z, 0.0443032, 1e-5); -} - -TEST_F(DistortionCorrectorTest, TestIsInputValid) -{ - // input normal pointcloud without twist - sensor_msgs::msg::PointCloud2 pointcloud = - generatePointCloudMsg(true, false, node_->get_clock()->now()); - bool result = distortion_corrector_2d_->isInputValid(pointcloud); - EXPECT_FALSE(result); - - // input normal pointcloud with valid twist - auto twist_msg = generateTwistMsg(1.0, 0.5, node_->get_clock()->now()); - distortion_corrector_2d_->processTwistMessage(twist_msg); - - pointcloud = generatePointCloudMsg(true, false, node_->get_clock()->now()); - result = distortion_corrector_2d_->isInputValid(pointcloud); - EXPECT_TRUE(result); - - // input empty pointcloud - pointcloud = generatePointCloudMsg(false, false, node_->get_clock()->now()); - result = distortion_corrector_2d_->isInputValid(pointcloud); - EXPECT_FALSE(result); -} - -TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithBaseLink) -{ - distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); - EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists_); - EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed_); -} - -TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithLidarFrame) -{ - distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); - EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists_); - EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_needed_); -} - -TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithMissingFrame) -{ - distortion_corrector_2d_->setPointCloudTransform("base_link", "missing_lidar_frame"); - EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_exists_); - EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed_); -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyTwist) -{ - rclcpp::Time timestamp = node_->get_clock()->now(); - // Generate the point cloud message - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); - - // Process empty twist queue - distortion_corrector_2d_->initialize(); - distortion_corrector_2d_->undistortPointCloud(false, pointcloud); - - // Verify the point cloud is not changed - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - std::vector> expected_pointcloud = { - {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.0f, 0.0f, 10.0f}, {20.0f, 0.0f, 0.0f}, - {0.0f, 20.0f, 0.0f}, {0.0f, 0.0f, 20.0f}, {30.0f, 0.0f, 0.0f}, {0.0f, 30.0f, 0.0f}, - {0.0f, 0.0f, 30.0f}, {10.0f, 10.0f, 10.0f}, - }; - - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 1e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 1e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 1e-5); - } -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyPointCloud) -{ - rclcpp::Time timestamp = node_->get_clock()->now(); - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_2d_->processTwistMessage(twist_msg); - } - // Generate an empty point cloud message - sensor_msgs::msg::PointCloud2 empty_pointcloud = generatePointCloudMsg(false, false, timestamp); - - // Process empty point cloud - distortion_corrector_2d_->initialize(); - distortion_corrector_2d_->undistortPointCloud(true, empty_pointcloud); - - // Verify the point cloud is still empty - EXPECT_EQ(empty_pointcloud.width, 0); - EXPECT_EQ(empty_pointcloud.row_step, 0); -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithoutImuInBaseLink) -{ - // Generate the point cloud message - rclcpp::Time timestamp = node_->get_clock()->now(); - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); - - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_2d_->processTwistMessage(twist_msg); - } - - // Test using only twist - distortion_corrector_2d_->initialize(); - distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); - distortion_corrector_2d_->undistortPointCloud(false, pointcloud); - - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - - // Expected undistorted point cloud values - std::vector> expected_pointcloud = { - {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.012002f, 5.75338e-07f, 10.0f}, - {20.024f, 0.00191863f, 0.0f}, {0.0340828f, 20.0f, 0.0f}, {0.0479994f, 4.02654e-06f, 20.0f}, - {30.06f, 0.00575818f, 0.0f}, {0.0662481f, 30.0f, 0.0f}, {0.0839996f, 1.03542e-05f, 30.0f}, - {10.0931f, 10.0029f, 10.0f}, - }; - - // Verify each point in the undistorted point cloud - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); - } -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithImuInBaseLink) -{ - // Generate the point cloud message - rclcpp::Time timestamp = node_->get_clock()->now(); - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); - - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_2d_->processTwistMessage(twist_msg); - } - - // Generate and process multiple IMU messages - auto imu_msgs = generateImuMsgs(timestamp); - for (const auto & imu_msg : imu_msgs) { - distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); - } - - distortion_corrector_2d_->initialize(); - distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); - distortion_corrector_2d_->undistortPointCloud(true, pointcloud); - - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - - // Expected undistorted point cloud values - std::vector> expected_pointcloud = { - {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.0119991f, 5.75201e-07f, 10.0f}, - {20.024f, 0.0019192f, 0.0f}, {0.0321653f, 20.0f, 0.0f}, {0.0479994f, 6.32762e-06f, 20.0f}, - {30.06f, 0.00863842f, 0.0f}, {0.063369f, 30.0f, 0.0f}, {0.0839996f, 1.84079e-05f, 30.0f}, - {10.0912f, 10.0048f, 10.0f}, - }; - - // Verify each point in the undistorted point cloud - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); - } -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithImuInLidarFrame) -{ - // Generate the point cloud message - rclcpp::Time timestamp = node_->get_clock()->now(); - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, true, timestamp); - - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_2d_->processTwistMessage(twist_msg); - } - - // Generate and process multiple IMU messages - auto imu_msgs = generateImuMsgs(timestamp); - for (const auto & imu_msg : imu_msgs) { - distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); - } - - distortion_corrector_2d_->initialize(); - distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); - distortion_corrector_2d_->undistortPointCloud(true, pointcloud); - - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - // Expected undistorted point cloud values - std::vector> expected_pointcloud = { - {10.0f, -1.77636e-15f, -4.44089e-16f}, {-2.66454e-15f, 10.0f, -8.88178e-16f}, - {0.00622853f, 0.00600991f, 10.0084f}, {20.0106f, 0.010948f, 0.0157355f}, - {0.0176543f, 20.0176f, 0.0248379f}, {0.024499f, 0.0245179f, 20.0348f}, - {30.0266f, 0.0255826f, 0.0357166f}, {0.0355204f, 30.0353f, 0.0500275f}, - {0.047132f, 0.0439795f, 30.0606f}, {10.0488f, 10.046f, 10.0636f}, - }; - - // Verify each point in the undistorted point cloud - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); - } -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithoutImuInBaseLink) -{ - // Generate the point cloud message - rclcpp::Time timestamp = node_->get_clock()->now(); - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); - - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_3d_->processTwistMessage(twist_msg); - } - - // Test using only twist - distortion_corrector_3d_->initialize(); - distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); - distortion_corrector_3d_->undistortPointCloud(false, pointcloud); - - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - - // Expected undistorted point cloud values - std::vector> expected_pointcloud = { - {10.0f, 0.0f, 0.0f}, {0.0f, 10.0f, 0.0f}, {0.0119991f, 0.0f, 10.0f}, - {20.024f, 0.00120042f, 0.0f}, {0.0342002f, 20.0f, 0.0f}, {0.0479994f, 2.15994e-06f, 20.0f}, - {30.06f, 0.00450349f, 0.0f}, {0.0666005f, 30.0f, 0.0f}, {0.0839996f, 7.55993e-06f, 30.0f}, - {10.0936f, 10.0024f, 10.0f}, - }; - - // Verify each point in the undistorted point cloud - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); - } -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithImuInBaseLink) -{ - // Generate the point cloud message - rclcpp::Time timestamp = node_->get_clock()->now(); - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); - - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_3d_->processTwistMessage(twist_msg); - } - - // Generate and process multiple IMU messages - auto imu_msgs = generateImuMsgs(timestamp); - for (const auto & imu_msg : imu_msgs) { - distortion_corrector_3d_->processIMUMessage("base_link", imu_msg); - } - - distortion_corrector_3d_->initialize(); - distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); - distortion_corrector_3d_->undistortPointCloud(true, pointcloud); - - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - - // Expected undistorted point cloud values - std::vector> expected_pointcloud = { - {10.0f, 0.0f, 0.0f}, - {0.0f, 10.0f, 0.0f}, - {0.0118491f, -0.000149993f, 10.0f}, - {20.024f, 0.00220075f, 0.000600241f}, - {0.0327002f, 20.0f, 0.000900472f}, - {0.0468023f, -0.00119623f, 20.0f}, - {30.06f, 0.0082567f, 0.00225216f}, - {0.0621003f, 30.0f, 0.00270227f}, - {0.0808503f, -0.00313673f, 30.0f}, - {10.0904f, 10.0032f, 10.0024f}, - }; - - // Verify each point in the undistorted point cloud - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); - } -} - -TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithImuInLidarFrame) -{ - // Generate the point cloud message - rclcpp::Time timestamp = node_->get_clock()->now(); - sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, true, timestamp); - - // Generate and process multiple twist messages - auto twist_msgs = generateTwistMsgs(timestamp); - for (const auto & twist_msg : twist_msgs) { - distortion_corrector_3d_->processTwistMessage(twist_msg); - } - - // Generate and process multiple IMU messages - auto imu_msgs = generateImuMsgs(timestamp); - for (const auto & imu_msg : imu_msgs) { - distortion_corrector_3d_->processIMUMessage("base_link", imu_msg); - } - - distortion_corrector_3d_->initialize(); - distortion_corrector_3d_->setPointCloudTransform("base_link", "lidar_top"); - distortion_corrector_3d_->undistortPointCloud(true, pointcloud); - - const float * data_ptr = reinterpret_cast(pointcloud.data.data()); - // Expected undistorted point cloud values - std::vector> expected_pointcloud = { - {10.0f, 0.0f, 0.0f}, - {-4.76837e-07f, 10.0f, 4.76837e-07f}, - {0.00572586f, 0.00616837f, 10.0086f}, - {20.0103f, 0.0117249f, 0.0149349f}, - {0.0158343f, 20.0179f, 0.024497f}, - {0.0251098f, 0.0254798f, 20.0343f}, - {30.0259f, 0.0290527f, 0.034577f}, - {0.0319824f, 30.0358f, 0.0477753f}, - {0.0478067f, 0.0460052f, 30.06f}, - {10.0462f, 10.0489f, 10.0625f}, - }; - - // Verify each point in the undistorted point cloud - for (size_t i = 0; i < expected_pointcloud.size(); ++i) { - EXPECT_NEAR(data_ptr[i * 5], expected_pointcloud[i][0], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 1], expected_pointcloud[i][1], 5e-5); - EXPECT_NEAR(data_ptr[i * 5 + 2], expected_pointcloud[i][2], 5e-5); - } -} - -int main(int argc, char ** argv) -{ - ::testing::InitGoogleTest(&argc, argv); - rclcpp::init(argc, argv); - int ret = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return ret; -} From 0c152ff63e8b1f914e118cc1d46bf92b8e1b07e8 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Tue, 9 Jul 2024 21:02:02 +0900 Subject: [PATCH 140/151] fix(pointcloud_preprocessor): fix distortion corrector unit test (#7833) * fix: use pointcloud iterator instead of memcpy, remove reinterpret cast Signed-off-by: vividf * chore: set default debugging parameter to false Signed-off-by: vividf * style(pre-commit): autofix * chore: run precommit Signed-off-by: vividf * chore: fix TIER IV name Signed-off-by: vividf * chore: changed public variables to protected and add getters Signed-off-by: vividf * chore: add tolerance Signed-off-by: vividf * feat: add two tests for pure linear and rotation Signed-off-by: vividf * chore: change naming, fix tolerance value Signed-off-by: vividf * chore: add comment for quat Signed-off-by: vividf * fix: remove node_->get_clock() and use self-defined timestamp Signed-off-by: vividf * chore: remove redundant parameters Signed-off-by: vividf * chore: fix spell error and add tests in cmake Signed-off-by: vividf * chore: move all clock->now() to self-defined time Signed-off-by: vividf * chore: change function names Signed-off-by: vividf * chore: remove irrelevant variable Signed-off-by: vividf * chore: fix variables naming Signed-off-by: vividf * chore: change boolen naming: generate_points Signed-off-by: vividf * chore: add assert to make sure ms is not larger than a second Signed-off-by: vividf * chore: add note Signed-off-by: vividf * chore: add unifore initialization and semantic meaning for magic number Signed-off-by: vividf * chore: change vector to Eigen Signed-off-by: vividf * chore: fix explanation Signed-off-by: vividf * chore: fix more eigen Signed-off-by: vividf * chore: fix more magic numbers Signed-off-by: vividf * chore: add unit Signed-off-by: vividf * fix: use assert from gtest Signed-off-by: vividf --------- Signed-off-by: vividf Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa --- .../pointcloud_preprocessor/CMakeLists.txt | 4 + .../distortion_corrector.hpp | 9 + .../distortion_corrector.cpp | 29 +- .../test/test_distortion_corrector_node.cpp | 904 ++++++++++++++++++ 4 files changed, 945 insertions(+), 1 deletion(-) create mode 100644 sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index 53b6aae55d47b..2d0649fe43954 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -231,8 +231,12 @@ if(BUILD_TESTING) ament_add_gtest(test_utilities test/test_utilities.cpp ) + ament_add_gtest(distortion_corrector_node_tests + test/test_distortion_corrector_node.cpp + ) target_link_libraries(test_utilities pointcloud_preprocessor_filter) + target_link_libraries(distortion_corrector_node_tests pointcloud_preprocessor_filter) endif() diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 8a7b7c90113da..e37329a9a4cc3 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -48,6 +48,11 @@ namespace pointcloud_preprocessor class DistortionCorrectorBase { public: + virtual bool pointcloud_transform_exists() = 0; + virtual bool pointcloud_transform_needed() = 0; + virtual std::deque get_twist_queue() = 0; + virtual std::deque get_angular_velocity_queue() = 0; + virtual void processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) = 0; virtual void processIMUMessage( @@ -96,6 +101,10 @@ class DistortionCorrector : public DistortionCorrectorBase : node_(node), tf_buffer_(node_->get_clock()), tf_listener_(tf_buffer_) { } + bool pointcloud_transform_exists(); + bool pointcloud_transform_needed(); + std::deque get_twist_queue(); + std::deque get_angular_velocity_queue(); void processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) override; diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 8c8752c7e278e..f933d4c6f75d9 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -20,6 +20,31 @@ namespace pointcloud_preprocessor { + +template +bool DistortionCorrector::pointcloud_transform_exists() +{ + return pointcloud_transform_exists_; +} + +template +bool DistortionCorrector::pointcloud_transform_needed() +{ + return pointcloud_transform_needed_; +} + +template +std::deque DistortionCorrector::get_twist_queue() +{ + return twist_queue_; +} + +template +std::deque DistortionCorrector::get_angular_velocity_queue() +{ + return angular_velocity_queue_; +} + template void DistortionCorrector::processTwistMessage( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr twist_msg) @@ -349,7 +374,9 @@ inline void DistortionCorrector2D::undistortPointImplementation( theta_ += w * time_offset; baselink_quat_.setValue( 0, 0, autoware::universe_utils::sin(theta_ * 0.5f), - autoware::universe_utils::cos(theta_ * 0.5f)); // baselink_quat.setRPY(0.0, 0.0, theta); + autoware::universe_utils::cos( + theta_ * + 0.5f)); // baselink_quat.setRPY(0.0, 0.0, theta); (Note that the value is slightly different) const float dis = v * time_offset; x_ += dis * autoware::universe_utils::cos(theta_); y_ += dis * autoware::universe_utils::sin(theta_); diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp new file mode 100644 index 0000000000000..7997aaf43c202 --- /dev/null +++ b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -0,0 +1,904 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// Note: To regenerate the ground truth (GT) for the expected undistorted point cloud values, +// set the "debug_" value to true to display the point cloud values. Then, +// replace the expected values with the newly displayed undistorted point cloud values. +// +// Also, make sure the point stamp, twist stamp, and imu stamp are not identical. +// In the current hardcoded design, timestamp of pointcloud, twist, and imu msg are listed below +// pointcloud (1 msgs, 10points): +// 10.10, 10.11, 10.12, 10.13, 10.14, 10.15, 10.16, 10.17, 10.18, 10.19 +// twist (6msgs): +// 10.095, 10.119, 10.143, 10.167, 10.191, 10.215 +// imu (6msgs): +// 10.09, 10.117, 10.144, 10.171, 10.198, 10.225 + +#include "autoware/universe_utils/math/trigonometry.hpp" +#include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include + +class DistortionCorrectorTest : public ::testing::Test +{ +protected: + void SetUp() override + { + node_ = std::make_shared("test_node"); + distortion_corrector_2d_ = + std::make_shared(node_.get()); + distortion_corrector_3d_ = + std::make_shared(node_.get()); + + // Setup TF + tf_broadcaster_ = std::make_shared(node_); + tf_broadcaster_->sendTransform(generateStaticTransformMsg()); + + // Spin the node for a while to ensure transforms are published + auto start = std::chrono::steady_clock::now(); + auto timeout = std::chrono::seconds(1); + while (std::chrono::steady_clock::now() - start < timeout) { + rclcpp::spin_some(node_); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + + void TearDown() override {} + + void checkInput(int ms) { ASSERT_LT(ms, 1000) << "ms should be less than a second."; } + + rclcpp::Time addMilliseconds(rclcpp::Time stamp, int ms) + { + checkInput(ms); + auto ms_in_ns = rclcpp::Duration(0, ms * 1000000); + return stamp + ms_in_ns; + } + + rclcpp::Time subtractMilliseconds(rclcpp::Time stamp, int ms) + { + checkInput(ms); + auto ms_in_ns = rclcpp::Duration(0, ms * 1000000); + return stamp - ms_in_ns; + } + + geometry_msgs::msg::TransformStamped generateTransformMsg( + const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, + double qx, double qy, double qz, double qw) + { + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + geometry_msgs::msg::TransformStamped tf_msg; + tf_msg.header.stamp = timestamp; + tf_msg.header.frame_id = parent_frame; + tf_msg.child_frame_id = child_frame; + tf_msg.transform.translation.x = x; + tf_msg.transform.translation.y = y; + tf_msg.transform.translation.z = z; + tf_msg.transform.rotation.x = qx; + tf_msg.transform.rotation.y = qy; + tf_msg.transform.rotation.z = qz; + tf_msg.transform.rotation.w = qw; + return tf_msg; + } + + std::vector generateStaticTransformMsg() + { + // generate defined transformations + return { + generateTransformMsg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), + generateTransformMsg("base_link", "imu_link", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; + } + + std::shared_ptr generateTwistMsg( + double linear_x, double angular_z, rclcpp::Time stamp) + { + auto twist_msg = std::make_shared(); + twist_msg->header.stamp = stamp; + twist_msg->header.frame_id = "base_link"; + twist_msg->twist.twist.linear.x = linear_x; + twist_msg->twist.twist.angular.z = angular_z; + return twist_msg; + } + + std::shared_ptr generateImuMsg( + double angular_vel_x, double angular_vel_y, double angular_vel_z, rclcpp::Time stamp) + { + auto imu_msg = std::make_shared(); + imu_msg->header.stamp = stamp; + imu_msg->header.frame_id = "imu_link"; + imu_msg->angular_velocity.x = angular_vel_x; + imu_msg->angular_velocity.y = angular_vel_y; + imu_msg->angular_velocity.z = angular_vel_z; + return imu_msg; + } + + std::vector> generateTwistMsgs( + rclcpp::Time pointcloud_timestamp) + { + std::vector> twist_msgs; + rclcpp::Time twist_stamp = subtractMilliseconds(pointcloud_timestamp, 5); + + for (int i = 0; i < number_of_twist_msgs_; ++i) { + auto twist_msg = generateTwistMsg( + twist_linear_x_ + i * twist_linear_x_increment_, + twist_angular_z_ + i * twist_angular_z_increment_, twist_stamp); + twist_msgs.push_back(twist_msg); + + twist_stamp = addMilliseconds(twist_stamp, twist_msgs_interval_ms_); + } + + return twist_msgs; + } + + std::vector> generateImuMsgs( + rclcpp::Time pointcloud_timestamp) + { + std::vector> imu_msgs; + rclcpp::Time imu_stamp = subtractMilliseconds(pointcloud_timestamp, 10); + + for (int i = 0; i < number_of_imu_msgs_; ++i) { + auto imu_msg = generateImuMsg( + imu_angular_x_ + i * imu_angular_x_increment_, + imu_angular_y_ + i * imu_angular_y_increment_, + imu_angular_z_ + i * imu_angular_z_increment_, imu_stamp); + imu_msgs.push_back(imu_msg); + imu_stamp = addMilliseconds(imu_stamp, imu_msgs_interval_ms_); + } + + return imu_msgs; + } + + sensor_msgs::msg::PointCloud2 generatePointCloudMsg( + bool generate_points, bool is_lidar_frame, rclcpp::Time stamp) + { + sensor_msgs::msg::PointCloud2 pointcloud_msg; + pointcloud_msg.header.stamp = stamp; + pointcloud_msg.header.frame_id = is_lidar_frame ? "lidar_top" : "base_link"; + pointcloud_msg.height = 1; + pointcloud_msg.is_dense = true; + pointcloud_msg.is_bigendian = false; + + if (generate_points) { + std::array points = {{ + Eigen::Vector3f(10.0f, 0.0f, 0.0f), // point 1 + Eigen::Vector3f(0.0f, 10.0f, 0.0f), // point 2 + Eigen::Vector3f(0.0f, 0.0f, 10.0f), // point 3 + Eigen::Vector3f(20.0f, 0.0f, 0.0f), // point 4 + Eigen::Vector3f(0.0f, 20.0f, 0.0f), // point 5 + Eigen::Vector3f(0.0f, 0.0f, 20.0f), // point 6 + Eigen::Vector3f(30.0f, 0.0f, 0.0f), // point 7 + Eigen::Vector3f(0.0f, 30.0f, 0.0f), // point 8 + Eigen::Vector3f(0.0f, 0.0f, 30.0f), // point 9 + Eigen::Vector3f(10.0f, 10.0f, 10.0f) // point 10 + }}; + + // Generate timestamps for the points + std::vector timestamps = generatePointTimestamps(stamp, number_of_points_); + + sensor_msgs::PointCloud2Modifier modifier(pointcloud_msg); + modifier.setPointCloud2Fields( + 4, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, + sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, + "time_stamp", 1, sensor_msgs::msg::PointField::FLOAT64); + modifier.resize(number_of_points_); + + sensor_msgs::PointCloud2Iterator iter_x(pointcloud_msg, "x"); + sensor_msgs::PointCloud2Iterator iter_y(pointcloud_msg, "y"); + sensor_msgs::PointCloud2Iterator iter_z(pointcloud_msg, "z"); + sensor_msgs::PointCloud2Iterator iter_t(pointcloud_msg, "time_stamp"); + + for (size_t i = 0; i < number_of_points_; ++i) { + *iter_x = points[i].x(); + *iter_y = points[i].y(); + *iter_z = points[i].z(); + *iter_t = timestamps[i]; + ++iter_x; + ++iter_y; + ++iter_z; + ++iter_t; + } + } else { + pointcloud_msg.width = 0; + pointcloud_msg.row_step = 0; + } + + return pointcloud_msg; + } + + std::vector generatePointTimestamps( + rclcpp::Time pointcloud_timestamp, size_t number_of_points) + { + std::vector timestamps; + rclcpp::Time point_stamp = pointcloud_timestamp; + for (size_t i = 0; i < number_of_points; ++i) { + double timestamp = point_stamp.seconds(); + timestamps.push_back(timestamp); + point_stamp = addMilliseconds(point_stamp, points_interval_ms_); + } + + return timestamps; + } + + std::shared_ptr node_; + std::shared_ptr distortion_corrector_2d_; + std::shared_ptr distortion_corrector_3d_; + std::shared_ptr tf_broadcaster_; + + static constexpr float standard_tolerance_{1e-4}; + static constexpr float coarse_tolerance_{5e-3}; + static constexpr int number_of_twist_msgs_{6}; + static constexpr int number_of_imu_msgs_{6}; + static constexpr size_t number_of_points_{10}; + static constexpr int32_t timestamp_seconds_{10}; + static constexpr uint32_t timestamp_nanoseconds_{100000000}; + + static constexpr double twist_linear_x_{10.0}; + static constexpr double twist_angular_z_{0.02}; + static constexpr double twist_linear_x_increment_{2.0}; + static constexpr double twist_angular_z_increment_{0.01}; + + static constexpr double imu_angular_x_{0.01}; + static constexpr double imu_angular_y_{-0.02}; + static constexpr double imu_angular_z_{0.05}; + static constexpr double imu_angular_x_increment_{0.005}; + static constexpr double imu_angular_y_increment_{0.005}; + static constexpr double imu_angular_z_increment_{0.005}; + + static constexpr int points_interval_ms_{10}; + static constexpr int twist_msgs_interval_ms_{24}; + static constexpr int imu_msgs_interval_ms_{27}; + + // for debugging or regenerating the ground truth point cloud + bool debug_{false}; +}; + +TEST_F(DistortionCorrectorTest, TestProcessTwistMessage) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + auto twist_msg = generateTwistMsg(twist_linear_x_, twist_angular_z_, timestamp); + distortion_corrector_2d_->processTwistMessage(twist_msg); + + ASSERT_FALSE(distortion_corrector_2d_->get_twist_queue().empty()); + EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.linear.x, twist_linear_x_); + EXPECT_EQ(distortion_corrector_2d_->get_twist_queue().front().twist.angular.z, twist_angular_z_); +} + +TEST_F(DistortionCorrectorTest, TestProcessIMUMessage) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + auto imu_msg = generateImuMsg(imu_angular_x_, imu_angular_y_, imu_angular_z_, timestamp); + distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); + + ASSERT_FALSE(distortion_corrector_2d_->get_angular_velocity_queue().empty()); + EXPECT_NEAR( + distortion_corrector_2d_->get_angular_velocity_queue().front().vector.z, -0.03159, + standard_tolerance_); +} + +TEST_F(DistortionCorrectorTest, TestIsInputValid) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + + // input normal pointcloud without twist + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + bool result = distortion_corrector_2d_->isInputValid(pointcloud); + EXPECT_FALSE(result); + + // input normal pointcloud with valid twist + auto twist_msg = generateTwistMsg(twist_linear_x_, twist_angular_z_, timestamp); + distortion_corrector_2d_->processTwistMessage(twist_msg); + + pointcloud = generatePointCloudMsg(true, false, timestamp); + result = distortion_corrector_2d_->isInputValid(pointcloud); + EXPECT_TRUE(result); + + // input empty pointcloud + pointcloud = generatePointCloudMsg(false, false, timestamp); + result = distortion_corrector_2d_->isInputValid(pointcloud); + EXPECT_FALSE(result); +} + +TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithBaseLink) +{ + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed()); +} + +TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithLidarFrame) +{ + distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_exists()); + EXPECT_TRUE(distortion_corrector_2d_->pointcloud_transform_needed()); +} + +TEST_F(DistortionCorrectorTest, TestSetPointCloudTransformWithMissingFrame) +{ + distortion_corrector_2d_->setPointCloudTransform("base_link", "missing_lidar_frame"); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_exists()); + EXPECT_FALSE(distortion_corrector_2d_->pointcloud_transform_needed()); +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyTwist) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + // Generate the point cloud message + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Process empty twist queue + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->undistortPointCloud(false, pointcloud); + + // Verify the point cloud is not changed + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f), Eigen::Vector3f(20.0f, 0.0f, 0.0f), + Eigen::Vector3f(0.0f, 20.0f, 0.0f), Eigen::Vector3f(0.0f, 0.0f, 20.0f), + Eigen::Vector3f(30.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 30.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 30.0f), Eigen::Vector3f(10.0f, 10.0f, 10.0f)}}; + + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithEmptyPointCloud) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + // Generate an empty point cloud message + sensor_msgs::msg::PointCloud2 empty_pointcloud = generatePointCloudMsg(false, false, timestamp); + + // Process empty point cloud + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->undistortPointCloud(true, empty_pointcloud); + + // Verify the point cloud is still empty + EXPECT_EQ(empty_pointcloud.width, 0); + EXPECT_EQ(empty_pointcloud.row_step, 0); +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithoutImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + + // Test using only twist + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_2d_->undistortPointCloud(false, pointcloud); + + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + // Expected undistorted point cloud values + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.117124f, 10.0f, 0.0f), + Eigen::Vector3f(0.26f, 0.000135182f, 10.0f), Eigen::Vector3f(20.4f, 0.0213818f, 0.0f), + Eigen::Vector3f(0.50932f, 20.0005f, 0.0f), Eigen::Vector3f(0.699999f, 0.000819721f, 20.0f), + Eigen::Vector3f(30.8599f, 0.076f, 0.0f), Eigen::Vector3f(0.947959f, 30.0016f, 0.0f), + Eigen::Vector3f(1.22f, 0.00244382f, 30.0f), Eigen::Vector3f(11.3568f, 10.0463f, 10.0f)}}; + + // Verify each point in the undistorted point cloud + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_2d_->undistortPointCloud(true, pointcloud); + + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + // Expected undistorted point cloud values + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.122876f, 9.99996f, 0.0f), + Eigen::Vector3f(0.26f, -0.000115049f, 10.0f), Eigen::Vector3f(20.4f, -0.0174931f, 0.0f), + Eigen::Vector3f(0.56301f, 19.9996f, 0.0f), Eigen::Vector3f(0.7f, -0.000627014f, 20.0f), + Eigen::Vector3f(30.86f, -0.052675f, 0.0f), Eigen::Vector3f(1.1004f, 29.9987f, 0.0f), + Eigen::Vector3f(1.22f, -0.00166245f, 30.0f), Eigen::Vector3f(11.4249f, 9.97293f, 10.0f)}}; + + // Verify each point in the undistorted point cloud + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud2dWithImuInLidarFrame) +{ + // Generate the point cloud message + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, true, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_2d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_2d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "lidar_top"); + distortion_corrector_2d_->undistortPointCloud(true, pointcloud); + + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + // Expected undistorted point cloud values + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, -1.77636e-15f, -4.44089e-16f), + Eigen::Vector3f(0.049989f, 10.0608f, 0.0924992f), + Eigen::Vector3f(0.106107f, 0.130237f, 10.1986f), + Eigen::Vector3f(20.1709f, 0.210011f, 0.32034f), + Eigen::Vector3f(0.220674f, 20.2734f, 0.417974f), + Eigen::Vector3f(0.274146f, 0.347043f, 20.5341f), + Eigen::Vector3f(30.3673f, 0.457564f, 0.700818f), + Eigen::Vector3f(0.418014f, 30.5259f, 0.807963f), + Eigen::Vector3f(0.464088f, 0.600081f, 30.9292f), + Eigen::Vector3f(10.5657f, 10.7121f, 11.094f)}}; + + // Verify each point in the undistorted point cloud + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithoutImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_3d_->processTwistMessage(twist_msg); + } + + // Test using only twist + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_3d_->undistortPointCloud(false, pointcloud); + + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + // Expected undistorted point cloud values + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.117f, 10.0f, 0.0f), + Eigen::Vector3f(0.26f, 9.27035e-05f, 10.0f), Eigen::Vector3f(20.4f, 0.0222176f, 0.0f), + Eigen::Vector3f(0.51f, 20.0004f, 0.0f), Eigen::Vector3f(0.7f, 0.000706573f, 20.0f), + Eigen::Vector3f(30.8599f, 0.0760946f, 0.0f), Eigen::Vector3f(0.946998f, 30.0015f, 0.0f), + Eigen::Vector3f(1.22f, 0.00234201f, 30.0f), Eigen::Vector3f(11.3569f, 10.046f, 10.0f)}}; + + // Verify each point in the undistorted point cloud + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithImuInBaseLink) +{ + // Generate the point cloud message + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_3d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_3d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_3d_->undistortPointCloud(true, pointcloud); + + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + // Expected undistorted point cloud values + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.123015f, 9.99998f, 0.00430552f), + Eigen::Vector3f(0.266103f, -0.00895269f, 9.99992f), + Eigen::Vector3f(20.4f, -0.0176539f, -0.0193392f), + Eigen::Vector3f(0.563265f, 19.9997f, 0.035628f), + Eigen::Vector3f(0.734597f, -0.046068f, 19.9993f), + Eigen::Vector3f(30.8599f, -0.0517931f, -0.0658165f), + Eigen::Vector3f(1.0995f, 29.9989f, 0.0956997f), + Eigen::Vector3f(1.31283f, -0.113544f, 29.9977f), + Eigen::Vector3f(11.461f, 9.93096f, 10.0035f)}}; + + // Verify each point in the undistorted point cloud + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloud3dWithImuInLidarFrame) +{ + // Generate the point cloud message + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 pointcloud = generatePointCloudMsg(true, true, timestamp); + + // Generate and process multiple twist messages + auto twist_msgs = generateTwistMsgs(timestamp); + for (const auto & twist_msg : twist_msgs) { + distortion_corrector_3d_->processTwistMessage(twist_msg); + } + + // Generate and process multiple IMU messages + auto imu_msgs = generateImuMsgs(timestamp); + for (const auto & imu_msg : imu_msgs) { + distortion_corrector_3d_->processIMUMessage("base_link", imu_msg); + } + + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "lidar_top"); + distortion_corrector_3d_->undistortPointCloud(true, pointcloud); + + sensor_msgs::PointCloud2ConstIterator iter_x(pointcloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(pointcloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(pointcloud, "z"); + + // Expected undistorted point cloud values + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.046484f, 10.0622f, 0.098484f), + Eigen::Vector3f(0.107595f, 0.123767f, 10.2026f), + Eigen::Vector3f(20.1667f, 0.22465f, 0.313351f), + Eigen::Vector3f(0.201149f, 20.2784f, 0.464665f), + Eigen::Vector3f(0.290531f, 0.303489f, 20.5452f), + Eigen::Vector3f(30.3598f, 0.494116f, 0.672914f), + Eigen::Vector3f(0.375848f, 30.5336f, 0.933633f), + Eigen::Vector3f(0.510001f, 0.479651f, 30.9493f), + Eigen::Vector3f(10.5629f, 10.6855f, 11.1461f)}}; + + // Verify each point in the undistorted point cloud + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z << ")\n"; + EXPECT_NEAR(*iter_x, expected_pointcloud[i].x(), standard_tolerance_); + EXPECT_NEAR(*iter_y, expected_pointcloud[i].y(), standard_tolerance_); + EXPECT_NEAR(*iter_z, expected_pointcloud[i].z(), standard_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithPureLinearMotion) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 test2d_pointcloud = generatePointCloudMsg(true, false, timestamp); + sensor_msgs::msg::PointCloud2 test3d_pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process a single twist message with constant linear velocity + auto twist_msg = generateTwistMsg(1.0, 0.0, timestamp); + + distortion_corrector_2d_->processTwistMessage(twist_msg); + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_2d_->undistortPointCloud(false, test2d_pointcloud); + + distortion_corrector_3d_->processTwistMessage(twist_msg); + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_3d_->undistortPointCloud(false, test3d_pointcloud); + + // Generate expected point cloud for testing + sensor_msgs::msg::PointCloud2 expected_pointcloud_msg = + generatePointCloudMsg(true, false, timestamp); + + // Calculate expected point cloud values based on constant linear motion + double velocity = 1.0; // 1 m/s linear velocity + sensor_msgs::PointCloud2Iterator iter_x(expected_pointcloud_msg, "x"); + sensor_msgs::PointCloud2Iterator iter_y(expected_pointcloud_msg, "y"); + sensor_msgs::PointCloud2Iterator iter_z(expected_pointcloud_msg, "z"); + sensor_msgs::PointCloud2Iterator iter_t(expected_pointcloud_msg, "time_stamp"); + + std::vector expected_points; + for (; iter_t != iter_t.end(); ++iter_t, ++iter_x, ++iter_y, ++iter_z) { + double time_offset = *iter_t - timestamp.seconds(); + expected_points.emplace_back( + *iter_x + static_cast(velocity * time_offset), *iter_y, *iter_z); + } + + // Verify each point in the undistorted point cloud + sensor_msgs::PointCloud2Iterator test2d_iter_x(test2d_pointcloud, "x"); + sensor_msgs::PointCloud2Iterator test2d_iter_y(test2d_pointcloud, "y"); + sensor_msgs::PointCloud2Iterator test2d_iter_z(test2d_pointcloud, "z"); + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; test2d_iter_x != test2d_iter_x.end(); + ++test2d_iter_x, ++test2d_iter_y, ++test2d_iter_z, ++i) { + oss << "Point " << i << ": (" << *test2d_iter_x << ", " << *test2d_iter_y << ", " + << *test2d_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*test2d_iter_x, expected_points[i].x()); + EXPECT_FLOAT_EQ(*test2d_iter_y, expected_points[i].y()); + EXPECT_FLOAT_EQ(*test2d_iter_z, expected_points[i].z()); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } + + // Verify each point in the undistorted 2d point cloud with undistorted 3d point cloud + test2d_iter_x = sensor_msgs::PointCloud2Iterator(test2d_pointcloud, "x"); + test2d_iter_y = sensor_msgs::PointCloud2Iterator(test2d_pointcloud, "y"); + test2d_iter_z = sensor_msgs::PointCloud2Iterator(test2d_pointcloud, "z"); + sensor_msgs::PointCloud2Iterator test3d_iter_x(test3d_pointcloud, "x"); + sensor_msgs::PointCloud2Iterator test3d_iter_y(test3d_pointcloud, "y"); + sensor_msgs::PointCloud2Iterator test3d_iter_z(test3d_pointcloud, "z"); + + i = 0; + oss.str(""); + oss.clear(); + + oss << "Expected pointcloud:\n"; + for (; test2d_iter_x != test2d_iter_x.end(); ++test2d_iter_x, ++test2d_iter_y, ++test2d_iter_z, + ++test3d_iter_x, ++test3d_iter_y, ++test3d_iter_z, + ++i) { + oss << "Point " << i << " - 2D: (" << *test2d_iter_x << ", " << *test2d_iter_y << ", " + << *test2d_iter_z << ")" + << " vs 3D: (" << *test3d_iter_x << ", " << *test3d_iter_y << ", " << *test3d_iter_z + << ")\n"; + EXPECT_FLOAT_EQ(*test2d_iter_x, *test3d_iter_x); + EXPECT_FLOAT_EQ(*test2d_iter_y, *test3d_iter_y); + EXPECT_FLOAT_EQ(*test2d_iter_z, *test3d_iter_z); + } + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithPureRotationalMotion) +{ + rclcpp::Time timestamp(timestamp_seconds_, timestamp_nanoseconds_, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 test2d_pointcloud = generatePointCloudMsg(true, false, timestamp); + sensor_msgs::msg::PointCloud2 test3d_pointcloud = generatePointCloudMsg(true, false, timestamp); + + // Generate and process a single twist message with constant angular velocity + auto twist_msg = generateTwistMsg(0.0, 0.1, timestamp); + + distortion_corrector_2d_->processTwistMessage(twist_msg); + distortion_corrector_2d_->initialize(); + distortion_corrector_2d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_2d_->undistortPointCloud(false, test2d_pointcloud); + + distortion_corrector_3d_->processTwistMessage(twist_msg); + distortion_corrector_3d_->initialize(); + distortion_corrector_3d_->setPointCloudTransform("base_link", "base_link"); + distortion_corrector_3d_->undistortPointCloud(false, test3d_pointcloud); + + // Generate expected point cloud for testing + sensor_msgs::msg::PointCloud2 expected_pointcloud_msg = + generatePointCloudMsg(true, false, timestamp); + + // Calculate expected point cloud values based on constant rotational motion + double angular_velocity = 0.1; // 0.1 rad/s rotational velocity + sensor_msgs::PointCloud2Iterator iter_x(expected_pointcloud_msg, "x"); + sensor_msgs::PointCloud2Iterator iter_y(expected_pointcloud_msg, "y"); + sensor_msgs::PointCloud2Iterator iter_z(expected_pointcloud_msg, "z"); + sensor_msgs::PointCloud2Iterator iter_t(expected_pointcloud_msg, "time_stamp"); + + std::vector expected_pointcloud; + for (; iter_t != iter_t.end(); ++iter_t, ++iter_x, ++iter_y, ++iter_z) { + double time_offset = *iter_t - timestamp.seconds(); + float angle = angular_velocity * time_offset; + + // Set the quaternion for the current angle + tf2::Quaternion quaternion; + quaternion.setValue( + 0, 0, autoware::universe_utils::sin(angle * 0.5f), + autoware::universe_utils::cos(angle * 0.5f)); + + tf2::Vector3 point(*iter_x, *iter_y, *iter_z); + tf2::Vector3 rotated_point = tf2::quatRotate(quaternion, point); + expected_pointcloud.emplace_back( + static_cast(rotated_point.x()), static_cast(rotated_point.y()), + static_cast(rotated_point.z())); + } + + // Verify each point in the undistorted 2D point cloud + sensor_msgs::PointCloud2Iterator test2d_iter_x(test2d_pointcloud, "x"); + sensor_msgs::PointCloud2Iterator test2d_iter_y(test2d_pointcloud, "y"); + sensor_msgs::PointCloud2Iterator test2d_iter_z(test2d_pointcloud, "z"); + + size_t i = 0; + std::ostringstream oss; + oss << "Expected pointcloud:\n"; + + for (; test2d_iter_x != test2d_iter_x.end(); + ++test2d_iter_x, ++test2d_iter_y, ++test2d_iter_z, ++i) { + oss << "Point " << i << ": (" << *test2d_iter_x << ", " << *test2d_iter_y << ", " + << *test2d_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*test2d_iter_x, expected_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*test2d_iter_y, expected_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*test2d_iter_z, expected_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } + + // Verify each point in the undistorted 2D point cloud with undistorted 3D point cloud + test2d_iter_x = sensor_msgs::PointCloud2Iterator(test2d_pointcloud, "x"); + test2d_iter_y = sensor_msgs::PointCloud2Iterator(test2d_pointcloud, "y"); + test2d_iter_z = sensor_msgs::PointCloud2Iterator(test2d_pointcloud, "z"); + sensor_msgs::PointCloud2Iterator test3d_iter_x(test3d_pointcloud, "x"); + sensor_msgs::PointCloud2Iterator test3d_iter_y(test3d_pointcloud, "y"); + sensor_msgs::PointCloud2Iterator test3d_iter_z(test3d_pointcloud, "z"); + + i = 0; + oss.str(""); + oss.clear(); + + oss << "Expected pointcloud:\n"; + for (; test2d_iter_x != test2d_iter_x.end(); ++test2d_iter_x, ++test2d_iter_y, ++test2d_iter_z, + ++test3d_iter_x, ++test3d_iter_y, ++test3d_iter_z, + ++i) { + oss << "Point " << i << " - 2D: (" << *test2d_iter_x << ", " << *test2d_iter_y << ", " + << *test2d_iter_z << ")" + << " vs 3D: (" << *test3d_iter_x << ", " << *test3d_iter_y << ", " << *test3d_iter_z + << ")\n"; + EXPECT_NEAR(*test2d_iter_x, *test3d_iter_x, coarse_tolerance_); + EXPECT_NEAR(*test2d_iter_y, *test3d_iter_y, coarse_tolerance_); + EXPECT_NEAR(*test2d_iter_z, *test3d_iter_z, coarse_tolerance_); + } + + if (debug_) { + RCLCPP_INFO(node_->get_logger(), "%s", oss.str().c_str()); + } +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int ret = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return ret; +} From 93490979c97c91ce2aeda17201926c46844d38ca Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 9 Jul 2024 22:17:40 +0900 Subject: [PATCH 141/151] feat: migrating pointcloud types (#6996) * feat: changed most of sensing to the new type Signed-off-by: Kenzo Lobos-Tsunekawa * chore: started applying changes to the perception stack Signed-off-by: Kenzo Lobos-Tsunekawa * feat: confirmed operation until centerpoint Signed-off-by: Kenzo Lobos-Tsunekawa * feat: reverted to the original implementation of pointpainting Signed-off-by: Kenzo Lobos-Tsunekawa * chore: forgot to push a header Signed-off-by: Kenzo Lobos-Tsunekawa * feat: also implemented the changes for the subsample filters that were out of scope before Signed-off-by: Kenzo Lobos-Tsunekawa * fix: some point type changes were missing from the latest merge from main Signed-off-by: Kenzo Lobos-Tsunekawa * chore: removed unused code, added comments, and brought back a removed publish Signed-off-by: Kenzo Lobos-Tsunekawa * chore: replaced pointcloud_raw for pointcloud_raw_ex to avoid extra processing time in the drivers Signed-off-by: Kenzo Lobos-Tsunekawa * feat: added memory layout checks Signed-off-by: Kenzo Lobos-Tsunekawa * chore: updated documentation regarding the point types Signed-off-by: Kenzo Lobos-Tsunekawa * chore: added hyperlinks to the point definitions. will be valid only once the PR is merged Signed-off-by: Kenzo Lobos-Tsunekawa * fix: fixed compilation due to moving the utilities files to the base library Signed-off-by: Kenzo Lobos-Tsunekawa * chore: separated the utilities functions due to a dependency issue * chore: forgot that perception also uses the filter class Signed-off-by: Kenzo Lobos-Tsunekawa * feature: adapted the undistortion tests to the new point type Signed-off-by: Kenzo Lobos-Tsunekawa --------- Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> --- .../include/autoware_point_types/types.hpp | 91 +++++++- .../test/test_point_types.cpp | 9 + .../traffic_light.launch.xml | 2 +- .../scan_ground_filter_nodelet.hpp | 1 + .../src/scan_ground_filter_nodelet.cpp | 4 +- .../src/pointpainting_fusion/node.cpp | 6 +- .../src/detector.cpp | 24 +- .../src/lidar_apollo_segmentation_tvm.cpp | 26 ++- .../src/low_intensity_cluster_filter.cpp | 6 +- .../pointcloud_preprocessor/CMakeLists.txt | 14 +- .../docs/dual-return-outlier-filter.md | 4 +- .../docs/ring-outlier-filter.md | 11 +- .../concatenate_and_time_sync_nodelet.hpp | 4 +- .../concatenate_pointclouds.hpp | 4 +- .../faster_voxel_grid_downsample_filter.hpp | 4 +- .../ring_outlier_filter_nodelet.hpp | 14 +- .../polygon_remover/polygon_remover.hpp | 2 +- .../time_synchronizer_nodelet.hpp | 4 +- .../utility/{utilities.hpp => geometry.hpp} | 16 +- .../utility/memory.hpp | 40 ++++ .../vector_map_inside_area_filter.hpp | 4 +- .../blockage_diag/blockage_diag_nodelet.cpp | 10 +- .../concatenate_and_time_sync_nodelet.cpp | 63 ++++-- .../concatenate_pointclouds.cpp | 62 +++-- .../distortion_corrector.cpp | 43 +++- .../faster_voxel_grid_downsample_filter.cpp | 27 ++- .../voxel_grid_downsample_filter_nodelet.cpp | 2 +- .../pointcloud_preprocessor/src/filter.cpp | 26 +++ .../dual_return_outlier_filter_nodelet.cpp | 34 +-- .../ring_outlier_filter_nodelet.cpp | 149 ++++++------- .../time_synchronizer_nodelet.cpp | 47 ++-- .../utility/{utilities.cpp => geometry.cpp} | 93 +------- .../src/utility/memory.cpp | 211 ++++++++++++++++++ .../test/test_distortion_corrector_node.cpp | 35 +-- .../test/test_utilities.cpp | 4 +- 35 files changed, 767 insertions(+), 329 deletions(-) rename sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/{utilities.hpp => geometry.hpp} (78%) create mode 100644 sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp rename sensing/pointcloud_preprocessor/src/utility/{utilities.cpp => geometry.cpp} (52%) create mode 100644 sensing/pointcloud_preprocessor/src/utility/memory.cpp diff --git a/common/autoware_point_types/include/autoware_point_types/types.hpp b/common/autoware_point_types/include/autoware_point_types/types.hpp index 71ea80c5a9733..a3b0670280530 100644 --- a/common/autoware_point_types/include/autoware_point_types/types.hpp +++ b/common/autoware_point_types/include/autoware_point_types/types.hpp @@ -54,6 +54,23 @@ enum ReturnType : uint8_t { DUAL_ONLY, }; +struct PointXYZIRC +{ + float x{0.0F}; + float y{0.0F}; + float z{0.0F}; + std::uint8_t intensity{0U}; + std::uint8_t return_type{0U}; + std::uint16_t channel{0U}; + + friend bool operator==(const PointXYZIRC & p1, const PointXYZIRC & p2) noexcept + { + return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && + float_eq(p1.z, p2.z) && p1.intensity == p2.intensity && + p1.return_type == p2.return_type && p1.channel == p2.channel; + } +}; + struct PointXYZIRADRT { float x{0.0F}; @@ -75,25 +92,97 @@ struct PointXYZIRADRT } }; -enum class PointIndex { X, Y, Z, Intensity, Ring, Azimuth, Distance, ReturnType, TimeStamp }; +struct PointXYZIRCAEDT +{ + float x{0.0F}; + float y{0.0F}; + float z{0.0F}; + std::uint8_t intensity{0U}; + std::uint8_t return_type{0U}; + std::uint16_t channel{0U}; + float azimuth{0.0F}; + float elevation{0.0F}; + float distance{0.0F}; + std::uint32_t time_stamp{0U}; + + friend bool operator==(const PointXYZIRCAEDT & p1, const PointXYZIRCAEDT & p2) noexcept + { + return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && + float_eq(p1.z, p2.z) && p1.intensity == p2.intensity && + p1.return_type == p2.return_type && p1.channel == p2.channel && + float_eq(p1.azimuth, p2.azimuth) && float_eq(p1.distance, p2.distance) && + p1.time_stamp == p2.time_stamp; + } +}; + +enum class PointXYZIIndex { X, Y, Z, Intensity }; +enum class PointXYZIRCIndex { X, Y, Z, Intensity, ReturnType, Channel }; +enum class PointXYZIRADRTIndex { + X, + Y, + Z, + Intensity, + Ring, + Azimuth, + Distance, + ReturnType, + TimeStamp +}; +enum class PointXYZIRCAEDTIndex { + X, + Y, + Z, + Intensity, + ReturnType, + Channel, + Azimuth, + Elevation, + Distance, + TimeStamp +}; LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(azimuth); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(elevation); LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(distance); LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(return_type); LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(time_stamp); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(channel); + +using PointXYZIRCGenerator = std::tuple< + point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, + point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, + field_return_type_generator, field_channel_generator>; + using PointXYZIRADRTGenerator = std::tuple< point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, point_cloud_msg_wrapper::field_ring_generator, field_azimuth_generator, field_distance_generator, field_return_type_generator, field_time_stamp_generator>; +using PointXYZIRCAEDTGenerator = std::tuple< + point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, + point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, + field_return_type_generator, field_channel_generator, field_azimuth_generator, + field_elevation_generator, field_distance_generator, field_time_stamp_generator>; + } // namespace autoware_point_types +POINT_CLOUD_REGISTER_POINT_STRUCT( + autoware_point_types::PointXYZIRC, + (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( + std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel)) + POINT_CLOUD_REGISTER_POINT_STRUCT( autoware_point_types::PointXYZIRADRT, (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)( float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)( double, time_stamp, time_stamp)) +POINT_CLOUD_REGISTER_POINT_STRUCT( + autoware_point_types::PointXYZIRCAEDT, + (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( + std::uint8_t, return_type, + return_type)(std::uint16_t, channel, channel)(float, azimuth, azimuth)( + float, elevation, elevation)(float, distance, distance)(std::uint32_t, time_stamp, time_stamp)) #endif // AUTOWARE_POINT_TYPES__TYPES_HPP_ diff --git a/common/autoware_point_types/test/test_point_types.cpp b/common/autoware_point_types/test/test_point_types.cpp index 27ab1ef993ab3..16887ac2aa498 100644 --- a/common/autoware_point_types/test/test_point_types.cpp +++ b/common/autoware_point_types/test/test_point_types.cpp @@ -36,6 +36,15 @@ TEST(PointEquality, PointXYZIRADRT) EXPECT_EQ(pt0, pt1); } +TEST(PointEquality, PointXYZIRCAEDT) +{ + using autoware_point_types::PointXYZIRCAEDT; + + PointXYZIRCAEDT pt0{0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; + PointXYZIRCAEDT pt1{0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; + EXPECT_EQ(pt0, pt1); +} + TEST(PointEquality, FloatEq) { // test template diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index ed7ff059a6e53..6cc47de76ea96 100644 --- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -11,7 +11,7 @@ - + diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp index 3ae41173a7a7d..6bfdb271b14e9 100644 --- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp @@ -162,6 +162,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter int y_offset_; int z_offset_; int intensity_offset_; + int intensity_type_; bool offset_initialized_; void set_field_offsets(const PointCloud2ConstPtr & input); diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 7853aa400b6a5..2a2e96b47771d 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -96,8 +96,9 @@ inline void ScanGroundFilterComponent::set_field_offsets(const PointCloud2ConstP int intensity_index = pcl::getFieldIndex(*input, "intensity"); if (intensity_index != -1) { intensity_offset_ = input->fields[intensity_index].offset; + intensity_type_ = input->fields[intensity_index].datatype; } else { - intensity_offset_ = z_offset_ + sizeof(float); + intensity_offset_ = -1; } offset_initialized_ = true; } @@ -569,6 +570,7 @@ void ScanGroundFilterComponent::extractObjectPoints( PointCloud2 & out_object_cloud) { size_t output_data_size = 0; + for (const auto & i : in_indices.indices) { std::memcpy( &out_object_cloud.data[output_data_size], &in_cloud_ptr->data[i * in_cloud_ptr->point_step], diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 7973c22cc1d78..3fb2aca2171f7 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -296,13 +296,13 @@ void PointPaintingFusionNode::fuseOnSingleImage( // tf2::doTransform(painted_pointcloud_msg, transformed_pointcloud, transform_stamped); const auto x_offset = - painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointIndex::X)) + painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointXYZIRCIndex::X)) .offset; const auto y_offset = - painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointIndex::Y)) + painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointXYZIRCIndex::Y)) .offset; const auto z_offset = - painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointIndex::Z)) + painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointXYZIRCIndex::Z)) .offset; const auto class_offset = painted_pointcloud_msg.fields.at(4).offset; const auto p_step = painted_pointcloud_msg.point_step; diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index b704bab39338a..ba4d7f788b0f5 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -16,6 +16,8 @@ #include "lidar_apollo_instance_segmentation/feature_map.hpp" +#include + #include #include #include @@ -126,7 +128,27 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects( // convert from ros to pcl pcl::PointCloud::Ptr pcl_pointcloud_raw_ptr(new pcl::PointCloud); - pcl::fromROSMsg(transformed_cloud, *pcl_pointcloud_raw_ptr); + // pcl::fromROSMsg(transformed_cloud, *pcl_pointcloud_raw_ptr); + + auto pcl_pointcloud_raw = *pcl_pointcloud_raw_ptr; + pcl_pointcloud_raw.width = transformed_cloud.width; + pcl_pointcloud_raw.height = transformed_cloud.height; + pcl_pointcloud_raw.is_dense = transformed_cloud.is_dense == 1; + pcl_pointcloud_raw.resize(transformed_cloud.width * transformed_cloud.height); + + sensor_msgs::PointCloud2ConstIterator it_x(transformed_cloud, "x"); + sensor_msgs::PointCloud2ConstIterator it_y(transformed_cloud, "y"); + sensor_msgs::PointCloud2ConstIterator it_z(transformed_cloud, "z"); + sensor_msgs::PointCloud2ConstIterator it_intensity(transformed_cloud, "intensity"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_intensity) { + pcl::PointXYZI point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + point.intensity = static_cast(*it_intensity); + pcl_pointcloud_raw.emplace_back(std::move(point)); + } // generate feature map std::shared_ptr feature_map_ptr = diff --git a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp index e78cd57b3a4a1..088dab6377ac6 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp @@ -18,6 +18,8 @@ #include #include +#include + #include #include #include @@ -173,7 +175,29 @@ std::shared_ptr ApolloLidarSegmentation::detec sensor_msgs::msg::PointCloud2 transformed_cloud; ApolloLidarSegmentation::transformCloud(input, transformed_cloud, z_offset_); // convert from ros to pcl - pcl::fromROSMsg(transformed_cloud, *pcl_pointcloud_ptr_); + // pcl::fromROSMsg( + // transformed_cloud, *pcl_pointcloud_ptr_); // Manual conversion is needed since intensity + // comes as an uint8_t + + auto pcl_pointcloud = *pcl_pointcloud_ptr_; + pcl_pointcloud.width = input.width; + pcl_pointcloud.height = input.height; + pcl_pointcloud.is_dense = input.is_dense == 1; + pcl_pointcloud.resize(input.width * input.height); + + sensor_msgs::PointCloud2ConstIterator it_x(input, "x"); + sensor_msgs::PointCloud2ConstIterator it_y(input, "y"); + sensor_msgs::PointCloud2ConstIterator it_z(input, "z"); + sensor_msgs::PointCloud2ConstIterator it_intensity(input, "intensity"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_intensity) { + pcl::PointXYZI point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + point.intensity = static_cast(*it_intensity); + pcl_pointcloud.emplace_back(std::move(point)); + } // inference pipeline auto output = pipeline->schedule(pcl_pointcloud_ptr_); diff --git a/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp b/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp index 4772c355ec0b6..a5fd2b9a1c285 100644 --- a/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp +++ b/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp @@ -123,9 +123,9 @@ bool LowIntensityClusterFilter::isValidatedCluster(const sensor_msgs::msg::Point RCLCPP_WARN(get_logger(), "Invalid point cloud data. point_step is less than 16."); return true; } - for (sensor_msgs::PointCloud2ConstIterator iter(cluster, "intensity"); iter != iter.end(); - ++iter) { - mean_intensity += *iter; + for (sensor_msgs::PointCloud2ConstIterator iter(cluster, "intensity"); + iter != iter.end(); ++iter) { + mean_intensity += static_cast(*iter); } const size_t num_points = cluster.width * cluster.height; mean_intensity /= static_cast(num_points); diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index 2d0649fe43954..76b9cc91ea586 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -26,11 +26,13 @@ include_directories( add_library(pointcloud_preprocessor_filter_base SHARED src/filter.cpp + src/utility/memory.cpp ) target_include_directories(pointcloud_preprocessor_filter_base PUBLIC "$" "$" + ${autoware_point_types_INCLUDE_DIRS} ) ament_target_dependencies(pointcloud_preprocessor_filter_base @@ -41,6 +43,7 @@ ament_target_dependencies(pointcloud_preprocessor_filter_base tf2_ros autoware_universe_utils pcl_ros + autoware_point_types ) add_library(faster_voxel_grid_downsample_filter SHARED @@ -59,7 +62,6 @@ ament_target_dependencies(faster_voxel_grid_downsample_filter ) ament_auto_add_library(pointcloud_preprocessor_filter SHARED - src/utility/utilities.cpp src/concatenate_data/concatenate_and_time_sync_nodelet.cpp src/concatenate_data/concatenate_pointclouds.cpp src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -82,6 +84,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/blockage_diag/blockage_diag_nodelet.cpp src/polygon_remover/polygon_remover.cpp src/vector_map_filter/vector_map_inside_area_filter.cpp + src/utility/geometry.cpp ) target_link_libraries(pointcloud_preprocessor_filter @@ -227,16 +230,19 @@ ament_auto_package(INSTALL_TO_SHARE if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) find_package(ament_cmake_gtest) + ament_lint_auto_find_test_dependencies() + ament_add_gtest(test_utilities test/test_utilities.cpp ) - ament_add_gtest(distortion_corrector_node_tests - test/test_distortion_corrector_node.cpp + + ament_add_gtest(test_distortion_corrector_node + test/test_distortion_corrector_node.cpp ) target_link_libraries(test_utilities pointcloud_preprocessor_filter) - target_link_libraries(distortion_corrector_node_tests pointcloud_preprocessor_filter) + target_link_libraries(test_distortion_corrector_node pointcloud_preprocessor_filter) endif() diff --git a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md index c5a0b75e9b33b..d5993a803fa87 100644 --- a/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -10,7 +10,7 @@ This node can remove rain and fog by considering the light reflected from the ob ![outlier_filter-return_type](./image/outlier_filter-return_type.drawio.svg) -Therefore, in order to use this node, the sensor driver must publish custom data including `return_type`. please refer to [PointXYZIRADRT](../../../common/autoware_point_types/include/autoware_point_types/types.hpp#L57-L76) data structure. +Therefore, in order to use this node, the sensor driver must publish custom data including `return_type`. please refer to [PointXYZIRCAEDT](../../../common/autoware_point_types/include/autoware_point_types/types.hpp#L95-L116) data structure. Another feature of this node is that it publishes visibility as a diagnostic topic. With this function, for example, in heavy rain, the sensing module can notify that the processing performance has reached its limit, which can lead to ensuring the safety of the vehicle. @@ -73,7 +73,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref ## Assumptions / Known limits Not recommended for use as it is under development. -Input data must be `PointXYZIRADRT` type data including `return_type`. +Input data must be [PointXYZIRCAEDT](../../../common/autoware_point_types/include/autoware_point_types/types.hpp#L95-L116) type data including `return_type`. ## (Optional) Error detection and handling diff --git a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md index e87023ef00149..0a179ddf6a8ef 100644 --- a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md @@ -73,16 +73,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref ## Assumptions / Known limits -It is a prerequisite to input a scan point cloud in chronological order. In this repository it is defined as blow structure (please refer to [PointXYZIRADT](https://github.com/tier4/AutowareArchitectureProposal.iv/blob/5d8dff0db51634f0c42d2a3e87ca423fbee84348/sensing/preprocessor/pointcloud/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp#L53-L62)). - -- X: x -- Y: y -- z: z -- I: intensity -- R: ring -- A :azimuth -- D: distance -- T: time_stamp +This nodes requires that the points of the input point cloud are in chronological order and that individual points follow the memory layout specified by [PointXYZIRCAEDT](../../../common/autoware_point_types/include/autoware_point_types/types.hpp#L95-L116). ## (Optional) Error detection and handling diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 86c4ed5943540..619a0b8520b97 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -87,7 +87,7 @@ namespace pointcloud_preprocessor { -using autoware_point_types::PointXYZI; +using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; /** \brief @b PointCloudConcatenateDataSynchronizerComponent is a special form of data @@ -169,7 +169,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr); void publish(); - void convertToXYZICloud( + void convertToXYZIRCCloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); void setPeriod(const int64_t new_period); diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index ead66d98b8be7..77717c51e6981 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -86,7 +86,7 @@ namespace pointcloud_preprocessor { -using autoware_point_types::PointXYZI; +using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; /** \brief @b PointCloudConcatenationComponent is a special form of data * synchronizer: it listens for a set of input PointCloud messages on the same topic, @@ -160,7 +160,7 @@ class PointCloudConcatenationComponent : public rclcpp::Node void combineClouds(sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr); void publish(); - void convertToXYZICloud( + void convertToXYZIRCCloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); void setPeriod(const int64_t new_period); diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp index d80e62d08330d..379c4c79e555a 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp @@ -34,7 +34,7 @@ class FasterVoxelGridDownsampleFilter public: FasterVoxelGridDownsampleFilter(); void set_voxel_size(float voxel_size_x, float voxel_size_y, float voxel_size_z); - void set_field_offsets(const PointCloud2ConstPtr & input); + void set_field_offsets(const PointCloud2ConstPtr & input, const rclcpp::Logger & logger); void filter( const PointCloud2ConstPtr & input, PointCloud2 & output, const TransformInfo & transform_info, const rclcpp::Logger & logger); @@ -48,7 +48,7 @@ class FasterVoxelGridDownsampleFilter float intensity; uint32_t point_count_; - Centroid() : x(0), y(0), z(0), intensity(-1.0) {} + Centroid() : x(0), y(0), z(0), intensity(0) {} Centroid(float _x, float _y, float _z, float _intensity) : x(_x), y(_y), z(_z), intensity(_intensity) { diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp index 55ba79aac4593..08fbfe73f2744 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp @@ -35,12 +35,15 @@ namespace pointcloud_preprocessor { -using autoware_point_types::PointXYZI; using point_cloud_msg_wrapper::PointCloud2Modifier; class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter { protected: + using InputPointIndex = autoware_point_types::PointXYZIRCAEDTIndex; + using InputPointType = autoware_point_types::PointXYZIRCAEDT; + using OutputPointType = autoware_point_types::PointXYZIRC; + virtual void filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); @@ -83,8 +86,10 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter { if (walk_size > num_points_threshold_) return true; - auto first_point = reinterpret_cast(&input->data[data_idx_both_ends.first]); - auto last_point = reinterpret_cast(&input->data[data_idx_both_ends.second]); + auto first_point = + reinterpret_cast(&input->data[data_idx_both_ends.first]); + auto last_point = + reinterpret_cast(&input->data[data_idx_both_ends.second]); const auto x = first_point->x - last_point->x; const auto y = first_point->y - last_point->y; @@ -94,8 +99,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter } void setUpPointCloudFormat( - const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size, - size_t num_fields); + const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size); float calculateVisibilityScore(const PointCloud2 & input); public: diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp index 49baed4ed7ed5..4d2e66eea700e 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp @@ -16,7 +16,7 @@ #define POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ #include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/utility/utilities.hpp" +#include "pointcloud_preprocessor/utility/geometry.hpp" #include #include diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp index 4153cee7695f8..2dc98a571ff2c 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp @@ -87,7 +87,7 @@ namespace pointcloud_preprocessor { -using autoware_point_types::PointXYZI; +using autoware_point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; // cspell:ignore Yoshi /** \brief @b PointCloudDataSynchronizerComponent is a special form of data @@ -166,7 +166,7 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node std::map synchronizeClouds(); void publish(); - void convertToXYZICloud( + void convertToXYZIRCCloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); void setPeriod(const int64_t new_period); diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/utilities.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/geometry.hpp similarity index 78% rename from sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/utilities.hpp rename to sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/geometry.hpp index 654057e7bb8d7..0175f88ceb89c 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/utilities.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/geometry.hpp @@ -1,4 +1,4 @@ -// Copyright 2022 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POINTCLOUD_PREPROCESSOR__UTILITY__UTILITIES_HPP_ -#define POINTCLOUD_PREPROCESSOR__UTILITY__UTILITIES_HPP_ +#ifndef POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ +#define POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ #include #include @@ -81,14 +81,6 @@ void remove_polygon_cgal_from_cloud( bool point_within_cgal_polys( const pcl::PointXYZ & point, const std::vector & polyline_polygons); -/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to - * say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */ -bool is_data_layout_compatible_with_PointXYZI(const sensor_msgs::msg::PointCloud2 & input); - -/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRADRT. That - * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */ -bool is_data_layout_compatible_with_PointXYZIRADRT(const sensor_msgs::msg::PointCloud2 & input); - } // namespace pointcloud_preprocessor::utils -#endif // POINTCLOUD_PREPROCESSOR__UTILITY__UTILITIES_HPP_ +#endif // POINTCLOUD_PREPROCESSOR__UTILITY__GEOMETRY_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp new file mode 100644 index 0000000000000..ef87a4f31457b --- /dev/null +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/memory.hpp @@ -0,0 +1,40 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ +#define POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ + +#include + +namespace pointcloud_preprocessor::utils +{ +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZI. That is to + * say whether you can memcpy from the PointCloud2 data buffer to a PointXYZI */ +bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input); + +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRC. That is + * to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRC */ +bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCloud2 & input); + +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRADRT. That + * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRADRT */ +bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::PointCloud2 & input); + +/** \brief Return whether the input PointCloud2 data has the same layout than PointXYZIRCAEDT. That + * is to say whether you can memcpy from the PointCloud2 data buffer to a PointXYZIRCAEDT */ +bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input); + +} // namespace pointcloud_preprocessor::utils + +#endif // POINTCLOUD_PREPROCESSOR__UTILITY__MEMORY_HPP_ diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp index d376a47ae8ab0..e2ba7bcd883aa 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp @@ -1,4 +1,4 @@ -// Copyright 2022 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -16,7 +16,7 @@ #define POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_ #include "pointcloud_preprocessor/filter.hpp" -#include "pointcloud_preprocessor/utility/utilities.hpp" +#include "pointcloud_preprocessor/utility/geometry.hpp" #include #include diff --git a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp index 773e6db056990..aae50a18f2024 100644 --- a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp @@ -21,7 +21,7 @@ namespace pointcloud_preprocessor { -using autoware_point_types::PointXYZIRADRT; +using autoware_point_types::PointXYZIRCAEDT; using diagnostic_msgs::msg::DiagnosticStatus; BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options) @@ -175,7 +175,7 @@ void BlockageDiagComponent::filter( } ideal_horizontal_bins = static_cast( (angle_range_deg_[1] + compensate_angle - angle_range_deg_[0]) / horizontal_resolution_); - pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); + pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); cv::Mat full_size_depth_map( cv::Size(ideal_horizontal_bins, vertical_bins), CV_16UC1, cv::Scalar(0)); @@ -196,7 +196,7 @@ void BlockageDiagComponent::filter( sky_blockage_range_deg_[1] = angle_range_deg_[1]; } else { for (const auto p : pcl_input->points) { - double azimuth_deg = p.azimuth / 100.; + double azimuth_deg = p.azimuth * (180.0 / M_PI); if ( ((azimuth_deg > angle_range_deg_[0]) && (azimuth_deg <= angle_range_deg_[1] + compensate_angle)) || @@ -208,9 +208,9 @@ void BlockageDiagComponent::filter( uint16_t depth_intensity = UINT16_MAX * (1.0 - std::min(p.distance / max_distance_range_, 1.0)); if (is_channel_order_top2down_) { - full_size_depth_map.at(p.ring, horizontal_bin_index) = depth_intensity; + full_size_depth_map.at(p.channel, horizontal_bin_index) = depth_intensity; } else { - full_size_depth_map.at(vertical_bins - p.ring - 1, horizontal_bin_index) = + full_size_depth_map.at(vertical_bins - p.channel - 1, horizontal_bin_index) = depth_intensity; } } diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index 17f650fcb8e54..d10ba9a3fbd29 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -51,6 +51,8 @@ #include "pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp" +#include "pointcloud_preprocessor/utility/memory.hpp" + #include #include @@ -491,40 +493,56 @@ void PointCloudConcatenateDataSynchronizerComponent::publish() } /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void PointCloudConcatenateDataSynchronizerComponent::convertToXYZICloud( +void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) { output_ptr->header = input_ptr->header; - PointCloud2Modifier output_modifier{*output_ptr, input_ptr->header.frame_id}; + PointCloud2Modifier output_modifier{ + *output_ptr, input_ptr->header.frame_id}; output_modifier.reserve(input_ptr->width); - bool has_intensity = std::any_of( - input_ptr->fields.begin(), input_ptr->fields.end(), - [](auto & field) { return field.name == "intensity"; }); + bool has_valid_intensity = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_return_type = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_channel = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; + }); sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); - if (has_intensity) { - sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i) { - PointXYZI point; + if (has_valid_intensity && has_valid_return_type && has_valid_channel) { + sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); + sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); + sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { + PointXYZIRC point; point.x = *it_x; point.y = *it_y; point.z = *it_z; point.intensity = *it_i; + point.return_type = *it_r; + point.channel = *it_c; output_modifier.push_back(std::move(point)); } } else { for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { - PointXYZI point; + PointXYZIRC point; point.x = *it_x; point.y = *it_y; point.z = *it_z; - point.intensity = 0.0f; output_modifier.push_back(std::move(point)); } } @@ -549,15 +567,28 @@ void PointCloudConcatenateDataSynchronizerComponent::setPeriod(const int64_t new void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name) { + if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), "The pointcloud layout is not compatible with PointXYZIRC. Aborting"); + + if (utils::is_data_layout_compatible_with_point_xyzi(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), + "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); + } + + return; + } + std::lock_guard lock(mutex_); - sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2()); + sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); auto input = std::make_shared(*input_ptr); if (input->data.empty()) { RCLCPP_WARN_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); } else { - // convert to XYZI pointcloud if pointcloud is not empty - convertToXYZICloud(input, xyzi_input_ptr); + // convert to XYZIRC pointcloud if pointcloud is not empty + convertToXYZIRCCloud(input, xyzirc_input_ptr); } const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr); @@ -566,7 +597,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( [](const auto & e) { return e.second != nullptr; }); if (is_already_subscribed_this) { - cloud_stdmap_tmp_[topic_name] = xyzi_input_ptr; + cloud_stdmap_tmp_[topic_name] = xyzirc_input_ptr; if (!is_already_subscribed_tmp) { auto period = std::chrono::duration_cast( @@ -579,7 +610,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( timer_->reset(); } } else { - cloud_stdmap_[topic_name] = xyzi_input_ptr; + cloud_stdmap_[topic_name] = xyzirc_input_ptr; const bool is_subscribed_all = std::all_of( std::begin(cloud_stdmap_), std::end(cloud_stdmap_), diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index 0ecaa5588bf65..2ff73c7913f0a 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -14,6 +14,8 @@ #include "pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp" +#include "pointcloud_preprocessor/utility/memory.hpp" + #include #include @@ -325,39 +327,56 @@ void PointCloudConcatenationComponent::publish() } /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void PointCloudConcatenationComponent::convertToXYZICloud( +void PointCloudConcatenationComponent::convertToXYZIRCCloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) { output_ptr->header = input_ptr->header; - PointCloud2Modifier output_modifier{*output_ptr, input_ptr->header.frame_id}; + + PointCloud2Modifier output_modifier{ + *output_ptr, input_ptr->header.frame_id}; output_modifier.reserve(input_ptr->width); - bool has_intensity = std::any_of( - input_ptr->fields.begin(), input_ptr->fields.end(), - [](auto & field) { return field.name == "intensity"; }); + bool has_valid_intensity = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_return_type = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_channel = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; + }); sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); - if (has_intensity) { - sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i) { - PointXYZI point; + if (has_valid_intensity && has_valid_return_type && has_valid_channel) { + sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); + sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); + sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { + PointXYZIRC point; point.x = *it_x; point.y = *it_y; point.z = *it_z; point.intensity = *it_i; + point.return_type = *it_r; + point.channel = *it_c; output_modifier.push_back(std::move(point)); } } else { for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { - PointXYZI point; + PointXYZIRC point; point.x = *it_x; point.y = *it_y; point.z = *it_z; - point.intensity = 0.0f; output_modifier.push_back(std::move(point)); } } @@ -382,10 +401,23 @@ void PointCloudConcatenationComponent::setPeriod(const int64_t new_period) void PointCloudConcatenationComponent::cloud_callback( const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name) { + if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), "The pointcloud layout is not compatible with PointXYZIRC. Aborting"); + + if (utils::is_data_layout_compatible_with_point_xyzi(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), + "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); + } + + return; + } + std::lock_guard lock(mutex_); auto input = std::make_shared(*input_ptr); - sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2()); - convertToXYZICloud(input, xyzi_input_ptr); + sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); + convertToXYZIRCCloud(input, xyzirc_input_ptr); const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr); const bool is_already_subscribed_tmp = std::any_of( @@ -393,7 +425,7 @@ void PointCloudConcatenationComponent::cloud_callback( [](const auto & e) { return e.second != nullptr; }); if (is_already_subscribed_this) { - cloud_stdmap_tmp_[topic_name] = xyzi_input_ptr; + cloud_stdmap_tmp_[topic_name] = xyzirc_input_ptr; if (!is_already_subscribed_tmp) { auto period = std::chrono::duration_cast( @@ -406,7 +438,7 @@ void PointCloudConcatenationComponent::cloud_callback( timer_->reset(); } } else { - cloud_stdmap_[topic_name] = xyzi_input_ptr; + cloud_stdmap_[topic_name] = xyzirc_input_ptr; const bool is_subscribed_all = std::all_of( std::begin(cloud_stdmap_), std::end(cloud_stdmap_), diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index f933d4c6f75d9..4a7152a3cd38a 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -14,8 +14,9 @@ #include "pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" -#include "autoware/universe_utils/math/trigonometry.hpp" +#include "pointcloud_preprocessor/utility/memory.hpp" +#include #include namespace pointcloud_preprocessor @@ -181,6 +182,22 @@ bool DistortionCorrector::isInputValid(sensor_msgs::msg::PointCloud2 & pointc "Required field time stamp doesn't exist in the point cloud."); return false; } + + if (!utils::is_data_layout_compatible_with_point_xyzircaedt(pointcloud)) { + RCLCPP_ERROR( + node_->get_logger(), + "The pointcloud layout is not compatible with PointXYZIRCAEDT. Aborting"); + + if (utils::is_data_layout_compatible_with_point_xyziradrt(pointcloud)) { + RCLCPP_ERROR( + node_->get_logger(), + "The pointcloud layout is compatible with PointXYZIRADRT. You may be using legacy " + "code/data"); + } + + return false; + } + return true; } @@ -193,10 +210,12 @@ void DistortionCorrector::undistortPointCloud( sensor_msgs::PointCloud2Iterator it_x(pointcloud, "x"); sensor_msgs::PointCloud2Iterator it_y(pointcloud, "y"); sensor_msgs::PointCloud2Iterator it_z(pointcloud, "z"); - sensor_msgs::PointCloud2ConstIterator it_time_stamp(pointcloud, "time_stamp"); + sensor_msgs::PointCloud2ConstIterator it_time_stamp(pointcloud, "time_stamp"); - double prev_time_stamp_sec{*it_time_stamp}; - const double first_point_time_stamp_sec{*it_time_stamp}; + double prev_time_stamp_sec{ + pointcloud.header.stamp.sec + 1e-9 * (pointcloud.header.stamp.nanosec + *it_time_stamp)}; + const double first_point_time_stamp_sec{ + pointcloud.header.stamp.sec + 1e-9 * (pointcloud.header.stamp.nanosec + *it_time_stamp)}; std::deque::iterator it_twist; std::deque::iterator it_imu; @@ -214,29 +233,33 @@ void DistortionCorrector::undistortPointCloud( bool is_imu_time_stamp_too_late = false; bool is_twist_valid = true; bool is_imu_valid = true; + double global_point_stamp; for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_time_stamp) { is_twist_valid = true; is_imu_valid = true; + global_point_stamp = + pointcloud.header.stamp.sec + 1e-9 * (pointcloud.header.stamp.nanosec + *it_time_stamp); + // Get closest twist information - while (it_twist != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) { + while (it_twist != std::end(twist_queue_) - 1 && global_point_stamp > twist_stamp) { ++it_twist; twist_stamp = rclcpp::Time(it_twist->header.stamp).seconds(); } - if (std::abs(*it_time_stamp - twist_stamp) > 0.1) { + if (std::abs(global_point_stamp - twist_stamp) > 0.1) { is_twist_time_stamp_too_late = true; is_twist_valid = false; } // Get closest IMU information if (use_imu && !angular_velocity_queue_.empty()) { - while (it_imu != std::end(angular_velocity_queue_) - 1 && *it_time_stamp > imu_stamp) { + while (it_imu != std::end(angular_velocity_queue_) - 1 && global_point_stamp > imu_stamp) { ++it_imu; imu_stamp = rclcpp::Time(it_imu->header.stamp).seconds(); } - if (std::abs(*it_time_stamp - imu_stamp) > 0.1) { + if (std::abs(global_point_stamp - imu_stamp) > 0.1) { is_imu_time_stamp_too_late = true; is_imu_valid = false; } @@ -244,12 +267,12 @@ void DistortionCorrector::undistortPointCloud( is_imu_valid = false; } - float time_offset = static_cast(*it_time_stamp - prev_time_stamp_sec); + float time_offset = static_cast(global_point_stamp - prev_time_stamp_sec); // Undistort a single point based on the strategy undistortPoint(it_x, it_y, it_z, it_twist, it_imu, time_offset, is_twist_valid, is_imu_valid); - prev_time_stamp_sec = *it_time_stamp; + prev_time_stamp_sec = global_point_stamp; } warnIfTimestampIsTooLate(is_twist_time_stamp_too_late, is_imu_time_stamp_too_late); diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp index 9c07a4ec47cba..88a79edc9ce69 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp @@ -29,16 +29,27 @@ void FasterVoxelGridDownsampleFilter::set_voxel_size( Eigen::Array3f::Ones() / Eigen::Array3f(voxel_size_x, voxel_size_y, voxel_size_z); } -void FasterVoxelGridDownsampleFilter::set_field_offsets(const PointCloud2ConstPtr & input) +void FasterVoxelGridDownsampleFilter::set_field_offsets( + const PointCloud2ConstPtr & input, const rclcpp::Logger & logger) { x_offset_ = input->fields[pcl::getFieldIndex(*input, "x")].offset; y_offset_ = input->fields[pcl::getFieldIndex(*input, "y")].offset; z_offset_ = input->fields[pcl::getFieldIndex(*input, "z")].offset; intensity_index_ = pcl::getFieldIndex(*input, "intensity"); + + if ( + intensity_index_ < 0 || input->fields[pcl::getFieldIndex(*input, "intensity")].datatype != + sensor_msgs::msg::PointField::UINT8) { + RCLCPP_ERROR( + logger, + "There is no intensity field in the input point cloud or the intensity field is not of type " + "UINT8."); + } + if (intensity_index_ != -1) { intensity_offset_ = input->fields[intensity_index_].offset; } else { - intensity_offset_ = z_offset_ + sizeof(float); + intensity_offset_ = -1; } offset_initialized_ = true; } @@ -49,7 +60,7 @@ void FasterVoxelGridDownsampleFilter::filter( { // Check if the field offset has been set if (!offset_initialized_) { - set_field_offsets(input); + set_field_offsets(input, logger); } // Compute the minimum and maximum voxel coordinates @@ -85,10 +96,9 @@ Eigen::Vector4f FasterVoxelGridDownsampleFilter::get_point_from_global_offset( const PointCloud2ConstPtr & input, size_t global_offset) { float intensity = 0.0; - if (intensity_index_ == -1) { - intensity = -1.0; - } else { - intensity = *reinterpret_cast(&input->data[global_offset + intensity_offset_]); + if (intensity_index_ >= 0) { + intensity = static_cast( + *reinterpret_cast(&input->data[global_offset + intensity_offset_])); } Eigen::Vector4f point( *reinterpret_cast(&input->data[global_offset + x_offset_]), @@ -179,7 +189,8 @@ void FasterVoxelGridDownsampleFilter::copy_centroids_to_output( *reinterpret_cast(&output.data[output_data_size + x_offset_]) = centroid[0]; *reinterpret_cast(&output.data[output_data_size + y_offset_]) = centroid[1]; *reinterpret_cast(&output.data[output_data_size + z_offset_]) = centroid[2]; - *reinterpret_cast(&output.data[output_data_size + intensity_offset_]) = centroid[3]; + *reinterpret_cast(&output.data[output_data_size + intensity_offset_]) = + static_cast(centroid[3]); output_data_size += output.point_step; } } diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp index f11f37397a142..6e7469ff05f67 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp @@ -108,7 +108,7 @@ void VoxelGridDownsampleFilterComponent::faster_filter( std::scoped_lock lock(mutex_); FasterVoxelGridDownsampleFilter faster_voxel_filter; faster_voxel_filter.set_voxel_size(voxel_size_x_, voxel_size_y_, voxel_size_z_); - faster_voxel_filter.set_field_offsets(input); + faster_voxel_filter.set_field_offsets(input, this->get_logger()); faster_voxel_filter.filter(input, output, transform_info, this->get_logger()); } diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/pointcloud_preprocessor/src/filter.cpp index 035be38f4c342..a0b1814995d8b 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/pointcloud_preprocessor/src/filter.cpp @@ -51,6 +51,8 @@ #include "pointcloud_preprocessor/filter.hpp" +#include "pointcloud_preprocessor/utility/memory.hpp" + #include #include @@ -411,6 +413,30 @@ bool pointcloud_preprocessor::Filter::convert_output_costly(std::unique_ptrget_logger(), "[input_indices_callback] Invalid input!"); return; diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp index d8f5c78ab1e73..1fa067ce75db6 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp @@ -28,7 +28,7 @@ namespace pointcloud_preprocessor { -using autoware_point_types::PointXYZIRADRT; +using autoware_point_types::PointXYZIRCAEDT; using autoware_point_types::ReturnType; using diagnostic_msgs::msg::DiagnosticStatus; @@ -121,22 +121,22 @@ void DualReturnOutlierFilterComponent::filter( if (indices) { RCLCPP_WARN(get_logger(), "Indices are not supported and will be ignored"); } - pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); + pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); uint32_t vertical_bins = vertical_bins_; uint32_t horizontal_bins = 36; - float max_azimuth = 36000.0f; + float max_azimuth = 2 * M_PI; float min_azimuth = 0.0f; switch (roi_mode_map_[roi_mode_]) { case 2: { - max_azimuth = max_azimuth_deg_ * 100.0; - min_azimuth = min_azimuth_deg_ * 100.0; + max_azimuth = max_azimuth_deg_ * (M_PI / 180.0); + min_azimuth = min_azimuth_deg_ * (M_PI / 180.0); break; } default: { - max_azimuth = 36000.0f; + max_azimuth = 2 * M_PI; min_azimuth = 0.0f; break; } @@ -145,13 +145,13 @@ void DualReturnOutlierFilterComponent::filter( uint32_t horizontal_resolution = static_cast((max_azimuth - min_azimuth) / horizontal_bins); - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); + pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); pcl_output->points.reserve(pcl_input->points.size()); - std::vector> pcl_input_ring_array; - std::vector> weak_first_pcl_input_ring_array; + std::vector> pcl_input_ring_array; + std::vector> weak_first_pcl_input_ring_array; - pcl::PointCloud::Ptr noise_output(new pcl::PointCloud); + pcl::PointCloud::Ptr noise_output(new pcl::PointCloud); noise_output->points.reserve(pcl_input->points.size()); pcl_input_ring_array.resize( vertical_bins); // TODO(davidw): this is for Pandar 40 only, make dynamic @@ -160,9 +160,9 @@ void DualReturnOutlierFilterComponent::filter( // Split into 36 x 10 degree bins x 40 lines (TODO: change to dynamic) for (const auto & p : pcl_input->points) { if (p.return_type == ReturnType::DUAL_WEAK_FIRST) { - weak_first_pcl_input_ring_array.at(p.ring).push_back(p); + weak_first_pcl_input_ring_array.at(p.channel).push_back(p); } else { - pcl_input_ring_array.at(p.ring).push_back(p); + pcl_input_ring_array.at(p.channel).push_back(p); } } @@ -175,16 +175,16 @@ void DualReturnOutlierFilterComponent::filter( } std::vector deleted_azimuths; std::vector deleted_distances; - pcl::PointCloud temp_segment; + pcl::PointCloud temp_segment; bool keep_next = false; - uint ring_id = weak_first_single_ring.points.front().ring; + uint ring_id = weak_first_single_ring.points.front().channel; for (auto iter = std::begin(weak_first_single_ring) + 1; iter != std::end(weak_first_single_ring) - 1; ++iter) { const float min_dist = std::min(iter->distance, (iter + 1)->distance); const float max_dist = std::max(iter->distance, (iter + 1)->distance); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; - azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; + azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 2 * M_PI : azimuth_diff; if (max_dist < min_dist * weak_first_distance_ratio_ && azimuth_diff < max_azimuth_diff) { temp_segment.points.push_back(*iter); @@ -294,14 +294,14 @@ void DualReturnOutlierFilterComponent::filter( if (input_ring.size() < 2) { continue; } - pcl::PointCloud temp_segment; + pcl::PointCloud temp_segment; bool keep_next = false; // uint ring_id = input_ring.points.front().ring; for (auto iter = std::begin(input_ring) + 1; iter != std::end(input_ring) - 1; ++iter) { const float min_dist = std::min(iter->distance, (iter + 1)->distance); const float max_dist = std::max(iter->distance, (iter + 1)->distance); float azimuth_diff = (iter + 1)->azimuth - iter->azimuth; - azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; + azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 2 * M_PI : azimuth_diff; if (max_dist < min_dist * general_distance_ratio_ && azimuth_diff < max_azimuth_diff) { temp_segment.points.push_back(*iter); diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index a9722d041c42c..aeb5dfc1acdf7 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -82,24 +82,22 @@ void RingOutlierFilterComponent::faster_filter( } stop_watch_ptr_->toc("processing_time", true); - output.point_step = sizeof(PointXYZI); + output.point_step = sizeof(OutputPointType); output.data.resize(output.point_step * input->width); size_t output_size = 0; - pcl::PointCloud::Ptr outlier_pcl(new pcl::PointCloud); - - const auto ring_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Ring)).offset; - const auto azimuth_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Azimuth)).offset; - const auto distance_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Distance)).offset; - const auto intensity_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::Intensity)).offset; - const auto return_type_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::ReturnType)).offset; - const auto time_stamp_offset = - input->fields.at(static_cast(autoware_point_types::PointIndex::TimeStamp)).offset; + pcl::PointCloud::Ptr outlier_pcl(new pcl::PointCloud); + + const auto input_channel_offset = + input->fields.at(static_cast(InputPointIndex::Channel)).offset; + const auto input_azimuth_offset = + input->fields.at(static_cast(InputPointIndex::Azimuth)).offset; + const auto input_distance_offset = + input->fields.at(static_cast(InputPointIndex::Distance)).offset; + const auto input_intensity_offset = + input->fields.at(static_cast(InputPointIndex::Intensity)).offset; + const auto input_return_type_offset = + input->fields.at(static_cast(InputPointIndex::ReturnType)).offset; std::vector> ring2indices; ring2indices.reserve(max_rings_num_); @@ -110,7 +108,8 @@ void RingOutlierFilterComponent::faster_filter( } for (size_t data_idx = 0; data_idx < input->data.size(); data_idx += input->point_step) { - const uint16_t ring = *reinterpret_cast(&input->data[data_idx + ring_offset]); + const uint16_t ring = + *reinterpret_cast(&input->data[data_idx + input_channel_offset]); ring2indices[ring].push_back(data_idx); } @@ -132,30 +131,30 @@ void RingOutlierFilterComponent::faster_filter( // if(std::abs(iter->distance - (iter+1)->distance) <= std::sqrt(iter->distance) * 0.08) const float & current_azimuth = - *reinterpret_cast(&input->data[current_data_idx + azimuth_offset]); + *reinterpret_cast(&input->data[current_data_idx + input_azimuth_offset]); const float & next_azimuth = - *reinterpret_cast(&input->data[next_data_idx + azimuth_offset]); + *reinterpret_cast(&input->data[next_data_idx + input_azimuth_offset]); float azimuth_diff = next_azimuth - current_azimuth; - azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff; + azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 2 * M_PI : azimuth_diff; const float & current_distance = - *reinterpret_cast(&input->data[current_data_idx + distance_offset]); + *reinterpret_cast(&input->data[current_data_idx + input_distance_offset]); const float & next_distance = - *reinterpret_cast(&input->data[next_data_idx + distance_offset]); + *reinterpret_cast(&input->data[next_data_idx + input_distance_offset]); if ( std::max(current_distance, next_distance) < std::min(current_distance, next_distance) * distance_ratio_ && - azimuth_diff < 100.f) { - continue; // Determined to be included in the same walk + azimuth_diff < 1.0 * (180.0 / M_PI)) { // one degree + continue; // Determined to be included in the same walk } if (isCluster( input, std::make_pair(indices[walk_first_idx], indices[walk_last_idx]), walk_last_idx - walk_first_idx + 1)) { for (int i = walk_first_idx; i <= walk_last_idx; i++) { - auto output_ptr = reinterpret_cast(&output.data[output_size]); - auto input_ptr = reinterpret_cast(&input->data[indices[i]]); + auto output_ptr = reinterpret_cast(&output.data[output_size]); + auto input_ptr = reinterpret_cast(&input->data[indices[i]]); if (transform_info.need_transform) { Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); @@ -164,41 +163,38 @@ void RingOutlierFilterComponent::faster_filter( output_ptr->y = p[1]; output_ptr->z = p[2]; } else { - *output_ptr = *input_ptr; + output_ptr->x = input_ptr->x; + output_ptr->y = input_ptr->y; + output_ptr->z = input_ptr->z; } - const float & intensity = - *reinterpret_cast(&input->data[indices[i] + intensity_offset]); + const std::uint8_t & intensity = *reinterpret_cast( + &input->data[indices[i] + input_intensity_offset]); output_ptr->intensity = intensity; + const std::uint8_t & return_type = *reinterpret_cast( + &input->data[indices[i] + input_return_type_offset]); + output_ptr->return_type = return_type; + + const std::uint8_t & channel = *reinterpret_cast( + &input->data[indices[i] + input_channel_offset]); + output_ptr->channel = channel; + output_size += output.point_step; } } else if (publish_outlier_pointcloud_) { for (int i = walk_first_idx; i <= walk_last_idx; i++) { - PointXYZIRADRT outlier_point; auto input_ptr = - reinterpret_cast(&input->data[indices[walk_first_idx]]); + reinterpret_cast(&input->data[indices[walk_first_idx]]); + InputPointType outlier_point = *input_ptr; + if (transform_info.need_transform) { Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); p = transform_info.eigen_transform * p; outlier_point.x = p[0]; outlier_point.y = p[1]; outlier_point.z = p[2]; - } else { - outlier_point = *input_ptr; } - outlier_point.intensity = *reinterpret_cast( - &input->data[indices[walk_first_idx] + intensity_offset]); - outlier_point.ring = *reinterpret_cast( - &input->data[indices[walk_first_idx] + ring_offset]); - outlier_point.azimuth = *reinterpret_cast( - &input->data[indices[walk_first_idx] + azimuth_offset]); - outlier_point.distance = *reinterpret_cast( - &input->data[indices[walk_first_idx] + distance_offset]); - outlier_point.return_type = *reinterpret_cast( - &input->data[indices[walk_first_idx] + return_type_offset]); - outlier_point.time_stamp = *reinterpret_cast( - &input->data[indices[walk_first_idx] + time_stamp_offset]); outlier_pcl->push_back(outlier_point); } } @@ -212,8 +208,8 @@ void RingOutlierFilterComponent::faster_filter( input, std::make_pair(indices[walk_first_idx], indices[walk_last_idx]), walk_last_idx - walk_first_idx + 1)) { for (int i = walk_first_idx; i <= walk_last_idx; i++) { - auto output_ptr = reinterpret_cast(&output.data[output_size]); - auto input_ptr = reinterpret_cast(&input->data[indices[i]]); + auto output_ptr = reinterpret_cast(&output.data[output_size]); + auto input_ptr = reinterpret_cast(&input->data[indices[i]]); if (transform_info.need_transform) { Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); @@ -222,46 +218,42 @@ void RingOutlierFilterComponent::faster_filter( output_ptr->y = p[1]; output_ptr->z = p[2]; } else { - *output_ptr = *input_ptr; + output_ptr->x = input_ptr->x; + output_ptr->y = input_ptr->y; + output_ptr->z = input_ptr->z; } const float & intensity = - *reinterpret_cast(&input->data[indices[i] + intensity_offset]); + *reinterpret_cast(&input->data[indices[i] + input_intensity_offset]); output_ptr->intensity = intensity; + const std::uint8_t & return_type = *reinterpret_cast( + &input->data[indices[i] + input_return_type_offset]); + output_ptr->return_type = return_type; + + const std::uint8_t & channel = + *reinterpret_cast(&input->data[indices[i] + input_channel_offset]); + output_ptr->channel = channel; + output_size += output.point_step; } } else if (publish_outlier_pointcloud_) { for (int i = walk_first_idx; i < walk_last_idx; i++) { - PointXYZIRADRT outlier_point; - - auto input_ptr = reinterpret_cast(&input->data[indices[i]]); + auto input_ptr = reinterpret_cast(&input->data[indices[i]]); + InputPointType outlier_point = *input_ptr; if (transform_info.need_transform) { Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); p = transform_info.eigen_transform * p; outlier_point.x = p[0]; outlier_point.y = p[1]; outlier_point.z = p[2]; - } else { - outlier_point = *input_ptr; } - outlier_point.intensity = - *reinterpret_cast(&input->data[indices[i] + intensity_offset]); - outlier_point.ring = - *reinterpret_cast(&input->data[indices[i] + ring_offset]); - outlier_point.azimuth = - *reinterpret_cast(&input->data[indices[i] + azimuth_offset]); - outlier_point.distance = - *reinterpret_cast(&input->data[indices[i] + distance_offset]); - outlier_point.return_type = - *reinterpret_cast(&input->data[indices[i] + return_type_offset]); - outlier_point.time_stamp = - *reinterpret_cast(&input->data[indices[i] + time_stamp_offset]); + outlier_pcl->push_back(outlier_point); } } } - setUpPointCloudFormat(input, output, output_size, /*num_fields=*/4); + setUpPointCloudFormat(input, output, output_size); if (publish_outlier_pointcloud_) { PointCloud2 outlier; @@ -351,8 +343,7 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba } void RingOutlierFilterComponent::setUpPointCloudFormat( - const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size, - size_t num_fields) + const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size) { formatted_points.data.resize(points_size); // Note that `input->header.frame_id` is data before converted when `transform_info.need_transform @@ -365,40 +356,40 @@ void RingOutlierFilterComponent::setUpPointCloudFormat( formatted_points.is_bigendian = input->is_bigendian; formatted_points.is_dense = input->is_dense; - sensor_msgs::PointCloud2Modifier pcd_modifier(formatted_points); - pcd_modifier.setPointCloud2Fields( - num_fields, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, - sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, - "intensity", 1, sensor_msgs::msg::PointField::FLOAT32); + // This is a hack to get the correct fields in the output point cloud without creating the fields + // manually + sensor_msgs::msg::PointCloud2 msg_aux; + pcl::toROSMsg(pcl::PointCloud(), msg_aux); + formatted_points.fields = msg_aux.fields; } float RingOutlierFilterComponent::calculateVisibilityScore( const sensor_msgs::msg::PointCloud2 & input) { - pcl::PointCloud::Ptr input_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr input_cloud(new pcl::PointCloud); pcl::fromROSMsg(input, *input_cloud); const uint32_t vertical_bins = vertical_bins_; const uint32_t horizontal_bins = horizontal_bins_; - const float max_azimuth = max_azimuth_deg_ * 100.0; - const float min_azimuth = min_azimuth_deg_ * 100.0; + const float max_azimuth = max_azimuth_deg_ * (M_PI / 180.f); + const float min_azimuth = min_azimuth_deg_ * (M_PI / 180.f); const uint32_t horizontal_resolution = static_cast((max_azimuth - min_azimuth) / horizontal_bins); - std::vector> ring_point_clouds(vertical_bins); + std::vector> ring_point_clouds(vertical_bins); cv::Mat frequency_image(cv::Size(horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); // Split points into rings for (const auto & point : input_cloud->points) { - ring_point_clouds.at(point.ring).push_back(point); + ring_point_clouds.at(point.channel).push_back(point); } // Calculate frequency for each bin in each ring for (const auto & ring_points : ring_point_clouds) { if (ring_points.empty()) continue; - const uint ring_id = ring_points.front().ring; + const uint ring_id = ring_points.front().channel; std::vector frequency_in_ring(horizontal_bins, 0); for (const auto & point : ring_points.points) { diff --git a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp index 35c35471bf30e..0c9aa202f2afa 100644 --- a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -430,39 +430,56 @@ void PointCloudDataSynchronizerComponent::publish() } /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void PointCloudDataSynchronizerComponent::convertToXYZICloud( +void PointCloudDataSynchronizerComponent::convertToXYZIRCCloud( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) { output_ptr->header = input_ptr->header; - PointCloud2Modifier output_modifier{*output_ptr, input_ptr->header.frame_id}; + + PointCloud2Modifier output_modifier{ + *output_ptr, input_ptr->header.frame_id}; output_modifier.reserve(input_ptr->width); - bool has_intensity = std::any_of( - input_ptr->fields.begin(), input_ptr->fields.end(), - [](auto & field) { return field.name == "intensity"; }); + bool has_valid_intensity = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_return_type = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_channel = + std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](auto & field) { + return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; + }); sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); - if (has_intensity) { - sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i) { - PointXYZI point; + if (has_valid_intensity && has_valid_return_type && has_valid_channel) { + sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); + sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); + sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { + PointXYZIRC point; point.x = *it_x; point.y = *it_y; point.z = *it_z; point.intensity = *it_i; + point.return_type = *it_r; + point.channel = *it_c; output_modifier.push_back(std::move(point)); } } else { for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { - PointXYZI point; + PointXYZIRC point; point.x = *it_x; point.y = *it_y; point.z = *it_z; - point.intensity = 0.0f; output_modifier.push_back(std::move(point)); } } @@ -489,9 +506,9 @@ void PointCloudDataSynchronizerComponent::cloud_callback( { std::lock_guard lock(mutex_); auto input = std::make_shared(*input_ptr); - sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2()); + sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); if (input->data.size() > 0) { - convertToXYZICloud(input, xyzi_input_ptr); + convertToXYZIRCCloud(input, xyzirc_input_ptr); } const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr); @@ -500,7 +517,7 @@ void PointCloudDataSynchronizerComponent::cloud_callback( [](const auto & e) { return e.second != nullptr; }); if (is_already_subscribed_this) { - cloud_stdmap_tmp_[topic_name] = xyzi_input_ptr; + cloud_stdmap_tmp_[topic_name] = xyzirc_input_ptr; if (!is_already_subscribed_tmp) { auto period = std::chrono::duration_cast( @@ -513,7 +530,7 @@ void PointCloudDataSynchronizerComponent::cloud_callback( timer_->reset(); } } else { - cloud_stdmap_[topic_name] = xyzi_input_ptr; + cloud_stdmap_[topic_name] = xyzirc_input_ptr; const bool is_subscribed_all = std::all_of( std::begin(cloud_stdmap_), std::end(cloud_stdmap_), diff --git a/sensing/pointcloud_preprocessor/src/utility/utilities.cpp b/sensing/pointcloud_preprocessor/src/utility/geometry.cpp similarity index 52% rename from sensing/pointcloud_preprocessor/src/utility/utilities.cpp rename to sensing/pointcloud_preprocessor/src/utility/geometry.cpp index ec84a2467db78..e3013d05d925f 100644 --- a/sensing/pointcloud_preprocessor/src/utility/utilities.cpp +++ b/sensing/pointcloud_preprocessor/src/utility/geometry.cpp @@ -1,4 +1,4 @@ -// Copyright 2022 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,9 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/utility/utilities.hpp" - -#include +#include "pointcloud_preprocessor/utility/geometry.hpp" namespace pointcloud_preprocessor::utils { @@ -157,91 +155,4 @@ bool point_within_cgal_polys( return false; } -bool is_data_layout_compatible_with_PointXYZI(const sensor_msgs::msg::PointCloud2 & input) -{ - using autoware_point_types::PointIndex; - using autoware_point_types::PointXYZI; - if (input.fields.size() < 4) { - return false; - } - bool same_layout = true; - const auto & field_x = input.fields.at(static_cast(PointIndex::X)); - same_layout &= field_x.name == "x"; - same_layout &= field_x.offset == offsetof(PointXYZI, x); - same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_x.count == 1; - const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); - same_layout &= field_y.name == "y"; - same_layout &= field_y.offset == offsetof(PointXYZI, y); - same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_y.count == 1; - const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); - same_layout &= field_z.name == "z"; - same_layout &= field_z.offset == offsetof(PointXYZI, z); - same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_z.count == 1; - const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); - same_layout &= field_intensity.name == "intensity"; - same_layout &= field_intensity.offset == offsetof(PointXYZI, intensity); - same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_intensity.count == 1; - return same_layout; -} - -bool is_data_layout_compatible_with_PointXYZIRADRT(const sensor_msgs::msg::PointCloud2 & input) -{ - using autoware_point_types::PointIndex; - using autoware_point_types::PointXYZIRADRT; - if (input.fields.size() < 9) { - return false; - } - bool same_layout = true; - const auto & field_x = input.fields.at(static_cast(PointIndex::X)); - same_layout &= field_x.name == "x"; - same_layout &= field_x.offset == offsetof(PointXYZIRADRT, x); - same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_x.count == 1; - const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); - same_layout &= field_y.name == "y"; - same_layout &= field_y.offset == offsetof(PointXYZIRADRT, y); - same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_y.count == 1; - const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); - same_layout &= field_z.name == "z"; - same_layout &= field_z.offset == offsetof(PointXYZIRADRT, z); - same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_z.count == 1; - const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); - same_layout &= field_intensity.name == "intensity"; - same_layout &= field_intensity.offset == offsetof(PointXYZIRADRT, intensity); - same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_intensity.count == 1; - const auto & field_ring = input.fields.at(static_cast(PointIndex::Ring)); - same_layout &= field_ring.name == "ring"; - same_layout &= field_ring.offset == offsetof(PointXYZIRADRT, ring); - same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; - same_layout &= field_ring.count == 1; - const auto & field_azimuth = input.fields.at(static_cast(PointIndex::Azimuth)); - same_layout &= field_azimuth.name == "azimuth"; - same_layout &= field_azimuth.offset == offsetof(PointXYZIRADRT, azimuth); - same_layout &= field_azimuth.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_azimuth.count == 1; - const auto & field_distance = input.fields.at(static_cast(PointIndex::Distance)); - same_layout &= field_distance.name == "distance"; - same_layout &= field_distance.offset == offsetof(PointXYZIRADRT, distance); - same_layout &= field_distance.datatype == sensor_msgs::msg::PointField::FLOAT32; - same_layout &= field_distance.count == 1; - const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); - same_layout &= field_return_type.name == "return_type"; - same_layout &= field_return_type.offset == offsetof(PointXYZIRADRT, return_type); - same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; - same_layout &= field_return_type.count == 1; - const auto & field_time_stamp = input.fields.at(static_cast(PointIndex::TimeStamp)); - same_layout &= field_time_stamp.name == "time_stamp"; - same_layout &= field_time_stamp.offset == offsetof(PointXYZIRADRT, time_stamp); - same_layout &= field_time_stamp.datatype == sensor_msgs::msg::PointField::FLOAT64; - same_layout &= field_time_stamp.count == 1; - return same_layout; -} - } // namespace pointcloud_preprocessor::utils diff --git a/sensing/pointcloud_preprocessor/src/utility/memory.cpp b/sensing/pointcloud_preprocessor/src/utility/memory.cpp new file mode 100644 index 0000000000000..138573a2014ff --- /dev/null +++ b/sensing/pointcloud_preprocessor/src/utility/memory.cpp @@ -0,0 +1,211 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pointcloud_preprocessor/utility/memory.hpp" + +#include + +namespace pointcloud_preprocessor::utils +{ +bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input) +{ + using PointIndex = autoware_point_types::PointXYZIIndex; + using autoware_point_types::PointXYZI; + if (input.fields.size() < 4) { + return false; + } + bool same_layout = true; + const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + same_layout &= field_x.name == "x"; + same_layout &= field_x.offset == offsetof(PointXYZI, x); + same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_x.count == 1; + const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + same_layout &= field_y.name == "y"; + same_layout &= field_y.offset == offsetof(PointXYZI, y); + same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_y.count == 1; + const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + same_layout &= field_z.name == "z"; + same_layout &= field_z.offset == offsetof(PointXYZI, z); + same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_z.count == 1; + const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + same_layout &= field_intensity.name == "intensity"; + same_layout &= field_intensity.offset == offsetof(PointXYZI, intensity); + same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_intensity.count == 1; + return same_layout; +} + +bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCloud2 & input) +{ + using PointIndex = autoware_point_types::PointXYZIRCIndex; + using autoware_point_types::PointXYZIRC; + if (input.fields.size() < 6) { + return false; + } + bool same_layout = true; + const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + same_layout &= field_x.name == "x"; + same_layout &= field_x.offset == offsetof(PointXYZIRC, x); + same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_x.count == 1; + const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + same_layout &= field_y.name == "y"; + same_layout &= field_y.offset == offsetof(PointXYZIRC, y); + same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_y.count == 1; + const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + same_layout &= field_z.name == "z"; + same_layout &= field_z.offset == offsetof(PointXYZIRC, z); + same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_z.count == 1; + const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + same_layout &= field_intensity.name == "intensity"; + same_layout &= field_intensity.offset == offsetof(PointXYZIRC, intensity); + same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::UINT8; + same_layout &= field_intensity.count == 1; + const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); + same_layout &= field_return_type.name == "return_type"; + same_layout &= field_return_type.offset == offsetof(PointXYZIRC, return_type); + same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; + same_layout &= field_return_type.count == 1; + const auto & field_ring = input.fields.at(static_cast(PointIndex::Channel)); + same_layout &= field_ring.name == "channel"; + same_layout &= field_ring.offset == offsetof(PointXYZIRC, channel); + same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; + same_layout &= field_ring.count == 1; + + return same_layout; +} + +bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::PointCloud2 & input) +{ + using PointIndex = autoware_point_types::PointXYZIRADRTIndex; + using autoware_point_types::PointXYZIRADRT; + if (input.fields.size() < 9) { + return false; + } + bool same_layout = true; + const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + same_layout &= field_x.name == "x"; + same_layout &= field_x.offset == offsetof(PointXYZIRADRT, x); + same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_x.count == 1; + const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + same_layout &= field_y.name == "y"; + same_layout &= field_y.offset == offsetof(PointXYZIRADRT, y); + same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_y.count == 1; + const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + same_layout &= field_z.name == "z"; + same_layout &= field_z.offset == offsetof(PointXYZIRADRT, z); + same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_z.count == 1; + const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + same_layout &= field_intensity.name == "intensity"; + same_layout &= field_intensity.offset == offsetof(PointXYZIRADRT, intensity); + same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_intensity.count == 1; + const auto & field_ring = input.fields.at(static_cast(PointIndex::Ring)); + same_layout &= field_ring.name == "ring"; + same_layout &= field_ring.offset == offsetof(PointXYZIRADRT, ring); + same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; + same_layout &= field_ring.count == 1; + const auto & field_azimuth = input.fields.at(static_cast(PointIndex::Azimuth)); + same_layout &= field_azimuth.name == "azimuth"; + same_layout &= field_azimuth.offset == offsetof(PointXYZIRADRT, azimuth); + same_layout &= field_azimuth.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_azimuth.count == 1; + const auto & field_distance = input.fields.at(static_cast(PointIndex::Distance)); + same_layout &= field_distance.name == "distance"; + same_layout &= field_distance.offset == offsetof(PointXYZIRADRT, distance); + same_layout &= field_distance.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_distance.count == 1; + const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); + same_layout &= field_return_type.name == "return_type"; + same_layout &= field_return_type.offset == offsetof(PointXYZIRADRT, return_type); + same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; + same_layout &= field_return_type.count == 1; + const auto & field_time_stamp = input.fields.at(static_cast(PointIndex::TimeStamp)); + same_layout &= field_time_stamp.name == "time_stamp"; + same_layout &= field_time_stamp.offset == offsetof(PointXYZIRADRT, time_stamp); + same_layout &= field_time_stamp.datatype == sensor_msgs::msg::PointField::FLOAT64; + same_layout &= field_time_stamp.count == 1; + return same_layout; +} + +bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input) +{ + using PointIndex = autoware_point_types::PointXYZIRCAEDTIndex; + using autoware_point_types::PointXYZIRCAEDT; + if (input.fields.size() != 10) { + return false; + } + bool same_layout = true; + const auto & field_x = input.fields.at(static_cast(PointIndex::X)); + same_layout &= field_x.name == "x"; + same_layout &= field_x.offset == offsetof(PointXYZIRCAEDT, x); + same_layout &= field_x.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_x.count == 1; + const auto & field_y = input.fields.at(static_cast(PointIndex::Y)); + same_layout &= field_y.name == "y"; + same_layout &= field_y.offset == offsetof(PointXYZIRCAEDT, y); + same_layout &= field_y.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_y.count == 1; + const auto & field_z = input.fields.at(static_cast(PointIndex::Z)); + same_layout &= field_z.name == "z"; + same_layout &= field_z.offset == offsetof(PointXYZIRCAEDT, z); + same_layout &= field_z.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_z.count == 1; + const auto & field_intensity = input.fields.at(static_cast(PointIndex::Intensity)); + same_layout &= field_intensity.name == "intensity"; + same_layout &= field_intensity.offset == offsetof(PointXYZIRCAEDT, intensity); + same_layout &= field_intensity.datatype == sensor_msgs::msg::PointField::UINT8; + same_layout &= field_intensity.count == 1; + const auto & field_return_type = input.fields.at(static_cast(PointIndex::ReturnType)); + same_layout &= field_return_type.name == "return_type"; + same_layout &= field_return_type.offset == offsetof(PointXYZIRCAEDT, return_type); + same_layout &= field_return_type.datatype == sensor_msgs::msg::PointField::UINT8; + same_layout &= field_return_type.count == 1; + const auto & field_ring = input.fields.at(static_cast(PointIndex::Channel)); + same_layout &= field_ring.name == "channel"; + same_layout &= field_ring.offset == offsetof(PointXYZIRCAEDT, channel); + same_layout &= field_ring.datatype == sensor_msgs::msg::PointField::UINT16; + same_layout &= field_ring.count == 1; + const auto & field_azimuth = input.fields.at(static_cast(PointIndex::Azimuth)); + same_layout &= field_azimuth.name == "azimuth"; + same_layout &= field_azimuth.offset == offsetof(PointXYZIRCAEDT, azimuth); + same_layout &= field_azimuth.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_azimuth.count == 1; + const auto & field_elevation = input.fields.at(static_cast(PointIndex::Elevation)); + same_layout &= field_elevation.name == "elevation"; + same_layout &= field_elevation.offset == offsetof(PointXYZIRCAEDT, elevation); + same_layout &= field_elevation.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_elevation.count == 1; + const auto & field_distance = input.fields.at(static_cast(PointIndex::Distance)); + same_layout &= field_distance.name == "distance"; + same_layout &= field_distance.offset == offsetof(PointXYZIRCAEDT, distance); + same_layout &= field_distance.datatype == sensor_msgs::msg::PointField::FLOAT32; + same_layout &= field_distance.count == 1; + const auto & field_time_stamp = input.fields.at(static_cast(PointIndex::TimeStamp)); + same_layout &= field_time_stamp.name == "time_stamp"; + same_layout &= field_time_stamp.offset == offsetof(PointXYZIRCAEDT, time_stamp); + same_layout &= field_time_stamp.datatype == sensor_msgs::msg::PointField::UINT32; + same_layout &= field_time_stamp.count == 1; + return same_layout; +} + +} // namespace pointcloud_preprocessor::utils diff --git a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index 7997aaf43c202..3b500bfb3e982 100644 --- a/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -58,7 +58,7 @@ class DistortionCorrectorTest : public ::testing::Test // Spin the node for a while to ensure transforms are published auto start = std::chrono::steady_clock::now(); - auto timeout = std::chrono::seconds(1); + auto timeout = std::chrono::milliseconds(100); while (std::chrono::steady_clock::now() - start < timeout) { rclcpp::spin_some(node_); std::this_thread::sleep_for(std::chrono::milliseconds(10)); @@ -194,19 +194,24 @@ class DistortionCorrectorTest : public ::testing::Test }}; // Generate timestamps for the points - std::vector timestamps = generatePointTimestamps(stamp, number_of_points_); + std::vector timestamps = generatePointTimestamps(stamp, number_of_points_); sensor_msgs::PointCloud2Modifier modifier(pointcloud_msg); modifier.setPointCloud2Fields( - 4, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, + 10, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, - "time_stamp", 1, sensor_msgs::msg::PointField::FLOAT64); + "intensity", 1, sensor_msgs::msg::PointField::UINT8, "return_type", 1, + sensor_msgs::msg::PointField::UINT8, "channel", 1, sensor_msgs::msg::PointField::UINT16, + "azimuth", 1, sensor_msgs::msg::PointField::FLOAT32, "elevation", 1, + sensor_msgs::msg::PointField::FLOAT32, "distance", 1, sensor_msgs::msg::PointField::FLOAT32, + "time_stamp", 1, sensor_msgs::msg::PointField::UINT32); + modifier.resize(number_of_points_); sensor_msgs::PointCloud2Iterator iter_x(pointcloud_msg, "x"); sensor_msgs::PointCloud2Iterator iter_y(pointcloud_msg, "y"); sensor_msgs::PointCloud2Iterator iter_z(pointcloud_msg, "z"); - sensor_msgs::PointCloud2Iterator iter_t(pointcloud_msg, "time_stamp"); + sensor_msgs::PointCloud2Iterator iter_t(pointcloud_msg, "time_stamp"); for (size_t i = 0; i < number_of_points_; ++i) { *iter_x = points[i].x(); @@ -226,15 +231,15 @@ class DistortionCorrectorTest : public ::testing::Test return pointcloud_msg; } - std::vector generatePointTimestamps( + std::vector generatePointTimestamps( rclcpp::Time pointcloud_timestamp, size_t number_of_points) { - std::vector timestamps; - rclcpp::Time point_stamp = pointcloud_timestamp; + std::vector timestamps; + rclcpp::Time global_point_stamp = pointcloud_timestamp; for (size_t i = 0; i < number_of_points; ++i) { - double timestamp = point_stamp.seconds(); - timestamps.push_back(timestamp); - point_stamp = addMilliseconds(point_stamp, points_interval_ms_); + std::uint32_t relative_timestamp = (global_point_stamp - pointcloud_timestamp).nanoseconds(); + timestamps.push_back(relative_timestamp); + global_point_stamp = addMilliseconds(global_point_stamp, points_interval_ms_); } return timestamps; @@ -735,11 +740,11 @@ TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithPureLinearMotion) sensor_msgs::PointCloud2Iterator iter_x(expected_pointcloud_msg, "x"); sensor_msgs::PointCloud2Iterator iter_y(expected_pointcloud_msg, "y"); sensor_msgs::PointCloud2Iterator iter_z(expected_pointcloud_msg, "z"); - sensor_msgs::PointCloud2Iterator iter_t(expected_pointcloud_msg, "time_stamp"); + sensor_msgs::PointCloud2Iterator iter_t(expected_pointcloud_msg, "time_stamp"); std::vector expected_points; for (; iter_t != iter_t.end(); ++iter_t, ++iter_x, ++iter_y, ++iter_z) { - double time_offset = *iter_t - timestamp.seconds(); + double time_offset = static_cast(*iter_t) / 1e9; expected_points.emplace_back( *iter_x + static_cast(velocity * time_offset), *iter_y, *iter_z); } @@ -822,11 +827,11 @@ TEST_F(DistortionCorrectorTest, TestUndistortPointCloudWithPureRotationalMotion) sensor_msgs::PointCloud2Iterator iter_x(expected_pointcloud_msg, "x"); sensor_msgs::PointCloud2Iterator iter_y(expected_pointcloud_msg, "y"); sensor_msgs::PointCloud2Iterator iter_z(expected_pointcloud_msg, "z"); - sensor_msgs::PointCloud2Iterator iter_t(expected_pointcloud_msg, "time_stamp"); + sensor_msgs::PointCloud2Iterator iter_t(expected_pointcloud_msg, "time_stamp"); std::vector expected_pointcloud; for (; iter_t != iter_t.end(); ++iter_t, ++iter_x, ++iter_y, ++iter_z) { - double time_offset = *iter_t - timestamp.seconds(); + double time_offset = static_cast(*iter_t) / 1e9; float angle = angular_velocity * time_offset; // Set the quaternion for the current angle diff --git a/sensing/pointcloud_preprocessor/test/test_utilities.cpp b/sensing/pointcloud_preprocessor/test/test_utilities.cpp index 68c86dfbd0505..e3075b4b11e79 100644 --- a/sensing/pointcloud_preprocessor/test/test_utilities.cpp +++ b/sensing/pointcloud_preprocessor/test/test_utilities.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pointcloud_preprocessor/utility/utilities.hpp" +#include "pointcloud_preprocessor/utility/geometry.hpp" #include From 9b6db8cbf3e99a263e032d11adbbec5d3d8d7743 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 20 Sep 2024 10:48:31 +0900 Subject: [PATCH 142/151] fix(lidar_centerpoint, pointpainting): increase CAPACITY_POINT to avoid crashing (#1546) Signed-off-by: Tomohito Ando --- .../pointpainting_fusion/pointpainting_trt.hpp | 2 +- .../include/lidar_centerpoint/centerpoint_trt.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp index d28d9eb31216d..d5892de6d7edb 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp @@ -23,7 +23,7 @@ namespace image_projection_based_fusion { -static constexpr size_t CAPACITY_POINT = 1000000; +static constexpr size_t CAPACITY_POINT = 2000000; class PointPaintingTRT : public centerpoint::CenterPointTRT { public: diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp index 8cf250be0c049..383e8ef719d4d 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp @@ -32,7 +32,7 @@ namespace centerpoint { -static constexpr size_t CAPACITY_POINT = 1000000; +static constexpr size_t CAPACITY_POINT = 2000000; class NetworkParam { From afedb2f714957ccd20a886325e11e83241dd6ea6 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Mon, 7 Oct 2024 15:15:08 +0900 Subject: [PATCH 143/151] chore(path_optimizer): add warn msg for exceptional behavior (#9033) (#1580) Signed-off-by: Yuki Takagi --- planning/autoware_path_optimizer/src/mpt_optimizer.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index 1d49b6cb77d59..7697760fb960c 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -477,8 +477,13 @@ std::vector MPTOptimizer::optimizeTrajectory(const PlannerData const auto get_prev_optimized_traj_points = [&]() { if (prev_optimized_traj_points_ptr_) { + RCLCPP_WARN(logger_, "return the previous optimized_trajectory as exceptional behavior."); return *prev_optimized_traj_points_ptr_; } + RCLCPP_WARN( + logger_, + "Try to return the previous optimized_trajectory as exceptional behavior, " + "but this failure also. Then return path_smoother output."); return traj_points; }; @@ -505,8 +510,7 @@ std::vector MPTOptimizer::optimizeTrajectory(const PlannerData // 6. optimize steer angles const auto optimized_variables = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat); if (!optimized_variables) { - RCLCPP_INFO_EXPRESSION( - logger_, enable_debug_info_, "return std::nullopt since could not solve qp"); + RCLCPP_WARN(logger_, "return std::nullopt since could not solve qp"); return get_prev_optimized_traj_points(); } From 151d5d7474db9cbef549d167b2b4f130a76485b2 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Thu, 17 Oct 2024 16:51:18 +0900 Subject: [PATCH 144/151] chore(autoware_pointcloud_preprocessor): change unnecessary warning message to debug (#8525) (#1590) Co-authored-by: Yi-Hsiang Fang (Vivid) <146902905+vividf@users.noreply.github.com> --- .../src/concatenate_data/concatenate_and_time_sync_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index e998a79b27f77..d531d1b89b478 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -286,7 +286,7 @@ PointCloudConcatenateDataSynchronizerComponent::computeTransformToAdjustForOldTi // return identity if old_stamp is newer than new_stamp if (old_stamp > new_stamp) { - RCLCPP_WARN_STREAM_THROTTLE( + RCLCPP_DEBUG_STREAM_THROTTLE( get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), "old_stamp is newer than new_stamp,"); return Eigen::Matrix4f::Identity(); From bad00078065b71ce3ae6fa60ecff83a280f41aef Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 23 Oct 2024 10:26:01 +0900 Subject: [PATCH 145/151] chore(stop_filter): extract stop_filter.param.yaml to autoware_launch (#8681) (#1591) Co-authored-by: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> --- launch/tier4_localization_launch/launch/localization.launch.xml | 1 + .../pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index cfc09459a5cb1..e75e42da346ad 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -14,6 +14,7 @@ + diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index bdea584bd58ae..9f840182a007a 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -22,6 +22,7 @@ + From fdd665d67620403d03bd8e4477f244acd6ec0613 Mon Sep 17 00:00:00 2001 From: Xiaoyu WANG Date: Thu, 24 Oct 2024 08:46:08 +0900 Subject: [PATCH 146/151] fix: remove ScopedTimeTrack which causes goal planner crash (#1599) --- .../src/goal_planner_module.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 54a1c0830fb06..cfe5c797d7130 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1244,8 +1244,6 @@ bool GoalPlannerModule::hasDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1261,8 +1259,6 @@ bool GoalPlannerModule::hasNotDecidedPath( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - return checkDecidingPathStatus( planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, goal_searcher) @@ -1278,8 +1274,6 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const std::shared_ptr & safety_check_params, const std::shared_ptr goal_searcher) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; @@ -2375,8 +2369,6 @@ std::pair GoalPlannerModule::isSafePath( const std::shared_ptr & objects_filtering_params, const std::shared_ptr & safety_check_params) const { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } From 787f215fea4c75d424cfc6f3b4ed80f96bf2530c Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 29 Oct 2024 20:12:57 +0900 Subject: [PATCH 147/151] fix: fix internal door interface qos (#9144) Signed-off-by: Takagi, Isamu --- .../include/component_interface_specs/vehicle.hpp | 2 +- simulator/vehicle_door_simulator/src/dummy_doors.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp index e7ce2c5212a25..68c7c9c2cd606 100644 --- a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp +++ b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp @@ -92,7 +92,7 @@ struct DoorStatus static constexpr char name[] = "/vehicle/doors/status"; static constexpr size_t depth = 1; static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; - static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; } // namespace vehicle_interface diff --git a/simulator/vehicle_door_simulator/src/dummy_doors.cpp b/simulator/vehicle_door_simulator/src/dummy_doors.cpp index b78ca9973e7e1..cad0aa721dc73 100644 --- a/simulator/vehicle_door_simulator/src/dummy_doors.cpp +++ b/simulator/vehicle_door_simulator/src/dummy_doors.cpp @@ -29,7 +29,8 @@ DummyDoors::DummyDoors() : Node("dummy_doors") srv_layout_ = create_service( "~/doors/layout", std::bind(&DummyDoors::on_layout, this, _1, _2)); - pub_status_ = create_publisher("~/doors/status", rclcpp::QoS(1)); + pub_status_ = + create_publisher("~/doors/status", rclcpp::QoS(1).transient_local()); const auto period = rclcpp::Rate(5.0).period(); timer_ = rclcpp::create_timer(this, get_clock(), period, [this]() { on_timer(); }); From 3f2ba2686478aa6ac4eafff7d67c9db344cb60d8 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 27 Aug 2024 14:04:32 +0900 Subject: [PATCH 148/151] fix(goal_planner): fix zero velocity in middle of path (#8563) * fix(goal_planner): fix zero velocity in middle of path Signed-off-by: kosuke55 * add comment Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../util.hpp | 27 ++++++++++++++++--- .../src/goal_planner_module.cpp | 10 ++++++- .../src/shift_pull_over.cpp | 6 ++++- .../src/util.cpp | 11 +++++--- 4 files changed, 45 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp index 3c717a90c93ef..9739a87d0be30 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp @@ -82,12 +82,31 @@ bool isReferencePath( std::optional cropPath(const PathWithLaneId & path, const Pose & end_pose); PathWithLaneId cropForwardPoints( const PathWithLaneId & path, const size_t target_seg_idx, const double forward_length); + +/** + * @brief extend target_path by extend_length + * @param target_path original target path to extend + * @param reference_path reference path to extend + * @param extend_length length to extend + * @param remove_connected_zero_velocity flag to remove zero velocity if the last point of + * target_path has zero velocity + * @return extended path + */ PathWithLaneId extendPath( - const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, - const double extend_length); + const PathWithLaneId & target_path, const PathWithLaneId & reference_path, + const double extend_length, const bool remove_connected_zero_velocity); +/** + * @brief extend target_path to extend_pose + * @param target_path original target path to extend + * @param reference_path reference path to extend + * @param extend_pose pose to extend + * @param remove_connected_zero_velocity flag to remove zero velocity if the last point of + * target_path has zero velocity + * @return extended path + */ PathWithLaneId extendPath( - const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, - const Pose & extend_pose); + const PathWithLaneId & target_path, const PathWithLaneId & reference_path, + const Pose & extend_pose, const bool remove_connected_zero_velocity); std::vector createPathFootPrints( const PathWithLaneId & path, const double base_to_front, const double base_to_rear, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index cfe5c797d7130..63d8468ee4470 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -283,6 +283,10 @@ void GoalPlannerModule::onTimer() RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; } + // TODO(someone): The generated path inherits the velocity of the path of the previous module. + // Therefore, if the velocity of the path of the previous module changes (e.g. stop points are + // inserted, deleted), the path should be regenerated. + return false; }); if (!need_update) { @@ -1666,8 +1670,12 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const const double s_end = s_current + common_parameters.forward_path_length; return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); }); + + // NOTE: The previous module may insert a zero velocity at the end of the path, so remove it by + // setting remove_connected_zero_velocity=true. Inserting a velocity of 0 into the goal is the + // role of the goal planner, and the intermediate zero velocity after extension is unnecessary. const auto extended_prev_path = goal_planner_utils::extendPath( - getPreviousModuleOutput().path, reference_path, common_parameters.forward_path_length); + getPreviousModuleOutput().path, reference_path, common_parameters.forward_path_length, true); // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp index ba1ebfade0127..7d7c1b57f2b59 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -148,8 +148,12 @@ std::optional ShiftPullOver::generatePullOverPath( lanelet::utils::getArcCoordinates(road_lanes, shift_end_pose).length > lanelet::utils::getArcCoordinates(road_lanes, prev_module_path_terminal_pose).length; if (extend_previous_module_path) { // case1 + // NOTE: The previous module may insert a zero velocity at the end of the path, so remove it + // by setting remove_connected_zero_velocity=true. Inserting a velocity of 0 into the goal is + // the role of the goal planner, and the intermediate zero velocity after extension is + // unnecessary. return goal_planner_utils::extendPath( - prev_module_path, road_lane_reference_path_to_shift_end, shift_end_pose); + prev_module_path, road_lane_reference_path_to_shift_end, shift_end_pose, true); } else { // case2 return goal_planner_utils::cropPath(prev_module_path, shift_end_pose); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index 4526c584afd12..3b4d39d0c3a79 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -388,7 +388,7 @@ PathWithLaneId cropForwardPoints( PathWithLaneId extendPath( const PathWithLaneId & target_path, const PathWithLaneId & reference_path, - const double extend_length) + const double extend_length, const bool remove_connected_zero_velocity) { const auto & target_terminal_pose = target_path.points.back().point.pose; @@ -408,6 +408,11 @@ PathWithLaneId extendPath( } auto extended_path = target_path; + auto & target_terminal_vel = extended_path.points.back().point.longitudinal_velocity_mps; + if (remove_connected_zero_velocity && target_terminal_vel < 0.01) { + target_terminal_vel = clipped_path.points.front().point.longitudinal_velocity_mps; + } + const auto start_point = std::find_if(clipped_path.points.begin(), clipped_path.points.end(), [&](const auto & p) { const bool is_forward = @@ -426,7 +431,7 @@ PathWithLaneId extendPath( PathWithLaneId extendPath( const PathWithLaneId & target_path, const PathWithLaneId & reference_path, - const Pose & extend_pose) + const Pose & extend_pose, const bool remove_connected_zero_velocity) { const auto & target_terminal_pose = target_path.points.back().point.pose; const size_t target_path_terminal_idx = autoware::motion_utils::findNearestSegmentIndex( @@ -434,7 +439,7 @@ PathWithLaneId extendPath( const double extend_distance = autoware::motion_utils::calcSignedArcLength( reference_path.points, target_path_terminal_idx, extend_pose.position); - return extendPath(target_path, reference_path, extend_distance); + return extendPath(target_path, reference_path, extend_distance, remove_connected_zero_velocity); } std::vector createPathFootPrints( From 2eba6ab5e6bf604be6183e3603da19f046893eab Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 4 Sep 2024 01:37:33 +0900 Subject: [PATCH 149/151] feat(goal_planner): extend pull over lanes inward to extract objects (#8714) * feat(goal_planner): extend pull over lanes inward to extract objects Signed-off-by: kosuke55 * update from review Signed-off-by: kosuke55 * use optionale Signed-off-by: kosuke55 * rename lamda Signed-off-by: kosuke55 * return nullopt Signed-off-by: kosuke55 * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp Co-authored-by: Mamoru Sobue * pre-commit Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Mamoru Sobue --- .../goal_planner_module.hpp | 1 + .../goal_searcher.hpp | 10 +- .../goal_searcher_base.hpp | 10 +- .../util.hpp | 13 ++ .../src/goal_planner_module.cpp | 65 ++++++++-- .../src/goal_searcher.cpp | 34 ++--- .../src/util.cpp | 121 ++++++++++++++++++ 7 files changed, 204 insertions(+), 50 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 4c23292f63e61..98ae9e2a941d3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -266,6 +266,7 @@ struct GoalPlannerDebugData FreespacePlannerDebugData freespace_planner{}; std::vector ego_polygons_expanded{}; lanelet::ConstLanelet expanded_pull_over_lane_between_ego{}; + Polygon2d objects_extraction_polygon{}; }; struct LastApprovalData diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp index 5d056add4665e..6bdad3a3063ef 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp @@ -31,13 +31,12 @@ class GoalSearcher : public GoalSearcherBase public: GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint); - GoalCandidates search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) override; + GoalCandidates search(const std::shared_ptr & planner_data) override; void update( GoalCandidates & goal_candidates, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const override; + const std::shared_ptr & planner_data, + const PredictedObjects & objects) const override; // todo(kosuke55): Functions for this specific use should not be in the interface, // so it is better to consider interface design when we implement other goal searchers. @@ -47,7 +46,8 @@ class GoalSearcher : public GoalSearcherBase bool isSafeGoalWithMarginScaleFactor( const GoalCandidate & goal_candidate, const double margin_scale_factor, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const override; + const std::shared_ptr & planner_data, + const PredictedObjects & objects) const override; private: void countObjectsToAvoid( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp index baead4c229efd..b7d6ffe0710fe 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -53,13 +53,12 @@ class GoalSearcherBase const Pose & getReferenceGoal() const { return reference_goal_pose_; } MultiPolygon2d getAreaPolygons() const { return area_polygons_; } - virtual GoalCandidates search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) = 0; + virtual GoalCandidates search(const std::shared_ptr & planner_data) = 0; virtual void update( [[maybe_unused]] GoalCandidates & goal_candidates, [[maybe_unused]] const std::shared_ptr occupancy_grid_map, - [[maybe_unused]] const std::shared_ptr & planner_data) const + [[maybe_unused]] const std::shared_ptr & planner_data, + [[maybe_unused]] const PredictedObjects & objects) const { return; } @@ -69,7 +68,8 @@ class GoalSearcherBase virtual bool isSafeGoalWithMarginScaleFactor( const GoalCandidate & goal_candidate, const double margin_scale_factor, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const = 0; + const std::shared_ptr & planner_data, + const PredictedObjects & objects) const = 0; protected: GoalPlannerParameters parameters_{}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp index 9739a87d0be30..ed8b518904d46 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp @@ -62,6 +62,19 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( const geometry_msgs::msg::Pose ego_pose, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double outer_road_offset, const double inner_road_offset); + +/* + * @brief generate polygon to extract objects + * @param pull_over_lanes pull over lanes + * @param left_side left side or right side + * @param outer_offset outer offset from pull over lane boundary + * @param inner_offset inner offset from pull over lane boundary + * @return polygon to extract objects + */ +std::optional generateObjectExtractionPolygon( + const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, const double outer_offset, + const double inner_offset); + PredictedObjects extractObjectsInExpandedPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, const double forward_distance, double bound_offset, const PredictedObjects & objects); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 63d8468ee4470..2c8385fdcc293 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -459,18 +459,33 @@ void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - // extract static and dynamic objects in expanded pull over lanes + // extract static and dynamic objects in extraction polygon for path coliision check { const auto & p = parameters_; const auto & rh = *(planner_data_->route_handler); const auto objects = *(planner_data_->dynamic_object); - const auto static_target_objects = - goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects, p->th_moving_object_velocity); - const auto dynamic_target_objects = goal_planner_utils::extractObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects); + const double vehicle_width = planner_data_->parameters.vehicle_width; + const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( + rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length); + const auto objects_extraction_polygon = goal_planner_utils::generateObjectExtractionPolygon( + pull_over_lanes, left_side_parking_, p->detection_bound_offset, + p->margin_from_boundary + p->max_lateral_offset + vehicle_width); + if (objects_extraction_polygon.has_value()) { + debug_data_.objects_extraction_polygon = objects_extraction_polygon.value(); + } + PredictedObjects dynamic_target_objects{}; + for (const auto & object : objects.objects) { + const auto object_polygon = universe_utils::toPolygon2d(object); + if ( + objects_extraction_polygon.has_value() && + boost::geometry::intersects(object_polygon, objects_extraction_polygon.value())) { + dynamic_target_objects.objects.push_back(object); + } + } + const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_target_objects, p->th_moving_object_velocity); + + // these objects are used for path collision check not for safety check thread_safe_data_.set_static_target_objects(static_target_objects); thread_safe_data_.set_dynamic_target_objects(dynamic_target_objects); } @@ -739,7 +754,9 @@ bool GoalPlannerModule::planFreespacePath( { GoalCandidates goal_candidates{}; goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data); + goal_searcher->update( + goal_candidates, occupancy_grid_map, planner_data, + thread_safe_data_.get_static_target_objects()); thread_safe_data_.set_goal_candidates(goal_candidates); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; @@ -823,7 +840,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const // calculate goal candidates const auto & route_handler = planner_data_->route_handler; if (utils::isAllowedGoalModification(route_handler)) { - return goal_searcher_->search(occupancy_grid_map_, planner_data_); + return goal_searcher_->search(planner_data_); } // NOTE: @@ -1317,9 +1334,9 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( // check goal pose collision const auto modified_goal_opt = thread_safe_data_.get_modified_goal_pose(); if ( - modified_goal_opt && - !goal_searcher->isSafeGoalWithMarginScaleFactor( - modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, planner_data)) { + modified_goal_opt && !goal_searcher->isSafeGoalWithMarginScaleFactor( + modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, + planner_data, thread_safe_data_.get_static_target_objects())) { RCLCPP_DEBUG(getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } @@ -1475,7 +1492,9 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() // update goal candidates auto goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates, occupancy_grid_map_, planner_data_); + goal_searcher_->update( + goal_candidates, occupancy_grid_map_, planner_data_, + thread_safe_data_.get_static_target_objects()); // update pull over path candidates const auto pull_over_path_candidates = sortPullOverPathCandidatesByGoalPriority( @@ -2552,6 +2571,24 @@ void GoalPlannerModule::setDebugData() // Visualize goal candidates const auto goal_candidates = thread_safe_data_.get_goal_candidates(); add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); + + // Visualize objects extraction polygon + auto marker = autoware::universe_utils::createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "objects_extraction_polygon", 0, Marker::LINE_LIST, + autoware::universe_utils::createMarkerScale(0.1, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(0.0, 1.0, 1.0, 0.999)); + const double ego_z = planner_data_->self_odometry->pose.pose.position.z; + for (size_t i = 0; i < debug_data_.objects_extraction_polygon.outer().size(); ++i) { + const auto & current_point = debug_data_.objects_extraction_polygon.outer().at(i); + const auto & next_point = debug_data_.objects_extraction_polygon.outer().at( + (i + 1) % debug_data_.objects_extraction_polygon.outer().size()); + marker.points.push_back( + autoware::universe_utils::createPoint(current_point.x(), current_point.y(), ego_z)); + marker.points.push_back( + autoware::universe_utils::createPoint(next_point.x(), next_point.y(), ego_z)); + } + + debug_marker_.markers.push_back(marker); } // Visualize previous module output diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp index 04ee5278912ac..0a135562ddc6b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -97,9 +97,7 @@ GoalSearcher::GoalSearcher( { } -GoalCandidates GoalSearcher::search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) +GoalCandidates GoalSearcher::search(const std::shared_ptr & planner_data) { GoalCandidates goal_candidates{}; @@ -195,8 +193,6 @@ GoalCandidates GoalSearcher::search( } createAreaPolygons(original_search_poses, planner_data); - update(goal_candidates, occupancy_grid_map, planner_data); - return goal_candidates; } @@ -268,16 +264,10 @@ void GoalSearcher::countObjectsToAvoid( void GoalSearcher::update( GoalCandidates & goal_candidates, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const + const std::shared_ptr & planner_data, const PredictedObjects & objects) const { - const auto pull_over_lane_stop_objects = - goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, - parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); - if (parameters_.prioritize_goals_before_objects) { - countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects, planner_data); + countObjectsToAvoid(goal_candidates, objects, planner_data); } if (parameters_.goal_priority == "minimum_weighted_distance") { @@ -297,7 +287,7 @@ void GoalSearcher::update( const Pose goal_pose = goal_candidate.goal_pose; // check collision with footprint - if (checkCollision(goal_pose, pull_over_lane_stop_objects, occupancy_grid_map)) { + if (checkCollision(goal_pose, objects, occupancy_grid_map)) { goal_candidate.is_safe = false; continue; } @@ -305,7 +295,7 @@ void GoalSearcher::update( // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, + goal_pose, planner_data->parameters.vehicle_width, objects, parameters_.object_recognition_collision_check_hard_margins.back(), filter_inside); if (checkCollisionWithLongitudinalDistance( goal_pose, target_objects, occupancy_grid_map, planner_data)) { @@ -323,33 +313,25 @@ void GoalSearcher::update( bool GoalSearcher::isSafeGoalWithMarginScaleFactor( const GoalCandidate & goal_candidate, const double margin_scale_factor, const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const + const std::shared_ptr & planner_data, const PredictedObjects & objects) const { if (!parameters_.use_object_recognition) { return true; } const Pose goal_pose = goal_candidate.goal_pose; - - const auto pull_over_lane_stop_objects = - goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, - parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); - const double margin = parameters_.object_recognition_collision_check_hard_margins.back() * margin_scale_factor; if (utils::checkCollisionBetweenFootprintAndObjects( - vehicle_footprint_, goal_pose, pull_over_lane_stop_objects, margin)) { + vehicle_footprint_, goal_pose, objects, margin)) { return false; } // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, margin, - filter_inside); + goal_pose, planner_data->parameters.vehicle_width, objects, margin, filter_inside); if (checkCollisionWithLongitudinalDistance( goal_pose, target_objects, occupancy_grid_map, planner_data)) { return false; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index 3b4d39d0c3a79..9ad69411ded49 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -38,6 +38,7 @@ namespace autoware::behavior_path_planner::goal_planner_utils { +using autoware::universe_utils::calcDistance2d; using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::createDefaultMarker; using autoware::universe_utils::createMarkerColor; @@ -137,6 +138,126 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( -outer_road_offset); } +std::optional generateObjectExtractionPolygon( + const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, const double outer_offset, + const double inner_offset) +{ + // generate base boundary poses without orientation + std::vector base_boundary_poses{}; + for (const auto & lane : pull_over_lanes) { + const auto & bound = left_side ? lane.leftBound() : lane.rightBound(); + for (const auto & p : bound) { + Pose pose{}; + pose.position = createPoint(p.x(), p.y(), p.z()); + if (std::any_of(base_boundary_poses.begin(), base_boundary_poses.end(), [&](const auto & p) { + return calcDistance2d(p.position, pose.position) < 0.1; + })) { + continue; + } + base_boundary_poses.push_back(pose); + } + } + if (base_boundary_poses.size() < 2) { + return std::nullopt; + } + + // set orientation to next point + for (auto it = base_boundary_poses.begin(); it != std::prev(base_boundary_poses.end()); ++it) { + const auto & p = it->position; + const auto & next_p = std::next(it)->position; + const double yaw = autoware::universe_utils::calcAzimuthAngle(p, next_p); + it->orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + } + base_boundary_poses.back().orientation = + base_boundary_poses[base_boundary_poses.size() - 2].orientation; + + // generate outer and inner boundary poses + std::vector outer_boundary_points{}; + std::vector inner_boundary_points{}; + const double outer_direction_sign = left_side ? 1.0 : -1.0; + for (const auto & base_pose : base_boundary_poses) { + const Pose outer_pose = calcOffsetPose(base_pose, 0, outer_direction_sign * outer_offset, 0); + const Pose inner_pose = calcOffsetPose(base_pose, 0, -outer_direction_sign * inner_offset, 0); + outer_boundary_points.push_back(outer_pose.position); + inner_boundary_points.push_back(inner_pose.position); + } + + // remove self intersection + // if bound is intersected, remove them and insert intersection point + using BoostPoint = boost::geometry::model::d2::point_xy; + using LineString = boost::geometry::model::linestring; + const auto remove_self_intersection = [](const std::vector & bound) { + constexpr double INTERSECTION_CHECK_DISTANCE = 10.0; + std::vector modified_bound{}; + size_t i = 0; + while (i < bound.size() - 2) { + BoostPoint p1(bound.at(i).x, bound.at(i).y); + BoostPoint p2(bound.at(i + 1).x, bound.at(i + 1).y); + LineString p_line{}; + p_line.push_back(p1); + p_line.push_back(p2); + bool intersection_found = false; + for (size_t j = i + 2; j < bound.size() - 1; j++) { + const double distance = autoware::universe_utils::calcDistance2d(bound.at(i), bound.at(j)); + if (distance > INTERSECTION_CHECK_DISTANCE) { + break; + } + LineString q_line{}; + BoostPoint q1(bound.at(j).x, bound.at(j).y); + BoostPoint q2(bound.at(j + 1).x, bound.at(j + 1).y); + q_line.push_back(q1); + q_line.push_back(q2); + std::vector intersection_points; + boost::geometry::intersection(p_line, q_line, intersection_points); + if (intersection_points.empty()) { + continue; + } + modified_bound.push_back(bound.at(i)); + Point intersection_point{}; + intersection_point.x = intersection_points.at(0).x(); + intersection_point.y = intersection_points.at(0).y(); + intersection_point.z = bound.at(i).z; + modified_bound.push_back(intersection_point); + i = j + 1; + intersection_found = true; + break; + } + if (!intersection_found) { + modified_bound.push_back(bound.at(i)); + i++; + } + } + modified_bound.push_back(bound.back()); + return modified_bound; + }; + outer_boundary_points = remove_self_intersection(outer_boundary_points); + inner_boundary_points = remove_self_intersection(inner_boundary_points); + + // create clockwise polygon + Polygon2d polygon{}; + const auto & left_boundary_points = left_side ? outer_boundary_points : inner_boundary_points; + const auto & right_boundary_points = left_side ? inner_boundary_points : outer_boundary_points; + std::vector reversed_right_boundary_points = right_boundary_points; + std::reverse(reversed_right_boundary_points.begin(), reversed_right_boundary_points.end()); + for (const auto & left_point : left_boundary_points) { + autoware::universe_utils::Point2d point{left_point.x, left_point.y}; + polygon.outer().push_back(point); + } + for (const auto & right_point : reversed_right_boundary_points) { + autoware::universe_utils::Point2d point{right_point.x, right_point.y}; + polygon.outer().push_back(point); + } + autoware::universe_utils::Point2d first_point{ + left_boundary_points.front().x, left_boundary_points.front().y}; + polygon.outer().push_back(first_point); + + if (polygon.outer().size() < 3) { + return std::nullopt; + } + + return polygon; +} + PredictedObjects extractObjectsInExpandedPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, const double forward_distance, double bound_offset, const PredictedObjects & objects) From a82b1cb0a92240e417a4aecd3c3faa10aa39022c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 10 Sep 2024 03:19:09 +0900 Subject: [PATCH 150/151] feat(goal_planner): execute goal planner if previous module path terminal is pull over neighboring lane (#8715) Signed-off-by: kosuke55 --- .../README.md | 2 +- .../src/goal_planner_module.cpp | 45 ++++++++++++------- 2 files changed, 29 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md index 5e93c86c9be1c..485ec4cb2a359 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/README.md @@ -107,7 +107,7 @@ If the target path contains a goal, modify the points of the path so that the pa - Route is set with `allow_goal_modification=true` . - We can set this option with [SetRoute](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/routing/srv/SetRoute.srv#L2) api service. - We support `2D Rough Goal Pose` with the key bind `r` in RViz, but in the future there will be a panel of tools to manipulate various Route API from RViz. -- ego-vehicle is in the same lane as the goal. +- The terminal point of the current path is in the same lane sequence as the goal. If goal is on the road shoulder, then it is in the adjacent road lane sequence. diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 2c8385fdcc293..b321abe1490a1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -596,15 +596,25 @@ bool GoalPlannerModule::isExecutionRequested() const const Pose & current_pose = planner_data_->self_odometry->pose.pose; const Pose goal_pose = route_handler->getOriginalGoalPose(); - // check if goal_pose is in current_lanes. - lanelet::ConstLanelet current_lane{}; - // const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + // check if goal_pose is in current_lanes or neighboring road lanes const lanelet::ConstLanelets current_lanes = utils::getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_); - lanelet::utils::query::getClosestLanelet(current_lanes, current_pose, ¤t_lane); - const bool goal_is_in_current_lanes = std::any_of( - current_lanes.begin(), current_lanes.end(), [&](const lanelet::ConstLanelet & current_lane) { - return lanelet::utils::isInLanelet(goal_pose, current_lane); + const auto getNeighboringLane = + [&](const lanelet::ConstLanelet & lane) -> std::optional { + return left_side_parking_ ? route_handler->getLeftLanelet(lane, false, true) + : route_handler->getRightLanelet(lane, false, true); + }; + lanelet::ConstLanelets goal_check_lanes = current_lanes; + for (const auto & lane : current_lanes) { + auto neighboring_lane = getNeighboringLane(lane); + while (neighboring_lane) { + goal_check_lanes.push_back(neighboring_lane.value()); + neighboring_lane = getNeighboringLane(neighboring_lane.value()); + } + } + const bool goal_is_in_current_segment_lanes = std::any_of( + goal_check_lanes.begin(), goal_check_lanes.end(), [&](const lanelet::ConstLanelet & lane) { + return lanelet::utils::isInLanelet(goal_pose, lane); }); // check that goal is in current neighbor shoulder lane @@ -621,7 +631,7 @@ bool GoalPlannerModule::isExecutionRequested() const // if goal is not in current_lanes and current_shoulder_lanes, do not execute goal_planner, // because goal arc coordinates cannot be calculated. - if (!goal_is_in_current_lanes && !goal_is_in_current_shoulder_lanes) { + if (!goal_is_in_current_segment_lanes && !goal_is_in_current_shoulder_lanes) { return false; } @@ -629,7 +639,7 @@ bool GoalPlannerModule::isExecutionRequested() const // 1) goal_pose is in current_lanes, plan path to the original fixed goal // 2) goal_pose is NOT in current_lanes, do not execute goal_planner if (!utils::isAllowedGoalModification(route_handler)) { - return goal_is_in_current_lanes; + return goal_is_in_current_segment_lanes; } // if goal arc coordinates can be calculated, check if goal is in request_length @@ -651,7 +661,12 @@ bool GoalPlannerModule::isExecutionRequested() const parameters_->forward_goal_search_length); lanelet::ConstLanelet target_lane{}; lanelet::utils::query::getClosestLanelet(pull_over_lanes, goal_pose, &target_lane); - if (!isCrossingPossible(current_lane, target_lane)) { + + lanelet::ConstLanelet previous_module_terminal_lane{}; + route_handler->getClosestLaneletWithinRoute( + getPreviousModuleOutput().path.points.back().point.pose, &previous_module_terminal_lane); + + if (!isCrossingPossible(previous_module_terminal_lane, target_lane)) { return false; } @@ -2274,14 +2289,10 @@ bool GoalPlannerModule::isCrossingPossible( end_lane_sequence = route_handler->getLaneletSequence(end_lane, dist, dist, false); } - // Lambda function to get the neighboring lanelet based on left_side_parking_ - auto getNeighboringLane = + const auto getNeighboringLane = [&](const lanelet::ConstLanelet & lane) -> std::optional { - const auto neighboring_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane) - : route_handler->getRightShoulderLanelet(lane); - if (neighboring_lane) return neighboring_lane; - return left_side_parking_ ? route_handler->getLeftLanelet(lane) - : route_handler->getRightLanelet(lane); + return left_side_parking_ ? route_handler->getLeftLanelet(lane, false, true) + : route_handler->getRightLanelet(lane, false, true); }; // Iterate through start_lane_sequence to find a path to end_lane_sequence From f7167830f0b9c4b465299324e47b5ace1eb5c37a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 26 Sep 2024 19:50:57 +0900 Subject: [PATCH 151/151] feat(goal_planner): use neighboring lane of pull over lane to check goal footprint (#8716) move to utils and add tests Signed-off-by: kosuke55 --- .../util.hpp | 23 +++ .../src/goal_searcher.cpp | 10 +- .../src/util.cpp | 92 ++++++++++ .../test/test_util.cpp | 167 ++++++++++++++++++ 4 files changed, 286 insertions(+), 6 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp index ed8b518904d46..0f9eda8efe25c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp @@ -141,6 +141,29 @@ MarkerArray createLaneletPolygonMarkerArray( MarkerArray createNumObjectsToAvoidTextsMarkerArray( const GoalCandidates & goal_candidates, std::string && ns, const std_msgs::msg::ColorRGBA & color); +std::string makePathPriorityDebugMessage( + const std::vector & sorted_path_indices, + const std::vector & pull_over_path_candidates, + const std::map & goal_id_to_index, const GoalCandidates & goal_candidates, + const std::map & path_id_to_rough_margin_map, + const std::function & isSoftMargin, + const std::function & isHighCurvature); +/** + * @brief combine two points + * @param points lane points + * @param points_next next lane points + * @return combined points + */ +lanelet::Points3d combineLanePoints( + const lanelet::Points3d & points, const lanelet::Points3d & points_next); +/** @brief Create a lanelet that represents the departure check area. + * @param [in] pull_over_lanes Lanelets that the vehicle will pull over to. + * @param [in] route_handler RouteHandler object. + * @return Lanelet that goal footprints should be inside. + */ +lanelet::Lanelet createDepartureCheckLanelet( + const lanelet::ConstLanelets & pull_over_lanes, const route_handler::RouteHandler & route_handler, + const bool left_side_parking); } // namespace autoware::behavior_path_planner::goal_planner_utils #endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp index 0a135562ddc6b..4f0a18e01d034 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -115,11 +115,8 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); - auto lanes = utils::getExtendedCurrentLanes( - planner_data, backward_length, forward_length, - /*forward_only_in_route*/ false); - lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); - + const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet( + pull_over_lanes, *route_handler, left_side_parking_); const auto goal_arc_coords = lanelet::utils::getArcCoordinates(pull_over_lanes, reference_goal_pose_); const double s_start = std::max(0.0, goal_arc_coords.length - backward_length); @@ -177,7 +174,8 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p break; } - if (LaneDepartureChecker::isOutOfLane(lanes, transformed_vehicle_footprint)) { + if (!boost::geometry::within( + transformed_vehicle_footprint, departure_check_lane.polygon2d().basicPolygon())) { continue; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index 9ad69411ded49..96cb7d9cdf436 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -576,4 +576,96 @@ std::vector createPathFootPrints( return footprints; } +std::string makePathPriorityDebugMessage( + const std::vector & sorted_path_indices, + const std::vector & pull_over_path_candidates, + const std::map & goal_id_to_index, const GoalCandidates & goal_candidates, + const std::map & path_id_to_rough_margin_map, + const std::function & isSoftMargin, + const std::function & isHighCurvature) +{ + std::stringstream ss; + + // Unsafe goal and its priority are not visible as debug marker in rviz, + // so exclude unsafe goal from goal_priority + std::map goal_id_and_priority; + for (size_t i = 0; i < goal_candidates.size(); ++i) { + goal_id_and_priority[goal_candidates[i].id] = goal_candidates[i].is_safe ? i : -1; + } + + ss << "\n---------------------- path priority ----------------------\n"; + for (size_t i = 0; i < sorted_path_indices.size(); ++i) { + const auto & path = pull_over_path_candidates[sorted_path_indices[i]]; + // goal_index is same to goal priority including unsafe goal + const int goal_index = static_cast(goal_id_to_index.at(path.goal_id)); + const bool is_safe_goal = goal_candidates[goal_index].is_safe; + const int goal_priority = goal_id_and_priority[path.goal_id]; + + ss << "path_priority: " << i << ", path_type: " << magic_enum::enum_name(path.type) + << ", path_id: " << path.id << ", goal_id: " << path.goal_id + << ", goal_priority: " << (is_safe_goal ? std::to_string(goal_priority) : "unsafe") + << ", margin: " << path_id_to_rough_margin_map.at(path.id) + << (isSoftMargin(path) ? " (soft)" : " (hard)") + << ", curvature: " << path.getParkingPathMaxCurvature() + << (isHighCurvature(path) ? " (high)" : " (low)") << "\n"; + } + ss << "-----------------------------------------------------------\n"; + return ss.str(); +} + +lanelet::Points3d combineLanePoints( + const lanelet::Points3d & points, const lanelet::Points3d & points_next) +{ + lanelet::Points3d combined_points; + std::unordered_set point_ids; + for (const auto & point : points) { + if (point_ids.insert(point.id()).second) { + combined_points.push_back(point); + } + } + for (const auto & point : points_next) { + if (point_ids.insert(point.id()).second) { + combined_points.push_back(point); + } + } + return combined_points; +} + +lanelet::Lanelet createDepartureCheckLanelet( + const lanelet::ConstLanelets & pull_over_lanes, const route_handler::RouteHandler & route_handler, + const bool left_side_parking) +{ + const auto getBoundPoints = + [&](const lanelet::ConstLanelet & lane, const bool is_outer) -> lanelet::Points3d { + lanelet::Points3d points; + const auto & bound = left_side_parking ? (is_outer ? lane.leftBound() : lane.rightBound()) + : (is_outer ? lane.rightBound() : lane.leftBound()); + for (const auto & pt : bound) { + points.push_back(lanelet::Point3d(pt)); + } + return points; + }; + + const auto getMostInnerLane = [&](const lanelet::ConstLanelet & lane) -> lanelet::ConstLanelet { + return left_side_parking ? route_handler.getMostRightLanelet(lane, false, true) + : route_handler.getMostLeftLanelet(lane, false, true); + }; + + lanelet::Points3d outer_bound_points{}; + lanelet::Points3d inner_bound_points{}; + for (const auto & lane : pull_over_lanes) { + const auto current_outer_bound_points = getBoundPoints(lane, true); + const auto most_inner_lane = getMostInnerLane(lane); + const auto current_inner_bound_points = getBoundPoints(most_inner_lane, false); + outer_bound_points = combineLanePoints(outer_bound_points, current_outer_bound_points); + inner_bound_points = combineLanePoints(inner_bound_points, current_inner_bound_points); + } + + const auto outer_linestring = lanelet::LineString3d(lanelet::InvalId, outer_bound_points); + const auto inner_linestring = lanelet::LineString3d(lanelet::InvalId, inner_bound_points); + return lanelet::Lanelet( + lanelet::InvalId, left_side_parking ? outer_linestring : inner_linestring, + left_side_parking ? inner_linestring : outer_linestring); +} + } // namespace autoware::behavior_path_planner::goal_planner_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp new file mode 100644 index 0000000000000..b50ee083fddc8 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp @@ -0,0 +1,167 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include + +#include + +class TestUtilWithMap : public ::testing::Test +{ +protected: + void SetUp() override + { + rclcpp::init(0, nullptr); + // parameters + auto node_options = rclcpp::NodeOptions{}; + node_options.arguments(std::vector{ + "--ros-args", "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_vehicle_info.param.yaml"}); + auto node = rclcpp::Node::make_shared("test", node_options); + vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); + + // lanelet map + const std::string shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_behavior_path_planner_common", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + + // load map + route_handler = std::make_shared(map_bin_msg); + } + + void TearDown() override { rclcpp::shutdown(); } + +public: + std::shared_ptr route_handler; + autoware::vehicle_info_utils::VehicleInfo vehicle_info; +}; + +TEST_F(TestUtilWithMap, getBusStopAreaPolygons) +{ + const auto lanes = lanelet::utils::query::laneletLayer(route_handler->getLaneletMapPtr()); + const auto shoulder_lanes = lanelet::utils::query::shoulderLanelets(lanes); + const auto bus_stop_area_polygons = + autoware::behavior_path_planner::goal_planner_utils::getBusStopAreaPolygons(shoulder_lanes); + EXPECT_EQ(bus_stop_area_polygons.size(), 2); +} + +TEST_F(TestUtilWithMap, isWithinAreas) +{ + const auto lanes = lanelet::utils::query::laneletLayer(route_handler->getLaneletMapPtr()); + const auto shoulder_lanes = lanelet::utils::query::shoulderLanelets(lanes); + const auto bus_stop_area_polygons = + autoware::behavior_path_planner::goal_planner_utils::getBusStopAreaPolygons(shoulder_lanes); + + const auto footprint = vehicle_info.createFootprint(); + const geometry_msgs::msg::Pose baselink_pose = + geometry_msgs::build() + .position( + geometry_msgs::build().x(273.102814).y(402.194794).z(0.0)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.707390).w( + 0.706824)); + const auto baselink_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(baselink_pose)); + EXPECT_EQ( + autoware::behavior_path_planner::goal_planner_utils::isWithinAreas( + baselink_footprint, bus_stop_area_polygons), + true); +} + +TEST_F(TestUtilWithMap, combineLanePoints) +{ + // 1) combine points with no duplicate IDs + { + lanelet::Points3d points{ + {lanelet::Point3d(1, 0, 0), lanelet::Point3d(2, 0, 0), lanelet::Point3d(3, 0, 0)}}; + lanelet::Points3d points_next{ + {lanelet::Point3d(4, 0, 0), lanelet::Point3d(5, 0, 0), lanelet::Point3d(6, 0, 0)}}; + + const auto combined_points = + autoware::behavior_path_planner::goal_planner_utils::combineLanePoints(points, points_next); + EXPECT_EQ(combined_points.size(), 6); + } + + // 2) combine points with duplicate IDs + { + lanelet::Points3d points{ + {lanelet::Point3d(1, 0, 0), lanelet::Point3d(2, 0, 0), lanelet::Point3d(3, 0, 0)}}; + lanelet::Points3d points_next{ + {lanelet::Point3d(3, 0, 0), lanelet::Point3d(4, 0, 0), lanelet::Point3d(5, 0, 0)}}; + + const auto combined_points = + autoware::behavior_path_planner::goal_planner_utils::combineLanePoints(points, points_next); + EXPECT_EQ(combined_points.size(), 5); + } +} + +TEST_F(TestUtilWithMap, createDepartureCheckLanelet) +{ + const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + + const geometry_msgs::msg::Pose goal_pose = + geometry_msgs::build() + .position(geometry_msgs::build() + .x(433.42254638671875) + .y(465.3381652832031) + .z(0.0)) + .orientation(geometry_msgs::build() + .x(0.0) + .y(0.0) + .z(0.306785474523741) + .w(0.9517786888879384)); + + // 1) get target shoulder lane and check it's lane id + const auto target_shoulder_lane = route_handler->getPullOverTarget(goal_pose); + EXPECT_EQ(target_shoulder_lane.has_value(), true); + EXPECT_EQ(target_shoulder_lane.value().id(), 18391); + + // 2) get shoulder lane sequence + const auto target_shoulder_lanes = + route_handler->getShoulderLaneletSequence(target_shoulder_lane.value(), goal_pose); + EXPECT_EQ(target_shoulder_lanes.size(), 3); + + // 3) check if the right bound of the departure check lane extended to the right end matches the + // right bound of the rightmost lanelet + const auto to_points3d = [](const lanelet::ConstLineString3d & bound) { + lanelet::Points3d points; + for (const auto & pt : bound) { + points.push_back(lanelet::Point3d(pt)); + } + return points; + }; + + const auto departure_check_lane = + autoware::behavior_path_planner::goal_planner_utils::createDepartureCheckLanelet( + target_shoulder_lanes, *route_handler, true); + const auto departure_check_lane_right_bound_points = + to_points3d(departure_check_lane.rightBound()); + + const std::vector most_right_lanelet_ids = {18381, 18383, 18388}; + lanelet::Points3d right_bound_points; + for (const auto & id : most_right_lanelet_ids) { + const auto lanelet = lanelet_map_ptr->laneletLayer.get(id); + right_bound_points = autoware::behavior_path_planner::goal_planner_utils::combineLanePoints( + right_bound_points, to_points3d(lanelet.rightBound())); + } + + EXPECT_EQ(departure_check_lane_right_bound_points.size(), right_bound_points.size()); + for (size_t i = 0; i < departure_check_lane_right_bound_points.size(); ++i) { + EXPECT_EQ(departure_check_lane_right_bound_points.at(i).id(), right_bound_points.at(i).id()); + } +}

))^Oxts*3OGfy9i_* z78yO&Dxdsld-gk${qYjx0O)BxEUdEq>y>o#_Q1){Fl6gIen;bHRVJp*NW+DtwL9d3 z@OIk%dY*5p(V zmv!g#f<$+3585^lqG5&G`8yVPj>-a=sqo+GY7o+gZNpRu%~VF|gX+68{1C z{dqYj(j_x{md4}=`8Bmw_Q?GD3_iNYv!j)rzmMu3)4#+hW#k1CAHk3O%l;~#I+(N< zs|+p2Uy;P?zBt_cx>(TsO~$eymC@85w?yU(%!*%ozugoxYiQ2qiCrs*K`!n4pEp0k zfz~995F_S03`*Db`6!(hRyPCf)YYkq)aQH^+q-BYJdeZ6@z?5~f0(D-PRg-C$`wST z^499t6fRV3syND7xtfoZS3SUFUY;?+G(szrJIm!#c?$kkH0s$+7V?NL?MFkG^ZC|U zBXHZ60;i*SuQ6a`$;smIM6oz`o=OYR8P9+FtK;WJ`&EcM<*({kNbc3rQ$M?gA-;ng zwFtj=(W2kee6kjPVg9Y65&8);l6Xw9%&j3bHS~2X#&X)XL3O_;rvt8?U~asPsE2`+ z-lfAESCPGeW`)QBSG1Lp+ghnkw<0;+EdR4lyOB+Ho?~ft_+xQpQ}x=P(I2bQ1!X_h zv^bD5COzZ$ear5c`qbMXR5LE5-Y)yOy$$_9I$fjoUC5c6Rz|(%)WU;A1%~B2csU^z z+XJ4H!rI>CV6*4juPqilF8nS9iw#ooM!=8Lb`2fe|}c(-k`*!cAPoRR5n$XO>4 zxh35#RwF*=2>G4<-dXHAC~&?l%?~yHXp0T%%wP@t7WQ6H7f6JZpDCl_2*v?>-VVNy zYChE&sITamz-888nh(QjrqV7Mzl%yd~~rHy>20QfI~T0E7` z6nNU765Gy8_|Q5sW-v9p`MIlTRBO_AtJTQ-X;v5$-H=eY$Tng;Dpi3FlJl~hdrA&Q zbo2!`~m+JpFfQX(9CINvjI;>C$$^*_U5l)9|52A%B#&Jo*b?%`{A|Z zKyyv}5zhY07iUDc=t!Qt=d<;-zeN&5RftUhmi9I5>F0kB4Y+2I8zKx3c04WM+0P-C zRzJZ;i$7lHV|CT+esm{Q{_lnRX3zTNhgTK~l? z23RCRa2>lI`*#!BpNdHp=MK=C>4EUnfmWx1Q7Pvx&l;ZEK9$!Ay-k1M=cBj>ocanj zZ*1l!mg(9T#7|HT7wBIHA~{?1PHEm=X}C~?>lxYNECCoUAoh?Pm#(6SADgg|6>w?u-aG zc&gmV3*^KLoFrgDd2PmtEuJAd=zf6KbUg+hONu=5uV{Z))P5hC&bF6F3d$9m8-IOt zl{yjd)lZd(#N0exK@F)8iJsyJ4slop%A8DouXzXgb9noS!g}8@gMB&9ipcpzM0c4< zzf*x3)-5)rW;00jde(`F^+UWp?- zq7Zo#{kIDP$u*jfAID5a{RO&C7An~O+YC$4%y2gTj_5BlOosryZwW^1(uPLybr?kc zSnXPkORkVpp%YPl2&p_NY{6QfiU3nN{q?`kU{k{5SQA9AnNnRI;?Z7C(j8 zGn(zbV1AByQ4B`hwW)^l%8*;5^!6|jCatFQy>xjg3zO6gmtIxitHXK@n$NOLt-S)C z+y8jfi}qsiN9^fK)l~;hU4~sBk?goU{yq5~@Y0`bA;$-@Lp6FmsYdpA;z?K+^V;9? zF#;Y|uOQX*as7_+ri#e#aMT`cqeyq;msqh5WtYk_zik2+B#-qD+=ajUu6!G48_;wm z_5YeoT`2tpo}z1{K%4A zNls=F2@?WKhRh4T+0hoLMWUJ{&CJ(KwUf?hbQ>n+JsF=_Ewwv~+83H)$Vx)JY<@j_ zIxwSZQ5kO_4I}EB9|1SS89E4PauM>c?^l;Wm(1cxAqNT*q)o2-TZ9J{`NSVJr)oIW zW+t>Z-pwp4^;5t0r8>FDw$4K zT8Z>F?&#k%-LP*N-ZcH*apyXceY?$UZSCrWy#&{!#dk%+Zr8E5lyO|j#}~ngecQ(b z*S)XzZ;N=qgJYKrW@eU6>iv#vSDv506r9cr@aUUqQ0Dgx0WNQES{5gMBW)E!@X@BIK;uUba7- zJ?|PF?^9V0gcL4#76v=>pVOY4OgZy1=g{S-)e|E4O*3bFt@c^R7g%$3AqLC!Xk_Bz zV>>b@WssF36=B3_9(WjRaGGrsrP(%4dVoSH490!EKOD3Un>|tOr8fX14iuMef{L07 z(b7BV#fuk1lt=$;zX)tCJaFO$)j8sfMJFX_Tl`?vvuOrkM-ol^#vr!c^Ov0 zVOg1(=VV0NBTjT?t04g1Vs@a?z;0GTQt}C21`2Qa`UyKR0OiGK{j<00eSkV+9*#`- zbMLWh)j<)cPm)ctR@uv5x?wH7QcYpCNG80xHmm>~^xszt;==xFP_*Q}QXZwCbz z0Cl8JP%cLXea!IMHRN^9DQhL+!^Kd!mZ6UN;9b9Vv9ggJ~?RO7yu^-cQ>Rd?|4jq zAT2WC$$wL!@Gcq0?$d=N zpn5l5<3Er8eD%r3?6B7|2_S{F1vD2N)1FHO^fFmZ0;J|#_^uWLNcif^{J^-pQIP5?Mdan_C;ztfj>{&XNr zOhL=%UiZ}HHK&5u2DE!xxO?n zP$wNBB6|P=DLOF`T2)KqbiMoV{KRY@ZXH#%xMc2X8kk@&&=D_h0^rGL#l8P@39V`E zzakI+Z9V~pe%i6&jn!kE0c*RKmd z8f1T%8DO4}XcDsm>fX|4JT^bE26t)}RUg(e_-E^+R70>iTxbvnQ2CgAjaPScbUZ{B z!D1^{UT8`IjBA&)qumpgBTTd+WeE!pqsHim|Irwi zFWv(X`)7q@fL4L;f^)rkV^paTrh5OOsn|G$&6D?39O(?s+#r;8DA?d&Z@bEeeboV& z4)q}3er#CM&od2DIr-Wjl^_kZn|-#ql;~RKzud*os|%o&!obR7(F0{LAj$$8l$nAQ zd}8s86NTivYTc`Hj%WWoN2)3}G%r=ds7LVu)HrB?;tL?o`9_7#^^p@mj;d1kjekd9 zG0oOKFe`@*V)Euq?WX~P-*|Ic(ryp$K?do+g#M&bccNx3kW#NcX-!AEpV3q;k=-m2 ziHNh*NHsU*c6&$YPKuvKPqq%a#uk3L7HI4+;90;q+p$Xr z&s_(%;X3U$eDsVaYtjjdKmFYjpu^asY!&aYl0`HoFaL9|5wj8LQ~PZ?$Ov!i^A^jE z>vmd2ce?Vu#(|-1~sL2%Xz}pkA#&^Y8e4al`V?D>q;pOC39OC*(PISYr zHLHz&n{!q3;EvkLFj{C`2iMe_$R{$0yw!`VV=py_LMV6Y&h!QX_**bL+f;%zaoSdg z^-_Vi>+Ar!C4a5GYCa$KDk>2!cc%GImC2BgmWL>fZ3X=l6@V%;Wti@FEitu(9$V`e zHP>@HDHjV|3OI*i5x-ZJ5;17}W{a-65w&EEd>dVcI}f};jKTxImn7kT&^654VpvB8Usx^rM_kvmzFD6#-OgpbPx_UL|{( zOqTnFLqLuQ>V0>CL!|I4#$&SmRxqDyeP`>p7Me<$a<_GqR?x(Bjeg>SqSYKIR!o!f)RukSOyRb(duTSR}sxerd)cJk_!6=P`lS&4mf7F z7k{V)Ze5yew8@=atvaL_tOn9^5ppwI2vjTq3G#{Z$EW)c;bPBXVzPP-ZWzJg7(jo| z9v=z#vR3M${R#^3_$@r83Y&Nn*la7a@!-rTt#*$jL#n)bc)f={1?xD!fpH+?0CWSK z)_gnnl2GPj>FmM*9dTCJfJ*A--w=enSDVWuJ%8{_AK~d{$p#5Gu`)@t>xk_AI!)sw z{oHndQV7DN@AP(lpx{jFtG-MC*W#~&bBtgoPR(lSdLUGMS)VO1eHUTUguHvx9D3x` zG?!QBt#QZfpklh=+T7CQ&SRKZTE5_SgmLl6%1TC*)JCj%q1ogzCFg94U-K=d_HYIz zS>m1~ei4hQi+4Q<8HJE4&P9s75v3<5DqAaYqHLe~xb{&qO9bke!}b#~LIrX==O}>)MJ-xBCGbQC&0<`n@-gJXl_|x%dA0V=xdy&GuB4TeUo#0L?Jm zGQC^cWTBs$_|3iUD`NZg!jAlLy&vrdCnfi$-5DVEVo7UT=gR)8d|Z7_7i8_Y*20zq z&9{59TdXQ@{iv%|W;st5Q7??H9>aDKx(*Hpb0(uchuQFeaqB(Z=c7uJwaFgZ9;VHR285il;Em9@uv2F?J7UPZ? zC=(k2Q(;LXi-c6yL`D1ps3qu$x$X z%2oPj`tJWWqq!iB2nc)p)U&)rN1m+j4@}*5i0~`OQ!)Ys5b zus|t5cYQ%=r7oXJke{a^P{4wkD11FS3f%UoFCk2`MhDdLXgHNYWJ4GwgP!U9<(ww- z4!>Dx#g+0}Q!n+XV;O+8p>#m_GH8Rglcehc_K|zm`>zG{zYvdT7DfF(EDDE$+A^P4 z*C{#eS|PQh#e@>io2>bXb0+!0`&_!t`soN4juQ9O!9_v-58xn@szQLKKxRSMDP0t+8(@Q{T*98KN}NvH)O|&_-fBA?ebc%u?QdGv9%p^I|yz-$IIM!;Z zsa?2D!r(xXyy4?;R&2ywV~ZR`i7L-!p(@={lYFEd#e(8*M|9zCd!r=V(Xn~$f#-el z0M|A2tI6K^bfzPmoc09)04TrsVZ{y891FnJJL#_*ztUgU1~e5M`~wCkfWQ%QmCP!1 z!ErCX^tSWKRcI=7Ob)2PF?fFGfzXjU=jF}*alwPdY=QhoFn8T3-_d`Gn!L}Gc_VJ1 zaB#7*rVEZYHiDpJ{47W@nR}p+R+Pm;A?bl!;YV_odGE(1KLG)SqS@)H=vS{Csv?O@ zfUOu9a+II0>y$3AdM~ZTd4vzOAzZAV&Am%fk>&B`gZq5ejuOFHMcy zEj)-oiFGC^0ohPMqJI*tLgZlkM^cCfJ$c%Y-U6M>wSpqQlx0AQ-H;~K)m$9e`X_Nw7YZCU=F?G}0NJxbC$6w3 z9Y7IeH=byxat9gEK!(3IaV`%SF~){B{#R!>@bG)gV5PYK<`Yv*rF^5m?ZbHGIS6Z3 zI1_(TAAhIxbuZB_xh6S@pZ!;U49E>elX<3K`A~)Uh3VbbgO32&o%B^q2K@ipj)!(0 zs*>tXLuW*K-QoE2vNB*a*m2)#Mg*#f^U!Q9|Jd%l;1ONL z?X5q$JN;M_6(Gb{4utpsK&t{ws6oItllOm~LHdtE^*xX;hnQ z1eLZHq16fs0jvWmLX;r^0tu+7s1>bM6oi0SQGtLmnS>!06%m0b%8-zNG6aPLWJnk? zy!{2yN?31Q?_0ig-+l3~Px1}>?6dc8@3YVOo#UwoPC^)LxwDnFBla6IgsZ?vuV@1? z4K^w6tgji_4BMH0y_5B|+o))7N*6e1{WFil_s5Gpu#N$WC#*kxU%>cvPqYhq_{%4l zb-$2`t8G@?=&0N=>)0-2d2KRDNM)S~Iy76?NcV8;0ol_;S)|7=8JqKMy@_Pj)yu}< zR8;#g4I1QF*A_b`tohL{L7g*$&l*mG?UQkpk7vE>TV${Erq2;&9M-6|&WJ;fQcLAt z&Paqo){WRWm*bT0S9oY#c260fMAdk+KK7{w?d{ZP?9KKN7-og<5U=vsDPJkKhK}qJ z=W$f09;#gKO=r_L`~no0h3ky6q6M%E)>GIPtkN2WBvqkcq zbIMgSp&L-hrnvuM%lf?WP1Fmqe8@b$&M!rOH1A>^0272 zKY=X9bHR~Z2Od)1td4^$AGVDc_>KLw1=!Lp4M|_)?sMYerJsK=4Jy2twOCy}@Z2r5-%hOr z+Rjfe2c)#$ZuDNi#`Strai7UZf+Q*Zgu-Sd`|cGmUeiHHiIY*gZxvRTFAwd zG2R~TU0ZZ)?slJ*v0e2i6d9p0d#-9)asPE zljUK!BTNlW<6*Wv*Wy%c3PN9FCM7;nQ~Ptuf*1iu)@R`_OY8|CbEHP=^?z&>e@c)L z>C(q+_IY(f>-N{}zH@13uiJbVr4rr#Bw#bQO8V${^_J(<%_Kwj*@A|WG!Cgb((jwS zg=EyPsdSMYq0rge^p)GszxEI<1b(?i;xEQz1eIJ+!)S9%Y+rkbWy`EOYy+2qT9Bl#b43))ZQA|s`mhuWVe)?THa=eKpdkQAf7VV@h7xit_YJ z#O=6W2t*XscALb&@^+d(zeC7Rl;-%`4xBCk33wxW-U*dkxXQPk(_Pb@OUte4qO_AW zs}rj(iZ(J#8`-;K1nTJFqTdUHeDBjESB`KA9{r!+`+<`D&6t6zM9&5(W-o7qlU&oZ zmju_>On2?1ke78Iw%3W?or+?&CV5jcB+VYu>&5tTe8CFV+3b zno~y^rE|h|(SH9+9PO36Kvc3N6*i83<28&Ux~`o84Z971q4wLC;3w!kOM~lO=HVPt zjxzSnrR7Ev+XZwsr;uAGEfbcp!%)eOH|#ztY>*~A8fxa(37c0+oJS?jl;=4WX8D)Y%oVNbcdWXd6`3!= zjHcr}=;?eyO9zg*S~I^`$nv}Akx`*=tk+2gaw($BSR{ zV=N+`U)dhnv4Xq@--IKe+7f4691yD;(b~^@utvF}5{#^FPIB*III=ChP$FbwCFZfGk-MuS-pR&fk>LFC@&jdYOLC6!2XztqC-y;?D6rcpRw+|cH0$O6@Na9wW)Oy}HUQB&DYgOB6N7f1N zzTeIDxdT^Bh$l*`(zNrx(3raKYt1^AFrjFxn#| zx%S^6OByjjyZ#hlF`?TC4>u;?Vt3a>3WE4pN^t>lP6j{0kFtk6Jdkd}_usZH)gWZx zu|J&k#E+^2R(|;vi$UEvKej)61LXT|og~O1N_;BQoAMDyl zpi54nSa95JL6^6$Y@Z8hm#^K+wzKT-O_H7_A80y22#=^omp(tD&#J7p$;IF~A#`am zue4HMr(BAkkBy?Duekpt}z4!77ntOyeTSiL?>9|PePEDFFq13uy zfqFdDC*vM~!z3*9{v?d7Fx?v$Ia156O%~<}2e6|B!mRT7wT613xdS_Wlb+f2J=d{_ zOFEa38@Qs+_rQUhW|$ync0t}#O3BD8;r>NE-RpHtl0#nv&Zx0|eOGwR$@Z20I;cML z`JA5c`aV*XbTo-nUD|R`cyL9v`{T{NG19M0$V~yogLUnLSP~D#4kC{>=}MNJkjGRc z8cnsiz_@DQH>h{IcQF8KG)IFwnk<^R#WC7wo$2cchLtImv?_4Ic!FYJ1 zlK@OiEJyDOG9R&ruX8}9er%D8cpz}ob|LO%2C>5zH@c%2ru+(RTmOT9A>A$?3ES+A zan_4HZxba&&&-2Mr99HBjpVK7`1teZS>Cc|-ex4bkyPm;tyf!aeoHtcx~h-eXEgl4 ziRFauJHt8Nq^@I=15sO>otrG_wtZ~di6%?nNbF0IIC|f4)AO=n;3YS6`?(@Yr|*_E z@<5BUu_aYwE=};sI3CJd41YE@-v7)AO%oS%XEr59h7T8VN9x)O*AT>w!}nj(&5MHz z3q$bLc0(?yLq2;&W}jwzv3K`s+&X zk_(?ix;u>vm~#_APaox- zzHmJ7zR424om$k&$6~SJt@?Q9@Y=-YrjpUHnl8&>Z>LAn4Gql^l^!gz__Yx}aZ3nu z1$i)27=)JfH}~Ra)DV)jtI?&H@QOwB^TnfhqVGNINHvPx|0YhUs%;0;E`P}0^EM?J zvxewzX0Pfwm%WcPA{F(Fy!1^D*^C;!6jZmHbx79Gs82VN4VA~s4B3sm7(7vn*0s2< zF-Ib5E{!Y?O0L}i#CzPUJ?Z(4&H4Jn{pYeH{*(+@^YTi?m8DIC+r8kZF8;}$(UJ#o z`RB)bA&TLswImn=yBfbUM+Eg4OFtD4PoDSLY z+}}lK>oHcczh0Oo?{CaBU#gt|@ksr0Kw#8u zi0Y{YQ#mDFy&A3lFDZ1vUXm!*#is3!j!iE^n1&W^=c6SL;_@Kh_OUTGL101tq3>q7 zc3#cV|6%OEduASU9A687bejC0lMD7s2J7MQcoCiLExzZShxkX@e1c=c#z=oH^sIe%t)NUAV5XPxbh63H!@&?M-&G zQYh%;e|b$sUtsJs8e%k|eGm}8a@Hl8z}a_4CT=M2@DgQ$m-1n;Wl%Qz=60u1I266A zSU@L>im3IE=6N0%KFW#|HCu^T=c+xv$JK;Y2eHy-*o6vgDPPm)AhEcLhGQ4t%BEXA zDlSNGFSYG^fE#%1R8w5uc<|hg!Y8>|yAMIGtzbk;j8m9qGk-Um4L{j?wqWADSYG|> zOKs|PMtb7CZoP02JtBwhK|&*(N)lTtYdfyZSr|8D6;$=@a5K4y8&D64U}HIn4X$kqb0I$5$kH^I zwY2e!hFUV=7)!lN%j;P|#E~Z9M&6|r^$AHjrBbmr3uRssO39DMyiV2CqxnYEhzd$2 z?9wC~EM$si0UinBBBTT{v27=zX$D{H^hG=;`YMwnnY|>~Xe8btl}`W7pbZHy26CB)9QLt&}sfjm(!gK&Gb#|^m5XKl|pPIo;3jb7> zrp39AzZWzCfRLxdVWde|k_ZD6RkfFDT9_EY)AiSwzjSUWHcg%wx8a>kNBdN^W8*Xg zM84B=?OYn1?&T0ealpUAyq>QJKhcIT*fD(dXDoD5hpZvV5V!Q z&~@b@M6xH4J%HHpuBnOcodKBLC)TgunASJhN4@}LbG+Mq8fjh%BD=)QwR7=2nzpw8 zfkZ^KLB*#SpMhk{193kZGAG^wR6VYf;8|GpB<|5PLQ}EJ;K$knZ&I+zer*7Q}@a9#Vcd- zTckQz-DGlT%z5$WudZvio+LClf_)r4*7yZt%yMfQfs)imHjg>loS2w`+f^p<>D*r? zY061xiNQkObnqfZ@0iVct9`H$!dJ4uKq~a1A8$;e-uqySr_SVVMAREPre2Ha|Aqe6 zo5y;wlI)or?lzeb9swgfc`504Fv7C2P9%LQ_mdBCZ?LLD^SpbDu;Atyleqb3;N_@w z)f>JClzKkqhNT*EY@olG%t&m(0d4=NLfknzcuZA`HvJQph;iS2f*lbU_8}hof%g8P zz!@7Or~_MUJ6riNtpvXEmxD)B$8><{XOqD6cJRXT2aR8W7g`pL!D###w!7IVB9(p0 z(I|()qqksVKZqaZWBz*hgZmE<)I*Q;;&&Hwmyc*A<2Y>vxb^Xz{hy3Dc2t`|O1NT} z^_d14_h;59Sk0<&WGoCyA(VgkSIn2?-SbBx&c}214+QG~D4vI;nwbx`^*yD(QuOxd z<>2hw+q(Y%NPz#}I@QC24-(*5XgHY-*{A-9%TgE&?rb~;B zp@3O=ZJZ>AOoNKC!IFJWNQwQySPU7>{?Nb%y6OU8_^8o&5Dy@Ibuy6t4nW$q;S`Kn zqtA?iw8&eY?|ocMK(Z?Klc(1v10J8L;1@HOqhOvu10W0hfu#K}8lAxWq%%0z>z_^n zx9X5*YihB7Lg4n+7~D!tKh(RC%=-g+f^*ja-{s)pxi#VQbCYBvQ>P(G&w^b?<%4c{ zvV&D-BmdX4k@4)i2pP_Ov^eumSRyir?XPJ6h}p=vz4rm6e?Xl1z-acNBh&wfLyues z(ZTwX07_&L-vEm>Ns8$6^uyUjbhs4dA;sXJEXmzw(k*!%DC?qa(f0CF!l!AclKnV% z8y<>#UpyZc|6YBHyBrQ6R@^|sdEYPAR-0)7LOMZNBGh&hL ztCmB&t-1ZrxiJEr;@x)fE4*==N3RD}Z+YD4MUqb8KWUcosddr{O=+e<w;H?1-I$GstR%<1i1dxurKp&9ow*Uscm} zk~$0I0SOSY>JLBDneRS!WnWTL2w}M8_VyG{Cvu)6Ek}A;OZkq|o zUp|{0i!L#Z*fudUL*1_Dw zN(yl)qPooO(WdC&wW$6-Eh3o)UgBze-bNRczd;YTj*EM~mj4?zwCs>W#86H4UYHWr zxDv9gcSUyS&e1aT&>?KY^Q+E@taP-D8d4PGF-aBd^g^h~9k49Io@mRnQl zTE}A14ylR9u&{0PTRpxpn(slK6%G3mkVh7PX&m#CZjA{besacON$|q(I;7V5et(=? z0`Y!%h%Zc0z>*Rz4oeS;?kIFj0AJjl{Qj-bB`Gk+P*_ThMZR`=8KmPgj8}Q3>TCSy zMS*KZ=tOx`q66WbfoB>m5mDDb8-BXeG^oY#lywHj1Z-l4D?acTQtY%vf+FM-%(=9D zD25c`h#=T-qpf0lNzh(W&>W+&Vu|JsWQd*OrrL^b%;)bH~abk$(9J-o42ZU+iF2kNy^us;`@; z_<#?xUSW4E$^ucwP+Q<@R0=c8AO%qp4rb#gsEFweh1BLII1L91sq=b|1O%$wd9B4U z_UQ|Zf$RH<6EJ_k)Xe!4kB-Pyx-^CPn^p(Kt+QjqDcuy5Rj2sC$;DtnW(Rn3I3s(S z6E&gN)Hik3Ro6`7J|j>~8cj@u8j%Z9y$(EARDyhH+8A8wefeDfwI~Oxr5EU4sfk@iNfc1lR>cP_69888?k2?}of8pA z9Wrq3tefGAxEXzXCDuE*>x3#X9~%J6iZ!NwsU7NQWgXQL8WS+nGK}hAWv$Yxh)55? zLMzwqDno2{CM;H3HzlavG&o3-R;x?`=vaF4mkmKbtvSZLx(LT*Lg^L@%(n1~aBU*mnVG?`3d^Yd(VT zm;eeXm%Le-zPioEKX=+mE@1s(K}U_X;AeX@ddtN2Ax zzc4gBMqn6QHwgL(F^H>DtafKQf-`KyW^dY`2$+%5KH&@S-ZHSgqbHi8<>;tS>*}8Yxs9)RMzLv( zVDE{MFvTbIVYZ0=cn;1Ek$315(BDYW+z)CB%r6VTrN48%+dWbUkjkiODZfUOAE9u z_F^N-^bH57I@5EI~&`DX^Q zWO31hD@JKd=Yv-7){P)GfwVOx6I8h`c%@uiQ$P>Orhv%Ijh&RZ`I~9lF@hi3GZizF z&whcL(B8gkXQ&B9gTdsNxdGg}{6mPgr3w?TmP%|B_#+cK}ZQg$|CnfFHnMz za;ELQ;7Hmn$?>WmlG-1AN?z>KT-mc5|EVjA!U7Nq8BLZL(2M)vOe^; zwfxGVnQ~}0Q@LlTJL6vtf*ZOL6reCoCqQ9?b!EkPsmuL?;7S6Z74ctq$^X0m< zc9l%Uwq5|5SM}Ns1|t4xpgL~6BPenx>>>xafnXhqv@kEYzvTSwQ8_KlB)+^9T95GN z_~J{7G{hFzlZAi{ScuR_{+J?8^_XGo39K;H%2wces!T!?d<0A(-hv<>MEvi7GjiPr z@0H3PbSX3q-njbR#;S<0^68RnxZityQ>2_(bhfg!8OSrh2@~Lm8x$44A4qe>R)uoL z!b3GF(@b+FkQR?bwI7HHuvVEQ@#=ugH0X@AoR)e8XfvB~P}xlWNIF}Wc0DCb(TD2c z{_I795=6X~iuTu7ATa^y5|2WsD=Pjr@F%#5Y&pkqrz)xQy!uoiZaWmtkD7#I z8UzwhAIz5%gMJ3`+|q_5w@#d-mJfn46$y55PP!JSem344k+Zk0Z^$Zz$pJzkJ&9ba zXk<;m7wf6=m-F{-MWMlR4+G=%3!gAg=rqP8RuA+&f#;4Haz^TP;2P<6SDOaYr7v+H z*zQRz;TyQ$FP1JRq=p8DiS>bY2HX-(b>JieE`G3l(T+u*vNz}sebZHn_FdYQ@TG0}Efov(tzsr%6Ep4ba(&W&HqQZ8ON))Hud(RRKxC};83ZBn`4*?{QG|GhBXuipM(De*XPjc literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_before_stop_line.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_before_stop_line.png new file mode 100644 index 0000000000000000000000000000000000000000..7e0bdd704ce58acf310bbb296fd3019fddae56d6 GIT binary patch literal 118035 zcmeEu2SC%;_P-lP-2)X7taVkHVakjwQ34`MmIwjDOc)7)umqo5Kx>^S#5zzB5El@Z zRsk0f2cSa0f> zU3a7A)-huQsAI-V*fV(&oOyOD`Xc-@)_beYhB5JZORC3=G1H}LZKJyTIy$>Kj9G!x z=>N4sTGEN)O)|18?`%u*vUT?sCp%E#6kK4e(3P znN0JAe|;6?Y~*Ctz%RUqhns_$gWYClm{(gC2SduCM>cOXCg`n@)_~t`&aMvdkB$S; zm4Y78aPp$K!x?QUDJgMD^glRhWb0__>a%N zPXQ^?D{xvXB=K-7`ae#C$67cb+XC6xlPk1vD->`m6!E+t8#J&V(knJ7@CJ3}FmRL~TYH87Ep1^x`3V_+tCUmY)74<`b}-oXu~v-jbW%AMYLy5T7BVqZ39WSdGq_Iong6`tMbcmhYzpo!{u-OmZ5SSxQc^|BAcq zz|FjscstqJQ|SHAW2Xl1RzD{P_~}KVz<7f;bMWPXo7{ah9NZAQ2l&XF2Sjo7&wl2H z*Jow=E5m`jVrpRPMjH^kei^3v4ahLC1Cw%RcWehXfXYyvf$w^@b`EY^DBjN0eg(3l zP^lDm&|)`qVS_EvmE=XCk?l1oZWJW@_70A=G&f+^=MnI3&LpIIREh_jwe|MsmkUQ{ zUj!-}unF-4XF*Z=&!C}fskVSF{S--Sd;5@9NN@0U2Oeu|*{CmV;kQA?&diraWJo&O zZrmzK)TH?6;p}ntezG`%pR5njo#;bw!P5yEiVS;qqOf-zp+(TFz=nKur<=eF5u*HchICNZb9qW=;m!~yplh{NX6z6?EMEoVK(?~e$Anh*W1=i)(vR#Lp13#On^oc^ej4- z(KnKz>mwSC5sg}Y`Wi9}m`4W9W1tE5YQiq_AJ@;qOkYxW<5oX&Gg*d(yP}^RJY&Cc zlan18(XrKSv!<2|j0fZ6CH4Jea0F*p646~zvj3VZeY24+$yUeI!$R6g643^0^nm-$@&2r?KJ4J^gyxq<}V{5AUaM>2w4duW92)g{?WySduyAe7Kz=(*_nB3bU&5fTj$1IZ)O5m`MK z5|Z;_I--l|2+`ft#a?5BB+*@)MwGSyG?G-*CHKo8=#->|5y=o&q#M4Z7JKQEJAOw$#zE1W!CKSL_Se>h^uBNUu?11lPqYZv` zxUJYV17o}gteRqB=0>*N2xthJXJD)gJJye(*e?3X_z^&x9WZp#LSsq7GcpKakR%(x zwZB9i$b}XTsPofvG57mBsnd6skw*CUSExf0O_0(Bw9|7jl>8g11BsOZg#L@v;q+Wg zB!N2E6#NPBz#xUKz#XtBm`{T2E1CITfove0`)ksx3%hHA)76ml18eR3*E|SU@JDrVpE+wx1j+aV zOE?P7_RIFafUBD3;7?-`jOo$WarNu{DiXrf0kr6B88N=}n!ya?M z8sZl`GX@_*6Qs5u&%k!c;1G%qvtN8iB7p@kN8WuuG7cRHdFs-9(0pK|uka%DHFaS> zND%p%BTU8(wl#XjqxJVqz?$j~a3B2sem`>9I!EKAny~icYi@{Tp*e=HbK~R`C#a1cxQ}cjsSTF!@m;^q`@zi=7Y(jpbX?fhG2w; z3=;5Dg(`x0TJ)&A26dvJD3p8=Aki84i)4a0%Wq9YXP&t{nb!jljN z@b!8Jj{{yN=nZx+W_Jc1V_7Es0Xy_{UU`282+LL>FT6j_MA@o880Tv;LcYLv6vs&d zY79YOkl|5gtA_XvC}Z*$C4yj#qDzEAi1UU+;X0u7*5EJY z(~!NxBn``v8tXzX><=QGucHkIm?ot^B!4^VTp#j7fIfsENL&9l+F(DCZ}^w^COZ(l z{f%^?9IoGA+)r8HJLVz$y*$%}3J%E0Uz4>VxrD!uZ@P5IQPBV5eqwPfcx}Ac5c$+t zj62L)_2)VCq=_g`+F#RxUr;aO75AWE=fJD<@+lu;r+&YN`K6Mn;{b(qs+S*BGkGJ* zDdKnq$br(aoUD|%oV4WUKfF2VU#hZFQqnTw1NB#@Ayrvfd2xBHd@U_$%c}^JKF^6t zm0wdeg?o5K*WX_kYIYb_o8?vief~!aq8>8Hsj>aN!lIXyo`D5Vl<_6!0IlJI0b2B@JX-iL^@AcG?%ZEI$VGjvx(Mvtzm3B^=nEpX|< z5NaCI;reKcs37WYbiHjGAc;?sv){JKd$Wc_RN*<>Z5!xN3Z$U2 z>c})Hw&p>lKrK{EhGYbmjG_HbIIE$Etxg+OA<;Ks24U~#S4lqi*!Cvs- z1j6Z&jxV9VM1}EogDVtRsQr$vt2Y!^X!>R(Dwuaa!Zvd%!3;UBy1w=<+O~E^lBldH zNid?*Z8aqO&pS){+G>L1@1iYDF!i89i5T29Ltj134HP{TP{DaUV{Hm=JYO?+Ntnx! zrmv~xP0;zz&htVNSBWNLNPk@~>Fv5d&5m0)LghCo9WTIX61LqLJ9XJQYV7SK@+*aTy1lGfk8Bk!< zghY)Io&gRG>>S<~#)Fg+v^+p@51qrbmjUTzbl+z!Ccy3*!o6Bx&{0wp4@SuZN^S#m zjY#4RtWrafyv2p?V*zafdN^p(V91~r8{7tH2%_3Lld=9N)a3E+Fj@+dvXY+-5YKK& zODZae<7E1$A7rfL6?iQ~gAJ9moQ$|EY#y>m{}DUIqw{~&PW|b|9Z4unV?|u7<;B(4 z$-&IjZyU%Uw2-)3m{~C3-+?9>o?XzEw{Um!w$t>W*-6W~8Q}DxsI2H^VN7v>#09hm z=t_M)XCws;I$Pa{?obpobCWcHf}jCT63KIa^AD159aDEA$T&11VYbeM*Z8wd+RX*V z$J%drcg z2G;Te^B}b0*{gor!9T&#Zv%Cpu=WG9DRGtk%zUCIJI~TJc{~n8hQxI3+wM!0I3~6LBcvfJL#gKv?Whov& z4>lTdyg=zcVlZTRT>2jkZ2r8#Ao$_?b62AePQZ|C^0AdRp<0LO{ilHV2p&iIQ>vY2H;u-nV`Y7Gk|UcDW5}^ekFwv;)^-p7rqRr|Hl3x z33bfc8DpJA0IHBHGq!*(Ed=JK(D{iO2@K#3G)dk7!ceP0085fVpl_h*gw-Gj?gY38 zYO==R2iG=+KtASPAYewp1=al z)YNtKJ%|tpLq9Rrn~RO6qmQHv>&d|+40CFR^($e$KmRQOfs~Y-xGcQFA}u8)FDD~E z4Ctj4r1=893{G4|TABx~L!cffj+5t||Bt{uFNgLmJ{Z>6|1CZk)UH3OIOJP=&>ydS ziw{r?@P8>j@S;#{c`qr6DgL`sO!6}F3gU{qcgzM#BMJ~i{9g$ecv-LCvmiv8mk;*- zCwh6)fozXQ@9{xak4z!M+hiM@sPIY_P7__k-UP#LMf~@sdQn_IzorK@oqF8zGr4fJ(oxIdyoejptF zJTvI#kc2AL){Epo{R@+VoYr-Z*ONJ20H*JyxS1i^dl2L7#fOMQXoQrcu)!d3_R$-{0s7+!!OW-9id$u03z%$ zae3^u_b-?wBm4WPh3?$q;N=W8_+j;u-$gQ>SoZ4^5CKBPix2+yz)embpns^@m6ifi zJYaSQu;5>SXtGdL8a}n8?8vGAyKzmP-!cYsaCF%7&(Td*hNt}l=q5R6n?^Uue=orC zBykYH>1@@~(g#d8f^0kfsNIDFH?jUSi|@`%4UL+Hi+e_fxDyo>@$pbzf~`n>m2NKZarmE`r| z404>L28`ig&uPGi7|`l}Yp;+L&pHp<+!5P3YOk2zb`7;X*iL`3J>rs|ZBf7Z!Sx%J z-!nky+HgC9Y)ijYl9W;a+4*9XWMwfw{Ga;Lqp(WX&dx!bPhp|F?9Sr{rdm%>m=~4 zhi^5jZ#64a6Z=-P>aR`pfBEIVre^h@aIoa%q{J1!l(2Xn)Mq0gDc6*y z1u^z;_}{7pvFm@rbJo_Dl$6r|uV~Q5{u^`2a*{Z3BR+e_!<`IS+0RY$gSYm-&td+G z?)p(X%x1jz3cwrZlfU`Aas9G1B2Dr?=a53`RvuvB^Pgd|f|D8ccE!KK2mM_NKIfhW zyx{*6uIR{qTO9)flt>#Iy+Z(vzHm1vM7QOAA~SY3fV@4|BxQw7f%iXv430mFE1xMIKUq!me6(4&&$F11#NT#J=TL`ei;Sv z;pK^cZ`jW(4E=d`Ng^abhJ%vm|0)~CL6M77X zBOb5v_RsP@JcIhLP4vjazDW)XL8WAQ#(dEJ4phAc@9n_30c`kJY%CVR{*y0v4n((K zzLGk)q=8)>_*!fK1>OU|a8P0NA<#R5)bKH5M907z5yrmT>o|V5tZ9B9ngqs8E>y=i zWlg%(a#4Mj@!{{J*ZgF6cmKUpdWS;PuRmTg?H`g8F5mfHW7_wJL-3ZT<{z20^3*tm zt@t=&oBgYg9=j(x$FJ!1PluO`Q>^l8qcoPOMyD<~IHs$v?50|NWkMsXJ^n*?bH18L z#^hO|>O0j%CLa>Qtt5Bl#Yy-*rxlv7%J9yq4-`GzzMR|@A6I^E?^4Di4Y%95g;L&a zb!j5;zrB#yc3o6Xi1kQ1+Usd@q7?1Ttv%CxmB&rM#v3#C%a8Gb+wg2*g(!nLXrk@o zLdn~^T%t|cx%A*raz-jnanQZ}Pph}WO|43jW6_l#=FFnb#h;)aVp`5|3oV|?nsQhe zzjN>e=ppvDvG}CK*w!7`fw(BQvPXY1>r;aPOhaF}N`3ePm$$34+G-0~$ zxj%)^rfv=;cv#})$KF^zVi^+_uNCFW`P^Q52+jRw;sj1w*%Z8dSEtg}Y`WPNnW-Mz$+0<5s4s z!8DvxXNIp?oymYjcM6}x7B^?gWY&J>=Jncau_9eN=N68c)(aflxvzfel8{?-;c%1&!+0;OlGaPw=y}789CPdmXg8p|i-Cs!M32DEO=evnPT>5sV{VBlo3OKP^2l{(Po2yPvyKy3jzrK0 zSldY7@J%U(iYwBCZ%Xk^DZW{Xq4wyTQhc)%-`uBRzQ;GE_@)%!l;WFGfIIyyruY_9 zd<(RPMycPF;#;8oE&DVyj{0UPzGa`jrDTV>jNg>vn^JsJif>BMZz@CnkJKq1DRNai zA1-g|S{1c#RkZK-QGso*qo&2(`uI4p^XdXqW5%T5%$0uSk$Wd`8XH@&u8-j+{ro^))p1imQIOH#2*$ zYWHv3=p5S7=&~Rt)AG~Q?}k^Bp!k;v^`NGYhp@sF2g-CDzk>RjC7}&7gFft1s6S|P zsF<97TP~pSRY3De>f4Y+j!&_P+)<|GqV!!OD@}_rtgFBx5#|+qToJcQstJ z>0>PEG3c8&O;FtGyR^qY#y&8$qzIqai3k_g4m$v~uhxPCG4iDz8dm=Gw>@8k$!pg} z3kJqr|8=V8hZr?s0lm{dyPPRsf|p;Dbbpv{2J2hA5*F)rZs}gM*zHiW&F!kcY{~9v zj_zCX!eIRx$J{e13w+Kg4@1D8YXJ-ufA1ddHljhPf9N0|8A zue&E!>b{7{A*VJ*3D=d>CPa*1ML19u9h`A8uyD6v_I2C)oBU_slVmL9SB@B*J03P+ z=JC4OXh+^kpn5W8gK%g=R7FlseNx$W^#&l(@}Y>kN(nE_1)6Pxpts`MAfmBpmyOq)$_l`Y(- z=v}E<+nC-vhw3j@6Eu?W9w-R5y||;Y7G~|Vx=V*s0pbJtdjw6LngjmNeOhd zV!U?nBZ^D)^v+$C9VTD0r91L`go<3-D`G^HS|qdBd#n7&o#ZYDW=9;aHw0$08!=w1 zAH&mY5_7Uw2-;YUiSj7l-*hA*NQUxs#ih(om662Ez_vBLx&HK5%knytf@?qBoWfFB zMbj7}fr#B9s?f*L<@9>#F%KH5ttU^3m@8YfM6xolog+xk zjTCII%8w|FwzO#$3Ao--^*%5zqq8QliG421A+D^VxYKp7;dwjmv_7(5v`t}faNBDV z@rl@-eT8LamhQKcyHd;QKQ&HTKoz*LD0~Oj z66Whmq?R9uUuK!;Q+a5SR28ds{nRARQufr;`#OjA?OJId{yinh#=r5lSxM*F#(5&C zm2X^$J*`EJZ3_~7)0xFa`tl=Hk&6TN<}YaQMC{E+>@80Ck=xr{r54fNc*`gx=}CNQ z_M@0H&!yhYHBg>Sit^Ncn*262T&>wfqJ);jVa-VG3#hr$bj&+nEIeaJ<x(C{ zTaM}KHRYH!%V4wjt>jdI%~#vdOnI1Dd+~W=BeFCq2=|om-YR0>QX?1 zw-mX%BizwFtHkuBd*E51F7b(YDzzm=Ut$hb>6n-B2+bH1asoOZN~a=Xxk9M#!NhDn zRU)(QhQi0)`~11Kd$Ux#8d9wunm%;zi!Ujpx9h8RydB%K@!fmjR|m4=M5+U_t79Z+ z&b6tunCO6yA62(&{&qfG`9^ZX&Am(JbP>)Zm*i8uLzu;3$6XO<3F{OPo#6Edsk(T?P|2?ZdYl4vo_p!S%Z&%?-OeY zZri5kfrAj4M^dMuI=en6&fgI@(Q*ZK`;^B{WeJ`M4mzV8$Oxf71+9x|dsX4E%(CqL zn@)0(mW==*%Bown_@&L}pd9zwI@6cwbqCgN_c^p;S3}2?x#gGF7%|r07=`fpv)y}= zD^>)*^Q_eoP6~SGX=2mdkcOLaMrKV^z{f{+|1j%pdJ;-DvGfw>vybngFXoB7*F6G;qUU(h`m5*wa!aFVkY$CH>N9u?bqHYu+0u6y4cYIAS!{g#oamJ60Q zGTp{N2kqBpKu^ES8MNuFxUxv4n)Jr7!ZJ&nitGr9AQIU+<9K(|len_;N~DI86WyxT z_$2XSX#qYIj*zq>S+4k}^T+p27g>7KF+X0ITB{>rqejw~DiTj^SiCCQ>+x3HRMu_F zQz0YwYw|jvF#S73Ia?knZ)`k~?cUc=a_XjI)`!{4T?ABud%IuRcGU~!(|V@MKLGo& zpzkKrGWFP^eXyosO9pRB7(>Qh(9z~nKjB>sho*_|t6p{1_-+G8+!?<@^V?dg)eq(p z0fDjt>eUulu;c3Ae1|nw4INB0U~l{hOwK#C(LNN=zGD${4((5^%w4+!0olU!R44Z% zC%VNsh4iXB8Jp?PPB1NtZ!f}{*@iCl3th;|E2VKl$+bCRGt0c5jH7*cd(X2-rTyhn z-xD(fS2tw#_1fjF2(G)qwCpNaba=!XnGq8M_L4;;%FaV)8M6#&oBZ}9W>>*x@%_XI z#Y^hel=RkeR&7Fp$_E{vVzCA=u6B6_eHCiiV~?(!AH0C-nz?>F>Khz7bPIUY#W_#f zxxfXkJc5w0A~9}MTb4w2X8H#uZ?o-w?>l;D1~1$-Y5G;!k8O>92Ffk9HiEbYaBe&w z80t)6-7Y=(+t77mQ~X0DrEW$4t_-ZcVNnb?TbT<2b2GTVy!yCXS_d1j;e8OSn@J)t6H&5=EVVy7@?SD%c((m^i_jGHK{QIpK@uf~`ziNaM24dA^=+_Huz=-~PE3 z*+OLSZc>+Fy@W%#2X0ULcub0`kQ7U(b9Rw8x8G4}*mt|oBG!i;-1#Ef?$vS2Y}~X3 zlUcWm!};k#+Kru!?AAS)?^K4AHDUc;rc%$lqr@VPPpoi@ds69Q|N4}wt=^x6L7$HD z8)Kc3I=j_w=n$zd@|1EigPIQB-lgi-*^>OWyLlq#jeEBGP=Ut;;y5%XikCf{kF8}E z5(BM5MQ;49=bM_4pY`_ME@CN%o-=jrwJmGw&O%5cu+$gYJ_}60(- ztoL#}64evis+e7OlG4S3I_`@sxGQMwrR$cMwcz%>-g-)~P-Cf2v0YS{+?&-wACE@Q z3vOF}!u96&yGGiZS-x7}X-wOIrX28&1vrVsoa}4nH>bYU6T&TZgX~A?t$;HXNNN2?R*dhiOGY7VF}eh@%_&V<@=UTeS2iNPWD6`sc=%) z!{y=oo=Bu#J6V+m=#sutZ*}iFZlR;rBz`{8fpMYng8x9`GJqp9SU6Jd0pzc*iVl!A zwWbwxG_+@mtc_2$6T7R^m`v<07tCDkm{R3mc92faNMTwY%w0ILWpk%G31p3=AOAh* za>yhkFcOIk`1Uj2dHWknyf%jfWPulunQ*5jAtpMA;dz&{W7qWZ8cGmOuGHhc-MX@K zmaRT#48CsL+L``UXX)9eNM{U14U~F2I$q_dZCC6d$aCh+ZRaGNB(_Hc{GhK~{R2Mf zW8A`#WA0R^1F`h&@hBPzIRq(zLnj1h(`K^ryPF~s%T&AOJxs07@INCH$aw$OW_|rF zh1#dMgNm2VdTa=&BZ|zWt}Qz-mJhg4SBY|cs@}UGka)NaaN5^z(FD%9NVhrnOF!j} z^LrK{A8!$mpwf;d1Qu32j!g)k4xT$ZjuBbkT!$$UbcI%$h%uvq`?( zgAZ_Vz`S!JKVf~!_CJbp9a+hO*?G&jOFcV&^UQjGLU3+y&-2X{aS#+Q>RcY7JO|Pk zG|%4D($;ts0hi|sQIc(&+HLRe&AIma=0UYGNjiDS^}gP$=p2KSvvdfjp1(*DT(@mj z+aQhj>y-ff2^UWUowpZ9xiHq_sZKWg;e3DP3 z6h^_YMe}j66en<@urH`NbY9`3PqSXv+AcW?du(5A{H?-E7?}DrZq4 zC$^9xy#Ch70Ei4DT;tR4NVlZ7mEg#!t%c>?iV!ZaYU3?OOY=ldL))s)Kr+lZqCxk4 zEo+fCX2$XXx}uJ*Oh3mg7EWRopFI)FCmwof0yeSM@u?Qt4Hf8P_t!t&vIp?5_3dDc0GyCs(C#i$QPj`C{XlSx zDto5FWAUt-s|Pd3x6KUh&=_kS!%ThS5}Sn_qNlf=RKa2D6VV%KRM~1^{`%_P90kvt z*$6wAW)s4i2rf(Z1MB9>`InJL@Y{0j2fyx~RuQMMw@{p$cS=dV(3;M%i-%0p^^R2V za{Fdp8fmh)BCz$rKJ~gN0n(1V&jc`GoZjQz!Yq(BAI#zom$p^#jDE4?G<5!FutUcm zTXyDx66}Nj(yRz0L4+9(BU{T8#SxddDKLZg^9%CxsHqhTsHx3fvco1o7KH_XK;s-r zL1u@E+~R!QqorHe_2HK6`n)FvNNnM@!4K8|C51FxCFamX0RX71A}}-{UrdJoB+N#> zN;B(nEF@x!a!(#a<1iov)^z%DYU1o3z*yW~#_>{Ic+k$&q`=pEZ2rUQ}kqhvBdRis5!@HJM*czA6GWE4ZFt@b1HiAkBdz{aC@s?8Dakh=7VtLKa`GMluVInq*I%!4Lf=6d6Usnjugb)(4X@AC^<`B*tM#GO*d z$j9v9-sb3>E}M=c`Eg~@#hogwIEhhvWZ}ZNl?|um6Bc%6M^eJ!9mN>wmfh0?vy0_8 zG8VzXPs)1Tt-9(df;T6#j>SE=$4_z~Z$4vR?p{oCbU<=);?fnoXW;3vN0wJK<%mQS zm|BWuwC@rzo{`baeb#h${7jVlKj3F-?l6C}v4W6$n&+W~a@W*LL7dBxTtB`y^R&#G z%BQD{o_a#Glcg=>{sY%EWB&LN*aE1f4_1{2JiPj$^kmlBYsq$pIK+r?ekZJb_8&D+ zx$X5K_|va~<;ZWV?D#da*EOxLr%`Zp0Z3P4rkeixrU&CbUB5pwBE9`}jMoQ>RUmE2 z$JhA_yz5emwtGG}qBE6sjFL5m4_8@`z8XMPdq^=mrloxs+K?q^v!p1XIdbAh@coIe zKKyoUms-c$T~d(B6RUg`a8Rtge6#rM(Gj{F{N<$#?l}~-RHT;m1ziK{c6&^4(Z1PD zsbxLllcq18rRSsn0;{;UB~$a`5`-%A!p66iWp*@w&X9J6PMl_U^IYV*<|txz zSlE>pms(qt`K0Sb**}2k(JgLShnD>Tf@8>*JiOER=IZ22^){C7H)&4;mgyaD`o}=d z*0Yuvt|F(}`fKAOVI@bs5?RXjrbdIV=O@Zv2#8p9`|(mVKTAE{*`QdxbG%(cYms1d zPfbzA0+GH~ISBN|m$xh%Vcf@#dju-`?%fPju?e{fA)DpO}Rc;&q&yE21T_1ggjBh{m!XTp1CN5#R+$+)EuFSsFj%L}S?LxH)nL$-E zO+OyXS8mpGYYL}7i0%hA-=EBApd}nk&Ftd5!8d+9H!}-L7nv`uAe9`kCc4Y2sgZnANq)ww;J)(w zidB01&R^22uEwn!c)9scd23?aJgC~740^7+`5ZZk4g)si6NP}|YkmMeEqt+y#6%Soiv;e^8bmqvmSYq*7;L`P(l2D?^B z*+x|7)=%OyC-(m#1_ry+`lSnb&zt)Q3F-;r#{){q^!$^ z=NII|;ADqMd0F!6=`auq{cyNWCHHmY)=BLcfNv+FIke;5Nud#PV z+>*5Uo;vC6=?94oGtO&gog$rW{V8Pv=dqc?7(RL<0WY*O6p=9;D1=opi+>sbu8@)g zDRGxA-#5O1+Fl{O@=k_EQtR!eY@wW|uWz1EJc?X=AwDj?(;e`)>v|aL(Tv+RKrq}z zy9{-vi7yM4eENFY1=%J+G32%7`idVPW=YXeMd8yivuvo99RD;2(t>@NwtS)+M{uxn zOA}(Snkqg?su3lvr?KX5wKQyhv?|)FPW8Qa^g+*xoK?m5)07$y?V6$N(G+1$#z@b2 z9 z9rn*&M1t!4!HizVhlk7QmEw)rY@OyZ7T<0%mxX=F;NABSmEE}Fkbi13 z+nrE$fVJwZubmb6zMEC_)?RC16_cghIzGJDF4Vsx3x%ZQpu985b2pMx>(iAqhACUOV^Il3fkI z=tO(on#+k1Vm-$5 zk>!g(*~MopDYT6*2{3H2HY+k_3Pj8XC7mkCsDprbXjyH%kj9?xsyjOM#ph9#485ig zLmi~NE?`|6v*G~0n@C|sKJ|Qf4iuU@! zT}S{4R2DvpnZVKi*@|Dq0eVi77Sm&}?_x}Z0VZ-)l((|$mpK;4P2hZVtLt+}NN*3nAEEF|On&l?d!et~xGSHeRh{%C5^HWbtElAX@|j6S7rwIaTuucG z?bCii#j$ByP1xz3S7XcB8Z*{>n4!#No(%YK&rd^~*qIPm@9Ozft;eXzW`<%5`xQO2 zhtYW`lx(2L8Ck|;=EFX!S|;bL06wXK4Es?suQL6+>XUMyb4buvr0>D1^5jWD^3~>~ zs6{A=U%tpd_5IJU9Ez;{J8wWZKZ<^e{GiSk9d89xx4aEoEc;`gLhUt-H=af@*;#_t z#@#2pGd~`CTc#|AGdUy9haGq-uA}xNnBFp^pr!@YOJmXEMo4ENaA?v zT!SQ(N}x7ADdr5HNSuvIFVSKp6)2q(jpFbm8)$jBQlFHs>e-wtFSyetv*o#O?WM@d zu#^Wa5vm_Iy4`Fo%*q_d6x5BjtA~_(X3?rBj}2p!`^E}9Pz$QWVVy|31-CEE5usZ( zQQBV9%M@C!-)Ho?p;QZJq)IU((EeH6(Lwu{iS{pZtjQ!!->2xl{bx(tGsb;rO$ZKr z3VA0}==Mp&FSmm>vqTiNJ+bM%;d^`$j+DLc$a4Q)tIhIRHgyQ$avfQ$)*XJ7aFscNLqf{mtL&qWD$<_g;i-;AUM@&aurD