From dbb7cbb130debe7e9a937af97aea2bc20a207e29 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 16 Feb 2022 15:32:46 +0900 Subject: [PATCH 01/37] feat(behavior_velocity): improve occlusion spot detection area polygon (#354) * feat(behavior_velocity): create triangle detection area polygon Signed-off-by: tanaka3 * chore(behavior_velocity): refactor Signed-off-by: tanaka3 * chore(behavior_velocity): refactor and use planner param Signed-off-by: tanaka3 * chore(behavior_velocity): refactor detection area creation Signed-off-by: tanaka3 * chore(behavior_velocity): refactor possible collision search Signed-off-by: tanaka3 * feat(behavior_velocity): create dynamic poly Signed-off-by: tanaka3 * feat(behavior_velocity): move dynamic object poly to upper function layer Signed-off-by: taikitanaka Signed-off-by: tanaka3 * chore(behavior_velocity): refactor utils Signed-off-by: taikitanaka Signed-off-by: tanaka3 * feat(behavior_velocity): add da polygon to public module too Signed-off-by: taikitanaka Signed-off-by: tanaka3 * feat(behavior_velocity): add da polygon gtest Signed-off-by: taikitanaka Signed-off-by: tanaka3 * chore(behavior_velocity): improve visualization Signed-off-by: tanaka3 * chore(behavior_velocity): visualize occlusion spot Signed-off-by: tanaka3 * chore(behavior_velocity): add debug topics Signed-off-by: tanaka3 * feat(behavior_velocity): better occlusion spot detection Signed-off-by: tanaka3 * chore(behavior_velocity): better expression and early return Signed-off-by: tanaka3 * feat(behavior_velocity): change cmp method of notable collision Signed-off-by: tanaka3 * !chore(dummy_perception): disable raytracing need to revert this before merge Signed-off-by: tanaka3 * chore(behavior_velocity): fix typo Signed-off-by: tanaka3 * chore(behavior_velocity): add description of detection area polygon Signed-off-by: tanaka3 * feat(behavior_velocity): filter occlusion by detection area Signed-off-by: tanaka3 * chore(behavior_velocity): early skip at continue case Signed-off-by: tanaka3 * chore(behavior_velocity): refactor names Signed-off-by: tanaka3 * feat(behavior_velocity): care corner position at grid Signed-off-by: tanaka3 * feat(behavior_velocity): introduce detection area max length Signed-off-by: tanaka3 * chore(behavior_velocity): minor update Signed-off-by: tanaka3 * chore(behavior_velocity): better visualization Signed-off-by: tanaka3 * ci(pre-commit): autofix * chore(behavior_velocity): better comment Signed-off-by: tanaka3 * doc(behavior_velocity): update doc Signed-off-by: tanaka3 * chore(behavior_velocity): minor fix Signed-off-by: tanaka3 * !chore(behavior_velocity): revert debug values Signed-off-by: tanaka3 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/occlusion_spot.param.yaml | 15 +- .../occlusion_spot/detection_area_poly.svg | 4 + .../scene_module/occlusion_spot/geometry.hpp | 36 +-- .../occlusion_spot/grid_utils.hpp | 5 +- .../occlusion_spot/occlusion_spot_utils.hpp | 68 +++-- .../risk_predictive_braking.hpp | 27 +- .../scene_occlusion_spot_in_private_road.hpp | 3 +- .../scene_occlusion_spot_in_public_road.hpp | 7 +- .../occlusion-spot-design.md | 46 ++-- .../src/scene_module/occlusion_spot/debug.cpp | 99 ++++--- .../scene_module/occlusion_spot/geometry.cpp | 158 ++++++------ .../occlusion_spot/grid_utils.cpp | 47 ++-- .../scene_module/occlusion_spot/manager.cpp | 16 +- .../occlusion_spot/occlusion_spot_utils.cpp | 114 ++++---- .../scene_occlusion_spot_in_private_road.cpp | 29 ++- .../scene_occlusion_spot_in_public_road.cpp | 18 +- .../test/src/test_geometry.cpp | 72 ------ .../test/src/test_grid_utils.cpp | 244 ++++-------------- .../test/src/test_risk_predictive_braking.cpp | 62 ++++- 19 files changed, 522 insertions(+), 548 deletions(-) create mode 100644 planning/behavior_velocity_planner/docs/occlusion_spot/detection_area_poly.svg diff --git a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml index 3397c6479a5be..078305a1b7375 100644 --- a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml +++ b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: occlusion_spot: + debug: false # [-] whether to publish debug markers. Note Default should be false for performance pedestrian_vel: 1.0 # [m/s] assume pedestrian is dashing from occlusion at this velocity threshold: detection_area_length: 100.0 # [m] the length of path to consider perception range @@ -9,13 +10,15 @@ motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety max_slow_down_acceleration: -1.5 # [m/s^2] minimum deceleration for safe deceleration. - min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed + non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. + non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. + min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed delay_time: 0.1 # [s] safety time buffer for delay system response safe_margin: 1.0 # [m] maximum safety distance for any error - sidewalk: + detection_area: min_occlusion_spot_size: 1.0 # [m] occupancy grid must contain an UNKNOWN area of at least size NxN to be considered a hidden obstacle. - slice_size: 1.5 # [m] size of sidewalk slices in both length and distance relative to the ego trajectory. - focus_range: 3.0 # [m] buffer around the ego path used to build the sidewalk area. + slice_length: 10.0 # [m] size of slices in both length and distance relative to the ego path. + max_lateral_distance: 4.0 # [m] buffer around the ego path used to build the detection area. grid: - free_space_max: 40 # maximum value of a free space cell in the occupancy grid - occupied_min: 60 # minimum value of an occupied cell in the occupancy grid + free_space_max: 40 # [-] maximum value of a free space cell in the occupancy grid + occupied_min: 60 # [-] minimum value of an occupied cell in the occupancy grid diff --git a/planning/behavior_velocity_planner/docs/occlusion_spot/detection_area_poly.svg b/planning/behavior_velocity_planner/docs/occlusion_spot/detection_area_poly.svg new file mode 100644 index 0000000000000..bf19afce34657 --- /dev/null +++ b/planning/behavior_velocity_planner/docs/occlusion_spot/detection_area_poly.svg @@ -0,0 +1,4 @@ + + + +
t_4
ego
ego
offset
offset
area which obstacle is coming  before ego vehicle pass
area which obstacle is coming  befo...
front bamper
front ba...
lateral max distance
lateral m...
calculate  lateral distance from TTC top consider case if obstacle coming out from here
calculate  lateral distance from TTC top consider c...
t_1
interpolated polygon
interpolated polygon
t_4
expand detail
expand detail
collision point of obstacle
collision point of obst...
place where obstacle  might be coming
place where obstacle  m...
area which ego vehicle pass before hidden obstacle is coming
area which ego vehicle pass before...
area which ego vehicle pass before hidden obstacle is coming
area which ego vehicle pass before...
detection area max length
detection area max length
max length is calculated from ego current velocity and current acceleration
max length is calculated from ego current velocity and current acceleration
area which planned velocity is not effective
area which planned velocity i...
area which planned velocity is not effective
area which planned velocity i...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/geometry.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/geometry.hpp index 1f7fde9acd103..e022df839bccb 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/geometry.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/geometry.hpp @@ -15,6 +15,8 @@ #ifndef SCENE_MODULE__OCCLUSION_SPOT__GEOMETRY_HPP_ #define SCENE_MODULE__OCCLUSION_SPOT__GEOMETRY_HPP_ +#include + #include #include @@ -24,37 +26,19 @@ namespace behavior_velocity_planner { -namespace geometry +namespace occlusion_spot_utils { namespace bg = boost::geometry; -// @brief represent the range of a slice -// (either by index on the lanelet centerline or by arc coordinates) -struct SliceRange -{ - double min_length{}; - double max_length{}; - double min_distance{}; - double max_distance{}; -}; - -// @brief representation of a slice along a path -struct Slice -{ - SliceRange range{}; - lanelet::BasicPolygon2d polygon{}; -}; - //!< @brief build slices all along the trajectory // using the given range and desired slice length and width void buildSlices( - std::vector & slices, const lanelet::ConstLanelet & path_lanelet, const SliceRange & range, - const double slice_length, const double slice_width, const double resolution); -//!< @brief build sidewalk slice from path -void buildSidewalkSlices( - std::vector & slice, const lanelet::ConstLanelet & path_lanelet, - const double longitudinal_offset, const double lateral_offset, const double min_size, - const double lateral_max_dist); + std::vector & slices, const lanelet::ConstLanelet & path_lanelet, const double offset, + const bool is_on_right, const PlannerParam & param); +//!< @brief build detection_area slice from path +void buildDetectionAreaPolygon( + std::vector & slices, const PathWithLaneId & path, const double offset, + const PlannerParam & param); //!< @brief calculate interpolation between a and b at distance ratio t template T lerp(T a, T b, double t) @@ -62,7 +46,7 @@ T lerp(T a, T b, double t) return a + t * (b - a); } -} // namespace geometry +} // namespace occlusion_spot_utils } // namespace behavior_velocity_planner #endif // SCENE_MODULE__OCCLUSION_SPOT__GEOMETRY_HPP_ diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp index 1601d49b5806d..8d7edf060cf6f 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/grid_utils.hpp @@ -19,7 +19,6 @@ #include #include #include -#include #include @@ -51,7 +50,7 @@ struct OcclusionSpotSquare { grid_map::Index index; // index of the anchor grid_map::Position position; // position of the anchor - int side_size; // number of cells for each side of the square + int min_occlusion_size; // number of cells for each side of the square }; // @brief structure representing a OcclusionSpot on the OccupancyGrid struct OcclusionSpot @@ -64,7 +63,7 @@ struct OcclusionSpot // if the given cell is a occlusion_spot square of size min_size*min_size in the given grid bool isOcclusionSpotSquare( OcclusionSpotSquare & occlusion_spot, const grid_map::Matrix & grid_data, - const grid_map::Index & cell, const int side_size, const grid_map::Size & grid_size); + const grid_map::Index & cell, const int min_occlusion_size, const grid_map::Size & grid_size); //!< @brief Find all occlusion spots inside the given lanelet void findOcclusionSpots( std::vector & occlusion_spot_positions, const grid_map::GridMap & grid, diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp index e03ec0d154597..260fdb40357be 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp @@ -18,7 +18,6 @@ #include #include #include -#include #include #include #include @@ -30,6 +29,8 @@ #include #include +#include + #include #include #include @@ -65,10 +66,10 @@ namespace occlusion_spot_utils { enum ROAD_TYPE { PRIVATE, PUBLIC, HIGHWAY, UNKNOWN }; -struct Sidewalk +struct DetectionArea { - double focus_range; // [m] distance to care about occlusion spot - double slice_size; // [m] size of each slice + double max_lateral_distance; // [m] distance to care about occlusion spot + double slice_length; // [m] size of each slice double min_occlusion_spot_size; // [m] minumum size to care about the occlusion spot }; struct Velocity @@ -77,6 +78,8 @@ struct Velocity double max_stop_jerk; // [m/s^3] emergency braking system jerk double max_stop_accel; // [m/s^2] emergency braking system deceleration double max_slow_down_accel; // [m/s^2] maximum allowed deceleration + double non_effective_jerk; // [m/s^3] too weak jerk for velocity planning. + double non_effective_accel; // [m/s^2] too weak deceleration for velocity planning. double min_allowed_velocity; // [m/s] minimum allowed velocity not to stop double a_ego; // [m/s^2] current ego acceleration double v_ego; // [m/s] current ego velocity @@ -84,24 +87,31 @@ struct Velocity double safe_margin; // [m] maximum safety distance for any error }; +struct LatLon +{ + double lateral_distance; // [m] lateral distance + double longitudinal_distance; // [m] longitudinal distance +}; + struct PlannerParam { + bool debug; // [-] // parameters in yaml - double detection_area_length; // [m] - double stuck_vehicle_vel; // [m/s] - double lateral_distance_thr; // [m] lateral distance threshold to consider - double pedestrian_vel; // [m/s] + double detection_area_length; // [m] + double detection_area_max_length; // [m] + double stuck_vehicle_vel; // [m/s] + double lateral_distance_thr; // [m] lateral distance threshold to consider + double pedestrian_vel; // [m/s] - double dist_thr; // [m] - double angle_thr; // [rad] - bool show_debug_grid; // [-] + double dist_thr; // [m] + double angle_thr; // [rad] // vehicle info double half_vehicle_width; // [m] half vehicle_width from vehicle info double baselink_to_front; // [m] wheel_base + front_overhang Velocity v; - Sidewalk sidewalk; + DetectionArea detection_area; grid_utils::GridParam grid; }; @@ -111,6 +121,22 @@ struct SafeMotion double safe_velocity; }; +// @brief represent the range of a each polygon +struct SliceRange +{ + double min_length{}; + double max_length{}; + double min_distance{}; + double max_distance{}; +}; + +// @brief representation of a polygon along a path +struct Slice +{ + SliceRange range{}; + lanelet::BasicPolygon2d polygon{}; +}; + struct ObstacleInfo { SafeMotion safe_motion; // safe motion of velocity and stop point @@ -199,6 +225,8 @@ inline bool isStuckVehicle(PredictedObject obj, const double min_vel) } void filterCollisionByRoadType( std::vector & possible_collisions, const DetectionAreaIdx road_type); +std::vector filterDynamicObjectByDetectionArea( + std::vector & objs, const std::vector polys); bool splineInterpolate( const PathWithLaneId & input, const double interval, PathWithLaneId * output, const rclcpp::Logger logger); @@ -228,17 +256,17 @@ void calcSlowDownPointsForPossibleCollision( DetectionAreaIdx extractTargetRoadArcLength( const LaneletMapPtr lanelet_map_ptr, const double max_range, const PathWithLaneId & path, const ROAD_TYPE & target_road_type); -//!< @brief convert a set of occlusion spots found on sidewalk slice -void generateSidewalkPossibleCollisionFromOcclusionSpot( - std::vector & possible_collisions, const grid_map::GridMap & grid, - const std::vector & occlusion_spot_positions, - const double offset_from_start_to_ego, const lanelet::ConstLanelet & path_lanelet, - const PlannerParam & param); +//!< @brief convert a set of occlusion spots found on detection_area slice +boost::optional generateOneNotableCollisionFromOcclusionSpot( + const grid_map::GridMap & grid, const std::vector & occlusion_spot_positions, + const double offset_from_start_to_ego, const BasicPoint2d basic_point, + const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param); //!< @brief generate possible collisions coming from occlusion spots on the side of the path -void generateSidewalkPossibleCollisions( +void createPossibleCollisionsInDetectionArea( + const std::vector & detection_area_polygons, std::vector & possible_collisions, const grid_map::GridMap & grid, const PathWithLaneId & path, const double offset_from_start_to_ego, const PlannerParam & param, - std::vector & debug); + std::vector & debug_points); } // namespace occlusion_spot_utils } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/risk_predictive_braking.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/risk_predictive_braking.hpp index 10e79f71930cb..59145de966dfe 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/risk_predictive_braking.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/risk_predictive_braking.hpp @@ -44,7 +44,32 @@ inline double calculateMinSlowDownVelocity( } /** - * @param: sv: ego velocity config + * + * @param: longitudinal_distance: longitudinal distance to collision + * @param: param: planner param + * @return lateral distance + **/ +inline double calculateLateralDistanceFromTTC( + const double longitudinal_distance, const PlannerParam & param) +{ + const auto & v = param.v; + const auto & p = param; + double v_min = 1.0; + const double lateral_buffer = 0.5; + const double min_distance = p.half_vehicle_width + lateral_buffer; + const double max_distance = p.detection_area.max_lateral_distance; + if (longitudinal_distance <= 0) return min_distance; + if (v_min < param.v.min_allowed_velocity) v_min = param.v.min_allowed_velocity; + // use min velocity if ego velocity is below min allowed + const double v0 = (v.v_ego > v_min) ? v.v_ego : v_min; + // here is a part where ego t(ttc) can be replaced by calculation of velocity smoother or ? + double t = longitudinal_distance / v0; + double lateral_distance = t * param.pedestrian_vel + p.half_vehicle_width; + return std::min(max_distance, std::max(min_distance, lateral_distance)); +} + +/** + * @param: v: ego velocity config * @param: ttc: time to collision * @return safe motion **/ diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.hpp index 93d382576c29e..fed53518eb1ca 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.hpp @@ -46,8 +46,9 @@ class OcclusionSpotInPrivateModule : public SceneModuleInterface { double z; std::string road_type = "private"; - std::vector sidewalks; + std::vector detection_areas; std::vector possible_collisions; + std::vector occlusion_points; PathWithLaneId path_raw; PathWithLaneId interp_path; }; diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.hpp index 250972dea8342..869084e7ed410 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.hpp @@ -44,10 +44,13 @@ class OcclusionSpotInPublicModule : public SceneModuleInterface struct DebugData { std::string road_type = "public"; - double z; - std::vector sidewalks; + std::vector detection_areas; std::vector parked_vehicle_point; std::vector possible_collisions; + std::vector occlusion_points; + PathWithLaneId path_raw; + PathWithLaneId interp_path; + double z; }; OcclusionSpotInPublicModule( diff --git a/planning/behavior_velocity_planner/occlusion-spot-design.md b/planning/behavior_velocity_planner/occlusion-spot-design.md index 2cbc0d2368fd0..7dc1cb6330cd1 100644 --- a/planning/behavior_velocity_planner/occlusion-spot-design.md +++ b/planning/behavior_velocity_planner/occlusion-spot-design.md @@ -47,17 +47,11 @@ This module considers any occlusion spot around ego path computed from the occup ![occupancy_grid](./docs/occlusion_spot/occupancy_grid.svg) -Occlusion spot computation: searching occlusion spots for all cells in the occupancy_grid inside "focus range" requires a lot of computational cost, so this module will stop searching if the first occlusion spot is found in the following searching process. - -![brief](./docs/occlusion_spot/sidewalk_slice.svg) - -Note that the accuracy and performance of this search method is limited due to the approximation. - #### Occlusion Spot Common ##### The Concept of Safe Velocity -Safe velocity is calculated from below parameters of ego emergency braking system and time to collision. +Safe velocity is calculated from the below parameters of ego emergency braking system and time to collision. - jerk limit[m/s^3] - deceleration limit[m/s2] @@ -68,11 +62,18 @@ Safe velocity is calculated from below parameters of ego emergency braking syste ##### Safe Behavior After Passing Safe Margin Point -This module defines safe margin consider ego distance to stop and collision path point geometrically. -while ego is cruising from safe margin to collision path point ego keeps same velocity as occlusion spot safe velocity. +This module defines safe margin to consider ego distance to stop and collision path point geometrically. +While ego is cruising from safe margin to collision path point, ego vehicle keeps the same velocity as occlusion spot safe velocity. ![brief](./docs/occlusion_spot/behavior_after_safe_margin.svg) +##### Detection area polygon + +Occlusion spot computation: searching occlusion spots for all cells in the occupancy_grid inside "max lateral distance" requires a lot of computational cost, so this module use only one most notable occlusion spot for each partition. (currently offset is from baselink to front for safety) +The maximum length of detection area depends on ego current vehicle velocity and acceleration. + +![brief](./docs/occlusion_spot/detection_area_poly.svg) + #### Module Parameters | Parameter | Type | Description | @@ -93,16 +94,16 @@ while ego is cruising from safe margin to collision path point ego keeps same ve | `delay_time` | double | [m/s] time buffer for the system delay | | `safe_margin` | double | [m] maximum error to stop with emergency braking system. | -| Parameter /sidewalk | Type | Description | -| ------------------------- | ------ | --------------------------------------------------------------- | -| `min_occlusion_spot_size` | double | [m] the length of path to consider occlusion spot | -| `slice_size` | double | [m] the distance of divided detection area | -| `focus_range` | double | [m] buffer around the ego path used to build the sidewalk area. | +| Parameter /detection_area | Type | Description | +| ------------------------- | ------ | --------------------------------------------------------------------- | +| `min_occlusion_spot_size` | double | [m] the length of path to consider occlusion spot | +| `slice_length` | double | [m] the distance of divided detection area | +| `max_lateral_distance` | double | [m] buffer around the ego path used to build the detection_area area. | -| Parameter /grid | Type | Description | -| ---------------- | ------ | --------------------------------------------------------------- | -| `free_space_max` | double | [-] maximum value of a free space cell in the occupancy grid | -| `occupied_min` | double | [-] buffer around the ego path used to build the sidewalk area. | +| Parameter /grid | Type | Description | +| ---------------- | ------ | --------------------------------------------------------------------- | +| `free_space_max` | double | [-] maximum value of a free space cell in the occupancy grid | +| `occupied_min` | double | [-] buffer around the ego path used to build the detection_area area. | #### Flowchart @@ -135,8 +136,13 @@ else (no) stop endif } -partition find_possible_collision { :calculate offset from start to ego; +partition generate_detection_area_polygon { +:convert path to path lanelet; +:generate left/right slice of polygon that starts from path start; +:generate interpolated polygon which is created from ego TTC and lateral distance that pedestrian can reach within ego TTC.; +} +partition find_possible_collision { :generate possible collision; :calculate collision path point and intersection point; note right @@ -201,6 +207,7 @@ note right - velocity is below `stuck_vehicle_vel`. end note } +:generate_detection_area_polygon; partition find_possible_collision { :generate possible collision behind parked vehicle; note right @@ -258,6 +265,7 @@ note right convert from occupancy grid to image to use opencv functions. end note } +:generate_detection_area_polygon; partition generate_possible_collision { :calculate offset from path start to ego; :generate possible collision from occlusion spot; diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/debug.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/debug.cpp index 4af5a95ce4413..4cae4d7b92a80 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/debug.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/debug.cpp @@ -27,13 +27,15 @@ namespace behavior_velocity_planner { namespace { +using builtin_interfaces::msg::Time; + visualization_msgs::msg::Marker makeArrowMarker( - const occlusion_spot_utils::PossibleCollisionInfo & possible_collision, int id) + const occlusion_spot_utils::PossibleCollisionInfo & possible_collision, const int id) { visualization_msgs::msg::Marker debug_marker; debug_marker.header.frame_id = "map"; debug_marker.ns = "occlusion spot arrow"; - debug_marker.id = id; + debug_marker.id = planning_utils::bitShift(id); debug_marker.type = visualization_msgs::msg::Marker::ARROW; debug_marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0); debug_marker.scale = tier4_autoware_utils::createMarkerScale(0.05, 0.2, 0.5); @@ -49,7 +51,7 @@ visualization_msgs::msg::Marker makeArrowMarker( std::vector makeSlowDownMarkers( const occlusion_spot_utils::PossibleCollisionInfo & possible_collision, - const std::string road_type, int id) + const std::string road_type, const int id) { // virtual wall std::vector debug_markers; @@ -59,7 +61,7 @@ std::vector makeSlowDownMarkers( wall_marker.lifetime = rclcpp::Duration::from_seconds(0.5); wall_marker.type = visualization_msgs::msg::Marker::CUBE; wall_marker.action = visualization_msgs::msg::Marker::ADD; - wall_marker.id = id; + wall_marker.id = planning_utils::bitShift(id); // cylinder at collision point wall_marker.pose = possible_collision.intersection_pose; wall_marker.pose.position.z += 1.0; @@ -73,7 +75,7 @@ std::vector makeSlowDownMarkers( visualization_msgs::msg::Marker slowdown_reason_marker; slowdown_reason_marker.header.frame_id = "map"; slowdown_reason_marker.ns = "slow factor_text"; - slowdown_reason_marker.id = id; + slowdown_reason_marker.id = planning_utils::bitShift(id); slowdown_reason_marker.lifetime = rclcpp::Duration::from_seconds(0.5); slowdown_reason_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; slowdown_reason_marker.action = visualization_msgs::msg::Marker::ADD; @@ -91,13 +93,14 @@ std::vector makeSlowDownMarkers( } std::vector makeCollisionMarkers( - const occlusion_spot_utils::PossibleCollisionInfo & possible_collision, int id, bool show_text) + const occlusion_spot_utils::PossibleCollisionInfo & possible_collision, const int id, + const bool show_text) { std::vector debug_markers; visualization_msgs::msg::Marker debug_marker; debug_marker.header.frame_id = "map"; debug_marker.ns = "collision_point"; - debug_marker.id = id; + debug_marker.id = planning_utils::bitShift(id); // cylinder at collision with margin point debug_marker.type = visualization_msgs::msg::Marker::CYLINDER; debug_marker.pose = possible_collision.collision_with_margin.pose; @@ -139,12 +142,13 @@ std::vector makeCollisionMarkers( } visualization_msgs::msg::MarkerArray makePolygonMarker( - const std::vector & polygons, double z) + const std::vector & polygons, const int id, const double z) { visualization_msgs::msg::MarkerArray debug_markers; visualization_msgs::msg::Marker debug_marker; debug_marker.header.frame_id = "map"; - debug_marker.id = 0; + debug_marker.header.stamp = rclcpp::Time(0); + debug_marker.id = planning_utils::bitShift(id); debug_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; debug_marker.action = visualization_msgs::msg::Marker::ADD; debug_marker.pose.position = tier4_autoware_utils::createMarkerPosition(0.0, 0.0, z); @@ -152,7 +156,7 @@ visualization_msgs::msg::MarkerArray makePolygonMarker( debug_marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1); debug_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.0, 1.0, 0.3); debug_marker.lifetime = rclcpp::Duration::from_seconds(0.1); - debug_marker.ns = "sidewalk"; + debug_marker.ns = "detection_area"; for (const auto & poly : polygons) { for (const auto & p : poly) { geometry_msgs::msg::Point point = @@ -196,23 +200,15 @@ visualization_msgs::msg::MarkerArray createPathMarkerArray( } template -visualization_msgs::msg::MarkerArray createMarkers( +visualization_msgs::msg::MarkerArray createPossibleCollisionMarkers( T & debug_data, [[maybe_unused]] const int64_t module_id_) { // add slow down markers for occlusion spot visualization_msgs::msg::MarkerArray occlusion_spot_slowdown_markers; auto & possible_collisions = debug_data.possible_collisions; - // sort collision - std::sort( - possible_collisions.begin(), possible_collisions.end(), - []( - occlusion_spot_utils::PossibleCollisionInfo pc1, - occlusion_spot_utils::PossibleCollisionInfo pc2) { - return pc1.arc_lane_dist_at_collision.length < pc2.arc_lane_dist_at_collision.length; - }); // draw virtual wall markers - int id = 0; + int id = planning_utils::bitShift(module_id_); for (const auto & possible_collision : possible_collisions) { std::vector collision_markers = makeSlowDownMarkers(possible_collision, debug_data.road_type, id++); @@ -222,7 +218,7 @@ visualization_msgs::msg::MarkerArray createMarkers( } // draw obstacle collision - id = 0; + id = planning_utils::bitShift(module_id_); for (const auto & possible_collision : possible_collisions) { // debug marker std::vector collision_markers = @@ -235,6 +231,25 @@ visualization_msgs::msg::MarkerArray createMarkers( return occlusion_spot_slowdown_markers; } +visualization_msgs::msg::MarkerArray createOcclusionMarkerArray( + const std::vector & occlusion_points, const int64_t module_id) +{ + visualization_msgs::msg::MarkerArray msg; + { + const Time now = rclcpp::Time(0); + auto marker = createDefaultMarker( + "map", now, "occlusion", 0, visualization_msgs::msg::Marker::SPHERE, + createMarkerColor(1.0, 0.0, 0.0, 0.999)); + marker.scale = createMarkerScale(0.5, 0.5, 0.5); + marker.lifetime = rclcpp::Duration::from_seconds(0.1); + for (size_t i = 0; i < occlusion_points.size(); ++i) { + marker.id = i + planning_utils::bitShift(module_id); + marker.pose.position = occlusion_points.at(i); + msg.markers.push_back(marker); + } + } + return msg; +} } // namespace visualization_msgs::msg::MarkerArray OcclusionSpotInPublicModule::createDebugMarkerArray() @@ -242,7 +257,16 @@ visualization_msgs::msg::MarkerArray OcclusionSpotInPublicModule::createDebugMar const auto current_time = this->clock_->now(); visualization_msgs::msg::MarkerArray debug_marker_array; - appendMarkerArray(createMarkers(debug_data_, module_id_), current_time, &debug_marker_array); + if (!debug_data_.possible_collisions.empty()) { + appendMarkerArray( + createPossibleCollisionMarkers(debug_data_, module_id_), current_time, &debug_marker_array); + } + if (!debug_data_.detection_areas.empty()) { + appendMarkerArray( + makePolygonMarker(debug_data_.detection_areas, module_id_, debug_data_.z), current_time, + &debug_marker_array); + } + return debug_marker_array; } visualization_msgs::msg::MarkerArray OcclusionSpotInPrivateModule::createDebugMarkerArray() @@ -250,15 +274,28 @@ visualization_msgs::msg::MarkerArray OcclusionSpotInPrivateModule::createDebugMa const auto current_time = this->clock_->now(); visualization_msgs::msg::MarkerArray debug_marker_array; - appendMarkerArray(createMarkers(debug_data_, module_id_), current_time, &debug_marker_array); - appendMarkerArray( - makePolygonMarker(debug_data_.sidewalks, debug_data_.z), current_time, &debug_marker_array); - appendMarkerArray( - createPathMarkerArray(debug_data_.path_raw, "path_raw", 0, 0.0, 1.0, 1.0), current_time, - &debug_marker_array); - appendMarkerArray( - createPathMarkerArray(debug_data_.interp_path, "path_interp", 0, 0.0, 1.0, 1.0), current_time, - &debug_marker_array); + if (!debug_data_.possible_collisions.empty()) { + appendMarkerArray( + createPossibleCollisionMarkers(debug_data_, module_id_), current_time, &debug_marker_array); + } + if (!debug_data_.detection_areas.empty()) { + appendMarkerArray( + makePolygonMarker(debug_data_.detection_areas, module_id_, debug_data_.z), current_time, + &debug_marker_array); + } + if (!debug_data_.interp_path.points.empty()) { + appendMarkerArray( + createPathMarkerArray(debug_data_.path_raw, "path_raw", 0, 0.0, 1.0, 1.0), current_time, + &debug_marker_array); + appendMarkerArray( + createPathMarkerArray(debug_data_.interp_path, "path_interp", 0, 0.0, 1.0, 1.0), current_time, + &debug_marker_array); + } + if (!debug_data_.occlusion_points.empty()) { + appendMarkerArray( + createOcclusionMarkerArray(debug_data_.occlusion_points, module_id_), current_time, + &debug_marker_array); + } return debug_marker_array; } } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/geometry.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/geometry.cpp index e88274458e229..acb1827bc686b 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/geometry.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/geometry.cpp @@ -16,13 +16,15 @@ #include #include #include +#include +#include #include #include namespace behavior_velocity_planner { -namespace geometry +namespace occlusion_spot_utils { using lanelet::BasicLineString2d; using lanelet::BasicPoint2d; @@ -30,106 +32,102 @@ using lanelet::BasicPolygon2d; namespace bg = boost::geometry; namespace lg = lanelet::geometry; -void createOffsetLineString( - const BasicLineString2d & in, const double offset, BasicLineString2d & offset_line_string) +BasicPoint2d calculateLateralOffsetPoint( + const BasicPoint2d & p0, const BasicPoint2d & p1, const double offset) { - for (size_t i = 0; i < in.size() - 1; i++) { - const auto & p0 = in.at(i); - const auto & p1 = in.at(i + 1); - // translation - const double dy = p1[1] - p0[1]; - const double dx = p1[0] - p0[0]; - // rotation (use inverse matrix of rotation) - const double yaw = std::atan2(dy, dx); - // translation - const double offset_x = p0[0] - std::sin(yaw) * offset; - const double offset_y = p0[1] + std::cos(yaw) * offset; - offset_line_string.emplace_back(BasicPoint2d{offset_x, offset_y}); - //! insert final offset linestring using prev vertical direction - if (i == in.size() - 2) { - const double offset_x = p1[0] - std::sin(yaw) * offset; - const double offset_y = p1[1] + std::cos(yaw) * offset; - offset_line_string.emplace_back(BasicPoint2d{offset_x, offset_y}); - } - } - return; + // translation + const double dy = p1[1] - p0[1]; + const double dx = p1[0] - p0[0]; + // rotation (use inverse matrix of rotation) + const double yaw = std::atan2(dy, dx); + const double offset_x = p1[0] - std::sin(yaw) * offset; + const double offset_y = p1[1] + std::cos(yaw) * offset; + return BasicPoint2d{offset_x, offset_y}; } void buildSlices( - std::vector & slices, const lanelet::ConstLanelet & path_lanelet, const SliceRange & range, - const double slice_length, const double slice_width, const double resolution) + std::vector & slices, const lanelet::ConstLanelet & path_lanelet, const double offset, + const bool is_on_right, const PlannerParam & param) { - const int num_lateral_slice = - static_cast(std::abs(range.max_distance - range.min_distance) / slice_width); + BasicLineString2d center_line = path_lanelet.centerline2d().basicLineString(); + const auto & p = param; /** - * @brief bounds - * +---------- outer bounds - * | +------ inner bounds(original path) - * | | + * @brief relationships for interpolated polygon + * + * +(min_length,max_distance)-+ - +---+(max_length,max_distance) = outer_polygons + * | | + * +--------------------------+ - +---+(max_length,min_distance) = inner_polygons */ - BasicLineString2d inner_bounds = path_lanelet.centerline2d().basicLineString(); - BasicLineString2d outer_bounds; - if (inner_bounds.size() < 2) return; - createOffsetLineString(inner_bounds, range.max_distance, outer_bounds); - const double ratio_dist_start = std::abs(range.min_distance / range.max_distance); - const double ratio_dist_increment = std::min(1.0, slice_width / std::abs(range.max_distance)); - lanelet::BasicPolygon2d poly; - const int num_step = static_cast(slice_length / resolution); + const double min_length = offset; // + p.baselink_to_front; + // Note: min_detection_area_length is for occlusion spot visualization but not effective for + // planning + const double min_detection_area_length = 10.0; + const double max_length = std::max( + min_detection_area_length, std::min(p.detection_area_max_length, p.detection_area_length)); + const double min_distance = (is_on_right) ? -p.half_vehicle_width : p.half_vehicle_width; + const double slice_length = p.detection_area.slice_length; + const int num_step = static_cast(slice_length); //! max index is the last index of path point - const int max_index = static_cast(inner_bounds.size() - 1); + const int max_index = static_cast(center_line.size() - 2); + int idx = 0; + /** + * Note: create polygon from path point is better than from ego offset to consider below + * - less computation cost and no need to recalculated interpolated point start from ego + * - less stable for localization noise + **/ for (int s = 0; s < max_index; s += num_step) { const double length = s * slice_length; - const double next_length = (s + num_step) * resolution; - for (int d = 0; d < num_lateral_slice; d++) { - const double ratio_dist = ratio_dist_start + d * ratio_dist_increment; - const double next_ratio_dist = ratio_dist_start + (d + 1.0) * ratio_dist_increment; - Slice slice; - BasicLineString2d inner_polygons; - BasicLineString2d outer_polygons; - // build interpolated polygon for lateral - for (int i = 0; i <= num_step; i++) { - if (s + i >= max_index) continue; - inner_polygons.emplace_back( - lerp(inner_bounds.at(s + i), outer_bounds.at(s + i), ratio_dist)); - outer_polygons.emplace_back( - lerp(inner_bounds.at(s + i), outer_bounds.at(s + i), next_ratio_dist)); - } - // Build polygon - inner_polygons.insert(inner_polygons.end(), outer_polygons.rbegin(), outer_polygons.rend()); - slice.polygon = lanelet::BasicPolygon2d(inner_polygons); - // add range info - slice.range.min_length = length; - slice.range.max_length = next_length; - slice.range.min_distance = ratio_dist * range.max_distance; - slice.range.max_distance = next_ratio_dist * range.max_distance; - slices.emplace_back(slice); + const double next_length = static_cast(s + num_step); + /// if (max_length < length) continue; + Slice slice; + BasicLineString2d inner_polygons; + BasicLineString2d outer_polygons; + // build connected polygon for lateral + for (int i = 0; i <= num_step; i++) { + idx = s + i; + const double arc_length_from_ego = std::max(0.0, static_cast(idx - min_length)); + if (arc_length_from_ego > max_length) break; + if (idx >= max_index) break; + const auto & c0 = center_line.at(idx); + const auto & c1 = center_line.at(idx + 1); + /** + * @brief points + * +--outer point (lateral distance obstacle can reach) + * | + * +--inner point(min distance) + */ + const BasicPoint2d inner_point = calculateLateralOffsetPoint(c0, c1, min_distance); + double lateral_distance = calculateLateralDistanceFromTTC(arc_length_from_ego, param); + if (is_on_right) lateral_distance *= -1; + const BasicPoint2d outer_point = calculateLateralOffsetPoint(c0, c1, lateral_distance); + inner_polygons.emplace_back(inner_point); + outer_polygons.emplace_back(outer_point); } + if (inner_polygons.empty()) continue; + // connect invert point + inner_polygons.insert(inner_polygons.end(), outer_polygons.rbegin(), outer_polygons.rend()); + slice.polygon = lanelet::BasicPolygon2d(inner_polygons); + // add range info + slice.range.min_length = length; + slice.range.max_length = next_length; + slices.emplace_back(slice); } } -void buildSidewalkSlices( - std::vector & slices, const lanelet::ConstLanelet & path_lanelet, - const double longitudinal_offset, const double lateral_offset, const double slice_size, - const double lateral_max_dist) +void buildDetectionAreaPolygon( + std::vector & slices, const PathWithLaneId & path, const double offset, + const PlannerParam & param) { std::vector left_slices; std::vector right_slices; - const double longitudinal_max_dist = lg::length2d(path_lanelet); - SliceRange left_slice_range = { - longitudinal_offset, longitudinal_max_dist, lateral_offset, lateral_offset + lateral_max_dist}; + lanelet::ConstLanelet path_lanelet = toPathLanelet(path); // in most case lateral distance is much more effective for velocity planning - const double slice_length = 4.0 * slice_size; - const double slice_width = slice_size; - const double resolution = 1.0; - buildSlices(left_slices, path_lanelet, left_slice_range, slice_length, slice_width, resolution); - SliceRange right_slice_range = { - longitudinal_offset, longitudinal_max_dist, -lateral_offset, - -lateral_offset - lateral_max_dist}; - buildSlices(right_slices, path_lanelet, right_slice_range, slice_length, slice_width, resolution); + buildSlices(left_slices, path_lanelet, offset, false /*is_on_right*/, param); + buildSlices(right_slices, path_lanelet, offset, true /*is_on_right*/, param); // Properly order lanelets from closest to furthest slices = left_slices; slices.insert(slices.end(), right_slices.begin(), right_slices.end()); return; } -} // namespace geometry +} // namespace occlusion_spot_utils } // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp index 498c873b30d5f..6e7d31e4b5705 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/grid_utils.cpp @@ -24,15 +24,22 @@ namespace grid_utils { bool isOcclusionSpotSquare( OcclusionSpotSquare & occlusion_spot, const grid_map::Matrix & grid_data, - const grid_map::Index & cell, int side_size, const grid_map::Size & grid_size) + const grid_map::Index & cell, int min_occlusion_size, const grid_map::Size & grid_size) { + const int offset = (min_occlusion_size != 1) ? (min_occlusion_size - 1) : min_occlusion_size; + const int cell_max_x = grid_size.x() - 1; + const int cell_max_y = grid_size.y() - 1; // Calculate ranges to check - int min_x; - int max_x; - int min_y; - int max_y; + int min_x = cell.x() - offset; + int max_x = cell.x() + offset; + int min_y = cell.y() - offset; + int max_y = cell.y() + offset; + if (min_x < 0) max_x += std::abs(min_x); + if (max_x > cell_max_x) min_x -= std::abs(max_x - cell_max_x); + if (min_y < 0) max_y += std::abs(min_y); + if (max_y > cell_max_y) min_y -= std::abs(max_y - cell_max_y); // No occlusion_spot with size 0 - if (side_size == 0) { + if (min_occlusion_size == 0) { return false; } /** @@ -41,25 +48,31 @@ bool isOcclusionSpotSquare( * . . * (min_x,max_y)...(max_x,max_y) */ - const int offset = side_size - 1; - min_x = cell.x(); - max_x = cell.x() + offset; - min_y = cell.y() - offset; - max_y = cell.y(); // Ensure we stay inside the grid min_x = std::max(0, min_x); - max_x = std::min(grid_size.x() - 1, max_x); + max_x = std::min(cell_max_x, max_x); min_y = std::max(0, min_y); - max_y = std::min(grid_size.y() - 1, max_y); + max_y = std::min(cell_max_y, max_y); + int not_unknown_count = 0; + if (grid_data(cell.x(), cell.y()) != grid_utils::occlusion_cost_value::UNKNOWN) { + return false; + } for (int x = min_x; x <= max_x; ++x) { for (int y = min_y; y <= max_y; ++y) { // if the value is not unknown value return false if (grid_data(x, y) != grid_utils::occlusion_cost_value::UNKNOWN) { - return false; + not_unknown_count++; } + /** + * @brief case pass o: unknown x: freespace or occupied + * oxx oxo oox xxx oxo oxo + * oox oxx oox ooo oox oxo ... etc + * ooo ooo oox ooo xoo oxo + */ + if (not_unknown_count > min_occlusion_size + 1) return false; } } - occlusion_spot.side_size = side_size; + occlusion_spot.min_occlusion_size = min_occlusion_size; occlusion_spot.index = cell; return true; } @@ -112,12 +125,12 @@ void getCornerPositions( const OcclusionSpotSquare & occlusion_spot_square) { // Special case with size = 1: only one cell - if (occlusion_spot_square.side_size == 1) { + if (occlusion_spot_square.min_occlusion_size == 1) { corner_positions.emplace_back(occlusion_spot_square.position); return; } std::vector corner_indexes; - const int offset = (occlusion_spot_square.side_size - 1) / 2; + const int offset = (occlusion_spot_square.min_occlusion_size - 1) / 2; /** * @brief relation of each grid position * bl br diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp index 316873d80d751..739fa9169c461 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp @@ -80,6 +80,7 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) // for crosswalk parameters auto & pp = planner_param_; // assume pedestrian coming out from occlusion spot with this velocity + pp.debug = node.declare_parameter(ns + ".debug", false); pp.pedestrian_vel = node.declare_parameter(ns + ".pedestrian_vel", 1.0); pp.detection_area_length = node.declare_parameter(ns + ".threshold.detection_area_length", 200.0); pp.stuck_vehicle_vel = node.declare_parameter(ns + ".threshold.stuck_vehicle_vel", 1.0); @@ -87,19 +88,22 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) pp.dist_thr = node.declare_parameter(ns + ".threshold.search_dist", 10.0); pp.angle_thr = node.declare_parameter(ns + ".threshold.search_angle", M_PI / 5.0); - pp.show_debug_grid = node.declare_parameter(ns + ".show_debug_grid", false); // ego additional velocity config pp.v.safety_ratio = node.declare_parameter(ns + ".motion.safety_ratio", 1.0); pp.v.delay_time = node.declare_parameter(ns + ".motion.delay_time", 0.1); pp.v.safe_margin = node.declare_parameter(ns + ".motion.safe_margin", 1.0); pp.v.max_slow_down_accel = node.declare_parameter(ns + ".motion.max_slow_down_accel", -1.5); + pp.v.non_effective_jerk = node.declare_parameter(ns + ".motion.non_effective_jerk", -0.3); + pp.v.non_effective_accel = + node.declare_parameter(ns + ".motion.non_effective_acceleration", -1.0); pp.v.min_allowed_velocity = node.declare_parameter(ns + ".motion.min_allowed_velocity", 1.0); - // sidewalk param - pp.sidewalk.min_occlusion_spot_size = - node.declare_parameter(ns + ".sidewalk.min_occlusion_spot_size", 2.0); - pp.sidewalk.focus_range = node.declare_parameter(ns + ".sidewalk.focus_range", 4.0); - pp.sidewalk.slice_size = node.declare_parameter(ns + ".sidewalk.slice_size", 1.5); + // detection_area param + pp.detection_area.min_occlusion_spot_size = + node.declare_parameter(ns + ".detection_area.min_occlusion_spot_size", 2.0); + pp.detection_area.max_lateral_distance = + node.declare_parameter(ns + ".detection_area.max_lateral_distance", 4.0); + pp.detection_area.slice_length = node.declare_parameter(ns + ".detection_area.slice_length", 1.5); // occupancy grid param pp.grid.free_space_max = node.declare_parameter(ns + ".grid.free_space_max", 10); pp.grid.occupied_min = node.declare_parameter(ns + ".grid.occupied_min", 51); diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp index 4922d994bc8e0..6b07021e50d5f 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp @@ -14,6 +14,7 @@ #include #include +#include #include #include #include @@ -33,6 +34,7 @@ namespace behavior_velocity_planner { +namespace bg = boost::geometry; namespace occlusion_spot_utils { lanelet::ConstLanelet toPathLanelet(const PathWithLaneId & path) @@ -400,6 +402,23 @@ DetectionAreaIdx extractTargetRoadArcLength( return DetectionAreaIdx(std::make_pair(start_dist, dist_sum)); } +std::vector filterDynamicObjectByDetectionArea( + std::vector & objs, const std::vector polys) +{ + std::vector filtered_obj; + // stuck points by predicted objects + for (const auto & object : objs) { + // check if the footprint is in the stuck detect area + const Polygon2d obj_footprint = planning_utils::toFootprintPolygon(object); + for (const auto & p : polys) { + if (!bg::disjoint(obj_footprint, p.polygon)) { + filtered_obj.emplace_back(object); + } + } + } + return filtered_obj; +} + void filterCollisionByRoadType( std::vector & possible_collisions, const DetectionAreaIdx area) { @@ -415,61 +434,45 @@ void filterCollisionByRoadType( } } -void generateSidewalkPossibleCollisions( +void createPossibleCollisionsInDetectionArea( + const std::vector & detection_area_polygons, std::vector & possible_collisions, const grid_map::GridMap & grid, const PathWithLaneId & path, const double offset_from_start_to_ego, const PlannerParam & param, - std::vector & debug) + std::vector & debug_points) { lanelet::ConstLanelet path_lanelet = toPathLanelet(path); if (path_lanelet.centerline2d().empty()) { return; } - std::vector sidewalk_slices; - geometry::buildSidewalkSlices( - sidewalk_slices, path_lanelet, 0.0, param.half_vehicle_width, param.sidewalk.slice_size, - param.sidewalk.focus_range); - double length_lower_bound = std::numeric_limits::max(); double distance_lower_bound = std::numeric_limits::max(); - // sort distance closest first to skip inferior collision - std::sort( - sidewalk_slices.begin(), sidewalk_slices.end(), - [](const geometry::Slice & s1, const geometry::Slice & s2) { - return std::abs(s1.range.min_distance) < std::abs(s2.range.min_distance); - }); - - std::sort( - sidewalk_slices.begin(), sidewalk_slices.end(), - [](const geometry::Slice & s1, const geometry::Slice & s2) { - return s1.range.min_length < s2.range.min_length; - }); - - for (const geometry::Slice & sidewalk_slice : sidewalk_slices) { - debug.push_back(sidewalk_slice.polygon); - if ((sidewalk_slice.range.min_length < length_lower_bound || - std::abs(sidewalk_slice.range.min_distance) < distance_lower_bound)) { - std::vector occlusion_spot_positions; - grid_utils::findOcclusionSpots( - occlusion_spot_positions, grid, sidewalk_slice.polygon, - param.sidewalk.min_occlusion_spot_size); - generateSidewalkPossibleCollisionFromOcclusionSpot( - possible_collisions, grid, occlusion_spot_positions, offset_from_start_to_ego, path_lanelet, - param); - if (!possible_collisions.empty()) { - length_lower_bound = sidewalk_slice.range.min_length; - distance_lower_bound = std::abs(sidewalk_slice.range.min_distance); - possible_collisions.insert( - possible_collisions.end(), possible_collisions.begin(), possible_collisions.end()); - debug.push_back(sidewalk_slice.polygon); - } + for (const Slice & detection_area_slice : detection_area_polygons) { + std::vector occlusion_spot_positions; + grid_utils::findOcclusionSpots( + occlusion_spot_positions, grid, detection_area_slice.polygon, + param.detection_area.min_occlusion_spot_size); + Point p; + for (const auto & op : occlusion_spot_positions) { + p.x = op[0]; + p.y = op[1]; + debug_points.emplace_back(p); } + if (occlusion_spot_positions.empty()) continue; + // for each partition find nearest occlusion spot from polygon's origin + BasicPoint2d base_point = detection_area_slice.polygon.at(0); + const auto pc = generateOneNotableCollisionFromOcclusionSpot( + grid, occlusion_spot_positions, offset_from_start_to_ego, base_point, path_lanelet, param); + if (!pc) continue; + const double lateral_distance = std::abs(pc.get().arc_lane_dist_at_collision.distance); + if (lateral_distance > distance_lower_bound) continue; + distance_lower_bound = lateral_distance; + possible_collisions.emplace_back(pc.get()); } } -void generateSidewalkPossibleCollisionFromOcclusionSpot( - std::vector & possible_collisions, const grid_map::GridMap & grid, - const std::vector & occlusion_spot_positions, - const double offset_from_start_to_ego, const lanelet::ConstLanelet & path_lanelet, - const PlannerParam & param) +boost::optional generateOneNotableCollisionFromOcclusionSpot( + const grid_map::GridMap & grid, const std::vector & occlusion_spot_positions, + const double offset_from_start_to_ego, const BasicPoint2d base_point, + const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param) { const double baselink_to_front = param.baselink_to_front; const double half_vehicle_width = param.half_vehicle_width; @@ -481,27 +484,34 @@ void generateSidewalkPossibleCollisionFromOcclusionSpot( lanelet::BasicPoint2d obstacle_point = {occlusion_spot_position[0], occlusion_spot_position[1]}; lanelet::ArcCoordinates arc_coord_occlusion_point = lanelet::geometry::toArcCoordinates(path_lanelet.centerline2d(), obstacle_point); + const double dist = + std::hypot(base_point[0] - obstacle_point[0], base_point[1] - obstacle_point[1]); + // skip if absolute distance is larger + if (distance_lower_bound < dist) continue; const double length_to_col = arc_coord_occlusion_point.length - baselink_to_front; - ArcCoordinates arc_coord_collision_point = { - length_to_col, - calcSignedLateralDistanceWithOffset(arc_coord_occlusion_point.distance, half_vehicle_width)}; + // skip if occlusion is behind ego bumper if (length_to_col < offset_from_start_to_ego) { continue; } + ArcCoordinates arc_coord_collision_point = { + length_to_col, + calcSignedLateralDistanceWithOffset(arc_coord_occlusion_point.distance, half_vehicle_width)}; PossibleCollisionInfo pc = calculateCollisionPathPointFromOcclusionSpot( arc_coord_occlusion_point, arc_coord_collision_point, path_lanelet, param); const auto & ip = pc.intersection_pose.position; bool collision_free_at_intersection = grid_utils::isCollisionFree(grid, occlusion_spot_position, grid_map::Position(ip.x, ip.y)); - // this is going to extract collision that is nearest to path - if ( - collision_free_at_intersection && distance_lower_bound > arc_coord_collision_point.distance) { - distance_lower_bound = arc_coord_collision_point.distance; - candidate = {pc}; + if (collision_free_at_intersection) { + distance_lower_bound = dist; + candidate = pc; has_collision = true; } } - if (has_collision) possible_collisions.emplace_back(candidate); + if (has_collision) { + return candidate; + } else { + return {}; + } } } // namespace occlusion_spot_utils diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp index 2bd245a91f76b..b8e7a3a9f77da 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include #include @@ -45,6 +46,7 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( [[maybe_unused]] tier4_planning_msgs::msg::StopReason * stop_reason) { debug_data_ = DebugData(); + debug_data_.road_type = "private"; if (path->points.size() < 2) { return true; } @@ -54,6 +56,9 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( param_.v.max_stop_accel = planner_data_->max_stop_acceleration_threshold; param_.v.v_ego = planner_data_->current_velocity->twist.linear.x; param_.v.a_ego = planner_data_->current_accel.get(); + param_.detection_area_max_length = planning_utils::calcJudgeLineDistWithJerkLimit( + param_.v.v_ego, param_.v.a_ego, param_.v.non_effective_accel, param_.v.non_effective_jerk, + 0.0); } const geometry_msgs::msg::Pose ego_pose = planner_data_->current_pose.pose; const auto & lanelet_map_ptr = planner_data_->lanelet_map; @@ -67,6 +72,7 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( PathWithLaneId clipped_path; utils::clipPathByLength(*path, clipped_path, max_range); PathWithLaneId interp_path; + //! never change this interpolation interval(will affect module accuracy) utils::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); debug_data_.interp_path = interp_path; int closest_idx = -1; @@ -82,18 +88,20 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( nav_msgs::msg::OccupancyGrid occ_grid = *occ_grid_ptr; grid_map::GridMap grid_map; grid_utils::denoiseOccupancyGridCV(occ_grid, grid_map, param_.grid); - if (param_.show_debug_grid) { - publisher_->publish(occ_grid); - } double offset_from_start_to_ego = utils::offsetFromStartToEgo(interp_path, ego_pose, closest_idx); + using Slice = occlusion_spot_utils::Slice; + std::vector detection_area_polygons; + utils::buildDetectionAreaPolygon( + detection_area_polygons, interp_path, offset_from_start_to_ego, param_); RCLCPP_DEBUG_STREAM_THROTTLE(logger_, *clock_, 3000, "closest_idx : " << closest_idx); RCLCPP_DEBUG_STREAM_THROTTLE( logger_, *clock_, 3000, "offset_from_start_to_ego : " << offset_from_start_to_ego); std::vector possible_collisions; // Note: Don't consider offset from path start to ego here - utils::generateSidewalkPossibleCollisions( - possible_collisions, grid_map, interp_path, offset_from_start_to_ego, param_, - debug_data_.sidewalks); + utils::createPossibleCollisionsInDetectionArea( + detection_area_polygons, possible_collisions, grid_map, interp_path, offset_from_start_to_ego, + param_, debug_data_.occlusion_points); + if (detection_area_polygons.empty()) return true; utils::filterCollisionByRoadType(possible_collisions, focus_area); RCLCPP_DEBUG_STREAM_THROTTLE( logger_, *clock_, 3000, "num possible collision:" << possible_collisions.size()); @@ -102,6 +110,15 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( utils::handleCollisionOffset(possible_collisions, offset_from_start_to_ego, 0.0); // apply safe velocity using ebs and pbs deceleration utils::applySafeVelocityConsideringPossibleCollision(path, possible_collisions, param_); + // these debug topics needs computation resource + if (param_.debug) { + publisher_->publish(occ_grid); + for (const auto & p : detection_area_polygons) { + debug_data_.detection_areas.emplace_back(p.polygon); + } + } else { + debug_data_.occlusion_points.clear(); + } debug_data_.z = path->points.front().point.pose.position.z; debug_data_.possible_collisions = possible_collisions; debug_data_.path_raw = *path; diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp index ceff1798eb2bc..99aebf5ad60d8 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include #include @@ -45,6 +46,7 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( [[maybe_unused]] tier4_planning_msgs::msg::StopReason * stop_reason) { debug_data_ = DebugData(); + debug_data_.road_type = "public"; if (path->points.size() < 2) { return true; } @@ -54,6 +56,9 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( param_.v.max_stop_accel = planner_data_->max_stop_acceleration_threshold; param_.v.v_ego = planner_data_->current_velocity->twist.linear.x; param_.v.a_ego = planner_data_->current_accel.get(); + param_.detection_area_max_length = planning_utils::calcJudgeLineDistWithJerkLimit( + param_.v.v_ego, param_.v.a_ego, param_.v.non_effective_accel, param_.v.non_effective_jerk, + 0.0); } const geometry_msgs::msg::Pose ego_pose = planner_data_->current_pose.pose; const auto & lanelet_map_ptr = planner_data_->lanelet_map; @@ -81,17 +86,26 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( std::vector obj = utils::getParkedVehicles(*dynamic_obj_arr_ptr, param_, debug_data_.parked_vehicle_point); double offset_from_start_to_ego = utils::offsetFromStartToEgo(interp_path, ego_pose, closest_idx); + using Slice = occlusion_spot_utils::Slice; + std::vector detection_area_polygons; + utils::buildDetectionAreaPolygon( + detection_area_polygons, interp_path, offset_from_start_to_ego, param_); + const auto filtered_obj = utils::filterDynamicObjectByDetectionArea(obj, detection_area_polygons); // Note: Don't consider offset from path start to ego here std::vector possible_collisions = utils::generatePossibleCollisionBehindParkedVehicle( - interp_path, param_, offset_from_start_to_ego, obj); + interp_path, param_, offset_from_start_to_ego, filtered_obj); utils::filterCollisionByRoadType(possible_collisions, focus_area); utils::calcSlowDownPointsForPossibleCollision(0, interp_path, 0.0, possible_collisions); // Note: Consider offset from path start to ego here utils::handleCollisionOffset(possible_collisions, offset_from_start_to_ego, 0.0); // apply safe velocity using ebs and pbs deceleration utils::applySafeVelocityConsideringPossibleCollision(path, possible_collisions, param_); - + if (param_.debug) { + for (const auto & p : detection_area_polygons) { + debug_data_.detection_areas.emplace_back(p.polygon); + } + } debug_data_.possible_collisions = possible_collisions; return true; } diff --git a/planning/behavior_velocity_planner/test/src/test_geometry.cpp b/planning/behavior_velocity_planner/test/src/test_geometry.cpp index cc1e631e91c58..0d7abf4bf7271 100644 --- a/planning/behavior_velocity_planner/test/src/test_geometry.cpp +++ b/planning/behavior_velocity_planner/test/src/test_geometry.cpp @@ -19,75 +19,3 @@ #include #include - -TEST(buildSlices, one_full_slice) -{ - using behavior_velocity_planner::geometry::buildSlices; - using behavior_velocity_planner::geometry::Slice; - using behavior_velocity_planner::geometry::SliceRange; - - /* Simple vertical lanelet - 3x3 slice on the left - 0 1 2 3 4 5 6 - 0 | |------ - 1 | | | - 2 | |SLICE| - 3 | |-----| - 4 | | - 5 | | - */ - const int nb_points = 6; - lanelet::ConstLanelet traj_lanelet = test::verticalLanelet({0.0, 0.0}, 1.0, 5.0, nb_points); - SliceRange range; - range.min_distance = 0.0; - range.max_distance = -3.0; - const double slice_length = 3.0; - const double slice_width = 1.5; - std::vector slices; - buildSlices(slices, traj_lanelet, range, slice_length, slice_width, 0.5); - ASSERT_EQ(slices.size(), static_cast(4)); - EXPECT_EQ(slices[0].range.min_length, 0.0); - EXPECT_EQ(slices[0].range.min_distance, 0.0); - EXPECT_EQ(slices[0].range.max_length, 3.0); - EXPECT_EQ(slices[0].range.max_distance, -1.5); -} - -TEST(buildSlices, 3x3square_slice) -{ - using behavior_velocity_planner::geometry::buildSlices; - using behavior_velocity_planner::geometry::Slice; - using behavior_velocity_planner::geometry::SliceRange; - - /* Simple vertical lanelet - 3x3 slice on the left - 0 1 2 3 4 5 6 - 0 | |------ - 1 | | | - 2 | |SLICE| - 3 | |-----| - */ - const int nb_points = 4; - const double len = 3.0; - lanelet::ConstLanelet lanelet = test::createLanelet({0.0, 0.0}, {0.0, len}, nb_points); - SliceRange range; - range.min_distance = -1.0; - range.max_distance = -3.0; - const double slice_length = 1.0; - const double slice_width = 1.0; - const int num_right_slice = - (len / slice_length) * (std::abs(range.max_distance - range.min_distance) / slice_width); - // - { - std::vector slices; - buildSlices(slices, lanelet, range, slice_length, slice_width, 1.0); - ASSERT_EQ(slices.size(), static_cast(num_right_slice)); - } - // change to the left side (positive distance) - range.min_distance = 1.0; - range.max_distance = 3.0; - { - std::vector slices; - buildSlices(slices, lanelet, range, slice_length, slice_width, 1.0); - ASSERT_EQ(slices.size(), static_cast(num_right_slice)); - } -} diff --git a/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp b/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp index 3eac8b058463d..b45c7cce4c63d 100644 --- a/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp +++ b/planning/behavior_velocity_planner/test/src/test_grid_utils.cpp @@ -37,217 +37,67 @@ struct indexEq using test::grid_param; -TEST(isOcclusionSpotSquare, one_cell_occlusion_spot) +TEST(isOcclusionSpotSquare, occlusion_spot_cell) { using behavior_velocity_planner::grid_utils::isOcclusionSpotSquare; using behavior_velocity_planner::grid_utils::OcclusionSpotSquare; using behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; // Prepare an occupancy grid with a single occlusion_spot - /* - 0 1 2 3 - 0 ? ? ? - 1 ? ? - 2 ? ? ? - 3 ? ? - */ - grid_map::GridMap grid = test::generateGrid(4, 4, 1.0); - std::unordered_set unknown_cells = { - {0, 0}, {0, 3}, {1, 1}, {1, 2}, {2, 0}, {2, 1}, {2, 2}, {3, 0}, {3, 2}, {3, 3}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } + const int min_occlusion_spot_size = 2; - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = isOcclusionSpotSquare(occlusion_spot, grid["layer"], {i, j}, 1, grid.getSize()); - if (unknown_cells.count({i, j})) { - ASSERT_TRUE(found); - } else { - ASSERT_FALSE(found); - } + // case simple + { + /* + 0 1 2 3 4 + 0 + 1 ? ? + 2 ? x ? + 3 ? ? + 4 + */ + grid_map::GridMap grid = test::generateGrid(5, 5, 1.0); + std::vector unknown_cells = {{1, 1}, {1, 2}, {1, 3}, {2, 2}, + {2, 3}, {3, 1}, {3, 2}}; + for (grid_map::Index index : unknown_cells) { + grid.at("layer", index) = UNKNOWN; } - } -} -TEST(isOcclusionSpotSquare, many_cells_occlusion_spot) -{ - using behavior_velocity_planner::grid_utils::isOcclusionSpotSquare; - using behavior_velocity_planner::grid_utils::OcclusionSpotSquare; - using behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; - const double resolution = 1.0; - const double size = 2 * resolution; - /* - 0 1 2 3 - 0 ? ? ? - 1 ? ? - 2 ? ? ? - 3 ? ? - */ - grid_map::GridMap grid = test::generateGrid(4, 4, resolution); - std::unordered_set unknown_cells; - std::unordered_set occlusion_spot_cells; - unknown_cells = {{0, 0}, {0, 3}, {1, 1}, {1, 2}, {2, 0}, {2, 1}, {2, 2}, {3, 0}, {3, 2}, {3, 3}}; - occlusion_spot_cells = {{2, 0}, {3, 0}, {1, 2}, {3, 3}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = - isOcclusionSpotSquare(occlusion_spot, grid["layer"], {i, j}, size, grid.getSize()); - if (occlusion_spot_cells.count({i, j})) { - ASSERT_TRUE(found); - } else { - ASSERT_FALSE(found); + // occlusion spot (2,2) + for (int i = 0; i < grid.getLength().x(); ++i) { + for (int j = 0; j < grid.getLength().y(); ++j) { + OcclusionSpotSquare occlusion_spot; + bool found = isOcclusionSpotSquare( + occlusion_spot, grid["layer"], {i, j}, min_occlusion_spot_size, grid.getSize()); + if (i == 2 && j == 2) { + EXPECT_TRUE(found); + } else { + EXPECT_FALSE(found); + } } } } - /* - 0 1 2 3 - 0 ? - 1 ? ? - 2 ? ? ? - 3 - */ - grid = test::generateGrid(4, 4, 1.0); - unknown_cells = {{0, 2}, {1, 1}, {2, 0}, {2, 1}, {2, 2}, {3, 2}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - - // No occlusion_spots - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = - isOcclusionSpotSquare(occlusion_spot, grid["layer"], {i, j}, size, grid.getSize()); - ASSERT_FALSE(found); + // case noisy + { + std::cout << "TooNoisyCase->No OcclusionSpot 2by2" << std::endl + << " 0|1|2|3|4| " << std::endl + << " 0 |?| | | | " << std::endl + << " 1 |?| | | | " << std::endl + << " 2 |?|?|?| | " << std::endl; + grid_map::GridMap grid = test::generateGrid(5, 3, 1.0); + std::vector unknown_cells = {{1, 0}, {1, 1}, {1, 2}, {2, 2}, {3, 2}}; + for (grid_map::Index index : unknown_cells) { + grid.at("layer", index) = UNKNOWN; } - } - /* - 0 1 2 3 - 0 - 1 ? ? - 2 ? ? - 3 - */ - grid = test::generateGrid(4, 4, 1.0); - unknown_cells = {{1, 1}, {1, 2}, {2, 1}, {2, 2}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - - // Only one occlusion_spot square - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = - isOcclusionSpotSquare(occlusion_spot, grid["layer"], {i, j}, size, grid.getSize()); - if (i == 1 && j == 2) { - ASSERT_TRUE(found); - } else { + for (int i = 0; i < grid.getLength().x(); ++i) { + for (int j = 0; j < grid.getLength().y(); ++j) { + OcclusionSpotSquare occlusion_spot; + bool found = isOcclusionSpotSquare( + occlusion_spot, grid["layer"], {i, j}, min_occlusion_spot_size, grid.getSize()); + if (found) { + std::cout << "i: " << i << " j: " << j << " change algorithm or update test" << std::endl; + } ASSERT_FALSE(found); } } } - - /* - 0 1 2 3 - 0 ? - 1 ? ? - 2 ? ? ? ? - 3 ? - */ - grid = test::generateGrid(4, 4, 1.0); - unknown_cells = {{0, 2}, {1, 0}, {1, 1}, {1, 2}, {1, 3}, {2, 1}, {2, 2}, {3, 2}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - occlusion_spot_cells = {{1, 1}, {1, 2}, {2, 1}, {2, 2}}; - - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = - isOcclusionSpotSquare(occlusion_spot, grid["layer"], {i, j}, size, grid.getSize()); - if (i == 1 && j == 2) { - ASSERT_TRUE(found); - } else { - ASSERT_FALSE(found); - } - } - } - - std::cout << "TooNoisyCase->No OcclusionSpot 2by2" << std::endl - << " 0|1|2|3|4| " << std::endl - << " 0 |?| | | | " << std::endl - << " 1 |?|?|?| | " << std::endl - << " 2 ?|?| |?| | " << std::endl - << " 3 |?| | | | " << std::endl - << " 4 |?| | | | " << std::endl; - grid = test::generateGrid(5, 5, 1.0); - unknown_cells = {{0, 2}, {1, 0}, {1, 1}, {1, 2}, {1, 3}, {2, 1}, {3, 1}, {3, 2}}; - for (grid_map::Index index : unknown_cells) { - grid.at("layer", index) = UNKNOWN; - } - occlusion_spot_cells = {{1, 1}, {1, 2}, {2, 1}, {2, 2}}; - - for (int i = 0; i < grid.getLength().x(); ++i) { - for (int j = 0; j < grid.getLength().y(); ++j) { - OcclusionSpotSquare occlusion_spot; - bool found = - isOcclusionSpotSquare(occlusion_spot, grid["layer"], {i, j}, size, grid.getSize()); - if (found) { - std::cout << "i: " << i << " j: " << j << " change algorithm or update test" << std::endl; - } - ASSERT_FALSE(found); - } - } -} - -TEST(buildSlices, test_buffer_offset) -{ - using behavior_velocity_planner::geometry::buildSlices; - using behavior_velocity_planner::geometry::Slice; - using behavior_velocity_planner::geometry::SliceRange; - - // Curving lanelet - // lanelet::Lanelet l; - // lanelet::Points3d line; - boost::geometry::model::linestring line; - boost::geometry::model::multi_polygon> - poly; - line.emplace_back(0.0, 1.0); - line.emplace_back(1.0, 4.0); - line.emplace_back(2.0, 6.0); - line.emplace_back(3.0, 7.0); - line.emplace_back(4.0, 6.0); - line.emplace_back(5.0, 4.0); - line.emplace_back(6.0, 1.0); - - boost::geometry::strategy::buffer::distance_asymmetric distance_strategy(0.0, 1.1); - boost::geometry::strategy::buffer::end_flat end_strategy; - boost::geometry::strategy::buffer::side_straight side_strategy; - boost::geometry::strategy::buffer::join_miter join_strategy; - boost::geometry::strategy::buffer::point_square point_strategy; - boost::geometry::buffer( - line, poly, distance_strategy, side_strategy, join_strategy, end_strategy, point_strategy); - - std::cout << boost::geometry::wkt(line) << "\n"; - std::cout << boost::geometry::wkt(poly[0]) << "\n"; - - boost::geometry::model::multi_point in1; - for (const auto & p : line) { - in1.push_back(p); - } - boost::geometry::model::multi_point in2; - for (const auto & p : poly[0].outer()) { - in2.push_back(p); - } - boost::geometry::model::multi_point output; - boost::geometry::difference(in2, in1, output); - - std::cout << boost::geometry::wkt(output) << "\n"; } diff --git a/planning/behavior_velocity_planner/test/src/test_risk_predictive_braking.cpp b/planning/behavior_velocity_planner/test/src/test_risk_predictive_braking.cpp index 644790d44e50c..ff47f2414428a 100644 --- a/planning/behavior_velocity_planner/test/src/test_risk_predictive_braking.cpp +++ b/planning/behavior_velocity_planner/test/src/test_risk_predictive_braking.cpp @@ -35,28 +35,76 @@ TEST(safeMotion, delay_jerk_acceleration) * case2 delay + jerk * case3 delay + jerk + acc */ - utils::Velocity v{1.0, -3.0, -4.5, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0}; + utils::Velocity v{}; + v.safety_ratio = 1.0; + v.max_stop_jerk = -3.0; + v.max_stop_accel = -4.5; + v.delay_time = 0.5; double ttc = 0.0; + const double eps = 1e-3; // case 1 delay { ttc = 0.5; utils::SafeMotion sm = utils::calculateSafeMotion(v, ttc); - EXPECT_DOUBLE_EQ(sm.safe_velocity, 0.0); - EXPECT_DOUBLE_EQ(sm.stop_dist, 0.0); + EXPECT_NEAR(sm.safe_velocity, 0.0, eps); + EXPECT_NEAR(sm.stop_dist, 0.0, eps); } // case 2 delay + jerk { ttc = 1.5; utils::SafeMotion sm = utils::calculateSafeMotion(v, ttc); - EXPECT_DOUBLE_EQ(sm.safe_velocity, 1.5); - EXPECT_DOUBLE_EQ(sm.stop_dist, 1.25); + EXPECT_NEAR(sm.safe_velocity, 1.5, eps); + EXPECT_NEAR(sm.stop_dist, 1.25, eps); } // case 3 delay + jerk + acc { ttc = 3.25; utils::SafeMotion sm = utils::calculateSafeMotion(v, ttc); - EXPECT_DOUBLE_EQ(sm.safe_velocity, 9); - EXPECT_DOUBLE_EQ(std::round(sm.stop_dist * 100.0) / 100.0, 13.92); + EXPECT_NEAR(sm.safe_velocity, 9, eps); + EXPECT_NEAR(std::round(sm.stop_dist * 100.0) / 100.0, 13.92, eps); + } +} + +TEST(detectionArea, calcLateralDistance) +{ + namespace utils = behavior_velocity_planner::occlusion_spot_utils; + using utils::calculateLateralDistanceFromTTC; + /** + * @brief check if calculation is correct in below parameter + * lateral distance is calculated from + * - ego velocity + * - min distance(safety margin) + * - max distance(ignore distance above this) + * - pedestrian velocity + * - min allowed velocity(not to stop) + */ + utils::PlannerParam p; + p.half_vehicle_width = 2.0; + p.baselink_to_front = 3.0; + p.pedestrian_vel = 1.5; + p.detection_area.max_lateral_distance = 5.0; + p.v.min_allowed_velocity = 1.5; + p.v.v_ego = 5.0; + const double offset_from_ego_to_start = 0.0; + { + for (size_t i = 0; i <= 15; i += 5) { + // arc length in path point + const double l = i * 1.0; + const double s = l - offset_from_ego_to_start; + const double d = utils::calculateLateralDistanceFromTTC(s, p); + const double eps = 1e-3; + std::cout << "s: " << l << " v: " << p.v.v_ego << " d: " << d << std::endl; + if (i == 0) + EXPECT_NEAR(d, 2.5, eps); + else if (i == 5) + EXPECT_NEAR(d, 3.5, eps); + else if (i == 10) + EXPECT_NEAR(d, 5.0, eps); + else if (i == 15) + EXPECT_NEAR(d, 5.0, eps); + else + break; + } } } From 3b19671181013a55648af976ccbbfe28c2074dfa Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 16 Feb 2022 17:34:27 +0900 Subject: [PATCH 02/37] refactor: move pacmod interface (#392) Signed-off-by: Takagi, Isamu --- vehicle/pacmod_interface/CMakeLists.txt | 45 -- vehicle/pacmod_interface/README.md | 81 --- .../pacmod_interface/config/pacmod.param.yaml | 19 - .../config/pacmod_extra.param.yaml | 20 - ...pacmod_additional_debug_publisher_node.hpp | 44 -- .../pacmod_dynamic_parameter_changer_node.hpp | 64 -- .../pacmod_diag_publisher.hpp | 112 --- .../pacmod_interface/pacmod_interface.hpp | 226 ------ ...cmod_additional_debug_publisher.launch.xml | 16 - .../launch/pacmod_interface.launch.xml | 27 - vehicle/pacmod_interface/package.xml | 32 - ...pacmod_additional_debug_publisher_main.cpp | 28 - ...pacmod_additional_debug_publisher_node.cpp | 160 ---- .../pacmod_dynamic_parameter_changer_main.cpp | 26 - .../pacmod_dynamic_parameter_changer_node.cpp | 166 ----- .../pacmod_diag_publisher.cpp | 186 ----- .../pacmod_diag_publisher_node.cpp | 27 - .../src/pacmod_interface/pacmod_interface.cpp | 685 ------------------ .../pacmod_interface_node.cpp | 27 - 19 files changed, 1991 deletions(-) delete mode 100644 vehicle/pacmod_interface/CMakeLists.txt delete mode 100644 vehicle/pacmod_interface/README.md delete mode 100644 vehicle/pacmod_interface/config/pacmod.param.yaml delete mode 100644 vehicle/pacmod_interface/config/pacmod_extra.param.yaml delete mode 100644 vehicle/pacmod_interface/include/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.hpp delete mode 100644 vehicle/pacmod_interface/include/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.hpp delete mode 100644 vehicle/pacmod_interface/include/pacmod_interface/pacmod_diag_publisher.hpp delete mode 100644 vehicle/pacmod_interface/include/pacmod_interface/pacmod_interface.hpp delete mode 100644 vehicle/pacmod_interface/launch/pacmod_additional_debug_publisher.launch.xml delete mode 100644 vehicle/pacmod_interface/launch/pacmod_interface.launch.xml delete mode 100644 vehicle/pacmod_interface/package.xml delete mode 100644 vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_main.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_main.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher_node.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp delete mode 100644 vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface_node.cpp diff --git a/vehicle/pacmod_interface/CMakeLists.txt b/vehicle/pacmod_interface/CMakeLists.txt deleted file mode 100644 index 177e506806ab6..0000000000000 --- a/vehicle/pacmod_interface/CMakeLists.txt +++ /dev/null @@ -1,45 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(pacmod_interface) - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_EXTENSIONS OFF) -endif() -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -ament_auto_add_executable(pacmod_additional_debug_publisher - src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.cpp - src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_main.cpp -) - -ament_auto_add_executable(pacmod_dynamic_parameter_changer - src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.cpp - src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_main.cpp -) - -ament_auto_add_executable(pacmod_interface - src/pacmod_interface/pacmod_interface.cpp - src/pacmod_interface/pacmod_interface_node.cpp -) - -ament_auto_add_executable(pacmod_diag_publisher - src/pacmod_interface/pacmod_diag_publisher.cpp - src/pacmod_interface/pacmod_diag_publisher_node.cpp -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_auto_package( - INSTALL_TO_SHARE - launch - config -) diff --git a/vehicle/pacmod_interface/README.md b/vehicle/pacmod_interface/README.md deleted file mode 100644 index 1f9c7fda886db..0000000000000 --- a/vehicle/pacmod_interface/README.md +++ /dev/null @@ -1,81 +0,0 @@ -# pacmod_interface - -`pacmod_interface` is the package to connect Autoware with Pacmod. - -## Input / Output - -### Input topics - -- From Autoware - - | Name | Type | Description | - | -------------------------------------- | -------------------------------------------------------- | ----------------------------------------------------- | - | `/control/command/control_cmd` | autoware_auto_control_msgs::msg::AckermannControlCommand | lateral and longitudinal control command | - | `/control/command/gear_cmd` | autoware_auto_vehicle_msgs::msg::GearCommand | gear command | - | `/control/command/turn_indicators_cmd` | autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand | turn indicators command | - | `/control/command/hazard_lights_cmd` | autoware_auto_vehicle_msgs::msg::HazardLightsCommand | hazard lights command | - | `/vehicle/engage` | autoware_auto_vehicle_msgs::msg::Engage | engage command | - | `/vehicle/command/actuation_cmd` | tier4_vehicle_msgs::msg::ActuationCommandStamped | actuation (accel/brake pedal, steering wheel) command | - | `/control/command/emergency_cmd` | tier4_vehicle_msgs::msg::VehicleEmergencyStamped | emergency command | - -- From Pacmod - - | Name | Type | Description | - | ------------------------- | --------------------------------- | ----------------------------------------------------------------------- | - | `/pacmod/steering_rpt` | pacmod3_msgs::msg::SystemRptFloat | current steering wheel angle | - | `/pacmod/wheel_speed_rpt` | pacmod3_msgs::msg::WheelSpeedRpt | current wheel speed | - | `/pacmod/accel_rpt` | pacmod3_msgs::msg::SystemRptFloat | current accel pedal | - | `/pacmod/brake_rpt` | pacmod3_msgs::msg::SystemRptFloat | current brake pedal | - | `/pacmod/shift_rpt` | pacmod3_msgs::msg::SystemRptInt | current gear status | - | `/pacmod/turn_rpt` | pacmod3_msgs::msg::SystemRptInt | current turn indicators status | - | `/pacmod/global_rpt` | pacmod3_msgs::msg::GlobalRpt | current status of other parameters (e.g. override_active, can_time_out) | - -### Output topics - -- To Pacmod - - | Name | Type | Description | - | ---------------------- | --------------------------------- | ----------------------------------------------------- | - | `pacmod/accel_cmd` | pacmod3_msgs::msg::SystemCmdFloat | accel pedal command | - | `pacmod/brake_cmd` | pacmod3_msgs::msg::SystemCmdFloat | brake pedal command | - | `pacmod/steering_cmd` | pacmod3_msgs::msg::SystemCmdFloat | steering wheel angle and angular velocity command | - | `pacmod/shift_cmd` | pacmod3_msgs::msg::SystemCmdInt | gear command | - | `pacmod/turn_cmd` | pacmod3_msgs::msg::SystemCmdInt | turn indicators command | - | `pacmod/raw_steer_cmd` | pacmod3_msgs::msg::SteerSystemCmd | raw steering wheel angle and angular velocity command | - -- To Autoware - - | Name | Type | Description | - | ---------------------------------------- | ------------------------------------------------------- | ---------------------------------------------------- | - | `/vehicle/status/control_mode` | autoware_auto_vehicle_msgs::msg::ControlModeReport | control mode | - | `/vehicle/status/velocity_status` | autoware_auto_vehicle_msgs::msg::VelocityReport | velocity | - | `/vehicle/status/steering_status` | autoware_auto_vehicle_msgs::msg::SteeringReport | steering wheel angle | - | `/vehicle/status/gear_status` | autoware_auto_vehicle_msgs::msg::GearReport | gear status | - | `/vehicle/status/turn_indicators_status` | autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport | turn indicators status | - | `/vehicle/status/hazard_lights_status` | autoware_auto_vehicle_msgs::msg::HazardLightsReport | hazard lights status | - | `/vehicle/status/actuation_status` | autoware_auto_vehicle_msgs::msg::ActuationStatusStamped | actuation (accel/brake pedal, steering wheel) status | - -## ROS Parameters - -| Name | Type | Description | -| --------------------------------- | ------ | ----------------------------------------------------------------------------------------- | -| `base_frame_id` | string | frame id (assigned in pacmod command, but it does not make sense) | -| `command_timeout_ms` | double | timeout [ms] | -| `loop_rate` | double | loop rate to publish commands | -| `steering_offset` | double | steering wheel angle offset | -| `enable_steering_rate_control` | bool | when enabled, max steering wheel rate is used for steering wheel angular velocity command | -| `emergency_brake` | double | brake pedal for emergency | -| `vgr_coef_a` | double | coefficient to calculate steering wheel angle | -| `vgr_coef_b` | double | coefficient to calculate steering wheel angle | -| `vgr_coef_c` | double | coefficient to calculate steering wheel angle | -| `accel_pedal_offset` | double | accel pedal offset | -| `brake_pedal_offset` | double | brake pedal offset | -| `max_throttle` | double | max accel pedal | -| `max_brake` | double | max brake pedal | -| `max_steering_wheel` | double | max steering wheel angle | -| `max_steering_wheel_rate` | double | max steering wheel angular velocity | -| `min_steering_wheel_rate` | double | min steering wheel angular velocity | -| `steering_wheel_rate_low_vel` | double | min steering wheel angular velocity when velocity is low | -| `steering_wheel_rate_low_stopped` | double | min steering wheel angular velocity when velocity is almost 0 | -| `low_vel_thresh` | double | threshold velocity to decide the velocity is low for `steering_wheel_rate_low_vel` | -| `hazard_thresh_time` | double | threshold time to keep hazard lights | diff --git a/vehicle/pacmod_interface/config/pacmod.param.yaml b/vehicle/pacmod_interface/config/pacmod.param.yaml deleted file mode 100644 index 11b4aca96f77e..0000000000000 --- a/vehicle/pacmod_interface/config/pacmod.param.yaml +++ /dev/null @@ -1,19 +0,0 @@ -/**: - ros__parameters: - base_frame_id: "base_link" - command_timeout_ms: 1000 - loop_rate: 30.0 - emergency_brake: 0.7 - max_throttle: 0.4 - max_brake: 0.8 - max_steering_wheel: 11.0 - min_steering_wheel: -11.0 - max_steering_wheel_rate: 5.0 - min_steering_wheel_rate: 3.0 - steering_offset: 0.0 - enable_steering_rate_control: false - vgr_coef_a: 15.713 - vgr_coef_b: 0.053 - vgr_coef_c: 0.042 - accel_pedal_offset: 0.0 - brake_pedal_offset: 0.0 diff --git a/vehicle/pacmod_interface/config/pacmod_extra.param.yaml b/vehicle/pacmod_interface/config/pacmod_extra.param.yaml deleted file mode 100644 index f20548d196bbd..0000000000000 --- a/vehicle/pacmod_interface/config/pacmod_extra.param.yaml +++ /dev/null @@ -1,20 +0,0 @@ -/**: - ros__parameters: - straight_p_gain: 0.8 - straight_i_gain: 0.002 - straight_lugre_fc: 0.02 - straight_rtz_offset: 0.085 - curve_p_gain: 0.4 - curve_i_gain: 0.002 - curve_lugre_fc: 0.01 - curve_rtz_offset: 0.085 - min_steer_thresh: 0.1 - max_steer_thresh: 0.4 - p_gain_rate_max: 1.5 - p_gain_rate_min: -5.0 - i_gain_rate_max: 0.05 - i_gain_rate_min: -0.05 - lugre_fc_rate_max: 0.1 - lugre_fc_rate_min: -0.1 - rtz_offset_rate_max: 0.5 - rtz_offset_rate_min: -0.5 diff --git a/vehicle/pacmod_interface/include/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.hpp b/vehicle/pacmod_interface/include/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.hpp deleted file mode 100644 index c3166ff95cb5d..0000000000000 --- a/vehicle/pacmod_interface/include/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.hpp +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright 2020 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 PACMOD_ADDITIONAL_DEBUG_PUBLISHER__PACMOD_ADDITIONAL_DEBUG_PUBLISHER_NODE_HPP_ -#define PACMOD_ADDITIONAL_DEBUG_PUBLISHER__PACMOD_ADDITIONAL_DEBUG_PUBLISHER_NODE_HPP_ - -#include - -#include -#include - -class PacmodAdditionalDebugPublisherNode : public rclcpp::Node -{ -private: - rclcpp::Publisher::SharedPtr debug_pub_; - rclcpp::Publisher::SharedPtr accel_cal_rpt_pub_; - rclcpp::Publisher::SharedPtr brake_cal_rpt_pub_; - rclcpp::Publisher::SharedPtr steer_cal_rpt_pub_; - - rclcpp::Subscription::SharedPtr sub_; - tier4_debug_msgs::msg::Float32MultiArrayStamped debug_value_; - tier4_debug_msgs::msg::Float32MultiArrayStamped accel_cal_rpt_; - tier4_debug_msgs::msg::Float32MultiArrayStamped brake_cal_rpt_; - tier4_debug_msgs::msg::Float32MultiArrayStamped steer_cal_rpt_; - bool calibration_active_; - void canTxCallback(const can_msgs::msg::Frame::ConstSharedPtr msg); - -public: - PacmodAdditionalDebugPublisherNode(); - ~PacmodAdditionalDebugPublisherNode() {} -}; - -#endif // PACMOD_ADDITIONAL_DEBUG_PUBLISHER__PACMOD_ADDITIONAL_DEBUG_PUBLISHER_NODE_HPP_ diff --git a/vehicle/pacmod_interface/include/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.hpp b/vehicle/pacmod_interface/include/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.hpp deleted file mode 100644 index 40b52b54b16b9..0000000000000 --- a/vehicle/pacmod_interface/include/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.hpp +++ /dev/null @@ -1,64 +0,0 @@ -// Copyright 2020 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 PACMOD_DYNAMIC_PARAMETER_CHANGER__PACMOD_DYNAMIC_PARAMETER_CHANGER_NODE_HPP_ -#define PACMOD_DYNAMIC_PARAMETER_CHANGER__PACMOD_DYNAMIC_PARAMETER_CHANGER_NODE_HPP_ - -#include - -#include -#include -#include - -struct ParamList -{ - double p_gain; - double i_gain; - double lugre_fc; - double rtz_offset; -}; - -class PacmodDynamicParameterChangerNode : public rclcpp::Node -{ -private: - rclcpp::Publisher::SharedPtr debug_pub_; - rclcpp::Publisher::SharedPtr can_pub_; - rclcpp::Subscription::SharedPtr steer_rpt_sub_; - - ParamList straight_course_param_; - ParamList curve_course_param_; - ParamList param_max_rate_; - ParamList param_min_rate_; - double min_steer_thresh_; - double max_steer_thresh_; - - ParamList current_param_list_; - rclcpp::Time current_param_time_; - -public: - PacmodDynamicParameterChangerNode(); - void subSteerRpt(const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr msg); - ParamList calculateParam( - const double current_steer_cmd, const double current_steer, const bool enabled); - void sendCanMsg(const ParamList param_list); - void sendDebugMsg(const ParamList param_list); - - ParamList interpolateParam(const ParamList p1, const ParamList p2, const double p1_rate); - ParamList rateLimit(const ParamList new_param, const ParamList current_param); - double rateLimit( - const double new_value, const double current_value, const double delta_time, - const double max_rate, const double min_rate); -}; - -#endif // PACMOD_DYNAMIC_PARAMETER_CHANGER__PACMOD_DYNAMIC_PARAMETER_CHANGER_NODE_HPP_ diff --git a/vehicle/pacmod_interface/include/pacmod_interface/pacmod_diag_publisher.hpp b/vehicle/pacmod_interface/include/pacmod_interface/pacmod_diag_publisher.hpp deleted file mode 100644 index a499864462397..0000000000000 --- a/vehicle/pacmod_interface/include/pacmod_interface/pacmod_diag_publisher.hpp +++ /dev/null @@ -1,112 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef PACMOD_INTERFACE__PACMOD_DIAG_PUBLISHER_HPP_ -#define PACMOD_INTERFACE__PACMOD_DIAG_PUBLISHER_HPP_ - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include - -class PacmodDiagPublisher : public rclcpp::Node -{ -public: - PacmodDiagPublisher(); - -private: - using PacmodFeedbacksSyncPolicy = message_filters::sync_policies::ApproximateTime< - pacmod3_msgs::msg::SystemRptFloat, pacmod3_msgs::msg::WheelSpeedRpt, - pacmod3_msgs::msg::SystemRptFloat, pacmod3_msgs::msg::SystemRptFloat, - pacmod3_msgs::msg::SystemRptInt, pacmod3_msgs::msg::SystemRptInt, pacmod3_msgs::msg::GlobalRpt>; - - /* subscribers */ - - // From Pacmod - std::unique_ptr> - steer_wheel_rpt_sub_; - std::unique_ptr> - wheel_speed_rpt_sub_; - std::unique_ptr> accel_rpt_sub_; - std::unique_ptr> brake_rpt_sub_; - std::unique_ptr> shift_rpt_sub_; - std::unique_ptr> turn_rpt_sub_; - std::unique_ptr> global_rpt_sub_; - std::unique_ptr> pacmod_feedbacks_sync_; - - // From CAN - rclcpp::Subscription::SharedPtr can_sub_; - - /* ros parameters */ - double can_timeout_sec_; - double pacmod3_msgs_timeout_sec_; - - /* variables */ - rclcpp::Time last_can_received_time_; - rclcpp::Time last_pacmod3_msgs_received_time_; - bool is_pacmod_rpt_received_ = false; - pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt_ptr_; // [rad] - pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt_ptr_; // [m/s] - pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr accel_rpt_ptr_; - pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr brake_rpt_ptr_; - pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr shift_rpt_ptr_; - pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt_ptr_; - pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr turn_rpt_ptr_; - - // Diagnostic Updater - std::shared_ptr updater_ptr_; - - /* callbacks */ - void callbackPacmodRpt( - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt, - const pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr accel_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr brake_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr shift_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr turn_rpt, - const pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt); - - void callbackCan(const can_msgs::msg::Frame::ConstSharedPtr can); - - /* functions */ - void checkPacmodMsgs(diagnostic_updater::DiagnosticStatusWrapper & stat); - std::string addMsg(const std::string & original_msg, const std::string & additional_msg); - - bool isTimeoutCanMsgs(); - bool isTimeoutPacmodMsgs(); - bool receivedPacmodMsgs(); - bool isBrakeActuatorAccident(); - bool isBrakeWireAccident(); - bool isAccelAccident(); - bool isOtherAccident(); -}; - -#endif // PACMOD_INTERFACE__PACMOD_DIAG_PUBLISHER_HPP_ diff --git a/vehicle/pacmod_interface/include/pacmod_interface/pacmod_interface.hpp b/vehicle/pacmod_interface/include/pacmod_interface/pacmod_interface.hpp deleted file mode 100644 index f9fb82e3a4dc8..0000000000000 --- a/vehicle/pacmod_interface/include/pacmod_interface/pacmod_interface.hpp +++ /dev/null @@ -1,226 +0,0 @@ -// Copyright 2017-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef PACMOD_INTERFACE__PACMOD_INTERFACE_HPP_ -#define PACMOD_INTERFACE__PACMOD_INTERFACE_HPP_ - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -class PacmodInterface : public rclcpp::Node -{ -public: - using ActuationCommandStamped = tier4_vehicle_msgs::msg::ActuationCommandStamped; - using ActuationStatusStamped = tier4_vehicle_msgs::msg::ActuationStatusStamped; - using SteeringWheelStatusStamped = tier4_vehicle_msgs::msg::SteeringWheelStatusStamped; - PacmodInterface(); - -private: - typedef message_filters::sync_policies::ApproximateTime< - pacmod3_msgs::msg::SystemRptFloat, pacmod3_msgs::msg::WheelSpeedRpt, - pacmod3_msgs::msg::SystemRptFloat, pacmod3_msgs::msg::SystemRptFloat, - pacmod3_msgs::msg::SystemRptInt, pacmod3_msgs::msg::SystemRptInt, pacmod3_msgs::msg::GlobalRpt> - PacmodFeedbacksSyncPolicy; - - /* subscribers */ - // From Autoware - rclcpp::Subscription::SharedPtr - control_cmd_sub_; - rclcpp::Subscription::SharedPtr gear_cmd_sub_; - rclcpp::Subscription::SharedPtr - turn_indicators_cmd_sub_; - rclcpp::Subscription::SharedPtr - hazard_lights_cmd_sub_; - rclcpp::Subscription::SharedPtr engage_cmd_sub_; - rclcpp::Subscription::SharedPtr actuation_cmd_sub_; - rclcpp::Subscription::SharedPtr emergency_sub_; - - // From Pacmod - std::unique_ptr> - steer_wheel_rpt_sub_; - std::unique_ptr> - wheel_speed_rpt_sub_; - std::unique_ptr> accel_rpt_sub_; - std::unique_ptr> brake_rpt_sub_; - std::unique_ptr> shift_rpt_sub_; - std::unique_ptr> turn_rpt_sub_; - std::unique_ptr> global_rpt_sub_; - std::unique_ptr> pacmod_feedbacks_sync_; - - /* publishers */ - // To Pacmod - rclcpp::Publisher::SharedPtr accel_cmd_pub_; - rclcpp::Publisher::SharedPtr brake_cmd_pub_; - rclcpp::Publisher::SharedPtr steer_cmd_pub_; - rclcpp::Publisher::SharedPtr shift_cmd_pub_; - rclcpp::Publisher::SharedPtr turn_cmd_pub_; - rclcpp::Publisher::SharedPtr - raw_steer_cmd_pub_; // only for debug - - // To Autoware - rclcpp::Publisher::SharedPtr - control_mode_pub_; - rclcpp::Publisher::SharedPtr vehicle_twist_pub_; - rclcpp::Publisher::SharedPtr - steering_status_pub_; - rclcpp::Publisher::SharedPtr gear_status_pub_; - rclcpp::Publisher::SharedPtr - turn_indicators_status_pub_; - rclcpp::Publisher::SharedPtr - hazard_lights_status_pub_; - rclcpp::Publisher::SharedPtr actuation_status_pub_; - rclcpp::Publisher::SharedPtr steering_wheel_status_pub_; - - rclcpp::TimerBase::SharedPtr timer_; - - /* ros param */ - std::string base_frame_id_; - int command_timeout_ms_; // vehicle_cmd timeout [ms] - bool is_pacmod_rpt_received_ = false; - bool is_pacmod_enabled_ = false; - bool is_clear_override_needed_ = false; - bool prev_override_ = false; - double loop_rate_; // [Hz] - double tire_radius_; // [m] - double wheel_base_; // [m] - double steering_offset_; // [rad] def: measured = truth + offset - double vgr_coef_a_; // variable gear ratio coeffs - double vgr_coef_b_; // variable gear ratio coeffs - double vgr_coef_c_; // variable gear ratio coeffs - double accel_pedal_offset_; // offset of accel pedal value - double brake_pedal_offset_; // offset of brake pedal value - double tire_radius_scale_factor_; // scale factor of tire radius - - double emergency_brake_; // brake command when emergency [m/s^2] - double max_throttle_; // max throttle [0~1] - double max_brake_; // max throttle [0~1] - double max_steering_wheel_; // max steering wheel angle [rad] - double max_steering_wheel_rate_; // [rad/s] - double min_steering_wheel_rate_; // [rad/s] - double steering_wheel_rate_low_vel_; // [rad/s] - double steering_wheel_rate_stopped_; // [rad/s] - double low_vel_thresh_; // [m/s] - - bool enable_steering_rate_control_; // use steering angle speed for command [rad/s] - - double hazard_thresh_time_; - int hazard_recover_count_ = 0; - const int hazard_recover_cmd_num_ = 5; - - vehicle_info_util::VehicleInfo vehicle_info_; - - /* input values */ - ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr_; - autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr control_cmd_ptr_; - autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr turn_indicators_cmd_ptr_; - autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr hazard_lights_cmd_ptr_; - autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr gear_cmd_ptr_; - - pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt_ptr_; // [rad] - pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt_ptr_; // [m/s] - pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr accel_rpt_ptr_; - pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr brake_rpt_ptr_; // [m/s] - pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr gear_cmd_rpt_ptr_; // [m/s] - pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt_ptr_; // [m/s] - pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr turn_rpt_ptr_; - pacmod3_msgs::msg::SteeringCmd prev_steer_cmd_; - - bool engage_cmd_{false}; - bool is_emergency_{false}; - rclcpp::Time control_command_received_time_; - rclcpp::Time actuation_command_received_time_; - rclcpp::Time last_shift_inout_matched_time_; - - /* callbacks */ - void callbackActuationCmd(const ActuationCommandStamped::ConstSharedPtr msg); - void callbackControlCmd( - const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg); - - void callbackEmergencyCmd( - const tier4_vehicle_msgs::msg::VehicleEmergencyStamped::ConstSharedPtr msg); - - void callbackGearCmd(const autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg); - void callbackTurnIndicatorsCommand( - const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg); - void callbackHazardLightsCommand( - const autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg); - void callbackEngage(const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg); - void callbackPacmodRpt( - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt, - const pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr accel_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr brake_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr gear_cmd_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr turn_rpt, - const pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt); - - /* functions */ - void publishCommands(); - double calculateVehicleVelocity( - const pacmod3_msgs::msg::WheelSpeedRpt & wheel_speed_rpt, - const pacmod3_msgs::msg::SystemRptInt & shift_rpt); - double calculateVariableGearRatio(const double vel, const double steer_wheel); - double calcSteerWheelRateCmd(const double gear_ratio); - uint16_t toPacmodShiftCmd(const autoware_auto_vehicle_msgs::msg::GearCommand & gear_cmd); - uint16_t toPacmodTurnCmd( - const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand & turn, - const autoware_auto_vehicle_msgs::msg::HazardLightsCommand & hazard); - uint16_t toPacmodTurnCmdWithHazardRecover( - const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand & turn, - const autoware_auto_vehicle_msgs::msg::HazardLightsCommand & hazard); - - std::optional toAutowareShiftReport(const pacmod3_msgs::msg::SystemRptInt & shift); - int32_t toAutowareTurnIndicatorsReport(const pacmod3_msgs::msg::SystemRptInt & turn); - int32_t toAutowareHazardLightsReport(const pacmod3_msgs::msg::SystemRptInt & turn); - double steerWheelRateLimiter( - const double current_steer_cmd, const double prev_steer_cmd, - const rclcpp::Time & current_steer_time, const rclcpp::Time & prev_steer_time, - const double steer_rate, const double current_steer_output, const bool engage); -}; - -#endif // PACMOD_INTERFACE__PACMOD_INTERFACE_HPP_ diff --git a/vehicle/pacmod_interface/launch/pacmod_additional_debug_publisher.launch.xml b/vehicle/pacmod_interface/launch/pacmod_additional_debug_publisher.launch.xml deleted file mode 100644 index 1912c1a1ec967..0000000000000 --- a/vehicle/pacmod_interface/launch/pacmod_additional_debug_publisher.launch.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/vehicle/pacmod_interface/launch/pacmod_interface.launch.xml b/vehicle/pacmod_interface/launch/pacmod_interface.launch.xml deleted file mode 100644 index a1ae8e0617c1c..0000000000000 --- a/vehicle/pacmod_interface/launch/pacmod_interface.launch.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle/pacmod_interface/package.xml b/vehicle/pacmod_interface/package.xml deleted file mode 100644 index d1fa093b90536..0000000000000 --- a/vehicle/pacmod_interface/package.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - pacmod_interface - 0.1.0 - AutonomouStuff pacmod interface as a ROS 2 node - Akihito Ohsato - Apache License 2.0 - - Akihito Ohsato - T.Ando - Horibe Takamasa - - autoware_auto_control_msgs - autoware_auto_vehicle_msgs - can_msgs - diagnostic_updater - message_filters - pacmod3_msgs - rclcpp - std_msgs - tier4_debug_msgs - tier4_vehicle_msgs - vehicle_info_util - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_main.cpp b/vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_main.cpp deleted file mode 100644 index eca9b0120bf40..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_main.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2020 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 - -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/vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.cpp b/vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.cpp deleted file mode 100644 index 26ae019372f6f..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_additional_debug_publisher/pacmod_additional_debug_publisher_node.cpp +++ /dev/null @@ -1,160 +0,0 @@ -// Copyright 2020 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 - -namespace -{ -bool isTargetId(uint32_t id) -{ - return id == 0x32C || id == 0x451 || id == 0x452 || id == 0x453 || id == 0x454 || id == 0x455 || - id == 0x456 || id == 0x457 || id == 0x790 || id == 0x791 || id == 0x792; -} -} // namespace - -PacmodAdditionalDebugPublisherNode::PacmodAdditionalDebugPublisherNode() -: Node("pacmod_additional_debug_publisher") -{ - using std::placeholders::_1; - - debug_pub_ = create_publisher( - "output/debug", rclcpp::QoS{1}); - sub_ = create_subscription( - "input/can_tx", rclcpp::QoS{1}, - std::bind(&PacmodAdditionalDebugPublisherNode::canTxCallback, this, _1)); - debug_value_.data.resize(17); - calibration_active_ = this->declare_parameter("calibration_active", false); - if (calibration_active_) { - accel_cal_rpt_pub_ = - create_publisher("output/accel_cal_rpt", 1); - brake_cal_rpt_pub_ = - create_publisher("output/brake_cal_rpt", 1); - steer_cal_rpt_pub_ = - create_publisher("output/steer_cal_rpt", 1); - accel_cal_rpt_.data.resize(3); - brake_cal_rpt_.data.resize(5); - steer_cal_rpt_.data.resize(3); - } -} - -void PacmodAdditionalDebugPublisherNode::canTxCallback( - const can_msgs::msg::Frame::ConstSharedPtr msg) -{ - if (isTargetId(msg->id)) { - float debug1 = 0.0; - float debug2 = 0.0; - float debug3 = 0.0; - float debug4 = 0.0; - if (msg->id == 0x790) { - int16_t temp = 0; - temp = (static_cast(msg->data[0]) << 8) | msg->data[1]; - accel_cal_rpt_.data.at(0) = static_cast(temp / 1000.0); // accel_a_volt - temp = (static_cast(msg->data[2]) << 8) | msg->data[3]; - accel_cal_rpt_.data.at(1) = static_cast(temp / 1000.0); // accel_b_volt - temp = (static_cast(msg->data[4]) << 8) | msg->data[5]; - accel_cal_rpt_.data.at(2) = static_cast(temp / 1000.0); // output - } else if (msg->id == 0x791) { - int16_t temp = 0; - int8_t temp1 = 0; - temp = (static_cast(msg->data[0]) << 8) | msg->data[1]; - brake_cal_rpt_.data.at(0) = static_cast(temp / 1000.0); // sks1_volt - temp = (static_cast(msg->data[2]) << 8) | msg->data[3]; - brake_cal_rpt_.data.at(1) = static_cast(temp / 1000.0); // sks2_volt - temp1 = static_cast(msg->data[4]); - brake_cal_rpt_.data.at(2) = static_cast(temp1 / 100.0); // pedal_position - temp1 = static_cast(msg->data[5]); - brake_cal_rpt_.data.at(3) = static_cast(temp1 / 100.0); // brake_cmd - temp = (static_cast(msg->data[6]) << 8) | msg->data[7]; - brake_cal_rpt_.data.at(4) = static_cast(temp / 1000.0); // globe_position - } else if (msg->id == 0x792) { - int16_t temp = 0; - temp = (static_cast(msg->data[0]) << 8) | msg->data[1]; - steer_cal_rpt_.data.at(0) = static_cast(temp / 1000.0); // trq1_volt - temp = (static_cast(msg->data[2]) << 8) | msg->data[3]; - steer_cal_rpt_.data.at(1) = static_cast(temp / 1000.0); // trq2_volt - temp = (static_cast(msg->data[4]) << 8) | msg->data[5]; - steer_cal_rpt_.data.at(2) = static_cast(temp / 1000.0); // position - } else if (msg->id == 0x32C) { - int16_t temp = 0; - temp = (static_cast(msg->data[0]) << 8) | msg->data[1]; - debug1 = temp / 1000.0; - temp = (static_cast(msg->data[2]) << 8) | msg->data[3]; - debug2 = temp / 100.0; - temp = (static_cast(msg->data[4]) << 8) | msg->data[5]; - debug3 = temp / 1000.0; - temp = (static_cast(msg->data[6]) << 8) | msg->data[7]; - debug4 = temp / 100.0; - } else { - union Data { - uint32_t uint32_value; - float float_value; - } temp; - temp.uint32_value = (static_cast(msg->data[3]) << 24) | - (static_cast(msg->data[2]) << 16) | - (static_cast(msg->data[1]) << 8) | msg->data[0]; - debug1 = temp.float_value; - temp.uint32_value = (static_cast(msg->data[7]) << 24) | - (static_cast(msg->data[6]) << 16) | - (static_cast(msg->data[5]) << 8) | msg->data[4]; - debug2 = temp.float_value; - } - switch (msg->id) { - case 0x32C: - debug_value_.data.at(0) = debug1; // steering pos - debug_value_.data.at(1) = debug2; // steering_eps_assist - debug_value_.data.at(2) = debug3; // steering rate - debug_value_.data.at(3) = debug4; // steering eps input - break; - case 0x451: - debug_value_.data.at(4) = debug1; // pid command - debug_value_.data.at(5) = debug2; // pid output - break; - case 0x452: - debug_value_.data.at(6) = debug1; // pid_error - debug_value_.data.at(7) = debug2; // pid_output - break; - case 0x453: - debug_value_.data.at(8) = debug1; // pid_p_term - debug_value_.data.at(9) = debug2; // pid_i_term - break; - case 0x454: - debug_value_.data.at(10) = debug1; // pid_d_term - debug_value_.data.at(11) = debug2; // pid_filtered_rate - break; - case 0x455: - debug_value_.data.at(12) = debug1; // lugre - debug_value_.data.at(13) = debug2; // rtz - break; - case 0x456: - debug_value_.data.at(14) = debug1; // lugre_rtz_filtered_rate - debug_value_.data.at(15) = debug2; // ctrl_dt - break; - case 0x457: - debug_value_.data.at(16) = debug1; // rpt_dt - break; - default: - break; - } - debug_value_.stamp = this->now(); - debug_pub_->publish(debug_value_); - if (calibration_active_) { - accel_cal_rpt_.stamp = this->now(); - brake_cal_rpt_.stamp = this->now(); - steer_cal_rpt_.stamp = this->now(); - accel_cal_rpt_pub_->publish(accel_cal_rpt_); - brake_cal_rpt_pub_->publish(brake_cal_rpt_); - steer_cal_rpt_pub_->publish(steer_cal_rpt_); - } - } -} diff --git a/vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_main.cpp b/vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_main.cpp deleted file mode 100644 index c0f0ad100d90a..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_main.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2020 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 - -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/vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.cpp b/vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.cpp deleted file mode 100644 index aa54680772cae..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_dynamic_parameter_changer/pacmod_dynamic_parameter_changer_node.cpp +++ /dev/null @@ -1,166 +0,0 @@ -// Copyright 2020 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 - -PacmodDynamicParameterChangerNode::PacmodDynamicParameterChangerNode() -: Node("pacmod_dynamic_parameter_changer") -{ - straight_course_param_.p_gain = declare_parameter("straight_p_gain", 0.8); - straight_course_param_.i_gain = declare_parameter("straight_i_gain", 0.002); - straight_course_param_.lugre_fc = declare_parameter("straight_lugre_fc", 0.03); - straight_course_param_.rtz_offset = declare_parameter("straight_rtz_offset", 0.085); - curve_course_param_.p_gain = declare_parameter("curve_p_gain", 0.3); - curve_course_param_.i_gain = declare_parameter("curve_i_gain", 0.002); - curve_course_param_.lugre_fc = declare_parameter("curve_lugre_fc", 0.01); - curve_course_param_.rtz_offset = declare_parameter("curve_rtz_offset", 0.085); - min_steer_thresh_ = declare_parameter("min_steer_thresh", 0.2); - max_steer_thresh_ = declare_parameter("max_steer_thresh", 0.5); - param_max_rate_.p_gain = declare_parameter("p_gain_rate_max", 5.0); - param_max_rate_.i_gain = declare_parameter("i_gain_rate_max", 0.05); - param_max_rate_.lugre_fc = declare_parameter("lugre_fc_rate_max", 0.1); - param_max_rate_.rtz_offset = declare_parameter("rtz_offset_rate_max", 0.5); - param_min_rate_.p_gain = declare_parameter("p_gain_rate_min", -1.5); - param_min_rate_.i_gain = declare_parameter("i_gain_rate_min", -0.05); - param_min_rate_.lugre_fc = declare_parameter("lugre_fc_rate_min", -0.1); - param_min_rate_.rtz_offset = declare_parameter("rtz_offset_rate_min", -0.5); - - current_param_list_ = curve_course_param_; - - can_pub_ = create_publisher("~/output/can", rclcpp::QoS{1}); - debug_pub_ = - create_publisher("~/debug/parameter", rclcpp::QoS{1}); - - using std::placeholders::_1; - steer_rpt_sub_ = create_subscription( - "~/input/steer_rpt", rclcpp::QoS{1}, - std::bind(&PacmodDynamicParameterChangerNode::subSteerRpt, this, _1)); -} - -void PacmodDynamicParameterChangerNode::subSteerRpt( - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr msg) -{ - current_param_list_ = calculateParam(std::abs(msg->command), std::abs(msg->output), msg->enabled); - current_param_time_ = now(); - sendCanMsg(current_param_list_); - sendDebugMsg(current_param_list_); -} - -ParamList PacmodDynamicParameterChangerNode::calculateParam( - const double current_steer_cmd, const double current_steer, const bool enabled) -{ - if (!enabled) { - // return curve (default) param - return curve_course_param_; - } - - const double steer = std::max(current_steer, current_steer_cmd); - // run straight course (steer is low) -> return straight-course-param - // run curve course (steer is high) -> return curve-course-param - - if (steer >= max_steer_thresh_) { - return curve_course_param_; - } else if (steer <= min_steer_thresh_) { - return straight_course_param_; - } - - const double straight_rate = - (max_steer_thresh_ - steer) / (max_steer_thresh_ - min_steer_thresh_); - - const auto interpolate_param = - interpolateParam(straight_course_param_, curve_course_param_, straight_rate); - return rateLimit(interpolate_param, current_param_list_); -} - -void PacmodDynamicParameterChangerNode::sendDebugMsg(const ParamList param_list) -{ - // publish debug msg - std_msgs::msg::Float32MultiArray msg; - msg.data.resize(4); - msg.data.at(0) = param_list.p_gain; - msg.data.at(1) = param_list.i_gain; - msg.data.at(2) = param_list.lugre_fc; - msg.data.at(3) = param_list.rtz_offset; - debug_pub_->publish(msg); -} - -void PacmodDynamicParameterChangerNode::sendCanMsg(const ParamList param_list) -{ - // encoding - can_msgs::msg::Frame frame; - frame.header.stamp = now(); - frame.id = 0x13C; - frame.is_rtr = false; - frame.is_extended = false; - frame.is_error = false; - frame.dlc = 8; - uint16_t kp_u = static_cast(1000.0 * param_list.p_gain); - uint16_t ki_u = static_cast(1000.0 * param_list.i_gain); - uint16_t fc_u = static_cast(1000.0 * param_list.lugre_fc); - uint16_t rtz_u = static_cast(1000.0 * param_list.rtz_offset); - frame.data[0] = (kp_u & 0xFF00) >> 8; - frame.data[1] = ki_u & 0x00FF; - frame.data[2] = (ki_u & 0xFF00) >> 8; - frame.data[3] = ki_u & 0x00FF; - frame.data[4] = (fc_u & 0xFF00) >> 8; - frame.data[5] = fc_u & 0x00FF; - frame.data[6] = (rtz_u & 0xFF00) >> 8; - frame.data[7] = rtz_u & 0x00FF; - - // publish can msg - can_pub_->publish(frame); -} - -ParamList PacmodDynamicParameterChangerNode::interpolateParam( - const ParamList p1, const ParamList p2, const double p1_rate) -{ - const double p2_rate = 1.0 - p1_rate; - ParamList p; - p.p_gain = p1.p_gain * p1_rate + p2.p_gain * p2_rate; - p.i_gain = p1.i_gain * p1_rate + p2.i_gain * p2_rate; - p.lugre_fc = p1.lugre_fc * p1_rate + p2.lugre_fc * p2_rate; - p.rtz_offset = p1.rtz_offset * p1_rate + p2.rtz_offset * p2_rate; - return p; -} - -ParamList PacmodDynamicParameterChangerNode::rateLimit( - const ParamList new_param, const ParamList current_param) -{ - ParamList limited_param; - const double dt = (now() - current_param_time_).seconds(); - - // apply rate limit - limited_param.p_gain = rateLimit( - new_param.p_gain, current_param.p_gain, dt, param_max_rate_.p_gain, param_min_rate_.p_gain); - limited_param.i_gain = rateLimit( - new_param.i_gain, current_param.i_gain, dt, param_max_rate_.i_gain, param_min_rate_.i_gain); - limited_param.lugre_fc = rateLimit( - new_param.lugre_fc, current_param.lugre_fc, dt, param_max_rate_.lugre_fc, - param_min_rate_.lugre_fc); - limited_param.rtz_offset = rateLimit( - new_param.rtz_offset, current_param.rtz_offset, dt, param_max_rate_.rtz_offset, - param_min_rate_.rtz_offset); - return limited_param; -} - -double PacmodDynamicParameterChangerNode::rateLimit( - const double new_value, const double current_value, const double delta_time, - const double max_rate, const double min_rate) -{ - const double dval = new_value - current_value; - const double limit_dval = std::min(delta_time * max_rate, std::max(dval, delta_time * min_rate)); - return current_value + limit_dval; -} diff --git a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher.cpp b/vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher.cpp deleted file mode 100644 index 049375d51c732..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher.cpp +++ /dev/null @@ -1,186 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include -#include -#include -#include -#include - -PacmodDiagPublisher::PacmodDiagPublisher() -: Node("pacmod_diag_publisher"), - last_can_received_time_(this->now()), - last_pacmod3_msgs_received_time_(this->now()) -{ - /* ros parameters */ - can_timeout_sec_ = declare_parameter("can_timeout_sec", 10.0); - pacmod3_msgs_timeout_sec_ = declare_parameter("pacmod_msg_timeout_sec", 10.0); - const double update_rate = declare_parameter("update_rate", 10.0); - - /* Diagnostic Updater */ - updater_ptr_ = std::make_shared(this, 1.0 / update_rate); - updater_ptr_->setHardwareID("pacmod_checker"); - updater_ptr_->add("pacmod_checker", this, &PacmodDiagPublisher::checkPacmodMsgs); - - /* register subscribers */ - can_sub_ = create_subscription( - "/pacmod/can_tx", 1, std::bind(&PacmodDiagPublisher::callbackCan, this, std::placeholders::_1)); - - steer_wheel_rpt_sub_ = - std::make_unique>( - this, "/pacmod/steering_rpt"); - wheel_speed_rpt_sub_ = - std::make_unique>( - this, "/pacmod/wheel_speed_rpt"); - accel_rpt_sub_ = std::make_unique>( - this, "/pacmod/accel_rpt"); - brake_rpt_sub_ = std::make_unique>( - this, "/pacmod/brake_rpt"); - shift_rpt_sub_ = std::make_unique>( - this, "/pacmod/shift_rpt"); - turn_rpt_sub_ = std::make_unique>( - this, "/pacmod/turn_rpt"); - global_rpt_sub_ = std::make_unique>( - this, "/pacmod/global_rpt"); - - pacmod_feedbacks_sync_ = - std::make_unique>( - PacmodFeedbacksSyncPolicy(10), *steer_wheel_rpt_sub_, *wheel_speed_rpt_sub_, *accel_rpt_sub_, - *brake_rpt_sub_, *shift_rpt_sub_, *turn_rpt_sub_, *global_rpt_sub_); - - pacmod_feedbacks_sync_->registerCallback(std::bind( - &PacmodDiagPublisher::callbackPacmodRpt, this, std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, - std::placeholders::_7)); -} - -void PacmodDiagPublisher::callbackCan( - [[maybe_unused]] const can_msgs::msg::Frame::ConstSharedPtr can) -{ - last_can_received_time_ = this->now(); -} - -void PacmodDiagPublisher::callbackPacmodRpt( - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt, - const pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr accel_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr brake_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr shift_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr turn_rpt, - const pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt) -{ - last_pacmod3_msgs_received_time_ = this->now(); - steer_wheel_rpt_ptr_ = steer_wheel_rpt; - wheel_speed_rpt_ptr_ = wheel_speed_rpt; - accel_rpt_ptr_ = accel_rpt; - brake_rpt_ptr_ = brake_rpt; - shift_rpt_ptr_ = shift_rpt; - global_rpt_ptr_ = global_rpt; - turn_rpt_ptr_ = turn_rpt; - is_pacmod_rpt_received_ = true; -} - -void PacmodDiagPublisher::checkPacmodMsgs(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - using DiagStatus = diagnostic_msgs::msg::DiagnosticStatus; - int8_t level = DiagStatus::OK; - std::string msg = ""; - - if (isTimeoutCanMsgs()) { - level = DiagStatus::ERROR; - msg = addMsg(msg, "CAN reception timeout."); - } - - if (isTimeoutPacmodMsgs()) { - level = DiagStatus::ERROR; - msg = addMsg(msg, "Pacmod msgs reception timeout."); - } - - if (!receivedPacmodMsgs()) { - if (level == DiagStatus::OK) { - msg = "OK"; - } - stat.summary(level, msg); - // do not receive pacmod msgs yet. - return; - } - - if (isBrakeActuatorAccident()) { - level = DiagStatus::ERROR; - msg = addMsg(msg, "Brake actuator failure."); - } - - if (isBrakeWireAccident()) { - level = DiagStatus::ERROR; - msg = addMsg(msg, "Brake wire failure."); - } - - if (isAccelAccident()) { - level = DiagStatus::ERROR; - msg = addMsg(msg, "Accel module failure."); - } - - if (level == DiagStatus::OK && isOtherAccident()) { - level = DiagStatus::ERROR; - msg = addMsg(msg, "Unknown Pacmod Error."); - } - - if (level == DiagStatus::OK) { - msg = "OK"; - } - stat.summary(level, msg); -} - -std::string PacmodDiagPublisher::addMsg( - const std::string & original_msg, const std::string & additional_msg) -{ - if (original_msg == "") { - return additional_msg; - } - - return original_msg + " ; " + additional_msg; -} - -bool PacmodDiagPublisher::isTimeoutCanMsgs() -{ - const double dt = (this->now() - last_can_received_time_).seconds(); - return dt > can_timeout_sec_; -} - -bool PacmodDiagPublisher::isTimeoutPacmodMsgs() -{ - const double dt = (this->now() - last_pacmod3_msgs_received_time_).seconds(); - return dt > pacmod3_msgs_timeout_sec_; -} - -bool PacmodDiagPublisher::receivedPacmodMsgs() { return is_pacmod_rpt_received_; } - -bool PacmodDiagPublisher::isBrakeActuatorAccident() -{ - return global_rpt_ptr_->pacmod_sys_fault_active && brake_rpt_ptr_->pacmod_fault; -} - -bool PacmodDiagPublisher::isBrakeWireAccident() -{ - return global_rpt_ptr_->pacmod_sys_fault_active && brake_rpt_ptr_->command_output_fault; -} - -bool PacmodDiagPublisher::isAccelAccident() -{ - return global_rpt_ptr_->pacmod_sys_fault_active && accel_rpt_ptr_->input_output_fault; -} - -bool PacmodDiagPublisher::isOtherAccident() { return global_rpt_ptr_->pacmod_sys_fault_active; } diff --git a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher_node.cpp b/vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher_node.cpp deleted file mode 100644 index c79f003d4bea9..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_diag_publisher_node.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include - -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/vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp b/vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp deleted file mode 100644 index d833cc97fbf75..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp +++ /dev/null @@ -1,685 +0,0 @@ -// Copyright 2017-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include -#include -#include -#include - -PacmodInterface::PacmodInterface() -: Node("pacmod_interface"), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()) -{ - /* setup parameters */ - base_frame_id_ = declare_parameter("base_frame_id", "base_link"); - command_timeout_ms_ = declare_parameter("command_timeout_ms", 1000); - loop_rate_ = declare_parameter("loop_rate", 30.0); - - /* parameters for vehicle specifications */ - tire_radius_ = vehicle_info_.wheel_radius_m; - wheel_base_ = vehicle_info_.wheel_base_m; - - steering_offset_ = declare_parameter("steering_offset", 0.0); - enable_steering_rate_control_ = declare_parameter("enable_steering_rate_control", false); - - /* parameters for emergency stop */ - emergency_brake_ = declare_parameter("emergency_brake", 0.7); - - /* vehicle parameters */ - vgr_coef_a_ = declare_parameter("vgr_coef_a", 15.713); - vgr_coef_b_ = declare_parameter("vgr_coef_b", 0.053); - vgr_coef_c_ = declare_parameter("vgr_coef_c", 0.042); - accel_pedal_offset_ = declare_parameter("accel_pedal_offset", 0.0); - brake_pedal_offset_ = declare_parameter("brake_pedal_offset", 0.0); - tire_radius_scale_factor_ = declare_parameter("tire_radius_scale_factor", 1.0); - - /* parameters for limitter */ - max_throttle_ = declare_parameter("max_throttle", 0.2); - max_brake_ = declare_parameter("max_brake", 0.8); - max_steering_wheel_ = declare_parameter("max_steering_wheel", 2.7 * M_PI); - max_steering_wheel_rate_ = declare_parameter("max_steering_wheel_rate", 6.6); - min_steering_wheel_rate_ = declare_parameter("min_steering_wheel_rate", 0.5); - steering_wheel_rate_low_vel_ = declare_parameter("steering_wheel_rate_low_vel", 5.0); - steering_wheel_rate_stopped_ = declare_parameter("steering_wheel_rate_stopped", 5.0); - low_vel_thresh_ = declare_parameter("low_vel_thresh", 1.389); // 5.0kmh - - /* parameters for turn signal recovery */ - hazard_thresh_time_ = declare_parameter("hazard_thresh_time", 0.20); // s - /* initialize */ - prev_steer_cmd_.header.stamp = this->now(); - prev_steer_cmd_.command = 0.0; - - /* subscribers */ - using std::placeholders::_1; - - // From autoware - control_cmd_sub_ = create_subscription( - "/control/command/control_cmd", 1, std::bind(&PacmodInterface::callbackControlCmd, this, _1)); - gear_cmd_sub_ = create_subscription( - "/control/command/gear_cmd", 1, std::bind(&PacmodInterface::callbackGearCmd, this, _1)); - turn_indicators_cmd_sub_ = - create_subscription( - "/control/command/turn_indicators_cmd", rclcpp::QoS{1}, - std::bind(&PacmodInterface::callbackTurnIndicatorsCommand, this, _1)); - hazard_lights_cmd_sub_ = - create_subscription( - "/control/command/hazard_lights_cmd", rclcpp::QoS{1}, - std::bind(&PacmodInterface::callbackHazardLightsCommand, this, _1)); - engage_cmd_sub_ = create_subscription( - "/vehicle/engage", rclcpp::QoS{1}, std::bind(&PacmodInterface::callbackEngage, this, _1)); - actuation_cmd_sub_ = create_subscription( - "/control/command/actuation_cmd", 1, - std::bind(&PacmodInterface::callbackActuationCmd, this, _1)); - emergency_sub_ = create_subscription( - "/control/command/emergency_cmd", 1, - std::bind(&PacmodInterface::callbackEmergencyCmd, this, _1)); - - // From pacmod - - steer_wheel_rpt_sub_ = - std::make_unique>( - this, "/pacmod/steering_rpt"); - wheel_speed_rpt_sub_ = - std::make_unique>( - this, "/pacmod/wheel_speed_rpt"); - accel_rpt_sub_ = std::make_unique>( - this, "/pacmod/accel_rpt"); - brake_rpt_sub_ = std::make_unique>( - this, "/pacmod/brake_rpt"); - shift_rpt_sub_ = std::make_unique>( - this, "/pacmod/shift_rpt"); - turn_rpt_sub_ = std::make_unique>( - this, "/pacmod/turn_rpt"); - global_rpt_sub_ = std::make_unique>( - this, "/pacmod/global_rpt"); - - pacmod_feedbacks_sync_ = - std::make_unique>( - PacmodFeedbacksSyncPolicy(10), *steer_wheel_rpt_sub_, *wheel_speed_rpt_sub_, *accel_rpt_sub_, - *brake_rpt_sub_, *shift_rpt_sub_, *turn_rpt_sub_, *global_rpt_sub_); - - pacmod_feedbacks_sync_->registerCallback(std::bind( - &PacmodInterface::callbackPacmodRpt, this, std::placeholders::_1, std::placeholders::_2, - std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, - std::placeholders::_7)); - - /* publisher */ - // To pacmod - accel_cmd_pub_ = - create_publisher("/pacmod/accel_cmd", rclcpp::QoS{1}); - brake_cmd_pub_ = - create_publisher("/pacmod/brake_cmd", rclcpp::QoS{1}); - steer_cmd_pub_ = - create_publisher("/pacmod/steering_cmd", rclcpp::QoS{1}); - shift_cmd_pub_ = - create_publisher("/pacmod/shift_cmd", rclcpp::QoS{1}); - turn_cmd_pub_ = - create_publisher("/pacmod/turn_cmd", rclcpp::QoS{1}); - raw_steer_cmd_pub_ = create_publisher( - "/pacmod/raw_steer_cmd", rclcpp::QoS{1}); // only for debug - - // To Autoware - control_mode_pub_ = create_publisher( - "/vehicle/status/control_mode", rclcpp::QoS{1}); - vehicle_twist_pub_ = create_publisher( - "/vehicle/status/velocity_status", rclcpp::QoS{1}); - steering_status_pub_ = create_publisher( - "/vehicle/status/steering_status", rclcpp::QoS{1}); - gear_status_pub_ = create_publisher( - "/vehicle/status/gear_status", rclcpp::QoS{1}); - turn_indicators_status_pub_ = - create_publisher( - "/vehicle/status/turn_indicators_status", rclcpp::QoS{1}); - hazard_lights_status_pub_ = create_publisher( - "/vehicle/status/hazard_lights_status", rclcpp::QoS{1}); - actuation_status_pub_ = - create_publisher("/vehicle/status/actuation_status", 1); - steering_wheel_status_pub_ = - create_publisher("/vehicle/status/steering_wheel_status", 1); - - // Timer - const auto period_ns = rclcpp::Rate(loop_rate_).period(); - timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, std::bind(&PacmodInterface::publishCommands, this)); -} - -void PacmodInterface::callbackActuationCmd(const ActuationCommandStamped::ConstSharedPtr msg) -{ - actuation_command_received_time_ = this->now(); - actuation_cmd_ptr_ = msg; -} - -void PacmodInterface::callbackEmergencyCmd( - const tier4_vehicle_msgs::msg::VehicleEmergencyStamped::ConstSharedPtr msg) -{ - is_emergency_ = msg->emergency; -} - -void PacmodInterface::callbackControlCmd( - const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg) -{ - control_command_received_time_ = this->now(); - control_cmd_ptr_ = msg; -} - -void PacmodInterface::callbackGearCmd( - const autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg) -{ - gear_cmd_ptr_ = msg; -} - -void PacmodInterface::callbackTurnIndicatorsCommand( - const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg) -{ - turn_indicators_cmd_ptr_ = msg; -} - -void PacmodInterface::callbackHazardLightsCommand( - const autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg) -{ - hazard_lights_cmd_ptr_ = msg; -} - -void PacmodInterface::callbackEngage( - const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg) -{ - engage_cmd_ = msg->engage; - is_clear_override_needed_ = true; -} - -void PacmodInterface::callbackPacmodRpt( - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt, - const pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr accel_rpt, - const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr brake_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr shift_rpt, - const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr turn_rpt, - const pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt) -{ - is_pacmod_rpt_received_ = true; - steer_wheel_rpt_ptr_ = steer_wheel_rpt; - wheel_speed_rpt_ptr_ = wheel_speed_rpt; - accel_rpt_ptr_ = accel_rpt; - brake_rpt_ptr_ = brake_rpt; - gear_cmd_rpt_ptr_ = shift_rpt; - global_rpt_ptr_ = global_rpt; - turn_rpt_ptr_ = turn_rpt; - - is_pacmod_enabled_ = - steer_wheel_rpt_ptr_->enabled && accel_rpt_ptr_->enabled && brake_rpt_ptr_->enabled; - RCLCPP_DEBUG( - get_logger(), - "enabled: is_pacmod_enabled_ %d, steer %d, accel %d, brake %d, shift %d, " - "global %d", - is_pacmod_enabled_, steer_wheel_rpt_ptr_->enabled, accel_rpt_ptr_->enabled, - brake_rpt_ptr_->enabled, gear_cmd_rpt_ptr_->enabled, global_rpt_ptr_->enabled); - - const double current_velocity = calculateVehicleVelocity( - *wheel_speed_rpt_ptr_, *gear_cmd_rpt_ptr_); // current vehicle speed > 0 [m/s] - const double current_steer_wheel = - steer_wheel_rpt_ptr_->output; // current vehicle steering wheel angle [rad] - const double adaptive_gear_ratio = - calculateVariableGearRatio(current_velocity, current_steer_wheel); - const double current_steer = current_steer_wheel / adaptive_gear_ratio - steering_offset_; - - std_msgs::msg::Header header; - header.frame_id = base_frame_id_; - header.stamp = get_clock()->now(); - - /* publish steering wheel status */ - { - SteeringWheelStatusStamped steering_wheel_status_msg; - steering_wheel_status_msg.stamp = header.stamp; - steering_wheel_status_msg.data = current_steer_wheel; - steering_wheel_status_pub_->publish(steering_wheel_status_msg); - } - - /* publish vehicle status control_mode */ - { - autoware_auto_vehicle_msgs::msg::ControlModeReport control_mode_msg; - control_mode_msg.stamp = header.stamp; - - if (global_rpt->enabled && is_pacmod_enabled_) { - control_mode_msg.mode = autoware_auto_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS; - } else { - control_mode_msg.mode = autoware_auto_vehicle_msgs::msg::ControlModeReport::MANUAL; - } - - control_mode_pub_->publish(control_mode_msg); - } - - /* publish vehicle status twist */ - { - autoware_auto_vehicle_msgs::msg::VelocityReport twist; - twist.header = header; - twist.longitudinal_velocity = current_velocity; // [m/s] - twist.heading_rate = current_velocity * std::tan(current_steer) / wheel_base_; // [rad/s] - vehicle_twist_pub_->publish(twist); - } - - /* publish current shift */ - { - autoware_auto_vehicle_msgs::msg::GearReport gear_report_msg; - gear_report_msg.stamp = header.stamp; - const auto opt_gear_report = toAutowareShiftReport(*gear_cmd_rpt_ptr_); - if (opt_gear_report) { - gear_report_msg.report = *opt_gear_report; - gear_status_pub_->publish(gear_report_msg); - } - } - - /* publish current status */ - { - autoware_auto_vehicle_msgs::msg::SteeringReport steer_msg; - steer_msg.stamp = header.stamp; - steer_msg.steering_tire_angle = current_steer; - steering_status_pub_->publish(steer_msg); - } - - /* publish control status */ - { - ActuationStatusStamped actuation_status; - actuation_status.header = header; - actuation_status.status.accel_status = accel_rpt_ptr_->output; - actuation_status.status.brake_status = brake_rpt_ptr_->output; - actuation_status.status.steer_status = current_steer; - actuation_status_pub_->publish(actuation_status); - } - - /* publish current turn signal */ - { - autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport turn_msg; - turn_msg.stamp = header.stamp; - turn_msg.report = toAutowareTurnIndicatorsReport(*turn_rpt); - turn_indicators_status_pub_->publish(turn_msg); - - autoware_auto_vehicle_msgs::msg::HazardLightsReport hazard_msg; - hazard_msg.stamp = header.stamp; - hazard_msg.report = toAutowareHazardLightsReport(*turn_rpt); - hazard_lights_status_pub_->publish(hazard_msg); - } -} - -void PacmodInterface::publishCommands() -{ - /* guard */ - if (!actuation_cmd_ptr_ || !control_cmd_ptr_ || !is_pacmod_rpt_received_ || !gear_cmd_ptr_) { - RCLCPP_INFO_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(1000).count(), - "vehicle_cmd = %d, pacmod3_msgs = %d", actuation_cmd_ptr_ != nullptr, - is_pacmod_rpt_received_); - return; - } - - const rclcpp::Time current_time = get_clock()->now(); - - double desired_throttle = actuation_cmd_ptr_->actuation.accel_cmd + accel_pedal_offset_; - double desired_brake = actuation_cmd_ptr_->actuation.brake_cmd + brake_pedal_offset_; - if (actuation_cmd_ptr_->actuation.brake_cmd <= std::numeric_limits::epsilon()) { - desired_brake = 0.0; - } - - /* check emergency and timeout */ - const double control_cmd_delta_time_ms = - (current_time - control_command_received_time_).seconds() * 1000.0; - const double actuation_cmd_delta_time_ms = - (current_time - actuation_command_received_time_).seconds() * 1000.0; - bool timeouted = false; - const int t_out = command_timeout_ms_; - if (t_out >= 0 && (control_cmd_delta_time_ms > t_out || actuation_cmd_delta_time_ms > t_out)) { - timeouted = true; - } - if (is_emergency_ || timeouted) { - RCLCPP_ERROR( - get_logger(), "Emergency Stopping, emergency = %d, timeouted = %d", is_emergency_, timeouted); - desired_throttle = 0.0; - desired_brake = emergency_brake_; - } - - const double current_velocity = - calculateVehicleVelocity(*wheel_speed_rpt_ptr_, *gear_cmd_rpt_ptr_); - const double current_steer_wheel = steer_wheel_rpt_ptr_->output; - - /* calculate desired steering wheel */ - double adaptive_gear_ratio = calculateVariableGearRatio(current_velocity, current_steer_wheel); - double desired_steer_wheel = - (control_cmd_ptr_->lateral.steering_tire_angle + steering_offset_) * adaptive_gear_ratio; - desired_steer_wheel = - std::min(std::max(desired_steer_wheel, -max_steering_wheel_), max_steering_wheel_); - - /* check clear flag */ - bool clear_override = false; - if (is_pacmod_enabled_ == true) { - is_clear_override_needed_ = false; - } else if (is_clear_override_needed_ == true) { - clear_override = true; - } - - /* make engage cmd false when a driver overrides vehicle control */ - if (!prev_override_ && global_rpt_ptr_->override_active) { - RCLCPP_WARN_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(1000).count(), - "Pacmod is overridden, enable flag is back to false"); - engage_cmd_ = false; - } - prev_override_ = global_rpt_ptr_->override_active; - - /* make engage cmd false when vehicle report is timed out, e.g. E-stop is depressed */ - const bool report_timed_out = ((current_time - global_rpt_ptr_->header.stamp).seconds() > 1.0); - if (report_timed_out) { - RCLCPP_WARN_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(1000).count(), - "Pacmod report is timed out, enable flag is back to false"); - engage_cmd_ = false; - } - - /* make engage cmd false when vehicle fault is active */ - if (global_rpt_ptr_->pacmod_sys_fault_active) { - RCLCPP_WARN_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(1000).count(), - "Pacmod fault is active, enable flag is back to false"); - engage_cmd_ = false; - } - RCLCPP_DEBUG( - get_logger(), - "is_pacmod_enabled_ = %d, is_clear_override_needed_ = %d, clear_override = " - "%d", - is_pacmod_enabled_, is_clear_override_needed_, clear_override); - - /* check shift change */ - const double brake_for_shift_trans = 0.7; - uint16_t desired_shift = gear_cmd_rpt_ptr_->output; - if (std::fabs(current_velocity) < 0.1) { // velocity is low -> the shift can be changed - if (toPacmodShiftCmd(*gear_cmd_ptr_) != gear_cmd_rpt_ptr_->output) { // need shift - // change. - desired_throttle = 0.0; - desired_brake = brake_for_shift_trans; // set brake to change the shift - desired_shift = toPacmodShiftCmd(*gear_cmd_ptr_); - RCLCPP_DEBUG( - get_logger(), "Doing shift change. current = %d, desired = %d. set brake_cmd to %f", - gear_cmd_rpt_ptr_->output, toPacmodShiftCmd(*gear_cmd_ptr_), desired_brake); - } - } - - /* publish accel cmd */ - { - pacmod3_msgs::msg::SystemCmdFloat accel_cmd; - accel_cmd.header.frame_id = base_frame_id_; - accel_cmd.header.stamp = current_time; - accel_cmd.enable = engage_cmd_; - accel_cmd.ignore_overrides = false; - accel_cmd.clear_override = clear_override; - accel_cmd.command = std::max(0.0, std::min(desired_throttle, max_throttle_)); - accel_cmd_pub_->publish(accel_cmd); - } - - /* publish brake cmd */ - { - pacmod3_msgs::msg::SystemCmdFloat brake_cmd; - brake_cmd.header.frame_id = base_frame_id_; - brake_cmd.header.stamp = current_time; - brake_cmd.enable = engage_cmd_; - brake_cmd.ignore_overrides = false; - brake_cmd.clear_override = clear_override; - brake_cmd.command = std::max(0.0, std::min(desired_brake, max_brake_)); - brake_cmd_pub_->publish(brake_cmd); - } - - /* publish steering cmd */ - { - pacmod3_msgs::msg::SteeringCmd steer_cmd; - steer_cmd.header.frame_id = base_frame_id_; - steer_cmd.header.stamp = current_time; - steer_cmd.enable = engage_cmd_; - steer_cmd.ignore_overrides = false; - steer_cmd.clear_override = clear_override; - steer_cmd.rotation_rate = calcSteerWheelRateCmd(adaptive_gear_ratio); - steer_cmd.command = steerWheelRateLimiter( - desired_steer_wheel, prev_steer_cmd_.command, current_time, prev_steer_cmd_.header.stamp, - steer_cmd.rotation_rate, current_steer_wheel, engage_cmd_); - steer_cmd_pub_->publish(steer_cmd); - prev_steer_cmd_ = steer_cmd; - } - - /* publish raw steering cmd for debug */ - { - pacmod3_msgs::msg::SteeringCmd raw_steer_cmd; - raw_steer_cmd.header.frame_id = base_frame_id_; - raw_steer_cmd.header.stamp = current_time; - raw_steer_cmd.enable = engage_cmd_; - raw_steer_cmd.ignore_overrides = false; - raw_steer_cmd.clear_override = clear_override; - raw_steer_cmd.command = desired_steer_wheel; - raw_steer_cmd.rotation_rate = - control_cmd_ptr_->lateral.steering_tire_rotation_rate * adaptive_gear_ratio; - raw_steer_cmd_pub_->publish(raw_steer_cmd); - } - - /* publish shift cmd */ - { - pacmod3_msgs::msg::SystemCmdInt shift_cmd; - shift_cmd.header.frame_id = base_frame_id_; - shift_cmd.header.stamp = current_time; - shift_cmd.enable = engage_cmd_; - shift_cmd.ignore_overrides = false; - shift_cmd.clear_override = clear_override; - shift_cmd.command = desired_shift; - shift_cmd_pub_->publish(shift_cmd); - } - - if (turn_indicators_cmd_ptr_ && hazard_lights_cmd_ptr_) { - /* publish shift cmd */ - pacmod3_msgs::msg::SystemCmdInt turn_cmd; - turn_cmd.header.frame_id = base_frame_id_; - turn_cmd.header.stamp = current_time; - turn_cmd.enable = engage_cmd_; - turn_cmd.ignore_overrides = false; - turn_cmd.clear_override = clear_override; - turn_cmd.command = - toPacmodTurnCmdWithHazardRecover(*turn_indicators_cmd_ptr_, *hazard_lights_cmd_ptr_); - turn_cmd_pub_->publish(turn_cmd); - } -} - -double PacmodInterface::calcSteerWheelRateCmd(const double gear_ratio) -{ - const auto current_vel = - std::fabs(calculateVehicleVelocity(*wheel_speed_rpt_ptr_, *gear_cmd_rpt_ptr_)); - - // send low steer rate at low speed - if (current_vel < std::numeric_limits::epsilon()) { - return steering_wheel_rate_stopped_; - } else if (current_vel < low_vel_thresh_) { - return steering_wheel_rate_low_vel_; - } - - if (!enable_steering_rate_control_) { - return max_steering_wheel_rate_; - } - - constexpr double margin = 1.5; - const double rate = margin * control_cmd_ptr_->lateral.steering_tire_rotation_rate * gear_ratio; - return std::min(std::max(std::fabs(rate), min_steering_wheel_rate_), max_steering_wheel_rate_); -} - -double PacmodInterface::calculateVehicleVelocity( - const pacmod3_msgs::msg::WheelSpeedRpt & wheel_speed_rpt, - const pacmod3_msgs::msg::SystemRptInt & shift_rpt) -{ - const double sign = (shift_rpt.output == pacmod3_msgs::msg::SystemRptInt::SHIFT_REVERSE) ? -1 : 1; - const double vel = - (wheel_speed_rpt.rear_left_wheel_speed + wheel_speed_rpt.rear_right_wheel_speed) * 0.5 * - tire_radius_ * tire_radius_scale_factor_; - return sign * vel; -} - -double PacmodInterface::calculateVariableGearRatio(const double vel, const double steer_wheel) -{ - return std::max( - 1e-5, vgr_coef_a_ + vgr_coef_b_ * vel * vel - vgr_coef_c_ * std::fabs(steer_wheel)); -} - -uint16_t PacmodInterface::toPacmodShiftCmd( - const autoware_auto_vehicle_msgs::msg::GearCommand & gear_cmd) -{ - using pacmod3_msgs::msg::SystemCmdInt; - - if (gear_cmd.command == autoware_auto_vehicle_msgs::msg::GearCommand::PARK) { - return SystemCmdInt::SHIFT_PARK; - } - if (gear_cmd.command == autoware_auto_vehicle_msgs::msg::GearCommand::REVERSE) { - return SystemCmdInt::SHIFT_REVERSE; - } - if (gear_cmd.command == autoware_auto_vehicle_msgs::msg::GearCommand::DRIVE) { - return SystemCmdInt::SHIFT_FORWARD; - } - if (gear_cmd.command == autoware_auto_vehicle_msgs::msg::GearCommand::LOW) { - return SystemCmdInt::SHIFT_LOW; - } - - return SystemCmdInt::SHIFT_NONE; -} - -std::optional PacmodInterface::toAutowareShiftReport( - const pacmod3_msgs::msg::SystemRptInt & shift) -{ - using autoware_auto_vehicle_msgs::msg::GearReport; - using pacmod3_msgs::msg::SystemRptInt; - - if (shift.output == SystemRptInt::SHIFT_PARK) { - return GearReport::PARK; - } - if (shift.output == SystemRptInt::SHIFT_REVERSE) { - return GearReport::REVERSE; - } - if (shift.output == SystemRptInt::SHIFT_FORWARD) { - return GearReport::DRIVE; - } - if (shift.output == SystemRptInt::SHIFT_LOW) { - return GearReport::LOW; - } - return {}; -} - -uint16_t PacmodInterface::toPacmodTurnCmd( - const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand & turn, - const autoware_auto_vehicle_msgs::msg::HazardLightsCommand & hazard) -{ - using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; - using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; - using pacmod3_msgs::msg::SystemCmdInt; - - // NOTE: hazard lights command has a highest priority here. - if (hazard.command == HazardLightsCommand::ENABLE) { - return SystemCmdInt::TURN_HAZARDS; - } - if (turn.command == TurnIndicatorsCommand::ENABLE_LEFT) { - return SystemCmdInt::TURN_LEFT; - } - if (turn.command == TurnIndicatorsCommand::ENABLE_RIGHT) { - return SystemCmdInt::TURN_RIGHT; - } - return SystemCmdInt::TURN_NONE; -} - -uint16_t PacmodInterface::toPacmodTurnCmdWithHazardRecover( - const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand & turn, - const autoware_auto_vehicle_msgs::msg::HazardLightsCommand & hazard) -{ - using pacmod3_msgs::msg::SystemRptInt; - - if (!engage_cmd_ || turn_rpt_ptr_->command == turn_rpt_ptr_->output) { - last_shift_inout_matched_time_ = this->now(); - return toPacmodTurnCmd(turn, hazard); - } - - if ((this->now() - last_shift_inout_matched_time_).seconds() < hazard_thresh_time_) { - return toPacmodTurnCmd(turn, hazard); - } - - // hazard recover mode - if (hazard_recover_count_ > hazard_recover_cmd_num_) { - last_shift_inout_matched_time_ = this->now(); - hazard_recover_count_ = 0; - } - hazard_recover_count_++; - - if ( - turn_rpt_ptr_->command != SystemRptInt::TURN_HAZARDS && - turn_rpt_ptr_->output == SystemRptInt::TURN_HAZARDS) { - // publish hazard commands for turning off the hazard lights - return SystemRptInt::TURN_HAZARDS; - } else if ( // NOLINT - turn_rpt_ptr_->command == SystemRptInt::TURN_HAZARDS && - turn_rpt_ptr_->output != SystemRptInt::TURN_HAZARDS) { - // publish none commands for turning on the hazard lights - return SystemRptInt::TURN_NONE; - } else { - // something wrong - RCLCPP_ERROR_STREAM( - get_logger(), "turn signal command and output do not match. " - << "COMMAND: " << turn_rpt_ptr_->command - << "; OUTPUT: " << turn_rpt_ptr_->output); - return toPacmodTurnCmd(turn, hazard); - } -} - -int32_t PacmodInterface::toAutowareTurnIndicatorsReport( - const pacmod3_msgs::msg::SystemRptInt & turn) -{ - using autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport; - using pacmod3_msgs::msg::SystemRptInt; - - if (turn.output == SystemRptInt::TURN_RIGHT) { - return TurnIndicatorsReport::ENABLE_RIGHT; - } else if (turn.output == SystemRptInt::TURN_LEFT) { - return TurnIndicatorsReport::ENABLE_LEFT; - } else if (turn.output == SystemRptInt::TURN_NONE) { - return TurnIndicatorsReport::DISABLE; - } - return TurnIndicatorsReport::DISABLE; -} - -int32_t PacmodInterface::toAutowareHazardLightsReport( - const pacmod3_msgs::msg::SystemRptInt & hazard) -{ - using autoware_auto_vehicle_msgs::msg::HazardLightsReport; - using pacmod3_msgs::msg::SystemRptInt; - - if (hazard.output == SystemRptInt::TURN_HAZARDS) { - return HazardLightsReport::ENABLE; - } - - return HazardLightsReport::DISABLE; -} - -double PacmodInterface::steerWheelRateLimiter( - const double current_steer_cmd, const double prev_steer_cmd, - const rclcpp::Time & current_steer_time, const rclcpp::Time & prev_steer_time, - const double steer_rate, const double current_steer_output, const bool engage) -{ - if (!engage) { - // return current steer as steer command ( do not apply steer rate filter ) - return current_steer_output; - } - - const double dsteer = current_steer_cmd - prev_steer_cmd; - const double dt = std::max(0.0, (current_steer_time - prev_steer_time).seconds()); - const double max_dsteer = std::fabs(steer_rate) * dt; - const double limited_steer_cmd = - prev_steer_cmd + std::min(std::max(-max_dsteer, dsteer), max_dsteer); - return limited_steer_cmd; -} diff --git a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface_node.cpp b/vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface_node.cpp deleted file mode 100644 index 514d839cbdf56..0000000000000 --- a/vehicle/pacmod_interface/src/pacmod_interface/pacmod_interface_node.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright 2017-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} From 95f047f3ea98cade5a897d9b432eae8407c643fb Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 17 Feb 2022 08:08:43 +0900 Subject: [PATCH 03/37] feat(atutoware.rviz): disable selectable for pointcloud visualization (#402) Signed-off-by: YamatoAndo --- launch/tier4_autoware_launch/rviz/autoware.rviz | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/launch/tier4_autoware_launch/rviz/autoware.rviz b/launch/tier4_autoware_launch/rviz/autoware.rviz index 4cf1b192fd95e..6c592fcbeddd2 100644 --- a/launch/tier4_autoware_launch/rviz/autoware.rviz +++ b/launch/tier4_autoware_launch/rviz/autoware.rviz @@ -354,7 +354,7 @@ Visualization Manager: Min Intensity: 0 Name: PointCloudMap Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 1 Size (m): 0.02 Style: Points @@ -423,7 +423,7 @@ Visualization Manager: Min Intensity: 0 Name: ConcatenatePointCloud Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 1 Size (m): 0.02 Style: Points @@ -598,7 +598,7 @@ Visualization Manager: Min Intensity: 0 Name: Initial Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 10 Size (m): 0.02 Style: Squares @@ -631,7 +631,7 @@ Visualization Manager: Min Intensity: 0 Name: Aligned Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 10 Size (m): 0.02 Style: Squares @@ -703,7 +703,7 @@ Visualization Manager: Min Intensity: -5 Name: NoGroundPointCloud Position Transformer: XYZ - Selectable: true + Selectable: false Size (Pixels): 3 Size (m): 0.02 Style: Points From 0b9458054edc8e35a76ac08f711c5d210c51f016 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 17 Feb 2022 10:57:11 +0900 Subject: [PATCH 04/37] ci: remove registering AutonomouStuff repository inside CI scripts (#394) Signed-off-by: Kenji Miyake --- .../build-and-test-differential-self-hosted.yaml | 5 ----- .github/workflows/build-and-test-differential.yaml | 10 ---------- .github/workflows/build-and-test-self-hosted.yaml | 5 ----- .github/workflows/build-and-test.yaml | 5 ----- .github/workflows/check-build-depends.yaml | 5 ----- 5 files changed, 30 deletions(-) diff --git a/.github/workflows/build-and-test-differential-self-hosted.yaml b/.github/workflows/build-and-test-differential-self-hosted.yaml index 6c2dcf960c10e..824ac368f936c 100644 --- a/.github/workflows/build-and-test-differential-self-hosted.yaml +++ b/.github/workflows/build-and-test-differential-self-hosted.yaml @@ -28,11 +28,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get modified packages id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 1eddcc9b06514..6e8ebef574ed5 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -19,11 +19,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get modified packages id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal @@ -66,11 +61,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get modified packages id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal diff --git a/.github/workflows/build-and-test-self-hosted.yaml b/.github/workflows/build-and-test-self-hosted.yaml index 1f8bc542855d6..c5a5ac4734bc5 100644 --- a/.github/workflows/build-and-test-self-hosted.yaml +++ b/.github/workflows/build-and-test-self-hosted.yaml @@ -16,11 +16,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get self packages id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 880f47192b558..1e422cc380f11 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -18,11 +18,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get self packages id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal diff --git a/.github/workflows/check-build-depends.yaml b/.github/workflows/check-build-depends.yaml index 2100b82172e10..65c72372e59fb 100644 --- a/.github/workflows/check-build-depends.yaml +++ b/.github/workflows/check-build-depends.yaml @@ -19,11 +19,6 @@ jobs: - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@tier4/proposal - - name: Register AutonomouStuff repository - uses: autowarefoundation/autoware-github-actions/register-autonomoustuff-repository@tier4/proposal - with: - rosdistro: galactic - - name: Get self packages id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal From e8f83f87d03cc20f70b1786102c046f149299029 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 17 Feb 2022 11:18:52 +0900 Subject: [PATCH 05/37] feat(planning_evaluator): add planning evaluator (#288) * Add Planning Evaluator (#2293) Co-authored-by: Takamasa Horibe Signed-off-by: kyoichi-sugahara * update planning msgs Signed-off-by: kyoichi-sugahara * update perception msgs Signed-off-by: kyoichi-sugahara * ci(pre-commit): autofix * delete quotes Signed-off-by: kyoichi-sugahara * modify README Signed-off-by: kyoichi-sugahara Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/planning_evaluator/CMakeLists.txt | 52 +++ planning/planning_evaluator/README.md | 96 ++++ .../metrics/deviation_metrics.hpp | 57 +++ .../planning_evaluator/metrics/metric.hpp | 122 ++++++ .../metrics/metrics_utils.hpp | 43 ++ .../metrics/obstacle_metrics.hpp | 51 +++ .../metrics/stability_metrics.hpp | 47 ++ .../metrics/trajectory_metrics.hpp | 90 ++++ .../planning_evaluator/metrics_calculator.hpp | 93 ++++ .../motion_evaluator_node.hpp | 74 ++++ .../include/planning_evaluator/parameters.hpp | 49 +++ .../planning_evaluator_node.hpp | 105 +++++ .../include/planning_evaluator/stat.hpp | 93 ++++ .../launch/motion_evaluator.launch.xml | 7 + .../launch/planning_evaluator.launch.xml | 12 + planning/planning_evaluator/package.xml | 32 ++ .../param/planning_evaluator.defaults.yaml | 30 ++ .../src/metrics/deviation_metrics.cpp | 83 ++++ .../src/metrics/metrics_utils.cpp | 48 ++ .../src/metrics/obstacle_metrics.cpp | 84 ++++ .../src/metrics/stability_metrics.cpp | 96 ++++ .../src/metrics/trajectory_metrics.cpp | 177 ++++++++ .../src/metrics_calculator.cpp | 124 ++++++ .../src/motion_evaluator_node.cpp | 103 +++++ .../src/planning_evaluator_node.cpp | 191 ++++++++ .../test/test_planning_evaluator_node.cpp | 409 ++++++++++++++++++ 26 files changed, 2368 insertions(+) create mode 100644 planning/planning_evaluator/CMakeLists.txt create mode 100644 planning/planning_evaluator/README.md create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics/metric.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics/metrics_utils.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics/obstacle_metrics.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics/stability_metrics.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics/trajectory_metrics.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/motion_evaluator_node.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/parameters.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp create mode 100644 planning/planning_evaluator/include/planning_evaluator/stat.hpp create mode 100644 planning/planning_evaluator/launch/motion_evaluator.launch.xml create mode 100644 planning/planning_evaluator/launch/planning_evaluator.launch.xml create mode 100644 planning/planning_evaluator/package.xml create mode 100644 planning/planning_evaluator/param/planning_evaluator.defaults.yaml create mode 100644 planning/planning_evaluator/src/metrics/deviation_metrics.cpp create mode 100644 planning/planning_evaluator/src/metrics/metrics_utils.cpp create mode 100644 planning/planning_evaluator/src/metrics/obstacle_metrics.cpp create mode 100644 planning/planning_evaluator/src/metrics/stability_metrics.cpp create mode 100644 planning/planning_evaluator/src/metrics/trajectory_metrics.cpp create mode 100644 planning/planning_evaluator/src/metrics_calculator.cpp create mode 100644 planning/planning_evaluator/src/motion_evaluator_node.cpp create mode 100644 planning/planning_evaluator/src/planning_evaluator_node.cpp create mode 100644 planning/planning_evaluator/test/test_planning_evaluator_node.cpp diff --git a/planning/planning_evaluator/CMakeLists.txt b/planning/planning_evaluator/CMakeLists.txt new file mode 100644 index 0000000000000..88998404cc506 --- /dev/null +++ b/planning/planning_evaluator/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 3.5) +project(planning_evaluator) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +ament_auto_add_library(${PROJECT_NAME}_node SHARED + src/metrics_calculator.cpp + src/${PROJECT_NAME}_node.cpp + src/motion_evaluator_node.cpp + src/metrics/deviation_metrics.cpp + src/metrics/metrics_utils.cpp + src/metrics/obstacle_metrics.cpp + src/metrics/stability_metrics.cpp + src/metrics/trajectory_metrics.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME}_node + PLUGIN "planning_diagnostics::PlanningEvaluatorNode" + EXECUTABLE ${PROJECT_NAME} +) + +rclcpp_components_register_node(${PROJECT_NAME}_node + PLUGIN "planning_diagnostics::MotionEvaluatorNode" + EXECUTABLE motion_evaluator +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + ament_add_gtest(test_${PROJECT_NAME} + test/test_planning_evaluator_node.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME}_node + ) +endif() + +ament_auto_package( + INSTALL_TO_SHARE + param + launch +) diff --git a/planning/planning_evaluator/README.md b/planning/planning_evaluator/README.md new file mode 100644 index 0000000000000..23c8101429c35 --- /dev/null +++ b/planning/planning_evaluator/README.md @@ -0,0 +1,96 @@ +# Planning Evaluator + +## Purpose + +This package provides nodes that generate metrics to evaluate the quality of planning and control. + +## Inner-workings / Algorithms + +The evaluation node calculates metrics each time it receives a trajectory `T(0)`. +Metrics are calculated using the following information: + +- the trajectory `T(0)` itself. +- the previous trajectory `T(-1)`. +- the _reference_ trajectory assumed to be used as the reference to plan `T(0)`. +- the current ego pose. +- the set of objects in the environment. + +These information are maintained by an instance of class `MetricsCalculator` +which is also responsible for calculating metrics. + +### Stat + +Each metric is calculated using a `Stat` instance which contains +the minimum, maximum, and mean values calculated for the metric +as well as the number of values measured. + +### Metric calculation and adding more metrics + +All possible metrics are defined in the `Metric` enumeration defined +`include/planning_evaluator/metrics/metric.hpp`. +This file also defines conversions from/to string as well as human readable descriptions +to be used as header of the output file. + +The `MetricsCalculator` is responsible for calculating metric statistics +through calls to function: + +```C++ +Stat MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const; +``` + +Adding a new metric `M` requires the following steps: + +- `metrics/metric.hpp`: add `M` to the `enum`, to the from/to string conversion maps, and to the description map. +- `metrics_calculator.cpp`: add `M` to the `switch/case` statement of the `calculate` function. +- Add `M` to the `selected_metrics` parameters. + +## Inputs / Outputs + +### Inputs + +| Name | Type | Description | +| ------------------------------ | ------------------------------------------------------ | ------------------------------------------------- | +| `~/input/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Main trajectory to evaluate | +| `~/input/reference_trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Reference trajectory to use for deviation metrics | +| `~/input/objects` | `autoware_auto_perception_msgs::msg::PredictedObjects` | Obstacles | + +### Outputs + +Each metric is published on a topic named after the metric name. + +| Name | Type | Description | +| ----------- | --------------------------------------- | ------------------------------------------------------- | +| `~/metrics` | `diagnostic_msgs::msg::DiagnosticArray` | DiagnosticArray with a DiagnosticStatus for each metric | + +When shut down, the evaluation node writes the values of the metrics measured during its lifetime +to a file as specified by the `output_file` parameter. + +## Parameters + +| Name | Type | Description | +| :-------------------------------- | :------- | :-------------------------------------------------------------------------- | +| `output_file` | `string` | file used to write metrics | +| `ego_frame` | `string` | frame used for the ego pose | +| `selected_metrics` | List | metrics to measure and publish | +| `trajectory.min_point_dist_m` | `double` | minimum distance between two successive points to use for angle calculation | +| `trajectory.lookahead.max_dist_m` | `double` | maximum distance from ego along the trajectory to use for calculation | +| `trajectory.lookahead.max_time_m` | `double` | maximum time ahead of ego along the trajectory to use for calculation | +| `obstacle.dist_thr_m` | `double` | distance between ego and the obstacle below which a collision is considered | + +## Assumptions / Known limits + +There is a strong assumption that when receiving a trajectory `T(0)`, +it has been generated using the last received reference trajectory and objects. +This can be wrong if a new reference trajectory or objects are published while `T(0)` is being calculated. + +Precision is currently limited by the resolution of the trajectories. +It is possible to interpolate the trajectory and reference trajectory to increase precision but would make computation significantly more expensive. + +## Future extensions / Unimplemented parts + +- Use `Route` or `Path` messages as reference trajectory. +- RSS metrics (done in another node ). +- Add option to publish the `min` and `max` metric values. For now only the `mean` value is published. +- `motion_evaluator_node`. + - Node which constructs a trajectory over time from the real motion of ego. + - Only a proof of concept is currently implemented. diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp new file mode 100644 index 0000000000000..e71b887ff3a10 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics/deviation_metrics.hpp @@ -0,0 +1,57 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ +#define PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ + +#include "planning_evaluator/stat.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +/** + * @brief calculate lateral deviation of the given trajectory from the reference trajectory + * @param [in] ref reference trajectory + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & traj); + +/** + * @brief calculate yaw deviation of the given trajectory from the reference trajectory + * @param [in] ref reference trajectory + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj); + +/** + * @brief calculate velocity deviation of the given trajectory from the reference trajectory + * @param [in] ref reference trajectory + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj); + +} // namespace metrics +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics/metric.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics/metric.hpp new file mode 100644 index 0000000000000..16811f91b32b1 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics/metric.hpp @@ -0,0 +1,122 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS__METRIC_HPP_ +#define PLANNING_EVALUATOR__METRICS__METRIC_HPP_ + +#include +#include +#include +#include + +namespace planning_diagnostics +{ +/** + * @brief Enumeration of trajectory metrics + */ +enum class Metric { + curvature, + point_interval, + relative_angle, + length, + duration, + velocity, + acceleration, + jerk, + lateral_deviation, + yaw_deviation, + velocity_deviation, + stability, + stability_frechet, + obstacle_distance, + obstacle_ttc, + SIZE, +}; + +/** TODO(Maxime CLEMENT): + * make the addition of metrics simpler, e.g. with some macro ADD_METRIC(metric, metric_description) + */ +static const std::unordered_map str_to_metric = { + {"curvature", Metric::curvature}, + {"point_interval", Metric::point_interval}, + {"relative_angle", Metric::relative_angle}, + {"length", Metric::length}, + {"duration", Metric::duration}, + {"velocity", Metric::velocity}, + {"acceleration", Metric::acceleration}, + {"jerk", Metric::jerk}, + {"lateral_deviation", Metric::lateral_deviation}, + {"yaw_deviation", Metric::yaw_deviation}, + {"velocity_deviation", Metric::velocity_deviation}, + {"stability", Metric::stability}, + {"stability_frechet", Metric::stability_frechet}, + {"obstacle_distance", Metric::obstacle_distance}, + {"obstacle_ttc", Metric::obstacle_ttc}, +}; +static const std::unordered_map metric_to_str = { + {Metric::curvature, "curvature"}, + {Metric::point_interval, "point_interval"}, + {Metric::relative_angle, "relative_angle"}, + {Metric::length, "length"}, + {Metric::duration, "duration"}, + {Metric::velocity, "velocity"}, + {Metric::acceleration, "acceleration"}, + {Metric::jerk, "jerk"}, + {Metric::lateral_deviation, "lateral_deviation"}, + {Metric::yaw_deviation, "yaw_deviation"}, + {Metric::velocity_deviation, "velocity_deviation"}, + {Metric::stability, "stability"}, + {Metric::stability_frechet, "stability_frechet"}, + {Metric::obstacle_distance, "obstacle_distance"}, + {Metric::obstacle_ttc, "obstacle_ttc"}}; + +// Metrics descriptions +static const std::unordered_map metric_descriptions = { + {Metric::curvature, "Curvature[1/rad]"}, + {Metric::point_interval, "Interval_between_points[m]"}, + {Metric::relative_angle, "Relative_angle[rad]"}, + {Metric::length, "Trajectory_length[m]"}, + {Metric::duration, "Trajectory_duration[s]"}, + {Metric::velocity, "Trajectory_velocity[m/s]"}, + {Metric::acceleration, "Trajectory_acceleration[m/s²]"}, + {Metric::jerk, "Trajectory_jerk[m/s³]"}, + {Metric::lateral_deviation, "Lateral_deviation[m]"}, + {Metric::yaw_deviation, "Yaw_deviation[rad]"}, + {Metric::velocity_deviation, "Velocity_deviation[m/s]"}, + {Metric::stability, "Stability[m]"}, + {Metric::stability_frechet, "StabilityFrechet[m]"}, + {Metric::obstacle_distance, "Obstacle_distance[m]"}, + {Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"}}; + +namespace details +{ +static struct CheckCorrectMaps +{ + CheckCorrectMaps() + { + if ( + str_to_metric.size() != static_cast(Metric::SIZE) || + metric_to_str.size() != static_cast(Metric::SIZE) || + metric_descriptions.size() != static_cast(Metric::SIZE)) { + std::cerr << "[metrics/metrics.hpp] Maps are not defined for all metrics: "; + std::cerr << str_to_metric.size() << " " << metric_to_str.size() << " " + << metric_descriptions.size() << std::endl; + } + } +} check; + +} // namespace details +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__METRICS__METRIC_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics/metrics_utils.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics/metrics_utils.hpp new file mode 100644 index 0000000000000..4806446d4270f --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics/metrics_utils.hpp @@ -0,0 +1,43 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_ +#define PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_ + +#include "planning_evaluator/stat.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +namespace utils +{ +using autoware_auto_planning_msgs::msg::Trajectory; + +/** + * @brief find the index in the trajectory at the given distance of the given index + * @param [in] traj input trajectory + * @param [in] curr_id index + * @param [in] distance distance + * @return index of the trajectory point at distance ahead of traj[curr_id] + */ +size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance); + +} // namespace utils +} // namespace metrics +} // namespace planning_diagnostics +#endif // PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics/obstacle_metrics.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics/obstacle_metrics.hpp new file mode 100644 index 0000000000000..848d92c91f13e --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics/obstacle_metrics.hpp @@ -0,0 +1,51 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_ +#define PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_ + +#include "planning_evaluator/stat.hpp" + +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::Trajectory; + +/** + * @brief calculate the distance to the closest obstacle at each point of the trajectory + * @param [in] obstacles obstacles + * @param [in] traj trajectory + * @return calculated statistics + */ +Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Trajectory & traj); + +/** + * @brief calculate the time to collision of the trajectory with the given obstacles + * Assume that "now" corresponds to the first trajectory point + * @param [in] obstacles obstacles + * @param [in] traj trajectory + * @return calculated statistics + */ +Stat calcTimeToCollision( + const PredictedObjects & obstacles, const Trajectory & traj, const double distance_threshold); + +} // namespace metrics +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics/stability_metrics.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics/stability_metrics.hpp new file mode 100644 index 0000000000000..c4bf1fe901604 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics/stability_metrics.hpp @@ -0,0 +1,47 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_ +#define PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_ + +#include "planning_evaluator/stat.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_planning_msgs::msg::Trajectory; + +/** + * @brief calculate the discrete Frechet distance between two trajectories + * @param [in] traj1 first trajectory + * @param [in] traj2 second trajectory + * @return calculated statistics + */ +Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2); + +/** + * @brief calculate the lateral distance between two trajectories + * @param [in] traj1 first trajectory + * @param [in] traj2 second trajectory + * @return calculated statistics + */ +Stat calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2); + +} // namespace metrics +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics/trajectory_metrics.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics/trajectory_metrics.hpp new file mode 100644 index 0000000000000..b55ad245d8425 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics/trajectory_metrics.hpp @@ -0,0 +1,90 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_ +#define PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_ + +#include "planning_evaluator/stat.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +/** + * @brief calculate relative angle metric (angle between successive points) + * @param [in] traj input trajectory + * @param [in] min_dist_threshold minimum distance between successive points + * @return calculated statistics + */ +Stat calcTrajectoryRelativeAngle(const Trajectory & traj, const double min_dist_threshold); + +/** + * @brief calculate metric for the distance between trajectory points + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryInterval(const Trajectory & traj); + +/** + * @brief calculate curvature metric + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryCurvature(const Trajectory & traj); + +/** + * @brief calculate length of the trajectory [m] + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryLength(const Trajectory & traj); + +/** + * @brief calculate duration of the trajectory [s] + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryDuration(const Trajectory & traj); + +/** + * @brief calculate velocity metrics for the trajectory + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryVelocity(const Trajectory & traj); + +/** + * @brief calculate acceleration metrics for the trajectory + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryAcceleration(const Trajectory & traj); + +/** + * @brief calculate jerk metrics for the trajectory + * @param [in] traj input trajectory + * @return calculated statistics + */ +Stat calcTrajectoryJerk(const Trajectory & traj); + +} // namespace metrics +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp b/planning/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp new file mode 100644 index 0000000000000..0ed2af7b3862e --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/metrics_calculator.hpp @@ -0,0 +1,93 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_ +#define PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_ + +#include "planning_evaluator/metrics/metric.hpp" +#include "planning_evaluator/parameters.hpp" +#include "planning_evaluator/stat.hpp" + +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "geometry_msgs/msg/pose.hpp" + +namespace planning_diagnostics +{ +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +class MetricsCalculator +{ +public: + Parameters parameters; + + MetricsCalculator() = default; + + /** + * @brief calculate + * @param [in] metric Metric enum value + * @return string describing the requested metric + */ + Stat calculate(const Metric metric, const Trajectory & traj) const; + + /** + * @brief set the reference trajectory used to calculate the deviation metrics + * @param [in] traj input reference trajectory + */ + void setReferenceTrajectory(const Trajectory & traj); + + /** + * @brief set the previous trajectory used to calculate the stability metrics + * @param [in] traj input previous trajectory + */ + void setPreviousTrajectory(const Trajectory & traj); + + /** + * @brief set the dynamic objects used to calculate obstacle metrics + * @param [in] traj input previous trajectory + */ + void setPredictedObjects(const PredictedObjects & objects); + + /** + * @brief set the ego pose + * @param [in] traj input previous trajectory + */ + void setEgoPose(const geometry_msgs::msg::Pose & pose); + +private: + /** + * @brief trim a trajectory from the current ego pose to some fixed time or distance + * @param [in] traj input trajectory to trim + * @param [in] max_dist_m [m] maximum distance ahead of the ego pose + * @param [in] max_time_s [s] maximum time ahead of the ego pose + * @return sub-trajectory starting from the ego pose and of maximum length max_dist_m, maximum + * duration max_time_s + */ + Trajectory getLookaheadTrajectory( + const Trajectory & traj, const double max_dist_m, const double max_time_s) const; + + Trajectory reference_trajectory_; + Trajectory reference_trajectory_lookahead_; + Trajectory previous_trajectory_; + Trajectory previous_trajectory_lookahead_; + PredictedObjects dynamic_objects_; + geometry_msgs::msg::Pose ego_pose_; +}; // class MetricsCalculator + +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/motion_evaluator_node.hpp b/planning/planning_evaluator/include/planning_evaluator/motion_evaluator_node.hpp new file mode 100644 index 0000000000000..28a4b2cba8365 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/motion_evaluator_node.hpp @@ -0,0 +1,74 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__MOTION_EVALUATOR_NODE_HPP_ +#define PLANNING_EVALUATOR__MOTION_EVALUATOR_NODE_HPP_ + +#include "planning_evaluator/metrics_calculator.hpp" +#include "planning_evaluator/stat.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" + +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "geometry_msgs/msg/transform_stamped.hpp" +#include + +#include +#include +#include +#include + +namespace planning_diagnostics +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +/** + * @brief Node for planning evaluation + */ +class MotionEvaluatorNode : public rclcpp::Node +{ +public: + explicit MotionEvaluatorNode(const rclcpp::NodeOptions & node_options); + ~MotionEvaluatorNode(); + + /** + * @brief callback on vehicle twist message + * @param [in] twist_msg twist message + */ + void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg); + +private: + geometry_msgs::msg::Pose getCurrentEgoPose() const; + + // ROS + rclcpp::Subscription::SharedPtr twist_sub_; + std::unique_ptr tf_buffer_ptr_; + std::unique_ptr tf_listener_ptr_; + + // Parameters + std::string output_file_str_; + + // Calculator + MetricsCalculator metrics_calculator_; + // Metrics + std::vector metrics_; + std::deque stamps_; + Trajectory accumulated_trajectory_; +}; +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__MOTION_EVALUATOR_NODE_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/parameters.hpp b/planning/planning_evaluator/include/planning_evaluator/parameters.hpp new file mode 100644 index 0000000000000..fb4acb53888f2 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/parameters.hpp @@ -0,0 +1,49 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__PARAMETERS_HPP_ +#define PLANNING_EVALUATOR__PARAMETERS_HPP_ + +#include "planning_evaluator/metrics/metric.hpp" + +#include + +namespace planning_diagnostics +{ +/** + * @brief Enumeration of trajectory metrics + */ +struct Parameters +{ + std::array(Metric::SIZE)> metrics{}; // default values to false + + struct + { + double min_point_dist_m = 0.1; + struct + { + double max_dist_m = 5.0; + double max_time_s = 3.0; + } lookahead; + } trajectory; + + struct + { + double dist_thr_m = 1.0; + } obstacle; +}; // struct Parameters + +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__PARAMETERS_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp b/planning/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp new file mode 100644 index 0000000000000..e9fd82c85cf7b --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/planning_evaluator_node.hpp @@ -0,0 +1,105 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_EVALUATOR__PLANNING_EVALUATOR_NODE_HPP_ +#define PLANNING_EVALUATOR__PLANNING_EVALUATOR_NODE_HPP_ + +#include "planning_evaluator/metrics_calculator.hpp" +#include "planning_evaluator/stat.hpp" +#include "rclcpp/rclcpp.hpp" +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" + +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "diagnostic_msgs/msg/diagnostic_array.hpp" + +#include +#include +#include +#include +#include + +namespace planning_diagnostics +{ +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using diagnostic_msgs::msg::DiagnosticArray; +using diagnostic_msgs::msg::DiagnosticStatus; + +/** + * @brief Node for planning evaluation + */ +class PlanningEvaluatorNode : public rclcpp::Node +{ +public: + explicit PlanningEvaluatorNode(const rclcpp::NodeOptions & node_options); + ~PlanningEvaluatorNode(); + + /** + * @brief callback on receiving a trajectory + * @param [in] traj_msg received trajectory message + */ + void onTrajectory(const Trajectory::ConstSharedPtr traj_msg); + + /** + * @brief callback on receiving a reference trajectory + * @param [in] traj_msg received trajectory message + */ + void onReferenceTrajectory(const Trajectory::ConstSharedPtr traj_msg); + + /** + * @brief callback on receiving a dynamic objects array + * @param [in] objects_msg received dynamic object array message + */ + void onObjects(const PredictedObjects::ConstSharedPtr objects_msg); + + /** + * @brief update the ego pose stored in the MetricsCalculator + */ + void updateCalculatorEgoPose(const std::string & target_frame); + + /** + * @brief publish the given metric statistic + */ + DiagnosticStatus generateDiagnosticStatus( + const Metric & metric, const Stat & metric_stat) const; + +private: + static bool isFinite(const TrajectoryPoint & p); + + // ROS + rclcpp::Subscription::SharedPtr traj_sub_; + rclcpp::Subscription::SharedPtr ref_sub_; + rclcpp::Subscription::SharedPtr objects_sub_; + rclcpp::Publisher::SharedPtr metrics_pub_; + std::shared_ptr transform_listener_{nullptr}; + std::unique_ptr tf_buffer_; + + // Parameters + std::string output_file_str_; + std::string ego_frame_str_; + + // Calculator + MetricsCalculator metrics_calculator_; + // Metrics + std::vector metrics_; + std::deque stamps_; + std::array>, static_cast(Metric::SIZE)> metric_stats_; +}; +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__PLANNING_EVALUATOR_NODE_HPP_ diff --git a/planning/planning_evaluator/include/planning_evaluator/stat.hpp b/planning/planning_evaluator/include/planning_evaluator/stat.hpp new file mode 100644 index 0000000000000..ce03aea7669b4 --- /dev/null +++ b/planning/planning_evaluator/include/planning_evaluator/stat.hpp @@ -0,0 +1,93 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#ifndef PLANNING_EVALUATOR__STAT_HPP_ +#define PLANNING_EVALUATOR__STAT_HPP_ + +namespace planning_diagnostics +{ +/** + * @brief class to incrementally build statistics + * @typedef T type of the values (default to double) + */ +template +class Stat +{ +public: + /** + * @brief add a value + * @param value value to add + */ + void add(const T & value) + { + if (value < min_) { + min_ = value; + } + if (value > max_) { + max_ = value; + } + ++count_; + mean_ = mean_ + (value - mean_) / count_; + } + + /** + * @brief get the mean value + */ + long double mean() const { return mean_; } + + /** + * @brief get the minimum value + */ + T min() const { return min_; } + + /** + * @brief get the maximum value + */ + T max() const { return max_; } + + /** + * @brief get the number of values used to build this statistic + */ + unsigned int count() const { return count_; } + + template + friend std::ostream & operator<<(std::ostream & os, const Stat & stat); + +private: + T min_ = std::numeric_limits::max(); + T max_ = std::numeric_limits::min(); + long double mean_ = 0.0; + unsigned int count_ = 0; +}; + +/** + * @brief overload << operator for easy print to output stream + */ +template +std::ostream & operator<<(std::ostream & os, const Stat & stat) +{ + if (stat.count() == 0) { + os << "None None None"; + } else { + os << stat.min() << " " << stat.max() << " " << stat.mean(); + } + return os; +} + +} // namespace planning_diagnostics + +#endif // PLANNING_EVALUATOR__STAT_HPP_ diff --git a/planning/planning_evaluator/launch/motion_evaluator.launch.xml b/planning/planning_evaluator/launch/motion_evaluator.launch.xml new file mode 100644 index 0000000000000..93a38884c6d49 --- /dev/null +++ b/planning/planning_evaluator/launch/motion_evaluator.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/planning/planning_evaluator/launch/planning_evaluator.launch.xml b/planning/planning_evaluator/launch/planning_evaluator.launch.xml new file mode 100644 index 0000000000000..e33ac129f2510 --- /dev/null +++ b/planning/planning_evaluator/launch/planning_evaluator.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/planning/planning_evaluator/package.xml b/planning/planning_evaluator/package.xml new file mode 100644 index 0000000000000..14b424b594ab6 --- /dev/null +++ b/planning/planning_evaluator/package.xml @@ -0,0 +1,32 @@ + + + planning_evaluator + 0.1.0 + ROS2 node for evaluating planners + + Maxime CLEMENT + + Apache License 2.0 + + ament_cmake_auto + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + diagnostic_msgs + eigen + geometry_msgs + nav_msgs + rclcpp + rclcpp_components + tf2 + tf2_ros + tier4_autoware_utils + + ament_cmake_gtest + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/planning_evaluator/param/planning_evaluator.defaults.yaml b/planning/planning_evaluator/param/planning_evaluator.defaults.yaml new file mode 100644 index 0000000000000..bd47deedb282f --- /dev/null +++ b/planning/planning_evaluator/param/planning_evaluator.defaults.yaml @@ -0,0 +1,30 @@ +/**: + ros__parameters: + output_file: "" # if empty, metrics are not written to file + ego_frame: base_link # reference frame of ego + + selected_metrics: + - curvature + - point_interval + - relative_angle + - length + - duration + - velocity + - acceleration + - jerk + - lateral_deviation + - yaw_deviation + - velocity_deviation + - stability + - stability_frechet + - obstacle_distance + - obstacle_ttc + + trajectory: + min_point_dist_m: 0.1 # [m] minimum distance between two successive points to use for angle calculation + lookahead: + max_dist_m: 5.0 # [m] maximum distance from ego along the trajectory to use for calculation + max_time_s: 3.0 # [s] maximum time ahead of ego along the trajectory to use for calculation + + obstacle: + dist_thr_m: 1.0 # [m] distance between ego and the obstacle below which a collision is considered diff --git a/planning/planning_evaluator/src/metrics/deviation_metrics.cpp b/planning/planning_evaluator/src/metrics/deviation_metrics.cpp new file mode 100644 index 0000000000000..669008ff86c9e --- /dev/null +++ b/planning/planning_evaluator/src/metrics/deviation_metrics.cpp @@ -0,0 +1,83 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/metrics/deviation_metrics.hpp" + +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & traj) +{ + Stat stat; + + if (ref.points.empty() || traj.points.empty()) { + return stat; + } + + /** TODO(Maxime CLEMENT): + * need more precise calculation, e.g., lateral distance from spline of the reference traj + */ + for (TrajectoryPoint p : traj.points) { + const size_t nearest_index = + tier4_autoware_utils::findNearestIndex(ref.points, p.pose.position); + stat.add( + tier4_autoware_utils::calcLateralDeviation(ref.points[nearest_index].pose, p.pose.position)); + } + return stat; +} + +Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj) +{ + Stat stat; + + if (ref.points.empty() || traj.points.empty()) { + return stat; + } + + /** TODO(Maxime CLEMENT): + * need more precise calculation, e.g., yaw distance from spline of the reference traj + */ + for (TrajectoryPoint p : traj.points) { + const size_t nearest_index = + tier4_autoware_utils::findNearestIndex(ref.points, p.pose.position); + stat.add(tier4_autoware_utils::calcYawDeviation(ref.points[nearest_index].pose, p.pose)); + } + return stat; +} + +Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj) +{ + Stat stat; + + if (ref.points.empty() || traj.points.empty()) { + return stat; + } + + // TODO(Maxime CLEMENT) need more precise calculation + for (TrajectoryPoint p : traj.points) { + const size_t nearest_index = + tier4_autoware_utils::findNearestIndex(ref.points, p.pose.position); + stat.add(p.longitudinal_velocity_mps - ref.points[nearest_index].longitudinal_velocity_mps); + } + return stat; +} + +} // namespace metrics +} // namespace planning_diagnostics diff --git a/planning/planning_evaluator/src/metrics/metrics_utils.cpp b/planning/planning_evaluator/src/metrics/metrics_utils.cpp new file mode 100644 index 0000000000000..e2fd04a1d7a6e --- /dev/null +++ b/planning/planning_evaluator/src/metrics/metrics_utils.cpp @@ -0,0 +1,48 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/metrics/trajectory_metrics.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +namespace utils +{ +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using tier4_autoware_utils::calcDistance2d; + +size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance) +{ + // Get Current Trajectory Point + const TrajectoryPoint & curr_p = traj.points.at(curr_id); + + size_t target_id = curr_id; + double current_distance = 0.0; + for (size_t traj_id = curr_id + 1; traj_id < traj.points.size(); ++traj_id) { + current_distance = calcDistance2d(traj.points.at(traj_id), curr_p); + if (current_distance >= distance) { + target_id = traj_id; + break; + } + } + + return target_id; +} + +} // namespace utils +} // namespace metrics +} // namespace planning_diagnostics diff --git a/planning/planning_evaluator/src/metrics/obstacle_metrics.cpp b/planning/planning_evaluator/src/metrics/obstacle_metrics.cpp new file mode 100644 index 0000000000000..46ad5c79b8b4f --- /dev/null +++ b/planning/planning_evaluator/src/metrics/obstacle_metrics.cpp @@ -0,0 +1,84 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/metrics/obstacle_metrics.hpp" + +#include "eigen3/Eigen/Core" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" + +#include +#include + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using tier4_autoware_utils::calcDistance2d; + +Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Trajectory & traj) +{ + Stat stat; + for (const TrajectoryPoint & p : traj.points) { + double min_dist = std::numeric_limits::max(); + for (const auto & object : obstacles.objects) { + // TODO(Maxime CLEMENT): take into account the shape, not only the centroid + const auto dist = calcDistance2d(object.kinematics.initial_pose_with_covariance.pose, p); + min_dist = std::min(min_dist, dist); + } + stat.add(min_dist); + } + return stat; +} + +Stat calcTimeToCollision( + const PredictedObjects & obstacles, const Trajectory & traj, const double distance_threshold) +{ + Stat stat; + /** TODO(Maxime CLEMENT): + * this implementation assumes static obstacles and does not work for dynamic obstacles + */ + TrajectoryPoint p0; + if (!traj.points.empty()) { + p0 = traj.points.front(); + } + + double t = 0.0; // [s] time from start of trajectory + for (const TrajectoryPoint & p : traj.points) { + const double traj_dist = calcDistance2d(p0, p); + if (p0.longitudinal_velocity_mps != 0) { + const double dt = traj_dist / std::abs(p0.longitudinal_velocity_mps); + t += dt; + for (auto obstacle : obstacles.objects) { + const double obst_dist = + calcDistance2d(p, obstacle.kinematics.initial_pose_with_covariance.pose); + // TODO(Maxime CLEMENT): take shape into consideration + if (obst_dist <= distance_threshold) { + stat.add(t); + break; + } + } + } + if (stat.count() > 0) { + break; + } + p0 = p; + } + return stat; +} + +} // namespace metrics +} // namespace planning_diagnostics diff --git a/planning/planning_evaluator/src/metrics/stability_metrics.cpp b/planning/planning_evaluator/src/metrics/stability_metrics.cpp new file mode 100644 index 0000000000000..f4b50d5d59d20 --- /dev/null +++ b/planning/planning_evaluator/src/metrics/stability_metrics.cpp @@ -0,0 +1,96 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/metrics/stability_metrics.hpp" + +#include "eigen3/Eigen/Core" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" + +#include + +namespace planning_diagnostics +{ +namespace metrics +{ +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2) +{ + Stat stat; + + if (traj1.points.empty() || traj2.points.empty()) { + return stat; + } + + Eigen::MatrixXd ca = Eigen::MatrixXd::Zero(traj1.points.size(), traj2.points.size()); + + for (size_t i = 0; i < traj1.points.size(); ++i) { + for (size_t j = 0; j < traj2.points.size(); ++j) { + const double dist = tier4_autoware_utils::calcDistance2d(traj1.points[i], traj2.points[j]); + if (i > 0 && j > 0) { + ca(i, j) = std::max(std::min(ca(i - 1, j), std::min(ca(i - 1, j - 1), ca(i, j - 1))), dist); + } else if (i > 0 /*&& j == 0*/) { + ca(i, j) = std::max(ca(i - 1, 0), dist); + } else if (j > 0 /*&& i == 0*/) { + ca(i, j) = std::max(ca(0, j - 1), dist); + } else { /* i == j == 0 */ + ca(i, j) = dist; + } + } + } + stat.add(ca(traj1.points.size() - 1, traj2.points.size() - 1)); + return stat; +} + +Stat calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2) +{ + Stat stat; + if (traj1.points.empty()) { + return stat; + } + for (const auto point : traj2.points) { + const auto p0 = tier4_autoware_utils::getPoint(point); + // find nearest segment + const size_t nearest_segment_idx = + tier4_autoware_utils::findNearestSegmentIndex(traj1.points, p0); + double dist; + // distance to segment + if ( + nearest_segment_idx == traj1.points.size() - 2 && + tier4_autoware_utils::calcLongitudinalOffsetToSegment(traj1.points, nearest_segment_idx, p0) > + tier4_autoware_utils::calcDistance2d( + traj1.points[nearest_segment_idx], traj1.points[nearest_segment_idx + 1])) { + // distance to last point + dist = tier4_autoware_utils::calcDistance2d(traj1.points.back(), p0); + } else if ( // NOLINT + nearest_segment_idx == 0 && tier4_autoware_utils::calcLongitudinalOffsetToSegment( + traj1.points, nearest_segment_idx, p0) <= 0) { + // distance to first point + dist = tier4_autoware_utils::calcDistance2d(traj1.points.front(), p0); + } else { + // orthogonal distance + const auto p1 = tier4_autoware_utils::getPoint(traj1.points[nearest_segment_idx]); + const auto p2 = tier4_autoware_utils::getPoint(traj1.points[nearest_segment_idx + 1]); + dist = std::abs((p2.x - p1.x) * (p1.y - p0.y) - (p1.x - p0.x) * (p2.y - p1.y)) / + std::sqrt((p2.x - p1.x) * (p2.x - p1.x) + (p2.y - p1.y) * (p2.y - p1.y)); + } + stat.add(dist); + } + return stat; +} + +} // namespace metrics +} // namespace planning_diagnostics diff --git a/planning/planning_evaluator/src/metrics/trajectory_metrics.cpp b/planning/planning_evaluator/src/metrics/trajectory_metrics.cpp new file mode 100644 index 0000000000000..cba03e8b2d90e --- /dev/null +++ b/planning/planning_evaluator/src/metrics/trajectory_metrics.cpp @@ -0,0 +1,177 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/metrics/trajectory_metrics.hpp" + +#include "planning_evaluator/metrics/metrics_utils.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +namespace planning_diagnostics +{ +namespace metrics +{ +using tier4_autoware_utils::calcCurvature; +using tier4_autoware_utils::calcDistance2d; + +Stat calcTrajectoryInterval(const Trajectory & traj) +{ + Stat stat; + for (size_t i = 1; i < traj.points.size(); ++i) { + stat.add(calcDistance2d(traj.points.at(i), traj.points.at(i - 1))); + } + return stat; +} + +Stat calcTrajectoryRelativeAngle(const Trajectory & traj, const double min_dist_threshold) +{ + Stat stat; + // We need at least three points to compute relative angle + const size_t relative_angle_points_num = 3; + if (traj.points.size() < relative_angle_points_num) { + return stat; + } + + for (size_t p1_id = 0; p1_id <= traj.points.size() - relative_angle_points_num; ++p1_id) { + // Get Point1 + const auto & p1 = traj.points.at(p1_id).pose.position; + + // Get Point2 + const auto & p2 = traj.points.at(p1_id + 1).pose.position; + + // Get Point3 + const auto & p3 = traj.points.at(p1_id + 2).pose.position; + + // ignore invert driving direction + if ( + traj.points.at(p1_id).longitudinal_velocity_mps < 0 || + traj.points.at(p1_id + 1).longitudinal_velocity_mps < 0 || + traj.points.at(p1_id + 2).longitudinal_velocity_mps < 0) { + continue; + } + + // convert to p1 coordinate + const double x3 = p3.x - p1.x; + const double x2 = p2.x - p1.x; + const double y3 = p3.y - p1.y; + const double y2 = p2.y - p1.y; + + // skip too close points case + if (std::hypot(x3, y3) < min_dist_threshold || std::hypot(x2, y2) < min_dist_threshold) { + continue; + } + + // calculate relative angle of vector p3 based on p1p2 vector + const double th = std::atan2(y2, x2); + const double th2 = + std::atan2(-x3 * std::sin(th) + y3 * std::cos(th), x3 * std::cos(th) + y3 * std::sin(th)); + stat.add(th2); + } + return stat; +} + +Stat calcTrajectoryCurvature(const Trajectory & traj) +{ + Stat stat; + // We need at least three points to compute curvature + if (traj.points.size() < 3) { + return stat; + } + + constexpr double points_distance = 1.0; + + for (size_t p1_id = 0; p1_id < traj.points.size() - 2; ++p1_id) { + // Get Point1 + const auto p1 = traj.points.at(p1_id).pose.position; + + // Get Point2 + const auto p2_id = utils::getIndexAfterDistance(traj, p1_id, points_distance); + const auto p2 = traj.points.at(p2_id).pose.position; + + // Get Point3 + const auto p3_id = utils::getIndexAfterDistance(traj, p2_id, points_distance); + const auto p3 = traj.points.at(p3_id).pose.position; + + // no need to check for pi, since there is no point with "points_distance" from p1. + if (p1_id == p2_id || p1_id == p3_id || p2_id == p3_id) { + break; + } + + stat.add(calcCurvature(p1, p2, p3)); + } + return stat; +} + +Stat calcTrajectoryLength(const Trajectory & traj) +{ + double length = 0.0; + for (size_t i = 1; i < traj.points.size(); ++i) { + length += calcDistance2d(traj.points.at(i), traj.points.at(i - 1)); + } + Stat stat; + stat.add(length); + return stat; +} + +Stat calcTrajectoryDuration(const Trajectory & traj) +{ + double duration = 0.0; + for (size_t i = 0; i < traj.points.size() - 1; ++i) { + const double length = calcDistance2d(traj.points.at(i), traj.points.at(i + 1)); + const double velocity = traj.points.at(i).longitudinal_velocity_mps; + if (velocity != 0) { + duration += length / std::abs(velocity); + } + } + Stat stat; + stat.add(duration); + return stat; +} + +Stat calcTrajectoryVelocity(const Trajectory & traj) +{ + Stat stat; + for (TrajectoryPoint p : traj.points) { + stat.add(p.longitudinal_velocity_mps); + } + return stat; +} + +Stat calcTrajectoryAcceleration(const Trajectory & traj) +{ + Stat stat; + for (TrajectoryPoint p : traj.points) { + stat.add(p.acceleration_mps2); + } + return stat; +} + +Stat calcTrajectoryJerk(const Trajectory & traj) +{ + Stat stat; + for (size_t i = 0; i < traj.points.size() - 1; ++i) { + const double vel = traj.points.at(i).longitudinal_velocity_mps; + if (vel != 0) { + const double duration = + calcDistance2d(traj.points.at(i), traj.points.at(i + 1)) / std::abs(vel); + if (duration != 0) { + const double start_accel = traj.points.at(i).acceleration_mps2; + const double end_accel = traj.points.at(i + 1).acceleration_mps2; + stat.add(end_accel - start_accel / duration); + } + } + } + return stat; +} +} // namespace metrics +} // namespace planning_diagnostics diff --git a/planning/planning_evaluator/src/metrics_calculator.cpp b/planning/planning_evaluator/src/metrics_calculator.cpp new file mode 100644 index 0000000000000..045331d1ee778 --- /dev/null +++ b/planning/planning_evaluator/src/metrics_calculator.cpp @@ -0,0 +1,124 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/metrics_calculator.hpp" + +#include "planning_evaluator/metrics/deviation_metrics.hpp" +#include "planning_evaluator/metrics/obstacle_metrics.hpp" +#include "planning_evaluator/metrics/stability_metrics.hpp" +#include "planning_evaluator/metrics/trajectory_metrics.hpp" +#include "tier4_autoware_utils/tier4_autoware_utils.hpp" + +namespace planning_diagnostics +{ +Stat MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const +{ + // Functions to calculate metrics + switch (metric) { + case Metric::curvature: + return metrics::calcTrajectoryCurvature(traj); + case Metric::point_interval: + return metrics::calcTrajectoryInterval(traj); + case Metric::relative_angle: + return metrics::calcTrajectoryRelativeAngle(traj, parameters.trajectory.min_point_dist_m); + case Metric::length: + return metrics::calcTrajectoryLength(traj); + case Metric::duration: + return metrics::calcTrajectoryDuration(traj); + case Metric::velocity: + return metrics::calcTrajectoryVelocity(traj); + case Metric::acceleration: + return metrics::calcTrajectoryAcceleration(traj); + case Metric::jerk: + return metrics::calcTrajectoryJerk(traj); + case Metric::lateral_deviation: + return metrics::calcLateralDeviation(reference_trajectory_, traj); + case Metric::yaw_deviation: + return metrics::calcYawDeviation(reference_trajectory_, traj); + case Metric::velocity_deviation: + return metrics::calcVelocityDeviation(reference_trajectory_, traj); + case Metric::stability_frechet: + return metrics::calcFrechetDistance( + getLookaheadTrajectory( + previous_trajectory_, parameters.trajectory.lookahead.max_dist_m, + parameters.trajectory.lookahead.max_time_s), + getLookaheadTrajectory( + traj, parameters.trajectory.lookahead.max_dist_m, + parameters.trajectory.lookahead.max_time_s)); + case Metric::stability: + return metrics::calcLateralDistance( + getLookaheadTrajectory( + previous_trajectory_, parameters.trajectory.lookahead.max_dist_m, + parameters.trajectory.lookahead.max_time_s), + getLookaheadTrajectory( + traj, parameters.trajectory.lookahead.max_dist_m, + parameters.trajectory.lookahead.max_time_s)); + case Metric::obstacle_distance: + return metrics::calcDistanceToObstacle(dynamic_objects_, traj); + case Metric::obstacle_ttc: + return metrics::calcTimeToCollision(dynamic_objects_, traj, parameters.obstacle.dist_thr_m); + default: + throw std::runtime_error( + "[MetricsCalculator][calculate()] unknown Metric " + + std::to_string(static_cast(metric))); + } +} + +void MetricsCalculator::setReferenceTrajectory(const Trajectory & traj) +{ + reference_trajectory_ = traj; +} + +void MetricsCalculator::setPreviousTrajectory(const Trajectory & traj) +{ + previous_trajectory_ = traj; +} + +void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects) +{ + dynamic_objects_ = objects; +} + +void MetricsCalculator::setEgoPose(const geometry_msgs::msg::Pose & pose) { ego_pose_ = pose; } + +Trajectory MetricsCalculator::getLookaheadTrajectory( + const Trajectory & traj, const double max_dist_m, const double max_time_s) const +{ + if (traj.points.empty()) { + return traj; + } + + const auto ego_index = + tier4_autoware_utils::findNearestSegmentIndex(traj.points, ego_pose_.position); + Trajectory lookahead_traj; + lookahead_traj.header = traj.header; + double dist = 0.0; + double time = 0.0; + auto curr_point_it = std::next(traj.points.begin(), ego_index); + auto prev_point_it = curr_point_it; + while (curr_point_it != traj.points.end() && dist <= max_dist_m && time <= max_time_s) { + lookahead_traj.points.push_back(*curr_point_it); + const auto d = tier4_autoware_utils::calcDistance2d( + prev_point_it->pose.position, curr_point_it->pose.position); + dist += d; + if (prev_point_it->longitudinal_velocity_mps != 0.0) { + time += d / std::abs(prev_point_it->longitudinal_velocity_mps); + } + prev_point_it = curr_point_it; + ++curr_point_it; + } + return lookahead_traj; +} + +} // namespace planning_diagnostics diff --git a/planning/planning_evaluator/src/motion_evaluator_node.cpp b/planning/planning_evaluator/src/motion_evaluator_node.cpp new file mode 100644 index 0000000000000..56b08fca81f9f --- /dev/null +++ b/planning/planning_evaluator/src/motion_evaluator_node.cpp @@ -0,0 +1,103 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/motion_evaluator_node.hpp" + +#include +#include +#include +#include +#include + +namespace planning_diagnostics +{ +MotionEvaluatorNode::MotionEvaluatorNode(const rclcpp::NodeOptions & node_options) +: Node("motion_evaluator", node_options) +{ + tf_buffer_ptr_ = std::make_unique(this->get_clock()); + tf_listener_ptr_ = std::make_unique(*tf_buffer_ptr_); + + twist_sub_ = create_subscription( + "~/input/twist", rclcpp::QoS{1}, + std::bind(&MotionEvaluatorNode::onOdom, this, std::placeholders::_1)); + + output_file_str_ = declare_parameter("output_file"); + + // List of metrics to calculate + for (const std::string & selected_metric : + declare_parameter>("selected_metrics")) { + Metric metric = str_to_metric.at(selected_metric); + metrics_.push_back(metric); + } +} + +MotionEvaluatorNode::~MotionEvaluatorNode() +{ + // column width is the maximum size we might print + 1 for the space between columns + const auto column_width = 20; // std::to_string(std::numeric_limits::max()).size() + 1; + // Write data using format + std::ofstream f(output_file_str_); + f << std::fixed << std::left; + for (Metric metric : metrics_) { + f << std::setw(3 * column_width) << metric_descriptions.at(metric); + } + f << std::endl; + for (Metric metric : metrics_) { + const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_); + f /* << std::setw(3 * column_width) */ << stat << " "; + } + f.close(); +} + +void MotionEvaluatorNode::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg) +{ + // TODO(Maxime CLEMENT): set some desired minimum time/distance between two points + TrajectoryPoint current_point; + current_point.pose = getCurrentEgoPose(); + current_point.longitudinal_velocity_mps = msg->twist.twist.linear.x; + const rclcpp::Time now = this->get_clock()->now(); + if (!accumulated_trajectory_.points.empty()) { + current_point.acceleration_mps2 = + (msg->twist.twist.linear.x - + accumulated_trajectory_.points.back().longitudinal_velocity_mps) / + (now - stamps_.back()).seconds(); + } + accumulated_trajectory_.points.push_back(current_point); + stamps_.push_back(now); +} + +geometry_msgs::msg::Pose MotionEvaluatorNode::getCurrentEgoPose() const +{ + geometry_msgs::msg::TransformStamped tf_current_pose; + + geometry_msgs::msg::Pose p; + try { + tf_current_pose = tf_buffer_ptr_->lookupTransform( + "map", "base_link", rclcpp::Time(0), rclcpp::Duration::from_seconds(1.0)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR(get_logger(), "%s", ex.what()); + return p; + } + + p.orientation = tf_current_pose.transform.rotation; + p.position.x = tf_current_pose.transform.translation.x; + p.position.y = tf_current_pose.transform.translation.y; + p.position.z = tf_current_pose.transform.translation.z; + return p; +} + +} // namespace planning_diagnostics + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(planning_diagnostics::MotionEvaluatorNode) diff --git a/planning/planning_evaluator/src/planning_evaluator_node.cpp b/planning/planning_evaluator/src/planning_evaluator_node.cpp new file mode 100644 index 0000000000000..cca9bbf7c62e3 --- /dev/null +++ b/planning/planning_evaluator/src/planning_evaluator_node.cpp @@ -0,0 +1,191 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_evaluator/planning_evaluator_node.hpp" + +#include "boost/lexical_cast.hpp" + +#include +#include +#include +#include +#include +#include +#include + +namespace planning_diagnostics +{ +PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_options) +: Node("planning_evaluator", node_options) +{ + using std::placeholders::_1; + + traj_sub_ = create_subscription( + "~/input/trajectory", 1, std::bind(&PlanningEvaluatorNode::onTrajectory, this, _1)); + + ref_sub_ = create_subscription( + "~/input/reference_trajectory", 1, + std::bind(&PlanningEvaluatorNode::onReferenceTrajectory, this, _1)); + + objects_sub_ = create_subscription( + "~/input/objects", 1, std::bind(&PlanningEvaluatorNode::onObjects, this, _1)); + tf_buffer_ = std::make_unique(this->get_clock()); + transform_listener_ = std::make_shared(*tf_buffer_); + + // Parameters + metrics_calculator_.parameters.trajectory.min_point_dist_m = + declare_parameter("trajectory.min_point_dist_m"); + metrics_calculator_.parameters.trajectory.lookahead.max_dist_m = + declare_parameter("trajectory.lookahead.max_dist_m"); + metrics_calculator_.parameters.trajectory.lookahead.max_time_s = + declare_parameter("trajectory.lookahead.max_time_s"); + metrics_calculator_.parameters.obstacle.dist_thr_m = + declare_parameter("obstacle.dist_thr_m"); + + output_file_str_ = declare_parameter("output_file"); + ego_frame_str_ = declare_parameter("ego_frame"); + + // List of metrics to calculate and publish + metrics_pub_ = create_publisher("~/metrics", 1); + for (const std::string & selected_metric : + declare_parameter>("selected_metrics")) { + Metric metric = str_to_metric.at(selected_metric); + metrics_.push_back(metric); + } +} + +PlanningEvaluatorNode::~PlanningEvaluatorNode() +{ + if (!output_file_str_.empty()) { + // column width is the maximum size we might print + 1 for the space between columns + // Write data using format + std::ofstream f(output_file_str_); + f << std::fixed << std::left; + // header + f << "#Stamp(ns)"; + for (Metric metric : metrics_) { + f << " " << metric_descriptions.at(metric); + f << " . ."; // extra "columns" to align columns headers + } + f << std::endl; + f << "#."; + for (Metric metric : metrics_) { + (void)metric; + f << " min max mean"; + } + f << std::endl; + // data + for (size_t i = 0; i < stamps_.size(); ++i) { + f << stamps_[i].nanoseconds(); + for (Metric metric : metrics_) { + const auto & stat = metric_stats_[static_cast(metric)][i]; + f << " " << stat; + } + f << std::endl; + } + f.close(); + } +} + +void PlanningEvaluatorNode::updateCalculatorEgoPose(const std::string & target_frame) +{ + try { + const geometry_msgs::msg::TransformStamped transform = + tf_buffer_->lookupTransform(target_frame, ego_frame_str_, tf2::TimePointZero); + geometry_msgs::msg::Pose ego_pose; + ego_pose.position.x = transform.transform.translation.x; + ego_pose.position.y = transform.transform.translation.y; + ego_pose.position.z = transform.transform.translation.z; + ego_pose.orientation = transform.transform.rotation; + metrics_calculator_.setEgoPose(ego_pose); + } catch (tf2::TransformException & ex) { + RCLCPP_INFO( + this->get_logger(), "Cannot set ego pose: could not transform %s to %s: %s", + target_frame.c_str(), ego_frame_str_.c_str(), ex.what()); + } +} + +DiagnosticStatus PlanningEvaluatorNode::generateDiagnosticStatus( + const Metric & metric, const Stat & metric_stat) const +{ + DiagnosticStatus status; + status.level = status.OK; + status.name = metric_to_str.at(metric); + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "min"; + key_value.value = boost::lexical_cast(metric_stat.min()); + status.values.push_back(key_value); + key_value.key = "max"; + key_value.value = boost::lexical_cast(metric_stat.max()); + status.values.push_back(key_value); + key_value.key = "mean"; + key_value.value = boost::lexical_cast(metric_stat.mean()); + status.values.push_back(key_value); + return status; +} + +void PlanningEvaluatorNode::onTrajectory(const Trajectory::ConstSharedPtr traj_msg) +{ + auto start = now(); + stamps_.push_back(traj_msg->header.stamp); + + updateCalculatorEgoPose(traj_msg->header.frame_id); + + DiagnosticArray metrics_msg; + metrics_msg.header.stamp = now(); + for (Metric metric : metrics_) { + const Stat metric_stat = metrics_calculator_.calculate(Metric(metric), *traj_msg); + metric_stats_[static_cast(metric)].push_back(metric_stat); + if (metric_stat.count() > 0) { + metrics_msg.status.push_back(generateDiagnosticStatus(metric, metric_stat)); + } + } + if (!metrics_msg.status.empty()) { + metrics_pub_->publish(metrics_msg); + } + metrics_calculator_.setPreviousTrajectory(*traj_msg); + auto runtime = (now() - start).seconds(); + RCLCPP_INFO(get_logger(), "Calculation time: %2.2f ms", runtime * 1e3); +} + +void PlanningEvaluatorNode::onReferenceTrajectory(const Trajectory::ConstSharedPtr traj_msg) +{ + metrics_calculator_.setReferenceTrajectory(*traj_msg); +} + +void PlanningEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg) +{ + metrics_calculator_.setPredictedObjects(*objects_msg); +} + +bool PlanningEvaluatorNode::isFinite(const TrajectoryPoint & point) +{ + const auto & o = point.pose.orientation; + const auto & p = point.pose.position; + const auto & v = point.longitudinal_velocity_mps; + const auto & w = point.lateral_velocity_mps; + const auto & a = point.acceleration_mps2; + const auto & z = point.heading_rate_rps; + const auto & f = point.front_wheel_angle_rad; + const auto & r = point.rear_wheel_angle_rad; + + return std::isfinite(o.x) && std::isfinite(o.y) && std::isfinite(o.z) && std::isfinite(o.w) && + std::isfinite(p.x) && std::isfinite(p.y) && std::isfinite(p.z) && std::isfinite(v) && + std::isfinite(w) && std::isfinite(a) && std::isfinite(z) && std::isfinite(f) && + std::isfinite(r); +} +} // namespace planning_diagnostics + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(planning_diagnostics::PlanningEvaluatorNode) diff --git a/planning/planning_evaluator/test/test_planning_evaluator_node.cpp b/planning/planning_evaluator/test/test_planning_evaluator_node.cpp new file mode 100644 index 0000000000000..8e9bcdd734222 --- /dev/null +++ b/planning/planning_evaluator/test/test_planning_evaluator_node.cpp @@ -0,0 +1,409 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ament_index_cpp/get_package_share_directory.hpp" +#include "gtest/gtest.h" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/time.hpp" +#include "tf2_ros/transform_broadcaster.h" + +#include + +#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" +#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "diagnostic_msgs/msg/diagnostic_array.hpp" +#include "geometry_msgs/msg/transform_stamped.hpp" + +#include "boost/lexical_cast.hpp" + +#include +#include +#include +#include + +using EvalNode = planning_diagnostics::PlanningEvaluatorNode; +using Trajectory = autoware_auto_planning_msgs::msg::Trajectory; +using TrajectoryPoint = autoware_auto_planning_msgs::msg::TrajectoryPoint; +using Objects = autoware_auto_perception_msgs::msg::PredictedObjects; +using diagnostic_msgs::msg::DiagnosticArray; + +class EvalTest : public ::testing::Test +{ +protected: + void SetUp() override + { + rclcpp::init(0, nullptr); + + rclcpp::NodeOptions options; + const auto share_dir = ament_index_cpp::get_package_share_directory("planning_evaluator"); + options.arguments( + {"--ros-args", "--params-file", share_dir + "/param/planning_evaluator.defaults.yaml"}); + + dummy_node = std::make_shared("planning_evaluator_test_node"); + eval_node = std::make_shared(options); + // Enable all logging in the node + auto ret = rcutils_logging_set_logger_level( + dummy_node->get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG); + if (ret != RCUTILS_RET_OK) { + std::cerr << "Failed to set logging severity to DEBUG\n"; + } + ret = rcutils_logging_set_logger_level( + eval_node->get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG); + if (ret != RCUTILS_RET_OK) { + std::cerr << "Failed to set logging severity to DEBUG\n"; + } + + traj_pub_ = + rclcpp::create_publisher(dummy_node, "/planning_evaluator/input/trajectory", 1); + ref_traj_pub_ = rclcpp::create_publisher( + dummy_node, "/planning_evaluator/input/reference_trajectory", 1); + objects_pub_ = + rclcpp::create_publisher(dummy_node, "/planning_evaluator/input/objects", 1); + + tf_broadcaster_ = std::make_unique(dummy_node); + publishEgoPose(0.0, 0.0, 0.0); + } + + ~EvalTest() override { rclcpp::shutdown(); } + + void setTargetMetric(planning_diagnostics::Metric metric) + { + const auto metric_str = planning_diagnostics::metric_to_str.at(metric); + const auto is_target_metric = [metric_str](const auto & status) { + return status.name == metric_str; + }; + metric_sub_ = rclcpp::create_subscription( + dummy_node, "/planning_evaluator/metrics", 1, [=](const DiagnosticArray::ConstSharedPtr msg) { + const auto it = std::find_if(msg->status.begin(), msg->status.end(), is_target_metric); + if (it != msg->status.end()) { + metric_value_ = boost::lexical_cast(it->values[2].value); + metric_updated_ = true; + } + }); + } + + Trajectory makeTrajectory(const std::vector> & traj) + { + Trajectory t; + t.header.frame_id = "map"; + TrajectoryPoint p; + for (const std::pair & point : traj) { + p.pose.position.x = point.first; + p.pose.position.y = point.second; + t.points.push_back(p); + } + return t; + } + + void publishTrajectory(const Trajectory & traj) + { + traj_pub_->publish(traj); + rclcpp::spin_some(eval_node); + rclcpp::spin_some(dummy_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } + void publishReferenceTrajectory(const Trajectory & traj) + { + ref_traj_pub_->publish(traj); + rclcpp::spin_some(eval_node); + rclcpp::spin_some(dummy_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } + void publishObjects(const Objects & obj) + { + objects_pub_->publish(obj); + rclcpp::spin_some(eval_node); + rclcpp::spin_some(dummy_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } + double publishTrajectoryAndGetMetric(const Trajectory & traj) + { + metric_updated_ = false; + traj_pub_->publish(traj); + while (!metric_updated_) { + rclcpp::spin_some(eval_node); + rclcpp::spin_some(dummy_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } + return metric_value_; + } + + void publishEgoPose(const double x, const double y, const double yaw) + { + geometry_msgs::msg::TransformStamped t; + + // Read message content and assign it to + // corresponding tf variables + t.header.stamp = dummy_node->now(); + t.header.frame_id = "map"; + t.child_frame_id = "base_link"; + + t.transform.translation.x = x; + t.transform.translation.y = y; + t.transform.translation.z = 0.0; + + tf2::Quaternion q; + q.setRPY(0.0, 0.0, yaw); + t.transform.rotation.x = q.x(); + t.transform.rotation.y = q.y(); + t.transform.rotation.z = q.z(); + t.transform.rotation.w = q.w(); + + tf_broadcaster_->sendTransform(t); + } + + // Latest metric value + bool metric_updated_ = false; + double metric_value_; + // Node + rclcpp::Node::SharedPtr dummy_node; + EvalNode::SharedPtr eval_node; + // Trajectory publishers + rclcpp::Publisher::SharedPtr traj_pub_; + rclcpp::Publisher::SharedPtr ref_traj_pub_; + rclcpp::Publisher::SharedPtr objects_pub_; + rclcpp::Subscription::SharedPtr metric_sub_; + // TF broadcaster + std::unique_ptr tf_broadcaster_; +}; + +TEST_F(EvalTest, TestCurvature) +{ + setTargetMetric(planning_diagnostics::Metric::curvature); + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}, {2.0, 0.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), -1.0); + t = makeTrajectory({{0.0, 0.0}, {2.0, -2.0}, {4.0, 0.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.5); +} + +TEST_F(EvalTest, TestPointInterval) +{ + setTargetMetric(planning_diagnostics::Metric::point_interval); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 1.0); + // double the average interval + TrajectoryPoint p; + p.pose.position.x = 0.0; + p.pose.position.y = 6.0; + t.points.push_back(p); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 2.0); +} + +TEST_F(EvalTest, TestRelativeAngle) +{ + setTargetMetric(planning_diagnostics::Metric::relative_angle); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}, {1.0, 1.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), -M_PI_4); + // add an angle of PI/4 to bring the average to 0 + TrajectoryPoint p; + p.pose.position.x = 1.0; + p.pose.position.y = 2.0; + t.points.push_back(p); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); +} + +TEST_F(EvalTest, TestLength) +{ + setTargetMetric(planning_diagnostics::Metric::length); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}, {0.0, 3.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 3.0); + TrajectoryPoint p; + p.pose.position.x = 3.0; + p.pose.position.y = 3.0; + t.points.push_back(p); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 6.0); +} + +TEST_F(EvalTest, TestVelocity) +{ + setTargetMetric(planning_diagnostics::Metric::velocity); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}, {0.0, 3.0}}); + for (TrajectoryPoint & p : t.points) { + p.longitudinal_velocity_mps = 1.0; + } +} + +TEST_F(EvalTest, TestDuration) +{ + setTargetMetric(planning_diagnostics::Metric::duration); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}, {0.0, 2.0}, {0.0, 3.0}}); + for (TrajectoryPoint & p : t.points) { + p.longitudinal_velocity_mps = 1.0; + } + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 3.0); + for (TrajectoryPoint & p : t.points) { + p.longitudinal_velocity_mps = 3.0; + } + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 1.0); +} + +TEST_F(EvalTest, TestAcceleration) +{ + setTargetMetric(planning_diagnostics::Metric::acceleration); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}}); + t.points[0].acceleration_mps2 = 1.0; + t.points[1].acceleration_mps2 = 1.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 1.0); + t.points[0].acceleration_mps2 = -1.0; + t.points[1].acceleration_mps2 = -1.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), -1.0); + t.points[0].acceleration_mps2 = 0.0; + t.points[1].acceleration_mps2 = 1.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.5); +} + +TEST_F(EvalTest, TestJerk) +{ + setTargetMetric(planning_diagnostics::Metric::jerk); + Trajectory t = makeTrajectory({{0.0, 0.0}, {0.0, 1.0}}); + t.points[0].longitudinal_velocity_mps = 1.0; + t.points[0].acceleration_mps2 = 1.0; + t.points[1].longitudinal_velocity_mps = 2.0; + t.points[1].acceleration_mps2 = 1.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + t.points[0].longitudinal_velocity_mps = 1.0; + t.points[0].acceleration_mps2 = 1.0; + t.points[1].longitudinal_velocity_mps = 1.0; + t.points[1].acceleration_mps2 = 0.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), -1.0); +} + +TEST_F(EvalTest, TestLateralDeviation) +{ + setTargetMetric(planning_diagnostics::Metric::lateral_deviation); + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 0.0}}); + publishReferenceTrajectory(t); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + Trajectory t2 = makeTrajectory({{0.0, 1.0}, {1.0, 1.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), 1.0); +} + +TEST_F(EvalTest, TestYawDeviation) +{ + auto setYaw = [](geometry_msgs::msg::Quaternion & msg, const double yaw_rad) { + tf2::Quaternion q; + q.setRPY(0.0, 0.0, yaw_rad); + msg.x = q.x(); + msg.y = q.y(); + msg.z = q.z(); + msg.w = q.w(); + }; + setTargetMetric(planning_diagnostics::Metric::yaw_deviation); + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 0.0}}); + for (auto & p : t.points) { + setYaw(p.pose.orientation, M_PI); + } + publishReferenceTrajectory(t); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + Trajectory t2 = t; + for (auto & p : t2.points) { + setYaw(p.pose.orientation, 0.0); + } + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), -M_PI); + for (auto & p : t2.points) { + setYaw(p.pose.orientation, -M_PI); + } + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), 0.0); +} + +TEST_F(EvalTest, TestVelocityDeviation) +{ + setTargetMetric(planning_diagnostics::Metric::velocity_deviation); + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}, {2.0, 2.0}}); + for (auto & p : t.points) { + p.longitudinal_velocity_mps = 0.0; + } + publishReferenceTrajectory(t); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + for (auto & p : t.points) { + p.longitudinal_velocity_mps = 1.0; + } + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 1.0); +} + +TEST_F(EvalTest, TestStability) +{ + setTargetMetric(planning_diagnostics::Metric::stability); + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}, {2.0, 2.0}, {3.0, 3.0}}); + publishTrajectory(t); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + t.points.back().pose.position.x = 0.0; + t.points.back().pose.position.y = 0.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + + Trajectory t2 = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}, {2.0, 2.0}, {3.0, 3.0}}); + publishTrajectory(t2); + t2.points.back().pose.position.x = 4.0; + t2.points.back().pose.position.y = 3.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), 1.0 / 4); +} + +TEST_F(EvalTest, TestFrechet) +{ + setTargetMetric(planning_diagnostics::Metric::stability_frechet); + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}, {2.0, 2.0}, {3.0, 3.0}}); + publishTrajectory(t); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.0); + + // variation in the last point: simple distance from previous last point + t.points.back().pose.position.x = 0.0; + t.points.back().pose.position.y = 0.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), std::sqrt(18.0)); + Trajectory t2 = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}, {2.0, 2.0}, {3.0, 3.0}}); + publishTrajectory(t2); + t2.points.back().pose.position.x = 4.0; + t2.points.back().pose.position.y = 3.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), 1.0); + + // variations in the middle points: cannot go back to previous points that minimize the distance + t2.points[2].pose.position.x = 0.5; + t2.points[2].pose.position.y = 0.5; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), std::sqrt(2 * (1.5 * 1.5))); +} + +TEST_F(EvalTest, TestObstacleDistance) +{ + setTargetMetric(planning_diagnostics::Metric::obstacle_distance); + Objects objs; + autoware_auto_perception_msgs::msg::PredictedObject obj; + obj.kinematics.initial_pose_with_covariance.pose.position.x = 0.0; + obj.kinematics.initial_pose_with_covariance.pose.position.y = 0.0; + objs.objects.push_back(obj); + publishObjects(objs); + + Trajectory t = makeTrajectory({{0.0, 0.0}, {1.0, 0.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 0.5); + Trajectory t2 = makeTrajectory({{0.0, 0.0}, {1.0, 0.0}, {2.0, 0.0}}); + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t2), 1.0); // (0.0 + 1.0 + 2.0) / 3 +} + +TEST_F(EvalTest, TestObstacleTTC) +{ + setTargetMetric(planning_diagnostics::Metric::obstacle_ttc); + Objects objs; + autoware_auto_perception_msgs::msg::PredictedObject obj; + obj.kinematics.initial_pose_with_covariance.pose.position.x = 0.0; + obj.kinematics.initial_pose_with_covariance.pose.position.y = 0.0; + objs.objects.push_back(obj); + publishObjects(objs); + + Trajectory t = makeTrajectory({{3.0, 0.0}, {0.0, 0.0}, {-1.0, 0.0}}); + for (TrajectoryPoint & p : t.points) { + p.longitudinal_velocity_mps = 1.0; + } + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 3.0); + // if no exact collision point, last point before collision is used + t.points[1].pose.position.x = 1.0; + EXPECT_DOUBLE_EQ(publishTrajectoryAndGetMetric(t), 2.0); +} From 5532d03f86a688025bdf0bf4ece7d207cdb38c6f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 17 Feb 2022 11:23:56 +0900 Subject: [PATCH 06/37] feat(interpolation): add functions for flexible usage (non-static spline interpolation) (#379) * implement spline interpolation class with some refactoring Signed-off-by: Takayuki Murooka * fixed runtime error with template functions Signed-off-by: Takayuki Murooka * fixed runtime error with template functions Signed-off-by: Takayuki Murooka * add new tests Signed-off-by: Takayuki Murooka * just rename function: getAccumulatedDistance -> getAccumulatedLength Signed-off-by: Takayuki Murooka * dealt not to extrapolation for spline Signed-off-by: Takayuki Murooka * add explanation to the function Signed-off-by: Takayuki Murooka * move SplineInterpolationPoints2d to another file Signed-off-by: Takayuki Murooka * use template for functions to slerp points Signed-off-by: Takayuki Murooka * move doxygen to header Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe --- common/interpolation/CMakeLists.txt | 1 + .../interpolation/interpolation_utils.hpp | 28 ++- .../interpolation/spline_interpolation.hpp | 43 +++++ .../spline_interpolation_points_2d.hpp | 67 +++++++ common/interpolation/package.xml | 2 + .../src/linear_interpolation.cpp | 3 +- .../src/spline_interpolation.cpp | 88 ++++++--- .../src/spline_interpolation_points_2d.cpp | 155 +++++++++++++++ .../test/src/test_interpolation_utils.cpp | 53 +++-- .../test/src/test_spline_interpolation.cpp | 181 +++++++++++++++++- 10 files changed, 561 insertions(+), 60 deletions(-) create mode 100644 common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp create mode 100644 common/interpolation/src/spline_interpolation_points_2d.cpp diff --git a/common/interpolation/CMakeLists.txt b/common/interpolation/CMakeLists.txt index 64abec9a6a278..e2c6abfd5ba8e 100644 --- a/common/interpolation/CMakeLists.txt +++ b/common/interpolation/CMakeLists.txt @@ -15,6 +15,7 @@ ament_auto_find_build_dependencies() ament_auto_add_library(interpolation SHARED src/linear_interpolation.cpp src/spline_interpolation.cpp + src/spline_interpolation_points_2d.cpp ) # Test diff --git a/common/interpolation/include/interpolation/interpolation_utils.hpp b/common/interpolation/include/interpolation/interpolation_utils.hpp index 98049fbd715ba..d170007685bbf 100644 --- a/common/interpolation/include/interpolation/interpolation_utils.hpp +++ b/common/interpolation/include/interpolation/interpolation_utils.hpp @@ -51,20 +51,18 @@ inline bool isNotDecreasing(const std::vector & x) return true; } -inline void validateInput( - const std::vector & base_keys, const std::vector & base_values, - const std::vector & query_keys) +inline void validateKeys( + const std::vector & base_keys, const std::vector & query_keys) { // when vectors are empty - if (base_keys.empty() || base_values.empty() || query_keys.empty()) { + if (base_keys.empty() || query_keys.empty()) { throw std::invalid_argument("Points is empty."); } // when size of vectors are less than 2 - if (base_keys.size() < 2 || base_values.size() < 2) { + if (base_keys.size() < 2) { throw std::invalid_argument( - "The size of points is less than 2. base_keys.size() = " + std::to_string(base_keys.size()) + - ", base_values.size() = " + std::to_string(base_values.size())); + "The size of points is less than 2. base_keys.size() = " + std::to_string(base_keys.size())); } // when indices are not sorted @@ -76,6 +74,22 @@ inline void validateInput( if (query_keys.front() < base_keys.front() || base_keys.back() < query_keys.back()) { throw std::invalid_argument("query_keys is out of base_keys"); } +} + +inline void validateKeysAndValues( + const std::vector & base_keys, const std::vector & base_values) +{ + // when vectors are empty + if (base_keys.empty() || base_values.empty()) { + throw std::invalid_argument("Points is empty."); + } + + // when size of vectors are less than 2 + if (base_keys.size() < 2 || base_values.size() < 2) { + throw std::invalid_argument( + "The size of points is less than 2. base_keys.size() = " + std::to_string(base_keys.size()) + + ", base_values.size() = " + std::to_string(base_values.size())); + } // when sizes of indices and values are not same if (base_keys.size() != base_values.size()) { diff --git a/common/interpolation/include/interpolation/spline_interpolation.hpp b/common/interpolation/include/interpolation/spline_interpolation.hpp index d429fe750297b..09a01d03727eb 100644 --- a/common/interpolation/include/interpolation/spline_interpolation.hpp +++ b/common/interpolation/include/interpolation/spline_interpolation.hpp @@ -15,6 +15,9 @@ #ifndef INTERPOLATION__SPLINE_INTERPOLATION_HPP_ #define INTERPOLATION__SPLINE_INTERPOLATION_HPP_ +#include "interpolation/interpolation_utils.hpp" +#include "tier4_autoware_utils/geometry/geometry.hpp" + #include #include #include @@ -26,6 +29,8 @@ namespace interpolation // NOTE: X(s) = a_i (s - s_i)^3 + b_i (s - s_i)^2 + c_i (s - s_i) + d_i : (i = 0, 1, ... N-1) struct MultiSplineCoef { + MultiSplineCoef() = default; + explicit MultiSplineCoef(const size_t num_spline) { a.resize(num_spline); @@ -40,9 +45,47 @@ struct MultiSplineCoef std::vector d; }; +// static spline interpolation functions std::vector slerp( const std::vector & base_keys, const std::vector & base_values, const std::vector & query_keys); } // namespace interpolation +// non-static 1-dimensional spline interpolation +// +// Usage: +// ``` +// SplineInterpolation spline; +// // memorize pre-interpolation result internally +// spline.calcSplineCoefficients(base_keys, base_values); +// const auto interpolation_result1 = spline.getSplineInterpolatedValues( +// base_keys, query_keys1); +// const auto interpolation_result2 = spline.getSplineInterpolatedValues( +// base_keys, query_keys2); +// ``` +class SplineInterpolation +{ +public: + SplineInterpolation() = default; + + void calcSplineCoefficients( + const std::vector & base_keys, const std::vector & base_values); + + //!< @brief get values of spline interpolation on designated sampling points. + //!< @details Assuming that query_keys are t vector for sampling, and interpolation is for x, + // meaning that spline interpolation was applied to x(t), + // return value will be x(t) vector + std::vector getSplineInterpolatedValues(const std::vector & query_keys) const; + + //!< @brief get 1st differential values of spline interpolation on designated sampling points. + //!< @details Assuming that query_keys are t vector for sampling, and interpolation is for x, + // meaning that spline interpolation was applied to x(t), + // return value will be dx/dt(t) vector + std::vector getSplineInterpolatedDiffValues(const std::vector & query_keys) const; + +private: + std::vector base_keys_; + interpolation::MultiSplineCoef multi_spline_coef_; +}; + #endif // INTERPOLATION__SPLINE_INTERPOLATION_HPP_ diff --git a/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp b/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp new file mode 100644 index 0000000000000..7d58213e115a5 --- /dev/null +++ b/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp @@ -0,0 +1,67 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_ +#define INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_ + +#include "interpolation/spline_interpolation.hpp" + +#include + +namespace interpolation +{ +template +std::vector slerpYawFromPoints(const std::vector & points); +} // namespace interpolation + +// non-static points spline interpolation +// NOTE: We can calculate yaw from the x and y by interpolation derivatives. +// +// Usage: +// ``` +// SplineInterpolationPoints2d spline; +// // memorize pre-interpolation result internally +// spline.calcSplineCoefficients(base_keys, base_values); +// const auto interpolation_result1 = spline.getSplineInterpolatedPoints( +// base_keys, query_keys1); +// const auto interpolation_result2 = spline.getSplineInterpolatedPoints( +// base_keys, query_keys2); +// const auto yaw_interpolation_result = spline.getSplineInterpolatedYaws( +// base_keys, query_keys1); +// ``` +class SplineInterpolationPoints2d +{ +public: + SplineInterpolationPoints2d() = default; + + template + void calcSplineCoefficients(const std::vector & points); + + // TODO(murooka) implement these functions + // std::vector getSplineInterpolatedPoints(const double width); + // std::vector getSplineInterpolatedPoses(const double width); + + geometry_msgs::msg::Point getSplineInterpolatedPoint(const size_t idx, const double s) const; + double getSplineInterpolatedYaw(const size_t idx, const double s) const; + + double getAccumulatedLength(const size_t idx) const; + +private: + SplineInterpolation slerp_x_; + SplineInterpolation slerp_y_; + + std::vector base_s_vec_; +}; + +#endif // INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_ diff --git a/common/interpolation/package.xml b/common/interpolation/package.xml index 0d1090567f917..72844e0702978 100644 --- a/common/interpolation/package.xml +++ b/common/interpolation/package.xml @@ -9,6 +9,8 @@ Apache License 2.0 ament_cmake_auto + tier4_autoware_utils + ament_lint_auto autoware_lint_common diff --git a/common/interpolation/src/linear_interpolation.cpp b/common/interpolation/src/linear_interpolation.cpp index 8f5544e74ebb1..48ae7c2501384 100644 --- a/common/interpolation/src/linear_interpolation.cpp +++ b/common/interpolation/src/linear_interpolation.cpp @@ -28,7 +28,8 @@ std::vector lerp( const std::vector & query_keys) { // throw exception for invalid arguments - interpolation_utils::validateInput(base_keys, base_values, query_keys); + interpolation_utils::validateKeys(base_keys, query_keys); + interpolation_utils::validateKeysAndValues(base_keys, base_values); // calculate linear interpolation std::vector query_values; diff --git a/common/interpolation/src/spline_interpolation.cpp b/common/interpolation/src/spline_interpolation.cpp index 525784adf6000..f8d14ff7bba37 100644 --- a/common/interpolation/src/spline_interpolation.cpp +++ b/common/interpolation/src/spline_interpolation.cpp @@ -14,8 +14,6 @@ #include "interpolation/spline_interpolation.hpp" -#include "interpolation/interpolation_utils.hpp" - #include namespace @@ -43,7 +41,7 @@ struct TDMACoef std::vector d; }; -std::vector solveTridiagonalMatrixAlgorithm(const TDMACoef & tdma_coef) +inline std::vector solveTridiagonalMatrixAlgorithm(const TDMACoef & tdma_coef) { const auto & a = tdma_coef.a; const auto & b = tdma_coef.b; @@ -79,10 +77,30 @@ std::vector solveTridiagonalMatrixAlgorithm(const TDMACoef & tdma_coef) return x; } +} // namespace + +namespace interpolation +{ +std::vector slerp( + const std::vector & base_keys, const std::vector & base_values, + const std::vector & query_keys) +{ + SplineInterpolation interpolator; -interpolation::MultiSplineCoef generateSplineCoefficients( + // calculate spline coefficients + interpolator.calcSplineCoefficients(base_keys, base_values); + + // interpolate base_keys at query_keys + return interpolator.getSplineInterpolatedValues(query_keys); +} +} // namespace interpolation + +void SplineInterpolation::calcSplineCoefficients( const std::vector & base_keys, const std::vector & base_values) { + // throw exceptions for invalid arguments + interpolation_utils::validateKeysAndValues(base_keys, base_values); + const size_t num_base = base_keys.size(); // N+1 std::vector diff_keys; // N @@ -115,55 +133,63 @@ interpolation::MultiSplineCoef generateSplineCoefficients( v.push_back(0.0); // calculate a, b, c, d of spline coefficients - interpolation::MultiSplineCoef multi_spline_coef(num_base - 1); // N + multi_spline_coef_ = interpolation::MultiSplineCoef{num_base - 1}; // N for (size_t i = 0; i < num_base - 1; ++i) { - multi_spline_coef.a[i] = (v[i + 1] - v[i]) / 6.0 / diff_keys[i]; - multi_spline_coef.b[i] = v[i] / 2.0; - multi_spline_coef.c[i] = + multi_spline_coef_.a[i] = (v[i + 1] - v[i]) / 6.0 / diff_keys[i]; + multi_spline_coef_.b[i] = v[i] / 2.0; + multi_spline_coef_.c[i] = diff_values[i] / diff_keys[i] - diff_keys[i] * (2 * v[i] + v[i + 1]) / 6.0; - multi_spline_coef.d[i] = base_values[i]; + multi_spline_coef_.d[i] = base_values[i]; } - return multi_spline_coef; + base_keys_ = base_keys; } -std::vector getSplineInterpolatedValues( - const std::vector & base_keys, const std::vector & query_keys, - const interpolation::MultiSplineCoef & multi_spline_coef) +std::vector SplineInterpolation::getSplineInterpolatedValues( + const std::vector & query_keys) const { - const auto & a = multi_spline_coef.a; - const auto & b = multi_spline_coef.b; - const auto & c = multi_spline_coef.c; - const auto & d = multi_spline_coef.d; + // throw exceptions for invalid arguments + interpolation_utils::validateKeys(base_keys_, query_keys); + + const auto & a = multi_spline_coef_.a; + const auto & b = multi_spline_coef_.b; + const auto & c = multi_spline_coef_.c; + const auto & d = multi_spline_coef_.d; std::vector res; size_t j = 0; for (const auto & query_key : query_keys) { - while (base_keys.at(j + 1) < query_key) { + while (base_keys_.at(j + 1) < query_key) { ++j; } - const double ds = query_key - base_keys.at(j); + const double ds = query_key - base_keys_.at(j); res.push_back(d.at(j) + (c.at(j) + (b.at(j) + a.at(j) * ds) * ds) * ds); } return res; } -} // namespace -namespace interpolation -{ -std::vector slerp( - const std::vector & base_keys, const std::vector & base_values, - const std::vector & query_keys) +std::vector SplineInterpolation::getSplineInterpolatedDiffValues( + const std::vector & query_keys) const { // throw exceptions for invalid arguments - interpolation_utils::validateInput(base_keys, base_values, query_keys); + interpolation_utils::validateKeys(base_keys_, query_keys); - // calculate spline coefficients - const auto multi_spline_coef = generateSplineCoefficients(base_keys, base_values); + const auto & a = multi_spline_coef_.a; + const auto & b = multi_spline_coef_.b; + const auto & c = multi_spline_coef_.c; - // interpolate base_keys at query_keys - return getSplineInterpolatedValues(base_keys, query_keys, multi_spline_coef); + std::vector res; + size_t j = 0; + for (const auto & query_key : query_keys) { + while (base_keys_.at(j + 1) < query_key) { + ++j; + } + + const double ds = query_key - base_keys_.at(j); + res.push_back(c.at(j) + (2.0 * b.at(j) + 3.0 * a.at(j) * ds) * ds); + } + + return res; } -} // namespace interpolation diff --git a/common/interpolation/src/spline_interpolation_points_2d.cpp b/common/interpolation/src/spline_interpolation_points_2d.cpp new file mode 100644 index 0000000000000..e0c0caf27d0c0 --- /dev/null +++ b/common/interpolation/src/spline_interpolation_points_2d.cpp @@ -0,0 +1,155 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "interpolation/spline_interpolation_points_2d.hpp" + +#include + +namespace +{ +std::vector calcEuclidDist(const std::vector & x, const std::vector & y) +{ + if (x.size() != y.size()) { + return std::vector{}; + } + + std::vector dist_v; + dist_v.push_back(0.0); + for (size_t i = 0; i < x.size() - 1; ++i) { + const double dx = x.at(i + 1) - x.at(i); + const double dy = y.at(i + 1) - y.at(i); + dist_v.push_back(dist_v.at(i) + std::hypot(dx, dy)); + } + + return dist_v; +} + +template +std::array, 3> getBaseValues(const std::vector & points) +{ + // calculate x, y + std::vector base_x; + std::vector base_y; + for (size_t i = 0; i < points.size(); i++) { + const auto & current_pos = tier4_autoware_utils::getPoint(points.at(i)); + if (i > 0) { + const auto & prev_pos = tier4_autoware_utils::getPoint(points.at(i - 1)); + if ( + std::fabs(current_pos.x - prev_pos.x) < 1e-6 && + std::fabs(current_pos.y - prev_pos.y) < 1e-6) { + continue; + } + } + base_x.push_back(current_pos.x); + base_y.push_back(current_pos.y); + } + + // calculate base_keys, base_values + if (base_x.size() < 2 || base_y.size() < 2) { + throw std::logic_error("The numbef of unique points is not enough."); + } + + const std::vector base_s = calcEuclidDist(base_x, base_y); + + return {base_s, base_x, base_y}; +} +} // namespace + +namespace interpolation +{ +template +std::vector slerpYawFromPoints(const std::vector & points) +{ + SplineInterpolationPoints2d interpolator; + + // calculate spline coefficients + interpolator.calcSplineCoefficients(points); + + // interpolate base_keys at query_keys + std::vector yaw_vec; + for (size_t i = 0; i < points.size(); ++i) { + const double yaw = interpolator.getSplineInterpolatedYaw(i, 0.0); + yaw_vec.push_back(yaw); + } + return yaw_vec; +} +template std::vector slerpYawFromPoints( + const std::vector & points); +} // namespace interpolation + +template +void SplineInterpolationPoints2d::calcSplineCoefficients(const std::vector & points) +{ + const auto base = getBaseValues(points); + + base_s_vec_ = base.at(0); + const auto & base_x_vec = base.at(1); + const auto & base_y_vec = base.at(2); + + // calculate spline coefficients + slerp_x_.calcSplineCoefficients(base_s_vec_, base_x_vec); + slerp_y_.calcSplineCoefficients(base_s_vec_, base_y_vec); +} + +geometry_msgs::msg::Point SplineInterpolationPoints2d::getSplineInterpolatedPoint( + const size_t idx, const double s) const +{ + if (base_s_vec_.size() <= idx) { + throw std::out_of_range("idx is out of range."); + } + + double whole_s = base_s_vec_.at(idx) + s; + if (whole_s < base_s_vec_.front()) { + whole_s = base_s_vec_.front(); + } + if (whole_s > base_s_vec_.back()) { + whole_s = base_s_vec_.back(); + } + + const double x = slerp_x_.getSplineInterpolatedValues({whole_s}).at(0); + const double y = slerp_y_.getSplineInterpolatedValues({whole_s}).at(0); + + geometry_msgs::msg::Point geom_point; + geom_point.x = x; + geom_point.y = y; + return geom_point; +} + +double SplineInterpolationPoints2d::getSplineInterpolatedYaw(const size_t idx, const double s) const +{ + if (base_s_vec_.size() <= idx) { + throw std::out_of_range("idx is out of range."); + } + + double whole_s = base_s_vec_.at(idx) + s; + if (whole_s < base_s_vec_.front()) { + whole_s = base_s_vec_.front(); + } + if (whole_s > base_s_vec_.back()) { + whole_s = base_s_vec_.back(); + } + + const double diff_x = slerp_x_.getSplineInterpolatedDiffValues({whole_s}).at(0); + const double diff_y = slerp_y_.getSplineInterpolatedDiffValues({whole_s}).at(0); + + return std::atan2(diff_y, diff_x); +} + +double SplineInterpolationPoints2d::getAccumulatedLength(const size_t idx) const +{ + if (base_s_vec_.size() <= idx) { + throw std::out_of_range("idx is out of range."); + } + return base_s_vec_.at(idx); +} diff --git a/common/interpolation/test/src/test_interpolation_utils.cpp b/common/interpolation/test/src/test_interpolation_utils.cpp index c2d8fc9dd4a6e..3eb40fd439c56 100644 --- a/common/interpolation/test/src/test_interpolation_utils.cpp +++ b/common/interpolation/test/src/test_interpolation_utils.cpp @@ -58,51 +58,66 @@ TEST(interpolation_utils, isNotDecreasing) EXPECT_EQ(interpolation_utils::isNotDecreasing(decreasing_vec), false); } -TEST(interpolation_utils, validateInput) +TEST(interpolation_utils, validateKeys) { - using interpolation_utils::validateInput; + using interpolation_utils::validateKeys; const std::vector base_keys{0.0, 1.0, 2.0, 3.0}; - const std::vector base_values{0.0, 1.0, 2.0, 3.0}; const std::vector query_keys{0.0, 1.0, 2.0, 3.0}; // valid - EXPECT_NO_THROW(validateInput(base_keys, base_values, query_keys)); + EXPECT_NO_THROW(validateKeys(base_keys, query_keys)); // empty const std::vector empty_vec; - EXPECT_THROW(validateInput(empty_vec, base_values, query_keys), std::invalid_argument); - EXPECT_THROW(validateInput(base_keys, empty_vec, query_keys), std::invalid_argument); - EXPECT_THROW(validateInput(base_keys, base_values, empty_vec), std::invalid_argument); + EXPECT_THROW(validateKeys(empty_vec, query_keys), std::invalid_argument); + EXPECT_THROW(validateKeys(base_keys, empty_vec), std::invalid_argument); // size is less than 2 const std::vector short_vec{0.0}; - EXPECT_THROW(validateInput(short_vec, base_values, query_keys), std::invalid_argument); - EXPECT_THROW(validateInput(base_keys, short_vec, query_keys), std::invalid_argument); - EXPECT_THROW(validateInput(short_vec, short_vec, query_keys), std::invalid_argument); + EXPECT_THROW(validateKeys(short_vec, query_keys), std::invalid_argument); // partly not increase const std::vector partly_not_increasing_vec{0.0, 0.0, 2.0, 3.0}; // NOTE: base_keys must be strictly monotonous increasing vector - EXPECT_THROW( - validateInput(partly_not_increasing_vec, base_values, query_keys), std::invalid_argument); + EXPECT_THROW(validateKeys(partly_not_increasing_vec, query_keys), std::invalid_argument); // NOTE: query_keys is allowed to be monotonous non-decreasing vector - EXPECT_NO_THROW(validateInput(base_keys, base_values, partly_not_increasing_vec)); + EXPECT_NO_THROW(validateKeys(base_keys, partly_not_increasing_vec)); // decrease const std::vector decreasing_vec{0.0, -1.0, 2.0, 3.0}; - EXPECT_THROW(validateInput(decreasing_vec, base_values, query_keys), std::invalid_argument); - EXPECT_THROW(validateInput(base_keys, base_values, decreasing_vec), std::invalid_argument); + EXPECT_THROW(validateKeys(decreasing_vec, query_keys), std::invalid_argument); + EXPECT_THROW(validateKeys(base_keys, decreasing_vec), std::invalid_argument); // out of range const std::vector front_out_query_keys{-1.0, 1.0, 2.0, 3.0}; - EXPECT_THROW(validateInput(base_keys, base_values, front_out_query_keys), std::invalid_argument); + EXPECT_THROW(validateKeys(base_keys, front_out_query_keys), std::invalid_argument); const std::vector back_out_query_keys{0.0, 1.0, 2.0, 4.0}; - EXPECT_THROW(validateInput(base_keys, base_values, back_out_query_keys), std::invalid_argument); + EXPECT_THROW(validateKeys(base_keys, back_out_query_keys), std::invalid_argument); +} + +TEST(interpolation_utils, validateKeysAndValues) +{ + using interpolation_utils::validateKeysAndValues; + + const std::vector base_keys{0.0, 1.0, 2.0, 3.0}; + const std::vector base_values{0.0, 1.0, 2.0, 3.0}; + + // valid + EXPECT_NO_THROW(validateKeysAndValues(base_keys, base_values)); + + // empty + const std::vector empty_vec; + EXPECT_THROW(validateKeysAndValues(empty_vec, base_values), std::invalid_argument); + EXPECT_THROW(validateKeysAndValues(base_keys, empty_vec), std::invalid_argument); + + // size is less than 2 + const std::vector short_vec{0.0}; + EXPECT_THROW(validateKeysAndValues(short_vec, base_values), std::invalid_argument); + EXPECT_THROW(validateKeysAndValues(base_keys, short_vec), std::invalid_argument); // size is different const std::vector different_size_base_values{0.0, 1.0, 2.0}; - EXPECT_THROW( - validateInput(base_keys, different_size_base_values, query_keys), std::invalid_argument); + EXPECT_THROW(validateKeysAndValues(base_keys, different_size_base_values), std::invalid_argument); } diff --git a/common/interpolation/test/src/test_spline_interpolation.cpp b/common/interpolation/test/src/test_spline_interpolation.cpp index 90f08df578848..e6c368b00a0f4 100644 --- a/common/interpolation/test/src/test_spline_interpolation.cpp +++ b/common/interpolation/test/src/test_spline_interpolation.cpp @@ -13,6 +13,8 @@ // limitations under the License. #include "interpolation/spline_interpolation.hpp" +#include "interpolation/spline_interpolation_points_2d.hpp" +#include "tier4_autoware_utils/geometry/geometry.hpp" #include @@ -71,7 +73,7 @@ TEST(spline_interpolation, slerp) } } - { // straight: size of base_keys is 2 + { // straight: size of base_keys is 2 (edge case in the implementation) const std::vector base_keys{0.0, 1.0}; const std::vector base_values{0.0, 1.5}; const std::vector query_keys = base_keys; @@ -83,7 +85,7 @@ TEST(spline_interpolation, slerp) } } - { // straight: size of base_keys is 3 + { // straight: size of base_keys is 3 (edge case in the implementation) const std::vector base_keys{0.0, 1.0, 2.0}; const std::vector base_values{0.0, 1.5, 3.0}; const std::vector query_keys = base_keys; @@ -95,3 +97,178 @@ TEST(spline_interpolation, slerp) } } } + +TEST(spline_interpolation, slerpYawFromPoints) +{ + using tier4_autoware_utils::createPoint; + + { // straight + std::vector points; + points.push_back(createPoint(0.0, 0.0, 0.0)); + points.push_back(createPoint(1.0, 1.5, 0.0)); + points.push_back(createPoint(2.0, 3.0, 0.0)); + points.push_back(createPoint(3.0, 4.5, 0.0)); + points.push_back(createPoint(4.0, 6.0, 0.0)); + + const std::vector ans{0.9827937, 0.9827937, 0.9827937, 0.9827937, 0.9827937}; + + const auto yaws = interpolation::slerpYawFromPoints(points); + for (size_t i = 0; i < yaws.size(); ++i) { + EXPECT_NEAR(yaws.at(i), ans.at(i), epsilon); + } + } + + { // curve + std::vector points; + points.push_back(createPoint(-2.0, -10.0, 0.0)); + points.push_back(createPoint(2.0, 1.5, 0.0)); + points.push_back(createPoint(3.0, 3.0, 0.0)); + points.push_back(createPoint(5.0, 10.0, 0.0)); + points.push_back(createPoint(10.0, 12.5, 0.0)); + + const std::vector ans{1.3593746, 0.9813541, 1.0419655, 0.8935115, 0.2932783}; + + const auto yaws = interpolation::slerpYawFromPoints(points); + for (size_t i = 0; i < yaws.size(); ++i) { + EXPECT_NEAR(yaws.at(i), ans.at(i), epsilon); + } + } + + { // size of base_keys is 1 (infeasible to interpolate) + std::vector points; + points.push_back(createPoint(1.0, 0.0, 0.0)); + + EXPECT_THROW(interpolation::slerpYawFromPoints(points), std::logic_error); + } + + { // straight: size of base_keys is 2 (edge case in the implementation) + std::vector points; + points.push_back(createPoint(1.0, 0.0, 0.0)); + points.push_back(createPoint(2.0, 1.5, 0.0)); + + const std::vector ans{0.9827937, 0.9827937}; + + const auto yaws = interpolation::slerpYawFromPoints(points); + for (size_t i = 0; i < yaws.size(); ++i) { + EXPECT_NEAR(yaws.at(i), ans.at(i), epsilon); + } + } + + { // straight: size of base_keys is 3 (edge case in the implementation) + std::vector points; + points.push_back(createPoint(1.0, 0.0, 0.0)); + points.push_back(createPoint(2.0, 1.5, 0.0)); + points.push_back(createPoint(3.0, 3.0, 0.0)); + + const std::vector ans{0.9827937, 0.9827937, 0.9827937}; + + const auto yaws = interpolation::slerpYawFromPoints(points); + for (size_t i = 0; i < yaws.size(); ++i) { + EXPECT_NEAR(yaws.at(i), ans.at(i), epsilon); + } + } +} + +TEST(spline_interpolation, SplineInterpolation) +{ + SplineInterpolation s; + + // curve: query_keys is random + const std::vector base_keys{-1.5, 1.0, 5.0, 10.0, 15.0, 20.0}; + const std::vector base_values{-1.2, 0.5, 1.0, 1.2, 2.0, 1.0}; + const std::vector query_keys{0.0, 8.0, 18.0}; + const std::vector ans{-0.075611, 0.997242, 1.573258}; + + s.calcSplineCoefficients(base_keys, base_values); + const std::vector query_values = s.getSplineInterpolatedValues(query_keys); + + for (size_t i = 0; i < query_values.size(); ++i) { + EXPECT_NEAR(query_values.at(i), ans.at(i), epsilon); + } +} + +TEST(spline_interpolation, SplineInterpolationPoints2d) +{ + using tier4_autoware_utils::createPoint; + + SplineInterpolationPoints2d s; + + // curve + std::vector points; + points.push_back(createPoint(-2.0, -10.0, 0.0)); + points.push_back(createPoint(2.0, 1.5, 0.0)); + points.push_back(createPoint(3.0, 3.0, 0.0)); + points.push_back(createPoint(5.0, 10.0, 0.0)); + points.push_back(createPoint(10.0, 12.5, 0.0)); + + s.calcSplineCoefficients(points); + + { // point + // front + const auto front_point = s.getSplineInterpolatedPoint(0, 0.0); + EXPECT_NEAR(front_point.x, -2.0, epsilon); + EXPECT_NEAR(front_point.y, -10.0, epsilon); + + // back + const auto back_point = s.getSplineInterpolatedPoint(4, 0.0); + EXPECT_NEAR(back_point.x, 10.0, epsilon); + EXPECT_NEAR(back_point.y, 12.5, epsilon); + + // random + const auto random_point = s.getSplineInterpolatedPoint(3, 0.5); + EXPECT_NEAR(random_point.x, 5.3036484, epsilon); + EXPECT_NEAR(random_point.y, 10.3343074, epsilon); + + // out of range of total length + const auto front_out_point = s.getSplineInterpolatedPoint(0.0, -0.1); + EXPECT_NEAR(front_out_point.x, -2.0, epsilon); + EXPECT_NEAR(front_out_point.y, -10.0, epsilon); + + const auto back_out_point = s.getSplineInterpolatedPoint(4.0, 0.1); + EXPECT_NEAR(back_out_point.x, 10.0, epsilon); + EXPECT_NEAR(back_out_point.y, 12.5, epsilon); + + // out of range of index + EXPECT_THROW(s.getSplineInterpolatedPoint(-1, 0.0), std::out_of_range); + EXPECT_THROW(s.getSplineInterpolatedPoint(5, 0.0), std::out_of_range); + } + + { // yaw + // front + EXPECT_NEAR(s.getSplineInterpolatedYaw(0, 0.0), 1.3593746, epsilon); + + // back + EXPECT_NEAR(s.getSplineInterpolatedYaw(4, 0.0), 0.2932783, epsilon); + + // random + EXPECT_NEAR(s.getSplineInterpolatedYaw(3, 0.5), 0.7757198, epsilon); + + // out of range of total length + EXPECT_NEAR(s.getSplineInterpolatedYaw(0.0, -0.1), 1.3593746, epsilon); + EXPECT_NEAR(s.getSplineInterpolatedYaw(4, 0.1), 0.2932783, epsilon); + + // out of range of index + EXPECT_THROW(s.getSplineInterpolatedYaw(-1, 0.0), std::out_of_range); + EXPECT_THROW(s.getSplineInterpolatedYaw(5, 0.0), std::out_of_range); + } + + { // accumulated distance + // front + EXPECT_NEAR(s.getAccumulatedLength(0), 0.0, epsilon); + + // back + EXPECT_NEAR(s.getAccumulatedLength(4), 26.8488511, epsilon); + + // random + EXPECT_NEAR(s.getAccumulatedLength(3), 21.2586811, epsilon); + + // out of range of index + EXPECT_THROW(s.getAccumulatedLength(-1), std::out_of_range); + EXPECT_THROW(s.getAccumulatedLength(5), std::out_of_range); + } + + // size of base_keys is 1 (infeasible to interpolate) + std::vector single_points; + single_points.push_back(createPoint(1.0, 0.0, 0.0)); + EXPECT_THROW(s.calcSplineCoefficients(single_points), std::logic_error); +} From ca45e4aa3af8837fd1853f69d036ea9c1ec2d2a3 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 17 Feb 2022 11:46:17 +0900 Subject: [PATCH 07/37] fix(motion_velocity_smoother): fix bug in merge filter (#393) --- .../src/smoother/jerk_filtered_smoother.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/planning/motion_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp b/planning/motion_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp index 7809c7b4828a6..9ab84b5ecf951 100644 --- a/planning/motion_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/motion_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -424,8 +424,7 @@ TrajectoryPoints JerkFilteredSmoother::mergeFilteredTrajectory( if (getVx(backward_filtered, 0) < v0) { double current_vel = v0; double current_acc = a0; - while (getVx(backward_filtered, i) < current_vel && current_vel <= getVx(forward_filtered, i) && - i < merged.size() - 1) { + while (getVx(backward_filtered, i) < current_vel && i < merged.size() - 1) { merged.at(i).longitudinal_velocity_mps = current_vel; merged.at(i).acceleration_mps2 = current_acc; @@ -443,6 +442,10 @@ TrajectoryPoints JerkFilteredSmoother::mergeFilteredTrajectory( current_vel = current_vel + current_acc * dt + 0.5 * j_min * dt * dt; current_acc = current_acc + j_min * dt; } + + if (current_vel > getVx(forward_filtered, i)) { + current_vel = getVx(forward_filtered, i); + } ++i; } } From 4ecc4de258fa31aab19fb1965d9285189b100c2b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 18 Feb 2022 11:35:50 +0900 Subject: [PATCH 08/37] feat(pointcloud_preprocessor): use unordered_map in ring_outlier_filter (#310) Signed-off-by: kosuke55 --- .../ring_outlier_filter_nodelet.cpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) 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 0529066e62cb8..5667accdfdbf0 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 @@ -43,15 +43,16 @@ void RingOutlierFilterComponent::filter( if (input->row_step < 1) { return; } - std::vector> input_ring_array(128); + std::unordered_map> input_ring_map; + input_ring_map.reserve(128); sensor_msgs::msg::PointCloud2::SharedPtr input_ptr = std::make_shared(*input); const auto ring_offset = input->fields.at(static_cast(autoware_point_types::PointIndex::Ring)).offset; for (std::size_t idx = 0U; idx < input_ptr->data.size(); idx += input_ptr->point_step) { - input_ring_array.at(*reinterpret_cast(&input_ptr->data[idx + ring_offset])) - .emplace_back(idx); + input_ring_map[*reinterpret_cast(&input_ptr->data[idx + ring_offset])].push_back( + idx); } PointCloud2Modifier output_modifier{output, input->header.frame_id}; @@ -64,14 +65,14 @@ void RingOutlierFilterComponent::filter( 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; - for (const auto & ring_indices : input_ring_array) { - if (ring_indices.size() < 2) { + for (const auto & ring_indices : input_ring_map) { + if (ring_indices.second.size() < 2) { continue; } - for (size_t idx = 0U; idx < ring_indices.size() - 1; ++idx) { - const auto & current_idx = ring_indices.at(idx); - const auto & next_idx = ring_indices.at(idx + 1); + for (size_t idx = 0U; idx < ring_indices.second.size() - 1; ++idx) { + const auto & current_idx = ring_indices.second.at(idx); + const auto & next_idx = ring_indices.second.at(idx + 1); tmp_indices.emplace_back(current_idx); // if(std::abs(iter->distance - (iter+1)->distance) <= std::sqrt(iter->distance) * 0.08) From 6447b109e72c57426a84297493ae539e19d2987a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 18 Feb 2022 11:43:55 +0900 Subject: [PATCH 09/37] feat(behavior_velocity_planner): use common calcSignedArcLength (#362) * feat(behavior_velocity_planner): use tier4_autoware_utils calcSignedArcLength Signed-off-by: kosuke55 * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/scene_module/detection_area/scene.cpp | 80 +--------------- .../src/scene_module/traffic_light/scene.cpp | 95 ++----------------- 2 files changed, 9 insertions(+), 166 deletions(-) diff --git a/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp index c8f6c034a8c37..1d8c136f03633 100644 --- a/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include @@ -28,82 +29,6 @@ namespace bg = boost::geometry; namespace { -std::pair findWayPointAndDistance( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const geometry_msgs::msg::Point & p) -{ - constexpr double max_lateral_dist = 3.0; - for (size_t i = 0; i < path.points.size() - 1; ++i) { - const auto & p_front = path.points.at(i).point.pose.position; - const auto & p_back = path.points.at(i + 1).point.pose.position; - - const double dx = p.x - p_front.x; - const double dy = p.y - p_front.y; - const double dx_wp = p_back.x - p_front.x; - const double dy_wp = p_back.y - p_front.y; - - const double theta = std::atan2(dy, dx) - std::atan2(dy_wp, dx_wp); - - const double dist = std::hypot(dx, dy); - const double dist_wp = std::hypot(dx_wp, dy_wp); - - // check lateral distance - if (std::fabs(dist * std::sin(theta)) > max_lateral_dist) { - continue; - } - - // if the point p is back of the way point, return negative distance - if (dist * std::cos(theta) < 0) { - return std::make_pair(static_cast(i), -1.0 * dist); - } - - if (dist * std::cos(theta) < dist_wp) { - return std::make_pair(static_cast(i), dist); - } - } - - // if the way point is not found, return negative distance from the way point at 0 - const double dx = p.x - path.points.front().point.pose.position.x; - const double dy = p.y - path.points.front().point.pose.position.y; - return std::make_pair(-1, -1.0 * std::hypot(dx, dy)); -} - -double calcArcLengthFromWayPoint( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int & src, const int & dst) -{ - double length = 0; - const size_t src_idx = src >= 0 ? static_cast(src) : 0; - const size_t dst_idx = dst >= 0 ? static_cast(dst) : 0; - for (size_t i = src_idx; i < dst_idx; ++i) { - const auto & p_front = path.points.at(i).point.pose.position; - const auto & p_back = path.points.at(i + 1).point.pose.position; - - length += std::hypot(p_back.x - p_front.x, p_back.y - p_front.y); - } - return length; -} - -double calcSignedArcLength( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) -{ - const std::pair src = findWayPointAndDistance(path, p1); - const std::pair dst = findWayPointAndDistance(path, p2); - if (dst.first == -1) { - const double dx = p1.x - p2.x; - const double dy = p1.y - p2.y; - return -1.0 * std::hypot(dx, dy); - } - - if (src.first < dst.first) { - return calcArcLengthFromWayPoint(path, src.first, dst.first) - src.second + dst.second; - } else if (src.first > dst.first) { - return -1.0 * (calcArcLengthFromWayPoint(path, dst.first, src.first) - dst.second + src.second); - } else { - return dst.second - src.second; - } -} - double calcSignedDistance(const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Point & p2) { Eigen::Affine3d map2p1; @@ -427,7 +352,8 @@ bool DetectionAreaModule::isOverLine( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const { - return calcSignedArcLength(path, self_pose.position, line_pose.position) < 0; + return tier4_autoware_utils::calcSignedArcLength( + path.points, self_pose.position, line_pose.position) < 0; } bool DetectionAreaModule::hasEnoughBrakingDistance( diff --git a/planning/behavior_velocity_planner/src/scene_module/traffic_light/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/traffic_light/scene.cpp index a19d71d3ad252..ce455ba278592 100644 --- a/planning/behavior_velocity_planner/src/scene_module/traffic_light/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/traffic_light/scene.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include // To be replaced by std::optional in C++17 @@ -32,93 +33,6 @@ namespace bg = boost::geometry; namespace { -std::pair findWayPointAndDistance( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const Eigen::Vector2d & p) -{ - constexpr double max_lateral_dist = 3.0; - for (size_t i = 0; i < input_path.points.size() - 1; ++i) { - const double dx = p.x() - input_path.points.at(i).point.pose.position.x; - const double dy = p.y() - input_path.points.at(i).point.pose.position.y; - const double dx_wp = input_path.points.at(i + 1).point.pose.position.x - - input_path.points.at(i).point.pose.position.x; - const double dy_wp = input_path.points.at(i + 1).point.pose.position.y - - input_path.points.at(i).point.pose.position.y; - - const double theta = std::atan2(dy, dx) - std::atan2(dy_wp, dx_wp); - - const double dist = std::hypot(dx, dy); - const double dist_wp = std::hypot(dx_wp, dy_wp); - - // check lateral distance - if (std::fabs(dist * std::sin(theta)) > max_lateral_dist) { - continue; - } - - // if the point p is back of the way point, return negative distance - if (dist * std::cos(theta) < 0) { - return std::make_pair(static_cast(i), -1.0 * dist); - } - - if (dist * std::cos(theta) < dist_wp) { - return std::make_pair(static_cast(i), dist); - } - } - - // if the way point is not found, return negative distance from the way point at 0 - const double dx = p.x() - input_path.points.at(0).point.pose.position.x; - const double dy = p.y() - input_path.points.at(0).point.pose.position.y; - return std::make_pair(-1, -1.0 * std::hypot(dx, dy)); -} - -double calcArcLengthFromWayPoint( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, const int & src, - const int & dst) -{ - double length = 0; - const size_t src_idx = src >= 0 ? static_cast(src) : 0; - const size_t dst_idx = dst >= 0 ? static_cast(dst) : 0; - for (size_t i = src_idx; i < dst_idx; ++i) { - const double dx_wp = input_path.points.at(i + 1).point.pose.position.x - - input_path.points.at(i).point.pose.position.x; - const double dy_wp = input_path.points.at(i + 1).point.pose.position.y - - input_path.points.at(i).point.pose.position.y; - length += std::hypot(dx_wp, dy_wp); - } - return length; -} - -double calcSignedArcLength( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, - const geometry_msgs::msg::Pose & p1, const Eigen::Vector2d & p2) -{ - std::pair src = - findWayPointAndDistance(input_path, Eigen::Vector2d(p1.position.x, p1.position.y)); - std::pair dst = findWayPointAndDistance(input_path, p2); - if (dst.first == -1) { - double dx = p1.position.x - p2.x(); - double dy = p1.position.y - p2.y(); - return -1.0 * std::hypot(dx, dy); - } - - if (src.first < dst.first) { - return calcArcLengthFromWayPoint(input_path, src.first, dst.first) - src.second + dst.second; - } else if (src.first > dst.first) { - return -1.0 * - (calcArcLengthFromWayPoint(input_path, dst.first, src.first) - dst.second + src.second); - } else { - return dst.second - src.second; - } -} - -[[maybe_unused]] double calcSignedDistance( - const geometry_msgs::msg::Pose & p1, const Eigen::Vector2d & p2) -{ - Eigen::Affine3d map2p1; - tf2::fromMsg(p1, map2p1); - auto basecoords_p2 = map2p1.inverse() * Eigen::Vector3d(p2.x(), p2.y(), p1.position.z); - return basecoords_p2.x() >= 0 ? basecoords_p2.norm() : -basecoords_p2.norm(); -} - bool getBackwardPointFromBasePoint( const Eigen::Vector2d & line_point1, const Eigen::Vector2d & line_point2, const Eigen::Vector2d & base_point, const double backward_length, Eigen::Vector2d & output_point) @@ -313,8 +227,11 @@ bool TrafficLightModule::modifyPathVelocity( } // Calculate dist to stop pose - const double signed_arc_length_to_stop_point = - calcSignedArcLength(input_path, self_pose.pose, stop_line_point); + geometry_msgs::msg::Point stop_line_point_msg; + stop_line_point_msg.x = stop_line_point.x(); + stop_line_point_msg.y = stop_line_point.y(); + const double signed_arc_length_to_stop_point = tier4_autoware_utils::calcSignedArcLength( + input_path.points, self_pose.pose.position, stop_line_point_msg); // Check state if (state_ == State::APPROACH) { From 2154e1f8107e41dd7d6d0a4bf13615a10e10175c Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 18 Feb 2022 14:01:51 +0900 Subject: [PATCH 10/37] fix: change the default mode of perception.launch (#409) * fix: change the default mode of perception.launch Signed-off-by: Kenji Miyake * chore: remove unnecessary comments Signed-off-by: Kenji Miyake * chore: remove default values Signed-off-by: Kenji Miyake --- launch/tier4_autoware_launch/launch/autoware.launch.xml | 4 +--- .../tier4_autoware_launch/launch/logging_simulator.launch.xml | 4 +--- .../launch/object_recognition/detection/detection.launch.xml | 3 +-- launch/tier4_perception_launch/launch/perception.launch.xml | 2 +- 4 files changed, 4 insertions(+), 9 deletions(-) diff --git a/launch/tier4_autoware_launch/launch/autoware.launch.xml b/launch/tier4_autoware_launch/launch/autoware.launch.xml index a96438ae5a40a..fc3116bbd1265 100644 --- a/launch/tier4_autoware_launch/launch/autoware.launch.xml +++ b/launch/tier4_autoware_launch/launch/autoware.launch.xml @@ -56,8 +56,7 @@ - - + @@ -70,7 +69,6 @@ - diff --git a/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml b/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml index adde77253073c..f9cdcface2657 100644 --- a/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml +++ b/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml @@ -84,8 +84,7 @@ - - + @@ -102,7 +101,6 @@ - diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 9288c881b3469..c0723af73b09c 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -1,9 +1,8 @@ - + - diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index c6026e60522fa..94414701a2f9c 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -3,7 +3,7 @@ - + From 5fabc5256d383088dff330e89a5cd24b86d33acf Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Fri, 18 Feb 2022 14:17:37 +0900 Subject: [PATCH 11/37] feat(behavior_velocity): apply and add max slowdown calculation utils (#388) * feat(behavior_velocity): add util to get max slow down velocity at target position Signed-off-by: tanaka3 * feat(behavior_velocity): apply slow down jerk accel limit Signed-off-by: tanaka3 * chore(behavior_velocity): consider edge case Signed-off-by: tanaka3 * chore(behavior_velocity): add behind ego case Signed-off-by: tanaka3 * chore(behavior_velocity): update comments and todos Signed-off-by: tanaka3 * chore(behavior_velocity): add discriminant as variable Signed-off-by: tanaka3 * ci(pre-commit): autofix * chore(behavior_velocity): fix typo Signed-off-by: tanaka3 * doc(behavior_velocity): add docs Signed-off-by: tanaka3 * chore(behavior_velocity): refactor Signed-off-by: taikitanaka * chore(behavior_velocity): change max slowdonw brake strength to a bit lower than emergency brake Signed-off-by: tanaka3 * chore(behavior_velocity): refactor min max Signed-off-by: tanaka3 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/occlusion_spot.param.yaml | 3 +- .../maximum_slowdown_velocity.svg | 4 + .../occlusion_spot/occlusion_spot_utils.hpp | 1 + .../include/utilization/util.hpp | 8 ++ .../occlusion-spot-design.md | 32 +++++-- .../scene_module/occlusion_spot/manager.cpp | 3 +- .../risk_predictive_braking.cpp | 10 ++- .../src/utilization/util.cpp | 86 +++++++++++++++++++ .../test/src/test_utilization.cpp | 35 ++++++++ 9 files changed, 168 insertions(+), 14 deletions(-) create mode 100644 planning/behavior_velocity_planner/docs/occlusion_spot/maximum_slowdown_velocity.svg diff --git a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml index 078305a1b7375..7ccda0468bac6 100644 --- a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml +++ b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml @@ -9,7 +9,8 @@ lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision motion: safety_ratio: 0.8 # [-] jerk/acceleration ratio for safety - max_slow_down_acceleration: -1.5 # [m/s^2] minimum deceleration for safe deceleration. + max_slow_down_jerk: -0.7 # [m/s^3] minimum jerk deceleration for safe brake. + max_slow_down_accel: -2.0 # [m/s^2] minimum accel deceleration for safe brake. non_effective_jerk: -0.3 # [m/s^3] weak jerk for velocity planning. non_effective_acceleration: -1.0 # [m/s^2] weak deceleration for velocity planning. min_allowed_velocity: 1.0 # [m/s] minimum velocity allowed diff --git a/planning/behavior_velocity_planner/docs/occlusion_spot/maximum_slowdown_velocity.svg b/planning/behavior_velocity_planner/docs/occlusion_spot/maximum_slowdown_velocity.svg new file mode 100644 index 0000000000000..e970eb3f87845 --- /dev/null +++ b/planning/behavior_velocity_planner/docs/occlusion_spot/maximum_slowdown_velocity.svg @@ -0,0 +1,4 @@ + + + +
t
v
t_{1}
x_{1}
x_{2}
const\ jerk
const \ accel
v_{1}


t_{1}=\frac{a_max-a_{0}}{j_max}...
t_{0}
v_{0}
x_{1}=\frac{j}{6}*t^3+\frac{a_{0...
t_{2}
x_{2}=\frac{a_{max}}{2}*t^2+v_{1...
a_{0}
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp index 260fdb40357be..dc6349dd12793 100644 --- a/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp @@ -77,6 +77,7 @@ struct Velocity double safety_ratio; // [-] safety margin for planning error double max_stop_jerk; // [m/s^3] emergency braking system jerk double max_stop_accel; // [m/s^2] emergency braking system deceleration + double max_slow_down_jerk; // [m/s^3] maximum allowed slowdown jerk double max_slow_down_accel; // [m/s^2] maximum allowed deceleration double non_effective_jerk; // [m/s^3] too weak jerk for velocity planning. double non_effective_accel; // [m/s^2] too weak deceleration for velocity planning. diff --git a/planning/behavior_velocity_planner/include/utilization/util.hpp b/planning/behavior_velocity_planner/include/utilization/util.hpp index 4926e53542ba0..24c71d056ba2f 100644 --- a/planning/behavior_velocity_planner/include/utilization/util.hpp +++ b/planning/behavior_velocity_planner/include/utilization/util.hpp @@ -137,6 +137,14 @@ double calcJudgeLineDistWithJerkLimit( const double velocity, const double acceleration, const double max_stop_acceleration, const double max_stop_jerk, const double delay_response_time); +double calcDecelerationVelocityFromDistanceToTarget( + const double max_slowdown_jerk, const double max_slowdown_accel, const double current_accel, + const double current_velocity, const double distance_to_target); + +double findReachTime( + const double jerk, const double accel, const double velocity, const double distance, + const double t_min, const double t_max); + tier4_planning_msgs::msg::StopReason initializeStopReason(const std::string & stop_reason); void appendStopReason( diff --git a/planning/behavior_velocity_planner/occlusion-spot-design.md b/planning/behavior_velocity_planner/occlusion-spot-design.md index 7dc1cb6330cd1..5d97f298106ff 100644 --- a/planning/behavior_velocity_planner/occlusion-spot-design.md +++ b/planning/behavior_velocity_planner/occlusion-spot-design.md @@ -51,7 +51,7 @@ This module considers any occlusion spot around ego path computed from the occup ##### The Concept of Safe Velocity -Safe velocity is calculated from the below parameters of ego emergency braking system and time to collision. +The safe slowdown velocity is calculated from the below parameters of ego emergency braking system and time to collision. - jerk limit[m/s^3] - deceleration limit[m/s2] @@ -60,6 +60,17 @@ Safe velocity is calculated from the below parameters of ego emergency braking s with these parameters we can briefly define safe motion before occlusion spot for ideal environment. ![occupancy_grid](./docs/occlusion_spot/safe_motion.svg) +##### Maximum Slowdown Velocity + +The maximum slowdown velocity is calculated from the below parameters of ego current velocity and acceleration with maximum slowdown jerk and maximum slowdown acceleration in order not to slowdown too much. + +- $j_{max}$ slowdown jerk limit[m/s^3] +- $a_{max}$ slowdown deceleration limit[m/s2] +- $v_{0}$ current velocity[m/s] +- $a_{0}$ current acceleration[m/s] + +![brief](./docs/occlusion_spot/maximum_slowdown_velocity.svg) + ##### Safe Behavior After Passing Safe Margin Point This module defines safe margin to consider ego distance to stop and collision path point geometrically. @@ -67,7 +78,7 @@ While ego is cruising from safe margin to collision path point, ego vehicle keep ![brief](./docs/occlusion_spot/behavior_after_safe_margin.svg) -##### Detection area polygon +##### DetectionArea Polygon Occlusion spot computation: searching occlusion spots for all cells in the occupancy_grid inside "max lateral distance" requires a lot of computational cost, so this module use only one most notable occlusion spot for each partition. (currently offset is from baselink to front for safety) The maximum length of detection area depends on ego current vehicle velocity and acceleration. @@ -86,13 +97,16 @@ The maximum length of detection area depends on ego current vehicle velocity and | `stuck_vehicle_vel` | double | [m/s] velocity below this value is assumed to stop | | `lateral_distance` | double | [m] maximum lateral distance to consider hidden collision | -| Parameter /motion | Type | Description | -| --------------------- | ------ | ------------------------------------------------------------ | -| `safety_ratio` | double | [-] safety ratio for jerk and acceleration | -| `max_slow_down_accel` | double | [m/s^2] deceleration to assume for predictive braking system | -| `v_min` | double | [m/s] minimum velocity not to stop | -| `delay_time` | double | [m/s] time buffer for the system delay | -| `safe_margin` | double | [m] maximum error to stop with emergency braking system. | +| Parameter /motion | Type | Description | +| ---------------------------- | ------ | -------------------------------------------------------- | +| `safety_ratio` | double | [-] safety ratio for jerk and acceleration | +| `max_slow_down_jerk` | double | [m/s^3] jerk for safe brake | +| `max_slow_down_accel` | double | [m/s^2] deceleration for safe brake | +| `non_effective_jerk` | double | [m/s^3] weak jerk for velocity planning. | +| `non_effective_acceleration` | double | [m/s^2] weak deceleration for velocity planning. | +| `min_allowed_velocity` | double | [m/s] minimum velocity allowed | +| `delay_time` | double | [m/s] time buffer for the system delay | +| `safe_margin` | double | [m] maximum error to stop with emergency braking system. | | Parameter /detection_area | Type | Description | | ------------------------- | ------ | --------------------------------------------------------------------- | diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp index 739fa9169c461..1ad0f5970c3f2 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/manager.cpp @@ -93,7 +93,8 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) pp.v.safety_ratio = node.declare_parameter(ns + ".motion.safety_ratio", 1.0); pp.v.delay_time = node.declare_parameter(ns + ".motion.delay_time", 0.1); pp.v.safe_margin = node.declare_parameter(ns + ".motion.safe_margin", 1.0); - pp.v.max_slow_down_accel = node.declare_parameter(ns + ".motion.max_slow_down_accel", -1.5); + pp.v.max_slow_down_jerk = node.declare_parameter(ns + ".motion.max_slow_down_jerk", -0.7); + pp.v.max_slow_down_accel = node.declare_parameter(ns + ".motion.max_slow_down_accel", -2.5); pp.v.non_effective_jerk = node.declare_parameter(ns + ".motion.non_effective_jerk", -0.3); pp.v.non_effective_accel = node.declare_parameter(ns + ".motion.non_effective_acceleration", -1.0); diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/risk_predictive_braking.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/risk_predictive_braking.cpp index ce6df41e80338..e2427b90ae055 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/risk_predictive_braking.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/risk_predictive_braking.cpp @@ -34,6 +34,8 @@ void applySafeVelocityConsideringPossibleCollision( return; } const double v0 = param.v.v_ego; + const double a0 = param.v.a_ego; + const double j_min = param.v.max_slow_down_jerk; const double a_min = param.v.max_slow_down_accel; const double v_min = param.v.min_allowed_velocity; for (auto & possible_collision : possible_collisions) { @@ -44,9 +46,11 @@ void applySafeVelocityConsideringPossibleCollision( const double v_safe = possible_collision.obstacle_info.safe_motion.safe_velocity; // min allowed velocity : min allowed velocity consider maximum allowed braking - const double v_slow_down = calculateMinSlowDownVelocity(v0, l_obs, a_min, v_safe); - - // coompare safe velocity consider EBS, minimum allowed velocity and original velocity + const double v_slow_down = + (l_obs < 0) + ? v_safe + : planning_utils::calcDecelerationVelocityFromDistanceToTarget(j_min, a_min, a0, v0, l_obs); + // compare safe velocity consider EBS, minimum allowed velocity and original velocity const double safe_velocity = calculateInsertVelocity(v_slow_down, v_safe, v_min, original_vel); possible_collision.obstacle_info.safe_motion.safe_velocity = safe_velocity; const auto & pose = possible_collision.collision_with_margin.pose; diff --git a/planning/behavior_velocity_planner/src/utilization/util.cpp b/planning/behavior_velocity_planner/src/utilization/util.cpp index 82c75705e06b5..b2f73a60d452d 100644 --- a/planning/behavior_velocity_planner/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner/src/utilization/util.cpp @@ -244,6 +244,92 @@ double calcJudgeLineDistWithJerkLimit( return std::max(0.0, x1 + x2 + x3); } +double findReachTime( + const double jerk, const double accel, const double velocity, const double distance, + const double t_min, const double t_max) +{ + const double j = jerk; + const double a = accel; + const double v = velocity; + const double d = distance; + const double min = t_min; + const double max = t_max; + auto f = [](const double t, const double j, const double a, const double v, const double d) { + return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; + }; + if (f(min, j, a, v, d) > 0 || f(max, j, a, v, d) < 0) { + std::logic_error("[behavior_velocity](findReachTime): search range is invalid"); + } + const double eps = 1e-5; + const int warn_iter = 100; + double lower = min; + double upper = max; + double t; + int iter = 0; + for (int i = 0;; i++) { + t = 0.5 * (lower + upper); + const double fx = f(t, j, a, v, d); + // std::cout<<"fx: "< 0.0) { + upper = t; + } else { + lower = t; + } + iter++; + if (iter > warn_iter) + std::cerr << "[behavior_velocity](findReachTime): current iter is over warning" << std::endl; + } + // std::cout<<"iter: "< 0 || max_slowdown_accel > 0) { + std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); + } + // case0: distance to target is behind ego + if (distance_to_target <= 0) return current_velocity; + auto ft = [](const double t, const double j, const double a, const double v, const double d) { + return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; + }; + auto vt = [](const double t, const double j, const double a, const double v) { + return j * t * t / 2.0 + a * t + v; + }; + const double j_max = max_slowdown_jerk; + const double a0 = current_accel; + const double a_max = max_slowdown_accel; + const double v0 = current_velocity; + const double l = distance_to_target; + const double t_const_jerk = (a_max - a0) / j_max; + const double d_const_jerk_stop = ft(t_const_jerk, j_max, a0, v0, 0.0); + const double d_const_acc_stop = l - d_const_jerk_stop; + + if (d_const_acc_stop < 0) { + // case0: distance to target is within constant jerk deceleration + // use binary search instead of solving cubic equation + const double t_jerk = findReachTime(j_max, a0, v0, l, 0, t_const_jerk); + const double velocity = vt(t_jerk, j_max, a0, v0); + return velocity; + } else { + const double v1 = vt(t_const_jerk, j_max, a0, v0); + const double discriminant_of_stop = 2.0 * a_max * d_const_acc_stop + v1 * v1; + // case3: distance to target is farther than distance to stop + if (discriminant_of_stop <= 0) { + return 0.0; + } + // case2: distance to target is within constant accel deceleration + // solve d = 0.5*a^2+v*t by t + const double t_acc = (-v1 + std::sqrt(discriminant_of_stop)) / a_max; + return vt(t_acc, 0.0, a_max, v1); + } + return current_velocity; +} + tier4_planning_msgs::msg::StopReason initializeStopReason(const std::string & stop_reason) { tier4_planning_msgs::msg::StopReason stop_reason_msg; diff --git a/planning/behavior_velocity_planner/test/src/test_utilization.cpp b/planning/behavior_velocity_planner/test/src/test_utilization.cpp index 4d16c285d0564..f2c557454b273 100644 --- a/planning/behavior_velocity_planner/test/src/test_utilization.cpp +++ b/planning/behavior_velocity_planner/test/src/test_utilization.cpp @@ -38,3 +38,38 @@ TEST(is_ahead_of, nominal) is_ahead = isAheadOf(target, origin); EXPECT_TRUE(is_ahead); } + +TEST(smoothDeceleration, calculateMaxSlowDownVelocity) +{ + using behavior_velocity_planner::planning_utils::calcDecelerationVelocityFromDistanceToTarget; + const double current_accel = 1.0; + const double current_velocity = 5.0; + const double max_slow_down_jerk = -1.0; + const double max_slow_down_accel = -2.0; + const double eps = 1e-3; + { + for (int i = -8; i <= 24; i += 8) { + // arc length in path point + const double l = i * 1.0; + const double v = calcDecelerationVelocityFromDistanceToTarget( + max_slow_down_jerk, max_slow_down_accel, current_accel, current_velocity, l); + // case 0 : behind ego + if (i == -8) EXPECT_NEAR(v, 5.0, eps); + // case 1 : const jerk + else if (i == 0) + EXPECT_NEAR(v, 5.0, eps); + // case 1 : const jerk + else if (i == 8) + EXPECT_NEAR(v, 5.380, eps); + // case 2 : const accel + else if (i == 16) + EXPECT_NEAR(v, 2.872, eps); + // case 3 : after stop + else if (i == 24) + EXPECT_NEAR(v, 0.00, eps); + else + continue; + std::cout << "s: " << l << " v: " << v << std::endl; + } + } +} From 0e70c7733e5c950bda5aa9db7b996aec14cd6c8f Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Fri, 18 Feb 2022 16:20:05 +0900 Subject: [PATCH 12/37] fix(accel_brake_map_calibrator): fix parameter file (#410) Signed-off-by: tomoya.kimura --- .../config/accel_brake_map_calibrator.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml index 30ffbf494297d..ffadfa4edd209 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/config/accel_brake_map_calibrator.param.yaml @@ -1,4 +1,4 @@ -accel_brake_map_calibrator: +/**: ros__parameters: update_hz: 10.0 initial_covariance: 0.05 From 6f000abc66ff1be919f72093ba8fd5b9ffa1d936 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Fri, 18 Feb 2022 19:18:50 +0900 Subject: [PATCH 13/37] feat(gyro_odometer): update readme (#412) * feat(gyro_odometer): update readme Signed-off-by: Yamato Ando * ci(pre-commit): autofix * modify sentences Signed-off-by: Yamato Ando * modify sentence Signed-off-by: Yamato Ando * fix sentences Signed-off-by: Yamato Ando * fix sentence Signed-off-by: Yamato Ando * fix sentence Signed-off-by: Yamato Ando * fix sentence Signed-off-by: Yamato Ando * fix sentence Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/gyro_odometer/README.md | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/localization/gyro_odometer/README.md b/localization/gyro_odometer/README.md index e4471ed3e58e7..dc8718f76449b 100644 --- a/localization/gyro_odometer/README.md +++ b/localization/gyro_odometer/README.md @@ -17,7 +17,6 @@ | Name | Type | Description | | ----------------------- | ------------------------------------------------ | ------------------------------- | -| `twist` | `geometry_msgs::msg::TwistStamped` | estimated twist | | `twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | estimated twist with covariance | ## Parameters @@ -28,4 +27,12 @@ ## Assumptions / Known limits -TBD. +- [Assumption] The frame_id of input twist message must be set to base_link. + +- [Assumption] The covariance in the input messages must be properly assigned. + +- [Assumption] The angular velocity is set to zero if both the longitudinal vehicle velocity and the angular velocity around the yaw axis are sufficiently small. This is for suppression of the IMU angular velocity bias. Without this process, we misestimate the vehicle status when stationary. + +- [Limitation] The frequency of the output messages depends on the frequency of the input IMU message. + +- [Limitation] We cannot produce reliable values for the lateral and vertical velocities. Therefore we assign large values to the corresponding elements in the output covariance matrix. From 0af7a423fc8c78838a0ea28bcbd8339cfe95ca56 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Fri, 18 Feb 2022 22:07:16 +0900 Subject: [PATCH 14/37] chore: add mermaid (#419) Signed-off-by: Kenji Miyake --- .pre-commit-config.yaml | 1 + mkdocs.yaml | 8 ++++++-- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 14528e5fec7c7..f3c030c55ed41 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -11,6 +11,7 @@ repos: - id: check-toml - id: check-xml - id: check-yaml + args: [--unsafe] - id: detect-private-key - id: end-of-file-fixer - id: mixed-line-ending diff --git a/mkdocs.yaml b/mkdocs.yaml index a5e536c87b589..3d29123093211 100644 --- a/mkdocs.yaml +++ b/mkdocs.yaml @@ -3,7 +3,7 @@ site_url: https://autowarefoundation.github.io/autoware.universe repo_url: https://github.com/autowarefoundation/autoware.universe edit_uri: edit/main/ docs_dir: . -copyright: Copyright © 2021 The Autoware Foundation +copyright: Copyright © 2022 The Autoware Foundation theme: name: material @@ -71,6 +71,10 @@ markdown_extensions: format: svg - pymdownx.arithmatex - pymdownx.highlight - - pymdownx.superfences + - pymdownx.superfences: + custom_fences: + - name: mermaid + class: mermaid + format: !!python/name:pymdownx.superfences.fence_code_format - toc: permalink: "#" From 702bbf644dd3c9508d59626d000d4edd885e6b83 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 19 Feb 2022 12:13:18 +0900 Subject: [PATCH 15/37] fix(simple psim): gear bug to update state in simple psim (#370) * fix(simple psim): gear bug to update state in simple psim Signed-off-by: Takayuki Murooka * upadte ideal acc geared model as well Signed-off-by: Takayuki Murooka --- .../sim_model_delay_steer_acc_geared.hpp | 6 ++- .../sim_model_ideal_steer_acc_geared.hpp | 6 ++- .../sim_model_delay_steer_acc_geared.cpp | 37 ++++++++++++------- .../sim_model_ideal_steer_acc_geared.cpp | 35 ++++++++++++------ 4 files changed, 54 insertions(+), 30 deletions(-) diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp index 3981a42a99fb9..da37a7825956c 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp @@ -142,11 +142,13 @@ class SimModelDelaySteerAccGeared : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; /** - * @brief calculate velocity with considering current velocity and gear + * @brief update state considering current gear * @param [in] state current state + * @param [in] prev_state previous state * @param [in] gear current gear (defined in autoware_auto_msgs/GearCommand) + * @param [in] dt delta time to update state */ - float64_t calcVelocityWithGear(const Eigen::VectorXd & state, const uint8_t gear) const; + void updateStateWithGear(Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt); }; #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp index 7158e170ed8b1..64a9e3109cf44 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp @@ -111,11 +111,13 @@ class SimModelIdealSteerAccGeared : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; /** - * @brief calculate velocity with considering current velocity and gear + * @brief update state considering current gear * @param [in] state current state + * @param [in] prev_state previous state * @param [in] gear current gear (defined in autoware_auto_msgs/GearCommand) + * @param [in] dt delta time to update state */ - float64_t calcVelocityWithGear(const Eigen::VectorXd & state, const uint8_t gear) const; + void updateStateWithGear(Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt); }; #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp index 092c672e311fa..0a16ce0d32454 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp @@ -58,17 +58,15 @@ void SimModelDelaySteerAccGeared::update(const float64_t & dt) delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front(); steer_input_queue_.pop_front(); - const auto prev_vx = state_(IDX::VX); - + const auto prev_state = state_; updateRungeKutta(dt, delayed_input); // take velocity limit explicitly state_(IDX::VX) = std::max(-vx_lim_, std::min(state_(IDX::VX), vx_lim_)); - state_(IDX::VX) = calcVelocityWithGear(state_, gear_); - - // calc acc directly after gear consideration - state_(IDX::ACCX) = (state_(IDX::VX) - prev_vx) / std::max(dt, 1.0e-5); + // consider gear + // update position and velocity first, and then acceleration is calculated naturally + updateStateWithGear(state_, prev_state, gear_, dt); } void SimModelDelaySteerAccGeared::initializeInputQueue(const float64_t & dt) @@ -107,9 +105,8 @@ Eigen::VectorXd SimModelDelaySteerAccGeared::calcModel( return d_state; } - -float64_t SimModelDelaySteerAccGeared::calcVelocityWithGear( - const Eigen::VectorXd & state, const uint8_t gear) const +void SimModelDelaySteerAccGeared::updateStateWithGear( + Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt) { using autoware_auto_vehicle_msgs::msg::GearCommand; if ( @@ -123,17 +120,29 @@ float64_t SimModelDelaySteerAccGeared::calcVelocityWithGear( gear == GearCommand::DRIVE_18 || gear == GearCommand::LOW || gear == GearCommand::LOW_2) { if (state(IDX::VX) < 0.0) { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } } else if (gear == GearCommand::REVERSE || gear == GearCommand::REVERSE_2) { if (state(IDX::VX) > 0.0) { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } } else if (gear == GearCommand::PARK) { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } else { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } - return state(IDX::VX); + state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); } diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp index 9f4b6663d05f5..8a8a55dffc538 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp @@ -33,13 +33,12 @@ float64_t SimModelIdealSteerAccGeared::getWz() float64_t SimModelIdealSteerAccGeared::getSteer() {return input_(IDX_U::STEER_DES);} void SimModelIdealSteerAccGeared::update(const float64_t & dt) { - const auto prev_vx = state_(IDX::VX); - + const auto prev_state = state_; updateRungeKutta(dt, input_); - state_(IDX::VX) = calcVelocityWithGear(state_, gear_); - - current_acc_ = (state_(IDX::VX) - prev_vx) / std::max(dt, 1.0e-5); + // consider gear + // update position and velocity first, and then acceleration is calculated naturally + updateStateWithGear(state_, prev_state, gear_, dt); } Eigen::VectorXd SimModelIdealSteerAccGeared::calcModel( @@ -59,8 +58,8 @@ Eigen::VectorXd SimModelIdealSteerAccGeared::calcModel( return d_state; } -float64_t SimModelIdealSteerAccGeared::calcVelocityWithGear( - const Eigen::VectorXd & state, const uint8_t gear) const +void SimModelIdealSteerAccGeared::updateStateWithGear( + Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt) { using autoware_auto_vehicle_msgs::msg::GearCommand; if ( @@ -74,17 +73,29 @@ float64_t SimModelIdealSteerAccGeared::calcVelocityWithGear( gear == GearCommand::DRIVE_18 || gear == GearCommand::LOW || gear == GearCommand::LOW_2) { if (state(IDX::VX) < 0.0) { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } } else if (gear == GearCommand::REVERSE || gear == GearCommand::REVERSE_2) { if (state(IDX::VX) > 0.0) { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } } else if (gear == GearCommand::PARK) { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } else { - return 0.0; + state(IDX::VX) = 0.0; + state(IDX::X) = prev_state(IDX::X); + state(IDX::Y) = prev_state(IDX::Y); + state(IDX::YAW) = prev_state(IDX::YAW); } - return state(IDX::VX); + current_acc_ = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); } From 10bd4c442beeb745de4d6d1de145447bd298b508 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 21 Feb 2022 11:52:44 +0900 Subject: [PATCH 16/37] feat(behavior_path_planner): make drivable area coordinate fixed to the map coordinate and make its size dynamic (#360) * make drivable area not to oscillate and its size dynamic Signed-off-by: Takayuki Murooka * update README for new parameters Signed-off-by: Takayuki Murooka * remove getLaneletScope from route_handler Signed-off-by: Takayuki Murooka * resolve temporary fix resolution multiplied by 10.0 Signed-off-by: Takayuki Murooka * dealt with edge case where length of a lane is too long Signed-off-by: Takayuki Murooka * rename function and put it in proper namespace Signed-off-by: Takayuki Murooka * update param for tier4_planning_launch Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe --- .../behavior_path_planner.param.yaml | 6 +- planning/behavior_path_planner/README.md | 22 ++ .../config/behavior_path_planner.param.yaml | 11 +- .../behavior_path_planner/parameters.hpp | 8 +- .../behavior_path_planner/utilities.hpp | 5 +- .../src/behavior_path_planner_node.cpp | 8 +- .../avoidance/avoidance_module.cpp | 3 +- .../lane_change/lane_change_module.cpp | 11 +- .../lane_following/lane_following_module.cpp | 3 +- .../scene_module/pull_out/pull_out_module.cpp | 17 +- .../pull_over/pull_over_module.cpp | 10 +- .../side_shift/side_shift_module.cpp | 3 +- .../behavior_path_planner/src/utilities.cpp | 247 ++++++++++++++++-- 13 files changed, 287 insertions(+), 67 deletions(-) diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml index fcdcf5c78cef0..dd8031b0438c6 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml @@ -8,7 +8,9 @@ minimum_lane_change_length: 12.0 minimum_pull_over_length: 16.0 drivable_area_resolution: 0.1 - drivable_area_width: 100.0 - drivable_area_height: 50.0 + drivable_lane_forward_length: 50.0 + drivable_lane_backward_length: 5.0 + drivable_lane_margin: 3.0 + drivable_area_margin: 6.0 refine_goal_search_radius_range: 7.5 intersection_search_distance: 30.0 diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index a6013e1a84da4..f07711647837a 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -53,6 +53,28 @@ The following modules are currently supported: ## Inner-workings / Algorithms +### Drivable Area Generation + +Drivable lanes are quantized and drawn on an image as a drivable area, whose resolution is `drivable_area_resolution`. +To prevent the quantization from causing instability to the planning modules, drivable area's pose follows the rules below. + +- Drivable area is generated in the map coordinate. +- Its position is quantized with `drivable_area_resolution`. +- Its orientation is 0. + +The size of the drivable area changes dynamically to realize both decreasing the computation cost and covering enough lanes to follow. +For the second purpose, the drivable area covers a certain length forward and backward lanes with some margins defined by parameters. + +#### Parameters for drivable area generation + +| Name | Unit | Type | Description | Default value | +| :---------------------------- | :--- | :----- | :------------------------------------------------------------------------- | :------------ | +| drivable_area_resolution | [m] | double | resolution of the image of the drivable area | 0.1 | +| drivable_lane_forward_length | [m] | double | length of the forward lane from the ego covered by the drivable area | 50.0 | +| drivable_lane_backward_length | [m] | double | length of the backward lane from the ego covered by the drivable area | 5.0 | +| drivable_lane_margin | [m] | double | forward and backward lane margin from the ego covered by the drivable area | 3.0 | +| drivable_area_margin | [m] | double | margin of width and height of the drivable area | 6.0 | + ### Behavior Tree In the behavior path planner, the behavior tree mechanism is used to manage which modules are activated in which situations. In general, this "behavior manager" like function is expected to become bigger as more and more modules are added in the future. To improve maintainability, we adopted the behavior tree. The behavior tree has the following advantages: easy visualization, easy configuration management (behaviors can be changed by replacing configuration files), and high scalability compared to the state machine. diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index a43aac42e6f29..7621cbd1c64e5 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -3,9 +3,16 @@ backward_path_length: 5.0 forward_path_length: 200.0 backward_length_buffer_for_end_of_lane: 5.0 + backward_length_buffer_for_end_of_pull_over: 5.0 + backward_length_buffer_for_end_of_pull_out: 5.0 minimum_lane_change_length: 12.0 + minimum_pull_over_length: 16.0 + drivable_area_resolution: 0.1 - drivable_area_width: 100.0 - drivable_area_height: 50.0 + drivable_lane_forward_length: 50.0 + drivable_lane_backward_length: 5.0 + drivable_lane_margin: 3.0 + drivable_area_margin: 6.0 + refine_goal_search_radius_range: 7.5 intersection_search_distance: 30.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp index fe5788a338dd1..c368217184681 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/parameters.hpp @@ -26,8 +26,12 @@ struct BehaviorPathPlannerParameters double minimum_pull_over_length; double minimum_pull_out_length; double drivable_area_resolution; - double drivable_area_width; - double drivable_area_height; + + double drivable_lane_forward_length; + double drivable_lane_backward_length; + double drivable_lane_margin; + double drivable_area_margin; + double refine_goal_search_radius_range; double turn_light_on_threshold_dis_lat; double turn_light_on_threshold_dis_long; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp index f49a932970473..487405eb0c22a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utilities.hpp @@ -248,9 +248,8 @@ cv::Point toCVPoint( const Point & geom_point, const double width_m, const double height_m, const double resolution); OccupancyGrid generateDrivableArea( - const lanelet::ConstLanelets & lanes, const PoseStamped & current_pose, const double width, - const double height, const double resolution, const double vehicle_length, - const RouteHandler & route_handler); + const lanelet::ConstLanelets & lanes, const double resolution, const double vehicle_length, + const std::shared_ptr planner_data); // goal management diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index fcafa0144dd66..778e292f2310a 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -151,9 +151,11 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() declare_parameter("backward_length_buffer_for_end_of_pull_out", 5.0); p.minimum_lane_change_length = declare_parameter("minimum_lane_change_length", 8.0); p.minimum_pull_over_length = declare_parameter("minimum_pull_over_length", 15.0); - p.drivable_area_resolution = declare_parameter("drivable_area_resolution", 0.1); - p.drivable_area_width = declare_parameter("drivable_area_width", 100.0); - p.drivable_area_height = declare_parameter("drivable_area_height", 50.0); + p.drivable_area_resolution = declare_parameter("drivable_area_resolution"); + p.drivable_lane_forward_length = declare_parameter("drivable_lane_forward_length"); + p.drivable_lane_backward_length = declare_parameter("drivable_lane_backward_length"); + p.drivable_lane_margin = declare_parameter("drivable_lane_margin"); + p.drivable_area_margin = declare_parameter("drivable_area_margin"); p.refine_goal_search_radius_range = declare_parameter("refine_goal_search_radius_range", 7.5); p.turn_light_on_threshold_dis_lat = declare_parameter("turn_light_on_threshold_dis_lat", 0.3); p.turn_light_on_threshold_dis_long = declare_parameter("turn_light_on_threshold_dis_long", 10.0); diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 1922cb97b1286..8a18c6450884c 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -1875,8 +1875,7 @@ void AvoidanceModule::generateExtendedDrivableArea(ShiftedPath * shifted_path) c { const auto & p = planner_data_->parameters; shifted_path->path.drivable_area = util::generateDrivableArea( - extended_lanelets, getEgoPose(), p.drivable_area_width, p.drivable_area_height, - p.drivable_area_resolution, p.vehicle_length, *(planner_data_->route_handler)); + extended_lanelets, p.drivable_area_resolution, p.vehicle_length, planner_data_); } } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp index cd563228ec4eb..472d59a4d9a0d 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/lane_change_module.cpp @@ -134,18 +134,14 @@ BehaviorModuleOutput LaneChangeModule::plan() auto path = util::resamplePathWithSpline(status_.lane_change_path.path, RESAMPLE_INTERVAL); // Generate drivable area { - const auto & route_handler = planner_data_->route_handler; const auto common_parameters = planner_data_->parameters; lanelet::ConstLanelets lanes; lanes.insert(lanes.end(), status_.current_lanes.begin(), status_.current_lanes.end()); lanes.insert(lanes.end(), status_.lane_change_lanes.begin(), status_.lane_change_lanes.end()); - const double width = common_parameters.drivable_area_width; - const double height = common_parameters.drivable_area_height; const double resolution = common_parameters.drivable_area_resolution; path.drivable_area = util::generateDrivableArea( - lanes, *(planner_data_->self_pose), width, height, resolution, - common_parameters.vehicle_length, *route_handler); + lanes, resolution, common_parameters.vehicle_length, planner_data_); } if (isAbortConditionSatisfied()) { @@ -255,9 +251,8 @@ PathWithLaneId LaneChangeModule::getReferencePath() const *route_handler, reference_path, current_lanes, parameters_.lane_change_prepare_duration, lane_change_buffer); reference_path.drivable_area = util::generateDrivableArea( - current_lanes, *planner_data_->self_pose, common_parameters.drivable_area_width, - common_parameters.drivable_area_height, common_parameters.drivable_area_resolution, - common_parameters.vehicle_length, *planner_data_->route_handler); + current_lanes, common_parameters.drivable_area_resolution, common_parameters.vehicle_length, + planner_data_); return reference_path; } diff --git a/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp b/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp index 3382dc899241b..44b118bfe5e70 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_following/lane_following_module.cpp @@ -127,8 +127,7 @@ PathWithLaneId LaneFollowingModule::getReferencePath() const } reference_path.drivable_area = util::generateDrivableArea( - current_lanes, *planner_data_->self_pose, p.drivable_area_width, p.drivable_area_height, - p.drivable_area_resolution, p.vehicle_length, *route_handler); + current_lanes, p.drivable_area_resolution, p.vehicle_length, planner_data_); return reference_path; } diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp index d7afa1e308b27..a634d095f63a5 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp @@ -209,7 +209,6 @@ PathWithLaneId PullOutModule::planCandidate() const BehaviorModuleOutput PullOutModule::planWaitingApproval() { BehaviorModuleOutput out; - const auto & route_handler = planner_data_->route_handler; const auto common_parameters = planner_data_->parameters; const auto current_lanes = getCurrentLanes(); const auto shoulder_lanes = getPullOutLanes(current_lanes); @@ -221,12 +220,9 @@ BehaviorModuleOutput PullOutModule::planWaitingApproval() lanelet::ConstLanelets lanes; lanes.insert(lanes.end(), current_lanes.begin(), current_lanes.end()); lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end()); - const double width = common_parameters.drivable_area_width; - const double height = common_parameters.drivable_area_height; const double resolution = common_parameters.drivable_area_resolution; candidatePath.drivable_area = util::generateDrivableArea( - lanes, *(planner_data_->self_pose), width, height, resolution, - common_parameters.vehicle_length, *route_handler); + lanes, resolution, common_parameters.vehicle_length, planner_data_); } for (size_t i = 1; i < candidatePath.points.size(); i++) { candidatePath.points.at(i).point.longitudinal_velocity_mps = 0.0; @@ -297,12 +293,9 @@ void PullOutModule::updatePullOutStatus() lanes.insert(lanes.end(), current_lanes.begin(), current_lanes.end()); lanes.insert(lanes.end(), pull_out_lanes.begin(), pull_out_lanes.end()); - const double width = common_parameters.drivable_area_width; - const double height = common_parameters.drivable_area_height; const double resolution = common_parameters.drivable_area_resolution; status_.pull_out_path.path.drivable_area = util::generateDrivableArea( - lanes, *(planner_data_->self_pose), width, height, resolution, - common_parameters.vehicle_length, *route_handler); + lanes, resolution, common_parameters.vehicle_length, planner_data_); } const auto arclength_start = @@ -341,10 +334,8 @@ PathWithLaneId PullOutModule::getReferencePath() const parameters_.deceleration_interval, goal_pose); reference_path.drivable_area = util::generateDrivableArea( - pull_out_lanes, *planner_data_->self_pose, common_parameters.drivable_area_width, - common_parameters.drivable_area_height, common_parameters.drivable_area_resolution, - common_parameters.vehicle_length, *planner_data_->route_handler); - + pull_out_lanes, common_parameters.drivable_area_resolution, common_parameters.vehicle_length, + planner_data_); return reference_path; } diff --git a/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp b/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp index 2808e6845a157..195b482708a21 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_over/pull_over_module.cpp @@ -227,12 +227,9 @@ void PullOverModule::updatePullOverStatus() lanes.insert(lanes.end(), current_lanes.begin(), current_lanes.end()); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); - const double width = common_parameters.drivable_area_width; - const double height = common_parameters.drivable_area_height; const double resolution = common_parameters.drivable_area_resolution; status_.pull_over_path.path.drivable_area = util::generateDrivableArea( - lanes, *(planner_data_->self_pose), width, height, resolution, - common_parameters.vehicle_length, *route_handler); + lanes, resolution, common_parameters.vehicle_length, planner_data_); } const auto current_pose = planner_data_->self_pose->pose; @@ -271,9 +268,8 @@ PathWithLaneId PullOverModule::getReferencePath() const parameters_.deceleration_interval, goal_pose); reference_path.drivable_area = util::generateDrivableArea( - current_lanes, *planner_data_->self_pose, common_parameters.drivable_area_width, - common_parameters.drivable_area_height, common_parameters.drivable_area_resolution, - common_parameters.vehicle_length, *planner_data_->route_handler); + current_lanes, common_parameters.drivable_area_resolution, common_parameters.vehicle_length, + planner_data_); return reference_path; } diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index f32dbc8ee7848..2f601f600cfec 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -352,8 +352,7 @@ void SideShiftModule::adjustDrivableArea(ShiftedPath * path) const { const auto & p = planner_data_->parameters; path->path.drivable_area = util::generateDrivableArea( - extended_lanelets, *(planner_data_->self_pose), p.drivable_area_width, p.drivable_area_height, - p.drivable_area_resolution, p.vehicle_length, *(planner_data_->route_handler)); + extended_lanelets, p.drivable_area_resolution, p.vehicle_length, planner_data_); } } diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 937476b414a1d..51a05797e4c34 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -26,6 +26,183 @@ #include #include +namespace drivable_area_utils +{ +double quantize(const double val, const double resolution) +{ + return std::round(val / resolution) * resolution; +} + +void updateMinMaxPosition( + const Eigen::Vector2d & point, double & min_x, double & min_y, double & max_x, double & max_y) +{ + min_x = std::min(min_x, point.x()); + min_y = std::min(min_y, point.y()); + max_x = std::max(max_x, point.x()); + max_y = std::max(max_y, point.y()); +} + +bool sumLengthFromTwoPoints( + const Eigen::Vector2d & base_point, const Eigen::Vector2d & target_point, + const double length_threshold, double & sum_length, double & min_x, double & min_y, + double & max_x, double & max_y) +{ + const double norm_length = (base_point - target_point).norm(); + sum_length += norm_length; + if (length_threshold < sum_length) { + const double diff_length = norm_length - (sum_length - length_threshold); + const Eigen::Vector2d interpolated_point = + base_point + diff_length * (target_point - base_point).normalized(); + updateMinMaxPosition(interpolated_point, min_x, min_y, max_x, max_y); + + const bool is_end = true; + return is_end; + } + + updateMinMaxPosition(target_point, min_x, min_y, max_x, max_y); + const bool is_end = false; + return is_end; +} + +std::array getLaneletScope( + const lanelet::ConstLanelets & lanes, const size_t nearest_lane_idx, + const geometry_msgs::msg::Pose & current_pose, const double forward_lane_length, + const double backward_lane_length, const double lane_margin) +{ + // define functions to get right/left bounds as a vector + const auto get_bound_funcs = + std::vector>{ + [](const lanelet::ConstLanelet & lane) -> lanelet::ConstLineString2d { + return lane.rightBound2d(); + }, + [](const lanelet::ConstLanelet & lane) -> lanelet::ConstLineString2d { + return lane.leftBound2d(); + }}; + + // calculate min/max x and y + double min_x = current_pose.position.x; + double min_y = current_pose.position.y; + double max_x = current_pose.position.x; + double max_y = current_pose.position.y; + + for (const auto & get_bound_func : get_bound_funcs) { + // search nearest point index to current pose + const auto & nearest_bound = get_bound_func(lanes.at(nearest_lane_idx)); + if (nearest_bound.empty()) { + continue; + } + + std::vector points; + for (const auto & point : nearest_bound) { + geometry_msgs::msg::Point p; + p.x = point.x(); + p.y = point.y(); + points.push_back(p); + } + const size_t nearest_point_idx = + tier4_autoware_utils::findNearestIndex(points, current_pose.position); + + drivable_area_utils::updateMinMaxPosition( + nearest_bound[nearest_point_idx].basicPoint(), min_x, min_y, max_x, max_y); + + // forward lanelet + double sum_length = 0.0; + size_t current_lane_idx = nearest_lane_idx; + auto current_lane = lanes.at(current_lane_idx); + size_t current_point_idx = nearest_point_idx; + while (true) { + const auto & bound = get_bound_func(current_lane); + if (current_point_idx != bound.size() - 1) { + const Eigen::Vector2d & current_point = bound[current_point_idx].basicPoint(); + const Eigen::Vector2d & next_point = bound[current_point_idx + 1].basicPoint(); + const bool is_end_lane = drivable_area_utils::sumLengthFromTwoPoints( + current_point, next_point, forward_lane_length + lane_margin, sum_length, min_x, min_y, + max_x, max_y); + if (is_end_lane) { + break; + } + + ++current_point_idx; + } else { + const auto previous_lane = current_lane; + const size_t previous_point_idx = get_bound_func(previous_lane).size() - 1; + const auto & previous_bound = get_bound_func(previous_lane); + drivable_area_utils::updateMinMaxPosition( + previous_bound[previous_point_idx].basicPoint(), min_x, min_y, max_x, max_y); + + if (current_lane_idx == lanes.size() - 1) { + break; + } + + current_lane_idx += 1; + current_lane = lanes.at(current_lane_idx); + current_point_idx = 0; + const auto & current_bound = get_bound_func(current_lane); + + const Eigen::Vector2d & prev_point = + get_bound_func(previous_lane)[previous_point_idx].basicPoint(); + const Eigen::Vector2d & current_point = + get_bound_func(current_lane)[current_point_idx].basicPoint(); + const bool is_end_lane = drivable_area_utils::sumLengthFromTwoPoints( + prev_point, current_point, forward_lane_length + lane_margin, sum_length, min_x, min_y, + max_x, max_y); + if (is_end_lane) { + break; + } + } + } + + // backward lanelet + current_point_idx = nearest_point_idx; + sum_length = 0.0; + current_lane_idx = nearest_lane_idx; + current_lane = lanes.at(current_lane_idx); + while (true) { + const auto & bound = get_bound_func(current_lane); + if (current_point_idx != 0) { + const Eigen::Vector2d & current_point = bound[current_point_idx].basicPoint(); + const Eigen::Vector2d & prev_point = bound[current_point_idx - 1].basicPoint(); + const bool is_end_lane = drivable_area_utils::sumLengthFromTwoPoints( + current_point, prev_point, backward_lane_length + lane_margin, sum_length, min_x, min_y, + max_x, max_y); + if (is_end_lane) { + break; + } + + --current_point_idx; + } else { + const auto next_lane = current_lane; + const size_t next_point_idx = 0; + const auto & next_bound = get_bound_func(next_lane); + drivable_area_utils::updateMinMaxPosition( + next_bound[next_point_idx].basicPoint(), min_x, min_y, max_x, max_y); + + if (current_lane_idx == 0) { + break; + } + + current_lane_idx -= 1; + current_lane = lanes.at(current_lane_idx); + const auto & current_bound = get_bound_func(current_lane); + current_point_idx = current_bound.size() - 1; + + const Eigen::Vector2d & next_point = get_bound_func(next_lane)[next_point_idx].basicPoint(); + const Eigen::Vector2d & current_point = + get_bound_func(current_lane)[current_point_idx].basicPoint(); + const bool is_end_lane = drivable_area_utils::sumLengthFromTwoPoints( + next_point, current_point, backward_lane_length + lane_margin, sum_length, min_x, min_y, + max_x, max_y); + if (is_end_lane) { + break; + } + } + } + } + + return {min_x, min_y, max_x, max_y}; +} +} // namespace drivable_area_utils + namespace behavior_path_planner { namespace util @@ -915,14 +1092,46 @@ bool containsGoal(const lanelet::ConstLanelets & lanes, const lanelet::Id & goal // input lanes must be in sequence OccupancyGrid generateDrivableArea( - const lanelet::ConstLanelets & lanes, const PoseStamped & current_pose, const double width, - const double height, const double resolution, const double vehicle_length, - const RouteHandler & route_handler) + const lanelet::ConstLanelets & lanes, const double resolution, const double vehicle_length, + const std::shared_ptr planner_data) { - // get drivable lanes + const auto & params = planner_data->parameters; + const auto route_handler = planner_data->route_handler; + const auto current_pose = planner_data->self_pose; + + // search closest lanelet to current pose from given lanelets + const int nearest_lane_idx = [&]() -> int { + lanelet::ConstLanelet closest_lanelet; + if (lanelet::utils::query::getClosestLanelet(lanes, current_pose->pose, &closest_lanelet)) { + for (size_t i = 0; i < lanes.size(); ++i) { + if (lanes.at(i).id() == closest_lanelet.id()) { + return i; + } + } + } + return 0; + }(); + + // calculate min/max x and y + const auto lanelet_scope = drivable_area_utils::getLaneletScope( + lanes, nearest_lane_idx, current_pose->pose, params.drivable_lane_forward_length, + params.drivable_lane_backward_length, params.drivable_lane_margin); + + const double min_x = + drivable_area_utils::quantize(lanelet_scope.at(0) - params.drivable_area_margin, resolution); + const double min_y = + drivable_area_utils::quantize(lanelet_scope.at(1) - params.drivable_area_margin, resolution); + const double max_x = + drivable_area_utils::quantize(lanelet_scope.at(2) + params.drivable_area_margin, resolution); + const double max_y = + drivable_area_utils::quantize(lanelet_scope.at(3) + params.drivable_area_margin, resolution); + + const double width = max_x - min_x; + const double height = max_y - min_y; + lanelet::ConstLanelets drivable_lanes = lanes; - if (containsGoal(lanes, route_handler.getGoalLaneId())) { - const auto lanes_after_goal = route_handler.getLanesAfterGoal(vehicle_length); + if (containsGoal(lanes, route_handler->getGoalLaneId())) { + const auto lanes_after_goal = route_handler->getLanesAfterGoal(vehicle_length); drivable_lanes.insert(drivable_lanes.end(), lanes_after_goal.begin(), lanes_after_goal.end()); } @@ -931,27 +1140,23 @@ OccupancyGrid generateDrivableArea( // calculate grid origin { - grid_origin.header = current_pose.header; - const double yaw = tf2::getYaw(current_pose.pose.orientation); - const double origin_offset_x_m = (-width / 4) * cos(yaw) - (-height / 2) * sin(yaw); - const double origin_offset_y_m = (-width / 4) * sin(yaw) + (-height / 2) * cos(yaw); - // Only current yaw should be considered as the orientation of grid_origin. - grid_origin.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); - grid_origin.pose.position.x = current_pose.pose.position.x + origin_offset_x_m; - grid_origin.pose.position.y = current_pose.pose.position.y + origin_offset_y_m; - grid_origin.pose.position.z = current_pose.pose.position.z; + grid_origin.header = current_pose->header; + + grid_origin.pose.position.x = min_x; + grid_origin.pose.position.y = min_y; + grid_origin.pose.position.z = current_pose->pose.position.z; } // header { - occupancy_grid.header.stamp = current_pose.header.stamp; + occupancy_grid.header.stamp = current_pose->header.stamp; occupancy_grid.header.frame_id = "map"; } // info { - const int width_cell = width / resolution; - const int height_cell = height / resolution; + const int width_cell = std::round(width / resolution); + const int height_cell = std::round(height / resolution); occupancy_grid.info.map_load_time = occupancy_grid.header.stamp; occupancy_grid.info.resolution = resolution; @@ -978,7 +1183,8 @@ OccupancyGrid generateDrivableArea( if (lane.hasAttribute("intersection_area")) { const std::string area_id = lane.attributeOr("intersection_area", "none"); - const auto intersection_area = route_handler.getIntersectionAreaById(atoi(area_id.c_str())); + const auto intersection_area = + route_handler->getIntersectionAreaById(atoi(area_id.c_str())); const auto poly = lanelet::utils::to2D(intersection_area).basicPolygon(); std::vector lane_polys{}; if (boost::geometry::intersection(poly, lane_poly, lane_polys)) { @@ -1398,8 +1604,7 @@ std::shared_ptr generateCenterLinePath( centerline_path->header = route_handler->getRouteHeader(); centerline_path->drivable_area = util::generateDrivableArea( - current_lanes, *pose, p.drivable_area_width, p.drivable_area_height, p.drivable_area_resolution, - p.vehicle_length, *route_handler); + current_lanes, p.drivable_area_resolution, p.vehicle_length, planner_data); return centerline_path; } From 4c424affd4c46a9e4ebf979fe64102dbbca65616 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Feb 2022 12:19:48 +0900 Subject: [PATCH 17/37] test(raw_vehicle_cmd_converter): add test (#415) * feat(raw_vehicle_cmd_converter): add test Signed-off-by: Takamasa Horibe * remove unused code Signed-off-by: Takamasa Horibe * remove unused code Signed-off-by: Takamasa Horibe --- .../raw_vehicle_cmd_converter/CMakeLists.txt | 9 + vehicle/raw_vehicle_cmd_converter/package.xml | 1 + .../test/map_data/test_accel_map.csv | 4 + .../test/map_data/test_brake_map.csv | 4 + .../test/map_data/test_steer_map.csv | 4 + .../test/test_raw_vehicle_cmd_converter.cpp | 165 ++++++++++++++++++ 6 files changed, 187 insertions(+) create mode 100644 vehicle/raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv create mode 100644 vehicle/raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv create mode 100644 vehicle/raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv create mode 100644 vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt index 89cf9abe24e49..0b8803e0fb46c 100644 --- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt @@ -38,12 +38,21 @@ rclcpp_components_register_node(raw_vehicle_cmd_converter_node_component if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + + # Unit tests + set(TEST_SOURCES + test/test_raw_vehicle_cmd_converter.cpp + ) + set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_raw_vehicle_cmd_converter) + ament_add_gtest(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} ${TEST_SOURCES}) + target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter raw_vehicle_cmd_converter_node_component) endif() ament_auto_package(INSTALL_TO_SHARE config data launch + test ) install(PROGRAMS scripts/plot_accel_brake_map.py diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index 971bf3ed8071e..c734fa6fba00d 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -21,6 +21,7 @@ rclpy + ament_cmake_gtest ament_lint_auto autoware_lint_common diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv b/vehicle/raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv new file mode 100644 index 0000000000000..48ac22d788204 --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/test/map_data/test_accel_map.csv @@ -0,0 +1,4 @@ +default,0.0, 10.0, 20.0 +0, 1.0, 11.0, 21.0 +0.5, 2.0, 22.0, 42.0 +1.0, 3.0, 33.0, 46.0 diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv b/vehicle/raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv new file mode 100644 index 0000000000000..40700dc192fd4 --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/test/map_data/test_brake_map.csv @@ -0,0 +1,4 @@ +default, 0.0, 10.0, 20.0 +0, -1.0, -11.0, -21.0 +0.5, -2.0, -22.0, -42.0 +1.0, -3.0, -33.0, -46.0 diff --git a/vehicle/raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv b/vehicle/raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv new file mode 100644 index 0000000000000..7ded51f8c6631 --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/test/map_data/test_steer_map.csv @@ -0,0 +1,4 @@ +default,-10, 0, 10 +-10, -10, -10, -10 + 0, 0, 0, 0 +10, 10, 10, 10 diff --git a/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp b/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp new file mode 100644 index 0000000000000..5c59aa4b2f09f --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp @@ -0,0 +1,165 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ament_index_cpp/get_package_share_directory.hpp" +#include "gtest/gtest.h" +#include "raw_vehicle_cmd_converter/accel_map.hpp" +#include "raw_vehicle_cmd_converter/brake_map.hpp" +#include "raw_vehicle_cmd_converter/steer_converter.hpp" + +#include + +/* + * Throttle data: (vel, throttle -> acc) + * 0.0, 10.0, 20.0 (vel) + * 0, 1.0, 11.0, 21.0 + * 0.5, 2.0, 22.0, 42.0 + * 1.0, 3.0, 33.0, 46.0 + * (throttle) + * + * + * Brake data: (vel, brake -> acc) + * 0.0, 10.0, 20.0 (vel) + * 0, -1.0, -11.0, -21.0 + * 0.5, -2.0, -22.0, -42.0 + * 1.0, -3.0, -33.0, -46.0 + *(brake) + * + * + * Steer data: (steer, vol -> steer_rotation_rate) + * -10, 0, 10 (steer) + * -10, -10, -10, -10 + * 0, 0, 0, 0 + * 10, 10, 10, 10 + * (voltage) + * + */ + +using raw_vehicle_cmd_converter::AccelMap; +using raw_vehicle_cmd_converter::BrakeMap; +using raw_vehicle_cmd_converter::SteerConverter; + +// may throw PackageNotFoundError exception for invalid package +const auto map_path = + ament_index_cpp::get_package_share_directory("raw_vehicle_cmd_converter") + "/test/map_data/"; + +bool loadAccelMapData(AccelMap & accel_map) +{ + return accel_map.readAccelMapFromCSV(map_path + "test_accel_map.csv"); +} + +bool loadBrakeMapData(BrakeMap & brake_map) +{ + return brake_map.readBrakeMapFromCSV(map_path + "test_brake_map.csv"); +} + +bool loadSteerMapData(SteerConverter & steer_map) +{ + return steer_map.setFFMap(map_path + "test_steer_map.csv"); +} + +TEST(ConverterTests, LoadValidPath) +{ + AccelMap accel_map; + BrakeMap brake_map; + SteerConverter steer_map; + + // for valid path + EXPECT_TRUE(loadAccelMapData(accel_map)); + EXPECT_TRUE(loadBrakeMapData(brake_map)); + EXPECT_TRUE(loadSteerMapData(steer_map)); + + // for invalid path + EXPECT_FALSE(accel_map.readAccelMapFromCSV("invalid.csv")); + EXPECT_FALSE(brake_map.readBrakeMapFromCSV("invalid.csv")); + EXPECT_FALSE(steer_map.setFFMap("invalid.csv")); +} + +TEST(ConverterTests, AccelMapCalculation) +{ + AccelMap accel_map; + loadAccelMapData(accel_map); + const auto calcThrottle = [&](double acc, double vel) { + double output; + accel_map.getThrottle(acc, vel, output); + return output; + }; + + // case for min vel + EXPECT_DOUBLE_EQ(calcThrottle(1.0, 0.0), 0.0); + EXPECT_DOUBLE_EQ(calcThrottle(1.5, 0.0), 0.25); + EXPECT_DOUBLE_EQ(calcThrottle(3.0, 0.0), 1.0); + + // case for min throttle + EXPECT_DOUBLE_EQ(calcThrottle(6.0, 5.0), 0.0); + EXPECT_DOUBLE_EQ(calcThrottle(21.0, 20.0), 0.0); + + // case for direct access + EXPECT_DOUBLE_EQ(calcThrottle(22.0, 10.0), 0.5); + EXPECT_DOUBLE_EQ(calcThrottle(46.0, 20.0), 1.0); + + // case for interpolation + EXPECT_DOUBLE_EQ(calcThrottle(9.0, 5.0), 0.25); +} + +TEST(ConverterTests, BrakeMapCalculation) +{ + BrakeMap brake_map; + loadBrakeMapData(brake_map); + const auto calcBrake = [&](double acc, double vel) { + double output; + brake_map.getBrake(acc, vel, output); + return output; + }; + + // case for min vel + EXPECT_DOUBLE_EQ(calcBrake(-1.0, 0.0), 0.0); + EXPECT_DOUBLE_EQ(calcBrake(-1.5, 0.0), 0.25); + EXPECT_DOUBLE_EQ(calcBrake(-3.0, 0.0), 1.0); + + // case for min brake + EXPECT_DOUBLE_EQ(calcBrake(-6.0, 5.0), 0.0); + EXPECT_DOUBLE_EQ(calcBrake(-21.0, 20.0), 0.0); + + // case for direct access + EXPECT_DOUBLE_EQ(calcBrake(-22.0, 10.0), 0.5); + EXPECT_DOUBLE_EQ(calcBrake(-46.0, 20.0), 1.0); + + // case for interpolation + EXPECT_DOUBLE_EQ(calcBrake(-9.0, 5.0), 0.25); +} + +TEST(ConverterTests, SteerMapCalculation) +{ + SteerConverter steer_map; + loadSteerMapData(steer_map); + const auto calcSteer = [&](double steer_vel, double steer) { + return steer_map.calcFFSteer(steer_vel, steer); + }; + + // case for min steer + EXPECT_DOUBLE_EQ(calcSteer(-10.0, -10.0), -10.0); + EXPECT_DOUBLE_EQ(calcSteer(-5.0, -10.0), -5.0); + EXPECT_DOUBLE_EQ(calcSteer(10.0, -10.0), 10.0); + + // case for min voltage + EXPECT_DOUBLE_EQ(calcSteer(-10.0, 5.0), -10.0); + + // case for direct access + EXPECT_DOUBLE_EQ(calcSteer(0.0, 0.0), 0.0); + EXPECT_DOUBLE_EQ(calcSteer(10.0, 0.0), 10.0); + + // case for interpolation + EXPECT_DOUBLE_EQ(calcSteer(5.0, 5.0), 5.0); +} From 393a01b0ad29cc4507a2f672191b728c7d125e65 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Feb 2022 12:21:07 +0900 Subject: [PATCH 18/37] fix(obstacle_stop_planner): fix debug topic name (#395) * fix name Signed-off-by: Takamasa Horibe * modify namespace for debug topics Signed-off-by: Takamasa Horibe * fix plotJuggler confiig in slow down Signed-off-by: Takamasa Horibe * apply clang Signed-off-by: Takamasa Horibe --- .../config/plot_juggler_adaptive_cruise.xml | 26 +++++++++---------- .../config/plot_juggler_slow_down.xml | 18 ++++++------- .../src/adaptive_cruise_control.cpp | 4 +-- .../src/debug_marker.cpp | 3 ++- 4 files changed, 26 insertions(+), 25 deletions(-) diff --git a/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml b/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml index 0c66f8aa47c8e..5770820fbba1d 100644 --- a/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml +++ b/planning/obstacle_stop_planner/config/plot_juggler_adaptive_cruise.xml @@ -11,17 +11,17 @@ - + - + - + @@ -32,7 +32,7 @@ - + @@ -45,27 +45,27 @@ - + - + - + - + - + @@ -76,12 +76,12 @@ - + - + @@ -114,8 +114,8 @@ - - + + diff --git a/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml b/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml index f4480787d9711..cbb840b12552a 100644 --- a/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml +++ b/planning/obstacle_stop_planner/config/plot_juggler_slow_down.xml @@ -13,11 +13,11 @@ - - - - - + + + + + @@ -26,14 +26,14 @@ - + - + @@ -41,7 +41,7 @@ - + @@ -73,7 +73,7 @@ - + diff --git a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp index b7433bab21db4..df4209c6d1c99 100644 --- a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -179,8 +179,8 @@ AdaptiveCruiseController::AdaptiveCruiseController( param_.rough_velocity_rate = node_->declare_parameter(acc_ns + "rough_velocity_rate", 0.9); /* publisher */ - pub_debug_ = - node_->create_publisher("~/debug_values", 1); + pub_debug_ = node_->create_publisher( + "~/adaptive_cruise_control/debug_values", 1); } void AdaptiveCruiseController::insertAdaptiveCruiseVelocity( diff --git a/planning/obstacle_stop_planner/src/debug_marker.cpp b/planning/obstacle_stop_planner/src/debug_marker.cpp index 42358e1aed101..491d2b3dfd904 100644 --- a/planning/obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/obstacle_stop_planner/src/debug_marker.cpp @@ -41,7 +41,8 @@ ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode( node_->create_publisher("~/debug/marker", 1); stop_reason_pub_ = node_->create_publisher("~/output/stop_reasons", 1); - pub_debug_values_ = node_->create_publisher("~/debug/debug_values", 1); + pub_debug_values_ = + node_->create_publisher("~/obstacle_stop/debug_values", 1); } bool ObstacleStopPlannerDebugNode::pushPolygon( From 8e499f68c88cd74fe8e978c479b7e071cd5f9ff6 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Feb 2022 13:54:17 +0900 Subject: [PATCH 19/37] feat(interpolation): add float key lerp api (#416) Signed-off-by: Takamasa Horibe --- .../interpolation/linear_interpolation.hpp | 5 +++++ common/interpolation/src/linear_interpolation.cpp | 6 ++++++ .../test/src/test_linear_interpolation.cpp | 15 +++++++++++++++ 3 files changed, 26 insertions(+) diff --git a/common/interpolation/include/interpolation/linear_interpolation.hpp b/common/interpolation/include/interpolation/linear_interpolation.hpp index 181e4dd302b65..1f8155613111e 100644 --- a/common/interpolation/include/interpolation/linear_interpolation.hpp +++ b/common/interpolation/include/interpolation/linear_interpolation.hpp @@ -26,6 +26,11 @@ double lerp(const double src_val, const double dst_val, const double ratio); std::vector lerp( const std::vector & base_keys, const std::vector & base_values, const std::vector & query_keys); + +double lerp( + const std::vector & base_keys, const std::vector & base_values, + const double query_key); + } // namespace interpolation #endif // INTERPOLATION__LINEAR_INTERPOLATION_HPP_ diff --git a/common/interpolation/src/linear_interpolation.cpp b/common/interpolation/src/linear_interpolation.cpp index 48ae7c2501384..32d3654dbbdd8 100644 --- a/common/interpolation/src/linear_interpolation.cpp +++ b/common/interpolation/src/linear_interpolation.cpp @@ -50,4 +50,10 @@ std::vector lerp( return query_values; } + +double lerp( + const std::vector & base_keys, const std::vector & base_values, double query_key) +{ + return lerp(base_keys, base_values, std::vector{query_key}).front(); +} } // namespace interpolation diff --git a/common/interpolation/test/src/test_linear_interpolation.cpp b/common/interpolation/test/src/test_linear_interpolation.cpp index 49a9352f3daaa..9c392943bd3c5 100644 --- a/common/interpolation/test/src/test_linear_interpolation.cpp +++ b/common/interpolation/test/src/test_linear_interpolation.cpp @@ -77,3 +77,18 @@ TEST(linear_interpolation, lerp_vector) } } } + +TEST(linear_interpolation, lerp_scalar_query) +{ + { // curve: query_keys is same as random + const std::vector base_keys{-1.5, 1.0, 5.0, 10.0, 15.0, 20.0}; + const std::vector base_values{-1.2, 0.5, 1.0, 1.2, 2.0, 1.0}; + const std::vector query_keys{0.0, 8.0, 18.0}; + const std::vector ans{-0.18, 1.12, 1.4}; + + for (size_t i = 0; i < query_keys.size(); ++i) { + const auto query_value = interpolation::lerp(base_keys, base_values, query_keys.at(i)); + EXPECT_NEAR(query_value, ans.at(i), epsilon); + } + } +} From d29390a06048d5cdae3a93c6ef588b08adc8200f Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Feb 2022 16:22:19 +0900 Subject: [PATCH 20/37] refactor(raw_vehicle_cmd_converter): replace interpolate implementation with common library (#418) Signed-off-by: Takamasa Horibe --- .../raw_vehicle_cmd_converter/CMakeLists.txt | 1 - .../raw_vehicle_cmd_converter/accel_map.hpp | 1 - .../raw_vehicle_cmd_converter/brake_map.hpp | 1 - .../raw_vehicle_cmd_converter/interpolate.hpp | 33 ------ .../steer_converter.hpp | 1 - vehicle/raw_vehicle_cmd_converter/package.xml | 1 + .../src/accel_map.cpp | 16 ++- .../src/brake_map.cpp | 16 ++- .../src/interpolate.cpp | 102 ------------------ .../src/steer_converter.cpp | 11 +- 10 files changed, 18 insertions(+), 165 deletions(-) delete mode 100644 vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/interpolate.hpp delete mode 100644 vehicle/raw_vehicle_cmd_converter/src/interpolate.cpp diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt index 0b8803e0fb46c..1c9f4a097f8a6 100644 --- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt @@ -19,7 +19,6 @@ ament_auto_add_library(actuation_map_converter SHARED src/accel_map.cpp src/brake_map.cpp src/csv_loader.cpp - src/interpolate.cpp src/pid.cpp src/steer_converter.cpp ) diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp index 4c7bedfed93b4..bb872db838f18 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp @@ -16,7 +16,6 @@ #define RAW_VEHICLE_CMD_CONVERTER__ACCEL_MAP_HPP_ #include "raw_vehicle_cmd_converter/csv_loader.hpp" -#include "raw_vehicle_cmd_converter/interpolate.hpp" #include diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp index a5065d244877b..ba1fadfcd61c9 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp @@ -16,7 +16,6 @@ #define RAW_VEHICLE_CMD_CONVERTER__BRAKE_MAP_HPP_ #include "raw_vehicle_cmd_converter/csv_loader.hpp" -#include "raw_vehicle_cmd_converter/interpolate.hpp" #include diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/interpolate.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/interpolate.hpp deleted file mode 100644 index 99ac24f71d5a1..0000000000000 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/interpolate.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef RAW_VEHICLE_CMD_CONVERTER__INTERPOLATE_HPP_ -#define RAW_VEHICLE_CMD_CONVERTER__INTERPOLATE_HPP_ - -#include -#include -#include - -namespace raw_vehicle_cmd_converter -{ -class LinearInterpolate -{ -public: - static bool interpolate( - const std::vector & base_index, const std::vector & base_value, - const double & return_index, double & return_value); -}; -} // namespace raw_vehicle_cmd_converter - -#endif // RAW_VEHICLE_CMD_CONVERTER__INTERPOLATE_HPP_ diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp index b476e4554bd43..3574850ac712d 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp @@ -16,7 +16,6 @@ #define RAW_VEHICLE_CMD_CONVERTER__STEER_CONVERTER_HPP_ #include "raw_vehicle_cmd_converter/csv_loader.hpp" -#include "raw_vehicle_cmd_converter/interpolate.hpp" #include "raw_vehicle_cmd_converter/pid.hpp" #include diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index c734fa6fba00d..83db4c6233095 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -13,6 +13,7 @@ autoware_auto_control_msgs autoware_auto_vehicle_msgs geometry_msgs + interpolation nav_msgs rclcpp rclcpp_components diff --git a/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp b/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp index 7ee2955bc4ad2..84bbb54534610 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp @@ -14,6 +14,8 @@ #include "raw_vehicle_cmd_converter/accel_map.hpp" +#include "interpolation/linear_interpolation.hpp" + #include #include #include @@ -62,7 +64,6 @@ bool AccelMap::readAccelMapFromCSV(std::string csv_path) bool AccelMap::getThrottle(double acc, double vel, double & throttle) { - LinearInterpolate linear_interp; std::vector accs_interpolated; if (vel < vel_index_.front()) { @@ -83,9 +84,7 @@ bool AccelMap::getThrottle(double acc, double vel, double & throttle) // (throttle, vel, acc) map => (throttle, acc) map by fixing vel for (std::vector accs : accel_map_) { - double acc_interpolated; - linear_interp.interpolate(vel_index_, accs, vel, acc_interpolated); - accs_interpolated.push_back(acc_interpolated); + accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); } // calculate throttle @@ -97,14 +96,13 @@ bool AccelMap::getThrottle(double acc, double vel, double & throttle) throttle = throttle_index_.back(); return true; } - linear_interp.interpolate(accs_interpolated, throttle_index_, acc, throttle); + throttle = interpolation::lerp(accs_interpolated, throttle_index_, acc); return true; } bool AccelMap::getAcceleration(double throttle, double vel, double & acc) { - LinearInterpolate linear_interp; std::vector accs_interpolated; if (vel < vel_index_.front()) { @@ -125,9 +123,7 @@ bool AccelMap::getAcceleration(double throttle, double vel, double & acc) // (throttle, vel, acc) map => (throttle, acc) map by fixing vel for (std::vector accs : accel_map_) { - double acc_interpolated; - linear_interp.interpolate(vel_index_, accs, vel, acc_interpolated); - accs_interpolated.push_back(acc_interpolated); + accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); } // calculate throttle @@ -141,7 +137,7 @@ bool AccelMap::getAcceleration(double throttle, double vel, double & acc) throttle = std::min(std::max(throttle, min_throttle), max_throttle); } - linear_interp.interpolate(throttle_index_, accs_interpolated, throttle, acc); + acc = interpolation::lerp(throttle_index_, accs_interpolated, throttle); return true; } diff --git a/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp b/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp index bae57dfcbd50f..9446d90203db3 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp @@ -14,6 +14,8 @@ #include "raw_vehicle_cmd_converter/brake_map.hpp" +#include "interpolation/linear_interpolation.hpp" + #include #include #include @@ -63,7 +65,6 @@ bool BrakeMap::readBrakeMapFromCSV(std::string csv_path) bool BrakeMap::getBrake(double acc, double vel, double & brake) { - LinearInterpolate linear_interp; std::vector accs_interpolated; if (vel < vel_index_.front()) { @@ -84,9 +85,7 @@ bool BrakeMap::getBrake(double acc, double vel, double & brake) // (throttle, vel, acc) map => (throttle, acc) map by fixing vel for (std::vector accs : brake_map_) { - double acc_interpolated; - linear_interp.interpolate(vel_index_, accs, vel, acc_interpolated); - accs_interpolated.push_back(acc_interpolated); + accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); } // calculate brake @@ -106,14 +105,13 @@ bool BrakeMap::getBrake(double acc, double vel, double & brake) } std::reverse(std::begin(accs_interpolated), std::end(accs_interpolated)); - linear_interp.interpolate(accs_interpolated, brake_index_rev_, acc, brake); + brake = interpolation::lerp(accs_interpolated, brake_index_rev_, acc); return true; } bool BrakeMap::getAcceleration(double brake, double vel, double & acc) { - LinearInterpolate linear_interp; std::vector accs_interpolated; if (vel < vel_index_.front()) { @@ -134,9 +132,7 @@ bool BrakeMap::getAcceleration(double brake, double vel, double & acc) // (throttle, vel, acc) map => (throttle, acc) map by fixing vel for (std::vector accs : brake_map_) { - double acc_interpolated; - linear_interp.interpolate(vel_index_, accs, vel, acc_interpolated); - accs_interpolated.push_back(acc_interpolated); + accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); } // calculate brake @@ -150,7 +146,7 @@ bool BrakeMap::getAcceleration(double brake, double vel, double & acc) brake = std::min(std::max(brake, min_brake), max_brake); } - linear_interp.interpolate(brake_index_, accs_interpolated, brake, acc); + acc = interpolation::lerp(brake_index_, accs_interpolated, brake); return true; } diff --git a/vehicle/raw_vehicle_cmd_converter/src/interpolate.cpp b/vehicle/raw_vehicle_cmd_converter/src/interpolate.cpp deleted file mode 100644 index a9dc90c2a0179..0000000000000 --- a/vehicle/raw_vehicle_cmd_converter/src/interpolate.cpp +++ /dev/null @@ -1,102 +0,0 @@ -// Copyright 2021 Tier IV, Inc. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "raw_vehicle_cmd_converter/interpolate.hpp" - -#include - -/* - * linear interpolation - */ - -namespace raw_vehicle_cmd_converter -{ -bool LinearInterpolate::interpolate( - const std::vector & base_index, const std::vector & base_value, - const double & return_index, double & return_value) -{ - auto isIncrease = [](const std::vector & x) { - for (size_t i = 0; i < x.size() - 1; ++i) { - if (x[i] > x[i + 1]) { - return false; - } - } - return true; - }; - - if (base_index.size() == 0 || base_value.size() == 0) { - printf( - "[interpolate] some vector size is zero: base_index.size() = %lu, base_value.size() = %lu", - base_index.size(), base_value.size()); - return false; - } - - // check if inputs are valid - if ( - !isIncrease(base_index) || return_index < base_index.front() || - base_index.back() < return_index || base_index.size() != base_value.size()) { - std::cerr << "[isIncrease] bad index, return false" << std::endl; - bool b1 = !isIncrease(base_index); - bool b3 = return_index < base_index.front(); - bool b4 = base_index.back() < return_index; - bool b5 = base_index.size() != base_value.size(); - printf("%d, %d, %d, %d\n", b1, b3, b4, b5); - printf("base_index = [%f, %f]\n", base_index.front(), base_index.back()); - printf( - "base_index.size() = %lu, base_value.size() = %lu\n", base_index.size(), base_value.size()); - printf("base_index: ["); - for (size_t i = 0; i < base_index.size(); ++i) { - printf("%f, ", base_index.at(i)); - } - printf("]\n"); - printf("base_value: ["); - for (size_t i = 0; i < base_value.size(); ++i) { - printf("%f, ", base_value.at(i)); - } - printf("]\n"); - printf("return_index = %f\n", return_index); - return false; - } - - // calculate linear interpolation - size_t i = 0; - if (base_index[i] == return_index) { - return_value = base_value[i]; - return true; - } - while (base_index[i] < return_index) { - ++i; - } - if (i <= 0 || base_index.size() - 1 < i) { - std::cerr << "? something wrong. skip this return_index." << std::endl; - return false; - } - - const double dist_base_return_index = base_index[i] - base_index[i - 1]; - const double dist_to_forward = base_index[i] - return_index; - const double dist_to_backward = return_index - base_index[i - 1]; - if (dist_to_forward < 0.0 || dist_to_backward < 0.0) { - std::cerr << "?? something wrong. skip this return_index. base_index[i - 1] = " - << base_index[i - 1] << ", return_index = " << return_index - << ", base_index[i] = " << base_index[i] << std::endl; - return false; - } - - const double value = (dist_to_backward * base_value[i] + dist_to_forward * base_value[i - 1]) / - dist_base_return_index; - return_value = value; - - return true; -} -} // namespace raw_vehicle_cmd_converter diff --git a/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp b/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp index 0300ac61b19c9..a5247d984fee5 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp @@ -14,6 +14,8 @@ #include "raw_vehicle_cmd_converter/steer_converter.hpp" +#include "interpolation/linear_interpolation.hpp" + #include #include @@ -134,7 +136,6 @@ void SteerConverter::calcFFMap(double steer_vel, double vehicle_vel, double & ou { rclcpp::Clock clock{RCL_ROS_TIME}; - LinearInterpolate linear_interp; std::vector steer_angle_velocities_interp; if (vehicle_vel < vel_index_.front()) { @@ -154,16 +155,14 @@ void SteerConverter::calcFFMap(double steer_vel, double vehicle_vel, double & ou } for (std::vector steer_angle_velocities : steer_map_) { - double steer_angle_vel_interp; - linear_interp.interpolate( - vel_index_, steer_angle_velocities, vehicle_vel, steer_angle_vel_interp); - steer_angle_velocities_interp.push_back(steer_angle_vel_interp); + steer_angle_velocities_interp.push_back( + interpolation::lerp(vel_index_, steer_angle_velocities, vehicle_vel)); } if (steer_vel < steer_angle_velocities_interp.front()) { steer_vel = steer_angle_velocities_interp.front(); } else if (steer_angle_velocities_interp.back() < steer_vel) { steer_vel = steer_angle_velocities_interp.back(); } - linear_interp.interpolate(steer_angle_velocities_interp, output_index_, steer_vel, output); + output = interpolation::lerp(steer_angle_velocities_interp, output_index_, steer_vel); } } // namespace raw_vehicle_cmd_converter From 288db04b488ff3bf1c6ff01a659b0fdb6f0a827c Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Mon, 21 Feb 2022 20:43:10 +0900 Subject: [PATCH 21/37] chore(dummy_perception_publisher): change raytrace param (#414) Signed-off-by: tanaka3 --- simulator/dummy_perception_publisher/src/node.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/simulator/dummy_perception_publisher/src/node.cpp b/simulator/dummy_perception_publisher/src/node.cpp index da5939bccea7d..a14d083a4e2e4 100644 --- a/simulator/dummy_perception_publisher/src/node.cpp +++ b/simulator/dummy_perception_publisher/src/node.cpp @@ -180,7 +180,9 @@ void DummyPerceptionPublisherNode::timerCallback() new pcl::PointCloud); pcl::VoxelGridOcclusionEstimation ray_tracing_filter; ray_tracing_filter.setInputCloud(merged_pointcloud_ptr); - ray_tracing_filter.setLeafSize(0.25, 0.25, 0.25); + // above this value raytrace won't be as expected + const double leaf_size = 0.02; + ray_tracing_filter.setLeafSize(leaf_size, leaf_size, leaf_size); ray_tracing_filter.initializeVoxelGrid(); for (size_t i = 0; i < v_pointcloud.size(); ++i) { pcl::PointCloud::Ptr ray_traced_pointcloud_ptr( From 737773d0b1f4f3ccc089f9cd4b7e9c81a4d69231 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 21 Feb 2022 21:12:27 +0900 Subject: [PATCH 22/37] feat(tier4_autoware_launch)!: move package to autoware_launch (#420) * feat(tier4_autoware_launch)!: move package to autoware_launch Signed-off-by: Kenji Miyake * remove unnecessary depends Signed-off-by: Kenji Miyake --- launch/tier4_autoware_launch/CMakeLists.txt | 16 - launch/tier4_autoware_launch/README.md | 17 - .../autoware_launch.drawio.svg | 4 - .../launch/autoware.launch.xml | 83 - .../launch/logging_simulator.launch.xml | 125 -- .../launch/planning_simulator.launch.xml | 81 - .../launch/pointcloud_container.launch.py | 57 - launch/tier4_autoware_launch/package.xml | 33 - .../tier4_autoware_launch/rviz/autoware.rviz | 1546 ----------------- .../rviz/image/autoware.png | Bin 600002 -> 0 bytes .../launch/sensing.launch.xml | 2 +- launch/tier4_sensing_launch/package.xml | 3 - launch/tier4_vehicle_launch/README.md | 8 +- 13 files changed, 5 insertions(+), 1970 deletions(-) delete mode 100644 launch/tier4_autoware_launch/CMakeLists.txt delete mode 100644 launch/tier4_autoware_launch/README.md delete mode 100644 launch/tier4_autoware_launch/autoware_launch.drawio.svg delete mode 100644 launch/tier4_autoware_launch/launch/autoware.launch.xml delete mode 100644 launch/tier4_autoware_launch/launch/logging_simulator.launch.xml delete mode 100644 launch/tier4_autoware_launch/launch/planning_simulator.launch.xml delete mode 100644 launch/tier4_autoware_launch/launch/pointcloud_container.launch.py delete mode 100644 launch/tier4_autoware_launch/package.xml delete mode 100644 launch/tier4_autoware_launch/rviz/autoware.rviz delete mode 100644 launch/tier4_autoware_launch/rviz/image/autoware.png diff --git a/launch/tier4_autoware_launch/CMakeLists.txt b/launch/tier4_autoware_launch/CMakeLists.txt deleted file mode 100644 index 084841e864534..0000000000000 --- a/launch/tier4_autoware_launch/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(tier4_autoware_launch) - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_auto_package( - INSTALL_TO_SHARE - launch - rviz -) diff --git a/launch/tier4_autoware_launch/README.md b/launch/tier4_autoware_launch/README.md deleted file mode 100644 index 3956ff62d7d26..0000000000000 --- a/launch/tier4_autoware_launch/README.md +++ /dev/null @@ -1,17 +0,0 @@ -# tier4_autoware_launch - -## Structure - -![tier4_autoware_launch](./autoware_launch.drawio.svg) - -## Package Dependencies - -Please see `` in `package.xml`. - -## Usage - -You can use the command as follows at shell script to launch `*.launch.xml` in `launch` directory. - -```bash -ros2 launch tier4_autoware_launch autoware.launch.xml map_path:=/path/to/map_folder vehicle_model:=lexus sensor_model:=aip_xx1 -``` diff --git a/launch/tier4_autoware_launch/autoware_launch.drawio.svg b/launch/tier4_autoware_launch/autoware_launch.drawio.svg deleted file mode 100644 index ac312a784e220..0000000000000 --- a/launch/tier4_autoware_launch/autoware_launch.drawio.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - -
autoware.launch.xml

package: tier4_autoware_launch
autoware.launch.xml...
launch name

package: package name
launch name...
ex:
ex:
node name

package: package name
node name...
vehicle_info_launch.py

package: tier4_vehicle_launch
vehicle_info_launch.py...
vehicle.launch.xml

package: tier4_vehicle_launch
vehicle.launch.xml...
system.launch.xml

package: tier4_system_launch
system.launch.xml...
map.launch.py

package: tier4_map_launch
map.launch.py...
localization.launch.xml

package: tier4_localization_launch
localization.launch.xml...
perception.launch.xml

package: tier4_perception_launch
perception.launch.xml...
planning.launch.xml

package: tier4_planning_launch
planning.launch.xml...
control.launch.py

package: tier4_control_launch
control.launch.py...
awapi_awiv_adapter.launch.xml

package: tier4_control_launch
awapi_awiv_adapter.launch.xml...
web_controller.launch.xml

package: tier4_control_launch
web_controller.launch.xml...
clock_publisher.launch.xml

package: tier4_control_launch
clock_publisher.launch.xml...
rviz2

package: rviz2
rviz2...
planning_simulator.xml

package: tier4_autoware_launch
planning_simulator.xml...
vehicle_info_launch.py

package: tier4_vehicle_launch
vehicle_info_launch.py...
vehicle.launch.xml

package: tier4_vehicle_launch
vehicle.launch.xml...
system.launch.xml

package: tier4_system_launch
system.launch.xml...
map.launch.py

package: tier4_map_launch
map.launch.py...
planning.launch.xml

package: tier4_planning_launch
planning.launch.xml...
control.launch.py

package: tier4_control_launch
control.launch.py...
awapi_awiv_adapter.launch.xml

package: tier4_control_launch
awapi_awiv_adapter.launch.xml...
web_controller.launch.xml

package: tier4_control_launch
web_controller.launch.xml...
clock_publisher.launch.xml

package: tier4_control_launch
clock_publisher.launch.xml...
rviz2

package: rviz2
rviz2...
logging_simulator.launch.xml

package: tier4_autoware_launch
logging_simulator.launch.xml...
vehicle_info_launch.py

package: tier4_vehicle_launch
vehicle_info_launch.py...
vehicle_description.launch.xml

package: tier4_vehicle_launch
vehicle_description.launch.xml...
system.launch.xml

package: tier4_system_launch
system.launch.xml...
map.launch.py

package: tier4_map_launch
map.launch.py...
perception.launch.xml

package: tier4_perception_launch
perception.launch.xml...
planning.launch.xml

package: tier4_planning_launch
planning.launch.xml...
control.launch.py

package: tier4_control_launch
control.launch.py...
web_controller.launch.xml

package: tier4_control_launch
web_controller.launch.xml...
rviz2

package: rviz2
rviz2...
$(var vehicle)
$(var vehicle)
True
True
$(var system)
$(var system)
True
True
$(var map)
$(var map)
True
True
sensing.launch.xml

package: tier4_sensing_launch
sensing.launch.xml...
sensing.launch.xml

package: tier4_sensing_launch
sensing.launch.xml...
$(var sensing)
$(var sensing)
True
True
localization.launch.xml

package: tier4_localization_launch
localization.launch.xml...
$(var localization)
$(var localization)
True
True
$(var perception)
$(var perception)
True
True
$(var planning)
$(var planning)
True
True
$(var control)
$(var control)
True
True
simulator.launch.xml

package: tier4_simulator_launch
simulator.launch.xml...
simulator.launch.xml

package: tier4_simulator_launch
simulator.launch.xml...
Viewer does not support full SVG 1.1
\ No newline at end of file diff --git a/launch/tier4_autoware_launch/launch/autoware.launch.xml b/launch/tier4_autoware_launch/launch/autoware.launch.xml deleted file mode 100644 index fc3116bbd1265..0000000000000 --- a/launch/tier4_autoware_launch/launch/autoware.launch.xml +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml b/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml deleted file mode 100644 index f9cdcface2657..0000000000000 --- a/launch/tier4_autoware_launch/launch/logging_simulator.launch.xml +++ /dev/null @@ -1,125 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/tier4_autoware_launch/launch/planning_simulator.launch.xml b/launch/tier4_autoware_launch/launch/planning_simulator.launch.xml deleted file mode 100644 index 89bf669cb5455..0000000000000 --- a/launch/tier4_autoware_launch/launch/planning_simulator.launch.xml +++ /dev/null @@ -1,81 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/tier4_autoware_launch/launch/pointcloud_container.launch.py b/launch/tier4_autoware_launch/launch/pointcloud_container.launch.py deleted file mode 100644 index 87c46bce69cf7..0000000000000 --- a/launch/tier4_autoware_launch/launch/pointcloud_container.launch.py +++ /dev/null @@ -1,57 +0,0 @@ -# Copyright 2021 Tier IV, Inc. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.actions import SetLaunchConfiguration -from launch.conditions import IfCondition -from launch.conditions import UnlessCondition -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer - - -def generate_launch_description(): - def add_launch_arg(name: str, default_value=None): - return DeclareLaunchArgument(name, default_value=default_value) - - set_container_executable = SetLaunchConfiguration( - "container_executable", - "component_container", - condition=UnlessCondition(LaunchConfiguration("use_multithread")), - ) - - set_container_mt_executable = SetLaunchConfiguration( - "container_executable", - "component_container_mt", - condition=IfCondition(LaunchConfiguration("use_multithread")), - ) - - pointcloud_container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), - namespace="/", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[], - output="screen", - ) - - return LaunchDescription( - [ - add_launch_arg("use_multithread", "false"), - add_launch_arg("container_name", "pointcloud_container"), - set_container_executable, - set_container_mt_executable, - pointcloud_container, - ] - ) diff --git a/launch/tier4_autoware_launch/package.xml b/launch/tier4_autoware_launch/package.xml deleted file mode 100644 index e747a6d27c493..0000000000000 --- a/launch/tier4_autoware_launch/package.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - tier4_autoware_launch - 0.1.0 - The tier4_autoware_launch package - - Yukihiro Saito - Apache License 2.0 - - ament_cmake_auto - - global_parameter_loader - python3-bson - python3-tornado - rviz2 - tier4_control_launch - tier4_localization_launch - tier4_map_launch - tier4_perception_launch - tier4_planning_launch - tier4_sensing_launch - tier4_simulator_launch - tier4_system_launch - tier4_vehicle_launch - web_controller - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/launch/tier4_autoware_launch/rviz/autoware.rviz b/launch/tier4_autoware_launch/rviz/autoware.rviz deleted file mode 100644 index 6c592fcbeddd2..0000000000000 --- a/launch/tier4_autoware_launch/rviz/autoware.rviz +++ /dev/null @@ -1,1546 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: ~ - Splitter Ratio: 0.557669460773468 - Tree Height: 397 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: ~ - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: ~ - Name: Views - Splitter Ratio: 0.5 - - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel - Name: InitialPoseButtonPanel - - Class: rviz_common/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: {} - Update Interval: 0 - Value: false - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/SteeringAngle - Enabled: true - Left: 128 - Length: 256 - Name: SteeringAngle - Scale: 17 - Text Color: 25; 255; 240 - Top: 128 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /vehicle/status/steering_status - Value: true - Value height offset: 0 - - Class: rviz_plugins/ConsoleMeter - Enabled: true - Left: 512 - Length: 256 - Name: ConsoleMeter - Scale: 3 - Text Color: 25; 255; 240 - Top: 128 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /vehicle/status/velocity_status - Value: true - Value height offset: 0 - - Alpha: 0.999 - Class: rviz_plugins/VelocityHistory - Color Border Vel Max: 3 - Constant Color: - Color: 255; 255; 255 - Value: true - Enabled: true - Name: VelocityHistory - Scale: 0.30000001192092896 - Timeout: 10 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /vehicle/status/velocity_status - Value: true - - Alpha: 0.30000001192092896 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera0/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera0/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - camera1/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera1/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - camera2/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera2/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - camera3/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera3/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - camera4/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera4/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - camera5/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - camera5/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - gnss_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - livox_front_left: - Alpha: 0.999 - Show Axes: false - Show Trail: false - livox_front_left_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - livox_front_right: - Alpha: 0.999 - Show Axes: false - Show Trail: false - livox_front_right_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - sensor_kit_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - tamagawa/imu_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - traffic_light_left_camera/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - traffic_light_left_camera/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - traffic_light_right_camera/camera_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - traffic_light_right_camera/camera_optical_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - velodyne_left: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_left_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_rear: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_rear_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_right: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_right_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_top: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - velodyne_top_base_link: - Alpha: 0.999 - Show Axes: false - Show Trail: false - Value: true - Name: VehicleModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_plugins/PolarGridDisplay - Color: 255; 255; 255 - Delta Range: 10 - Enabled: true - Max Alpha: 0.5 - Max Range: 100 - Max Wave Alpha: 0.5 - Min Alpha: 0.01 - Min Wave Alpha: 0.01 - Name: PolarGridDisplay - Reference Frame: base_link - Value: true - Wave Color: 255; 255; 255 - Wave Velocity: 40 - - Class: rviz_plugins/MaxVelocity - Enabled: true - Left: 595 - Length: 96 - Name: MaxVelocity - Text Color: 255; 255; 255 - Top: 280 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/current_max_velocity - Value: true - - Class: rviz_plugins/TurnSignal - Enabled: true - Height: 256 - Left: 196 - Name: TurnSignal - Top: 350 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /vehicle/status/turn_indicators_status - Value: true - Width: 512 - Enabled: true - Name: Vehicle - Enabled: true - Name: System - - Class: rviz_common/Group - Displays: - - Alpha: 0.20000000298023224 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 28.71826171875 - Min Value: -7.4224700927734375 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 237 - Min Color: 211; 215; 207 - Min Intensity: 0 - Name: PointCloudMap - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.02 - Style: Points - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/pointcloud_map - Use Fixed Frame: true - Use rainbow: false - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Lanelet2VectorMap - Namespaces: - center_lane_line: false - crosswalk_lanelets: true - lanelet direction: true - lanelet_id: false - left_lane_bound: true - parking_lots: true - parking_space: true - pedestrian_marking: true - right_lane_bound: true - road_lanelets: false - stop_lines: true - shoulder_center_lane_line: false - shoulder_left_lane_bound: true - shoulder_right_lane_bound: true - shoulder_road_lanelets: false - traffic_light: true - traffic_light_id: false - traffic_light_triangle: true - walkway_lanelets: true - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/vector_map_marker - Value: true - Enabled: true - Name: Map - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.4 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 5 - Min Value: -1 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: ConcatenatePointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.02 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/lidar/concatenated/pointcloud - Use Fixed Frame: false - Use rainbow: true - Value: true - - Alpha: 0.999 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: false - Name: MeasurementRange - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /sensing/lidar/crop_box_filter/crop_box_polygon - Value: false - Enabled: true - Name: LiDAR - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 233; 185; 110 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: false - Position: - Alpha: 0.20000000298023224 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Head Length: 0.699999988079071 - Head Radius: 1.2000000476837158 - Name: PoseWithCovariance - Shaft Length: 1 - Shaft Radius: 0.5 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /sensing/gnss/pose_with_covariance - Value: true - Enabled: false - Name: GNSS - Enabled: true - Name: Sensing - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.999 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 0; 170; 255 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: false - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovInitial - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/initial_pose_with_covariance - Value: true - - Alpha: 0.999 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 0; 255; 0 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: false - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovAligned - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose_with_covariance - Value: true - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: false - Line: - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Alpha: 0.999 - Name: PoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose - Value: true - - Alpha: 0.999 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 0; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Initial - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.02 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/util/downsample/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 0.999 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Aligned - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.02 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/points_aligned - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MonteCarloInitialPose - Namespaces: {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/monte_carlo_initial_pose_marker - Value: true - Enabled: true - Name: NDT - - Class: rviz_common/Group - Displays: - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Alpha: 0.999 - Name: PoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_twist_fusion_filter/pose - Value: true - Enabled: true - Name: EKF - Enabled: true - Name: Localization - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.999 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 15 - Min Value: -2 - Value: false - Axis: Z - Channel Name: z - Class: rviz_default_plugins/PointCloud2 - Color: 200; 200; 200 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 15 - Min Color: 0; 0; 0 - Min Intensity: -5 - Name: NoGroundPointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 3 - Size (m): 0.02 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/obstacle_segmentation/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: Segmentation - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/DetectedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Detection - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/TrackedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.999 - Color: 30; 144; 255 - CAR: - Alpha: 0.999 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.999 - Color: 119; 11; 32 - Class: autoware_auto_perception_rviz_plugin/PredictedObjects - Display 3d polygon: true - Display Label: true - Display PoseWithCovariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display UUID: true - Display Velocity: true - Enabled: true - MOTORCYCLE: - Alpha: 0.999 - Color: 119; 11; 32 - Name: PredictedObjects - Namespaces: {} - PEDESTRIAN: - Alpha: 0.999 - Color: 255; 192; 203 - TRAILER: - Alpha: 0.999 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.999 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.999 - Color: 255; 255; 255 - Value: true - Enabled: true - Name: Prediction - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RecognitionResultOnImage - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/debug/rois - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MapBasedDetectionResult - Namespaces: {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers - Value: true - Enabled: true - Name: TrafficLight - Enabled: true - Name: Perception - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: RouteArea - Namespaces: - goal_lanelets: true - left_lane_bound: false - right_lane_bound: false - route_lanelets: true - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/route_marker - Value: true - - Alpha: 0.999 - Axes Length: 1 - Axes Radius: 0.30000001192092896 - Class: rviz_default_plugins/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.5 - Name: GoalPose - Shaft Length: 3 - Shaft Radius: 0.20000000298023224 - Shape: Axes - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/echo_back_goal_pose - Value: true - Enabled: true - Name: MissionPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: ScenarioTrajectory - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/trajectory - Value: true - View Path: - Alpha: 0.999 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 0.999 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: Path - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/path - Value: true - View Path: - Alpha: 0.4000000059604645 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 0.4000000059604645 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Arrow - Namespaces: {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Crosswalk - Namespaces: - collision line: false - collision point: false - factor_text: true - slow factor_text: true - slow point: false - slow polygon line: false - slow virtual_wall: true - stop point: false - stop polygon line: false - stop_virtual_wall: true - walkway stop judge range: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Intersection - Namespaces: - candidate_collision_ego_lane_polygon: false - candidate_collision_object_polygons: false - conflicting_targets: false - detection_area: false - ego_lane: false - factor_text: true - judge_point_pose_line: false - path_raw: false - spline: false - stop_point_pose_line: false - stop_virtual_wall: true - stuck_vehicle_detect_area: false - stuck_targets: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Blind Spot - Namespaces: - conflict_area_for_blind_spot: false - conflicting_targets: false - detection_area: false - detection_area_for_blind_spot: false - factor_text: true - judge_point_pose_line: false - path_raw: false - stop_virtual_wall: true - spline: false - stop_point_pose_line: false - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrafficLight - Namespaces: - dead line factor_text: false - dead line virtual_wall: false - factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualTrafficLight - Namespaces: - end_lines: false - instrument_center: false - instrument_id: false - start_line: false - stop_factor_text: true - stop_line: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/virtual_traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: StopLine - Namespaces: - factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DetectionArea - Namespaces: - detection_area_correspondence: false - detection_area_id: false - detection_area_polygon: false - factor_text: true - obstacles: false - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: OcclusionSpot - Namespaces: - arrow: false - occlusion spot slow down: true - collision: false - info_obstacle: false - obstacle: false - sidewalk: false - slow factor_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: NoStoppingArea - Namespaces: - no_stopping_area_correspondence: false - no_stopping_area_id: false - no_stopping_area_polygon: false - stuck_vehicle_detect_area: false - stop_line_detect_area: false - stuck_points: false - stop_factor_text: true - stop_virtual_wall: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area - Value: true - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/output/path_candidate - Value: true - View Path: - Alpha: 0.30000001192092896 - Color: 115; 210; 22 - Constant Color: true - Value: true - Width: 2 - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - Enabled: true - Name: BehaviorPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: false - Name: Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/trajectory - Value: false - View Path: - Alpha: 0.999 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 0.999 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleStop - Namespaces: - collision_polygons: false - detection_polygons: false - slow_down_polygons: false - slow_down_detection_polygons: false - stop_obstacle_point: false - stop_obstacle_text: false - slow_down_obstacle_point: false - slow_down_obstacle_text: false - slow_down_start_virtual_wall: false - slow_down_start_factor_text: false - slow_down_end_virtual_wall: false - slow_down_end_factor_text: false - slow_down_end: false - stop_virtual_wall: true - stop_factor_text: true - slow_down_virtual_wall: true - slow_down_factor_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: SurroundObstacleCheck - Namespaces: - factor_text: true - virtual_wall: true - obstacle_point: true - no_start_obstacle_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleAvoidance - Namespaces: - avoiding_objects: false - base_bounds_line: false - bounds_candidate_base_text: false - bounds_candidate_for_base: false - bounds_candidate_for_top: false - bounds_candidate_top_text: false - constrain_rect: false - constrain_rect_text: false - constrain_rect_location: false - current_vehicle_footprint: false - extending_constrain_rect: false - extending_constrain_rect_text: false - extending_constrain_rect_location: false - fixed_mpt_points: false - fixed_points_for_extending: false - fixed_points_marker: false - interpolated_points_for_extending: false - interpolated_points_marker: false - interpolated_points_text_marker: false - non_fixed_points_for_extending: false - non_fixed_points_marker: false - num_vehicle_footprint: false - optimized_points_marker: false - optimized_points_text_marker: false - smoothed_points_text: false - straight_points_marker: false - top_bounds_line: false - mid_bounds_line: false - vehicle_footprint: false - virtual_wall: true - virtual_wall_text: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker - Value: true - Enabled: true - Name: MotionPlanning - Enabled: true - Name: LaneDriving - - Class: rviz_common/Group - Displays: - - Alpha: 0.699999988079071 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false - Enabled: false - Name: Costmap - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid - Update Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid_updates - Use Timestamp: false - Value: false - - Alpha: 0.999 - Arrow Length: 0.30000001192092896 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 255; 25; 0 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PartialPoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (3D) - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array - Value: true - - Alpha: 0.999 - Arrow Length: 0.5 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 0; 0; 255 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (Flat) - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/freespace_planner/debug/pose_array - Value: true - Enabled: true - Name: Parking - Enabled: true - Name: ScenarioPlanning - Enabled: true - Name: Planning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: Predicted Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/lateral/predicted_trajectory - Value: true - View Path: - Alpha: 1 - Color: 255; 255; 255 - Constant Color: true - Value: true - Width: 0.05000000074505806 - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/MPC - Namespaces: {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/mpc_follower/debug/markers - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/PurePursuit - Namespaces: {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/pure_pursuit/debug/markers - Value: false - Enabled: true - Name: Control - Enabled: true - Global Options: - Background Color: 10; 10; 10 - Default Light: true - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/goal - - Class: rviz_plugins/PedestrianInitialPoseTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Theta std deviation: 0.0872664600610733 - Velocity: 0 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 1 - Z std deviation: 0.029999999329447746 - - Class: rviz_plugins/CarInitialPoseTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Theta std deviation: 0.0872664600610733 - Velocity: 3 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Class: rviz_plugins/MissionCheckpointTool - Pose Topic: /planning/mission_planning/checkpoint - Theta std deviation: 0.2617993950843811 - X std deviation: 0.5 - Y std deviation: 0.5 - Z position: 0 - - Class: rviz_plugins/DeleteAllObjectsTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Value: true - Views: - Current: - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz_default_plugins) - X: 0 - Y: 0 - Saved: - - Class: rviz_default_plugins/ThirdPersonFollower - Distance: 18 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: ThirdPersonFollower - Near Clip Distance: 0.009999999776482582 - Pitch: 0.20000000298023224 - Target Frame: base_link - Value: ThirdPersonFollower (rviz) - Yaw: 3.141592025756836 - - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: TopDownOrtho - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz) - X: 0 - Y: 0 -Window Geometry: - Displays: - collapsed: false - Height: 1565 - Hide Left Dock: false - Hide Right Dock: false - Image: - collapsed: false - QMainWindow State: 000000ff00000000fd000000040000000000000329000006fffc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000001fb0000018200fffffffc00000275000002840000016c01000039fa000000000100000002fb0000000a0056006900650077007301000000000000033c0000015f00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000000ffffffff0000010b00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d0061006700650100000505000002680000002600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7a0000005afc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7a0000005afc0100000002fb0000000800540069006d0065010000000000000e7a0000057100fffffffb0000000800540069006d0065010000000000000450000000000000000000000b45000006ff00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 2813 - X: 67 - Y: 27 diff --git a/launch/tier4_autoware_launch/rviz/image/autoware.png b/launch/tier4_autoware_launch/rviz/image/autoware.png deleted file mode 100644 index cf2d1e8eff3550c4427f8d98dc2f1d0c41aa712a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 600002 zcmV)jK%u{hP)7yN`O?Xkq%$~9oY)Q?;&eu*+v#>X z?KqR;ff!Fr7GMDe1O_Yyffyu#W~o%FK~<``>eYL%zqQt0=j?m``@dJh*xmhX@#_7< zz2}~@&pvzYz4qP{7he8?rBWu!s@3bt&hxJ>hYmhf_U?M1OioRerKP2UpNWYH{$5;I zC|kB)RL;HVTK?^y#l^)kH9b>K9zR^3c=#*j$f3PuVq&uMnf@QRHvaRq$9@=N!2Laz z$*EFG`|h~!x3N#w`z$Rj@_v3#&oC>m`5czBz(_*|f zQ6?sFpT#mcF;x~97x*3g)-&=>y+_pC#srs%B|cUBJy}1EYw8-4ya(n1uN8~|?=3F! zTQjq(%Q+W5r#!v)(Q@ROePwcTGTp!3yZ`*2gEpt0j|n~F;zC)BxyNVfoIxHI7xWpu zs^`ZT`JUzm<>K8N^;--N}l`fdm6vC zSbslCt~sxqD(yS%Bg;uV_rye*g3K>1a@{7UXUZh^Nhu4b=c}Af;0217?~C8~uRH%$ ze{c>cKn34jqRh1?n3$NN?pa(o&4<9eo}NEhCZ}e2P2L+{_x=i5mL!Kf_x5JphrLPU z*#8242JgR&EMQ$UpTpxD_dNMgIJZT5X5(2q%9d>xmBR=3lzn?1=G-oKee32V==!Ji zMrW;i(g&R|ImP>8ZLw~Pi>GJl~X5<#ckUB)_q%bW8Fm3&)!sAmC&V}61>-RMMtKr zOY=3mgX_-gw;+p@g}D9XlXN|LXViLL>XK|bZK9}&cyw+qn zYwHDN^VahyNBeg_R2H$GIIr^arGN8#@qL~xoUe3F*7F+I_f*7A_WiLJ;tbLf`26>^ zFz$9;%T3n1)|LJHcVujg?c%fAx~0EFmW3vhl4)LhVuJb#;sQGYzn2zp*84dycX$uy z$U=S2uB|0`#}8$Fa*BI-YI3sd+4aq`5PKQ-o1B_0Yu9fo>o;xZca9v~Qw|^6r+vtM zwxs)%i83`a8#cvanVOs~Gppvx{5_e85^SxZ=1zMyY{2-8-{*BYXEgLn*todV z;u7auYk8V$s7o(lH`WuQ+J)TwlYBm1S7*J>(4}(yO>ZjeH*YI<-u|nyd2QdtxU%hw z`O$jK$X13-#d>&eX4{_69X8|YH5W#8_HbPddVnJA|hPPO@~=lK$K z7uFo|RQFNHao&ftEl;1K49QN%`8LUaV?uBp**6kj>vOL6!hEPjtqEn2@`XJkU4!f3 zv-77;gxpQXXQ#_)*dys2lKup4kbQ4Erp`~C$wOzJ&ih!ObRO~?k26R54|+p#syVh! z#aRa(E_v}@!E<5!USI3t34uicqwVKiNl>)w;d{!=s@0*`+reu^4qypoCgVazJ`}^r z6US(%;eoqKJ{#m(HiL=S8Eq~52WHRE7&clAvch2M80eZT{WRl2i{XtKd(;M3fH5jD zC^avlzXM@NhFJz+K6DKhCA5;d(K+#BOZijSu;@MILZuI34ke5Um*6hQkRyODW#a$CUbq~=1Bc6sh z@GToNvvXzD+&VrJK|=gU_ys_{s`c6gHf=LxB{BSOtc%rD_YRNE^7C~)|P z3}}vIm{8$h@0TSS+Fl>LCM9SGQk%OrE~&UU$pWONb%8;}>C(Lk40(txl_da+a020; zFamHdJR6M+{w;;BwUU9X?=&SkBp)%Vu|RCxcZOacUgyzIo(Z_i-&zU8p7HfUEH-Z5 zQMPQqxEwvauk73Xa9LQG9}gD$z$WCmBZILQs=h?W=O7AwmHqOuNkdkc3URnb9GiHZz zN@uCSx*ggEQa+EHu?UA)tVvwM4iJyc>tkIG#|QSrfqjp24FKroRa2AQ%%U?+@fx^jf=BUz(;#g0S&A%#<7UYV4cDtr(gg; zbOc2_@9}-lKj)JHiMjHMH~sDM;Mf18eB+)^aDHhQP63>q67X7p!w;_mH%yd;g@rPM zb&uzS?9q0%-D5pqJ2B)2>vZ#Nf1`ZhUH_^ar;N>Te_*}|JTs_vASoP=&|BKqI{7f| zz%!@kPjQ^HtJaj0Cyx?Hf0h2xRBf$zxpWiSsXg9(5W%v}N0cW%b&PmaFTL?rI^YAKCxy1PF zy|L1wabK3o+1oCH+p+9<{QmA?+&c#I;hzDG56ABN+87=0CV`s{EUkfL!@_JqRH(3d zGV&VNAu&Rlyupi$5y?zZuK0}fh&^tl%&uC?&5z9y1C(r5BQ6_dTK}0Vuv92!%T#Zh3`H|+fVA)}9D3vXTjK6S4}WW?U8s*Do& zw2{MTP$(@uHx4K$xR^ZyI(xdYIeGj@XQ?}T$%aZe zu4LHRVU?U?BlG1|8vu*xtOx<^7?AxFWY}2{&)WlKd0)f0Ao~RXE1ZHhG^u~^9KCb8 zjwjaI;DSbUHH@{Vw(h*NtlzY)JoEIEbYKeL!A66j+oC8kfUtfrmRh8;PP)&)&=&w* z*%0KVy#G@aPG^+PeghtZc^PKieJWc*uZ^=!`g`7y9bDIjI%O{+P>p@0Z&Ez$`R_P2 zTQtDush#tVfY{;1>kt$x`ZwZx@gOJUINN&8<>lmwBjuU>yT~BJnt+J}fOzEK-m-x6 zv-8}c6~fjsc;tShK{-{{tUHTNos-9&VZ?|)6A_(YVsQ@y7y+1|0gUJn4B0Tcea2O= z7@!3Yw0K&^IStwA8G*%!6vBuG=$VL!rgb}BuV67EkpyyKS542(m2EpOE2mB!FHi4z zL|~Lo!$RjK^v8+gNBDdfUH+nS>2qGny>EMl?6T^xR6ykT(Pzrh!%x%xwH*TE`q+_! zJiAVxJjwaBd?<3iBqN^-8LTRR1fG@6zR5P0BfNMPtSMx|20iu-K^P*jjJPWDYB@G| z#(W|2Iyr4Hr!$e?XM`2M5lOZ$X_B_Ez~T~_0^jw9zfnH=p8vBv^Yku(3P)DMX3aiN1(1I=2 zmvnX@xL2{A?k~rbp`(=g~BRECl^S#mL&q+eWjMa^I-75ZUXdFn;sEHE&!~-_8EE(PXeNV7$elWe-Hb zL@x;hIsDJfLmFG7d6_a|kXoaaalnYOWiMfjIgAz?5}gAlMV1!`b9w5~d#RurJ;l#&KogOJNz_8o!epmz0*!!Qi`5%n%*s_Vt?8`nc)>aWi@u;_!M3wWihWzfSTl?0Bt#%4~3dRyCX|gu?@&u^+3rzZ||M-h$tZ(pI+d2;bqLqutuCX_ollx z`nGA|Hcq)el0U%|+2!W2FFj4H&m2sSy+*uo#*x4kF4TZv7{GPzlFkgnHG@Ua(zcy* zX*qgmf7!eHp*UoN23%d}4G;;~1^qmn1Iw`tha!)8PIC0p&egi+p$m2X zL!ISlkeyYEO55R1umycL1%q9`Wh9ECDt1jcMH21S(P9IU>FHHv+qst$AOXOx+qjjW z@!-=>meZ$>SBF`axjKFkENi67S_HDOZo?LWBt%bic3Lfm6Aov(X@{@}=zs@(Q^3B0 z%5d6|rV0>XY&|BlEcBJx4Ih4G8%62^TJU=GnL zd=C-N>DjVo{id>T`ZS{`7he8CIP}7b-`HRHJney?7h{ZGGdRbvhNtIG5Rd|R!=|1mGY`?qc<ABDw*XNI}Kt5mgMif$k$%TmYDx3$Qm?SuKttI_N|BWonHAYGyYf0#3VR{v^RI z&!!x$3;Y6^^Z4bklQRK7kSRPLgG`8U2L+pU+SC;FG{IYCTpDz@bSLX>Q_k(=X$(u9 zA*A*e0AI+ZY`=zNm3b)z(@e68xv7cZ_7c<(Wt)h zS;Nc8FlmEqxrWU!9rlLz?Vx->bnl-Gp8>DnustPTY(~^JTrwD8-e!0KWC%n)M&wRW zc~;thv}KNR(3=2HP0H8nj>qO4RI)rgrVr5Yq2o!OFYQSPjD$=1VA`M_!p{IbT~>bekc7t(%6MY3%+9SPaDd{i6b^&N6p0>x;P+*)4;%%i>ReTTkK46P zsytGA21l>i91&j5F2ERy{td}*AH3N}lZbQy?-1BeJ0>0}#u^4KJ+6^=k+g8ozMxbT zxw8XEh9Zmv9qw`{RP|l&0olW0XcnA3llIoqgB=Rk?~&CIfWTf;8+!7%2d%@=g#i7K zVMQTD?Jym!Pf4qXRYXv|*H(-)#(vD-uN0yD-mn5%_SJ6}SnS`V0qya($Gz8Y*jl!o zcLfcqJx@N+z+$5MVhw990}e6frF0!9+8d2doi=m(r;Sn5H%%8_Sm2?lwO=G19iUNQ z%}$L`ie!HeSZ`L!di7|heM>bipeS$gbj?{bSgc;(FxdLQFz>@8i)4!OH>7eiBGmBu5=_cXi2w=@w4z~< zErHy~#S40+DaU4{O%vQqYwi}82u`MFSMmGMVTjgHpG?hgpRHQGzRb+5BADfCA$wp> z;Tf($Lx>`W@`0um`hKq1hI)uOPRI za+h-R8~-M2r+oEu9|(qH*z2KNNPBmlp4mg(==z_=HdMsh_9Nbv90zlP&pIm_eE>Vk z4qgj7tIQ&&ehKi)&Yz@g!tR7FMdTW`5M&de&wGP8qr?G<{80ww`68%1efngW4wGei z8r0@f@obSw5$jGGb^uV%ofr}=HB35ev4T#6%o>609V;GFrY~b3I?ol)iD%)`e&_4| z+LF9kr7Xi$J#)V7ui_mwx{5xOsz_063Y791ww^XWe;^gSf zQ#(ABTfoDvX}3gYXhvtVmAjERfk1t^fy*YNedkLDfabf7p;Bv)jXGU&B+{Sh??dHR zL@|T_oAfT#-PpXwa@;s}i}<(3TOnGEWjv3#)= z)!x_-jFpu*j6&!%T|p<8wh7uTDS%C<;XM>}K>qsiBL~Y(2J3cvZ_fOh;vtBWtLYa!~7a zHL8)lpZ9&1kH%DK(LH_^qELZbM3SPQ9qC7tu|HBli@rc|&J7NbvokYGkg|H+CQ|+Y zQtHx2l+d4VXKFJD4Vn$|Ew5r6s3^tI7)*0h-Gm(NigXHX2pQW{Xf`lKgO!(Gxkv;X zs0$GJk(}*t{Ptz6MH8EIgupfEd3FZlb12XOFa~U@U(n78p3ax1{d~&^nq$Q7?9EUCKyBElt|wR5bkJ=Xr|6b zTTs-?x$`vkRj>pNY2e|&0Gug^Okxi38C=seV8}GC4ZCmshHaEBu>a^} znVK$hYu1+y8@I{0k0_BNosfric1q50u7arnd35~?M6Com=gIWIZ`l7h6JC1DUnzh5 z-d|?!D|1Q_<%{=4@l*f<&+0v6=Y~PBfE=P$$~ng099u*T{fw`F+fS7*edfL8k^AoA zKBQa(^U3sN*GKT_EeC^g)a`h0wn!9E1K=VhTKR`~zZO=C!Z*};kq2vs0s;~SYF-;T zFBi#b<8^9LPz9AhHHPfKuA#mPd3FFvk!?ha74T7xtH7l59wi^hD}~cQlvGn#F*Zjq zJM270D1**Qhq)q%Lo5-@JI0-vA=ayQzHn@i!;7xGaY@E1szJ?_^_#Yq)oV7E-H&~} zY&!cq<}f;3P3r05LV>3OVRHzG!sadi&>_{P07rEC*nEIYO&v0RN3S&Ql`{j2XMVjp zed#L!Jw^)GG{fBoij}?;>hcv}^ZVjQJ3(LfGu6{d5>Ut>2%q11-c{x3;REI1{>M9D zF?(=fU=vz}_pkw@JR?4UQlu)3Oalxao~d|6K0y5(c^xhIHcp*Pi)SI{J}3&_RF)xA z60rfW`&`K?AGY9-!;{O(t*qdxLsL{F8^qZeF$%8q^l_Au!!C-86pyI8Epo;qlwieI z?W|qR&x@+Hq3n2zTFAf-mQZ(Lv@d7uc2=n8(eJ<4m+!HA%EcC<8lix-+KgK!>=snPOY zhvOiYw0idql6sNx{#fVEx*k14#6>mj#QxaSwvU{F!(LM1yvmcV#(o z;t2DfnS+slroX~G66D_mZLmhAqGG9XYND$4nE4?nh@whZGk9k&xa|35Zf-pdEuJx; zT%DdTv+!n@Qg%K373KRhWb zX|Qy>1K$r%`|~9|P7|qI5>x zgD6VE2y>-N2CE@OFdS)<(WV;;gtzF3q)JXT6+n?w1qK&vDcDS|+9;hU`-zc60wq__ z?8{YGU*mzMJ`xgqik5m8j}5?mXFZ(#g`E{}-n zsguVUQGz20&wb+95$Z{##h5aQF)B*rs_~jnM(vq9uR0$!#|`g=gWn)h5og&lstT>> zD0DB*KF%vsk{mr#lpnSd<;gWO0u%vs2)Ir2Gl+st&#vZg$Uepf5VUG;Eq}wF7nS)6 zvJUq?`2gR;b1{H4f1(^cyr1X!{HbGQW_Atd0PjObBWj5~Fn{tWpP3-^_+ieUo=er! zah6l3Pm}_N+^s+GQ{|4||F>c!q-yL~>gx0gh5_v^IuWsNvbiTFp3bM%QGhg1@EbU1 zk@6L5B8;zj)7(n73>vEgC~TT8%O&)I3(rKL$IcEpNi;?mqj3QnJhy4srYj=?y|4iJ zk<8fsv^+ot?69adRz$4L$ZR#tsD+g%G^LP%~b6mRq1daRPimz9HT<4P+5K54Pu4_fxOPcS4 z#jNo8o-U%uP8`58qV-yf>^UDL9nwon%u|I zy-os}t!mQP>8q6h6SdPG=o;NnQJcn>4zFPv77vi1%6MbcLOL^2q& z^z0EfWusD;qFO6Gsj9q2W1s>6dn{wVTR1n&Iz3UxO^}=&QuVz;Hv4{#L=V6b0$0r}Zx12n7c=@M_{eZm>V;aWf)*Tl!DuOkJmmQQR7<8h;ER}D5 z?NjBc$L^D{5i7e=G|pNwFNJk14fUz1$OTg|B^3CLxwPxb#>dqlXBps5=)=(`Gq#^dP|$-Y1BRN|^p0m>i12X}QGEQ4Xjb+NKcVvyQ&| ztZX($+t2OHZ&6{a6SND!3fLvc(R|hS{Jru73XFa3gN$H;=DKQb4d)8DVBLnZ37Xe$ z+{UrYt=YiJ*1!p3ooJr0Hh2c_Ti^rC56&2!A7UwCp5Oc5-$C6gZAW81&hMy0kb)PS zhsag+1UdiL5w$iC(o>LCfLYOoRSne6Fa;XI#)BOa)m~jJhz|d-T^v>S{8G<=NfpkB z#)1)}55T@U4l9LR&PKCou)d5Anq?I_Skn+`7*X}N-Z!eS(h=kw@=i;n9QX-Cz`5%# zh?EMoImJg{d9tW=M)WYln^^qq=Uz_Q2zt?|O$Ng0!K00X$sS`YJdAYwhA<#(Zmu5Cf+}{-H?~4g7Ju=H7c$v*~;_C!`XBl793CoH7OGu{w|87_2cZ2W|1Sv z*L7zri)t$u-j;|u94DpS?C_vQ*XqGoun2R zsU`Ef6y6cAc;*UX`A-gk$Zx~7yOE=I!6CqLrjbP$MLPi&7v{_E#{d?OSK4s(I-&>J z`pql|0Ara^|A~pRYSmgA4lrb%eDtg3z~0Au27mXVu`}@9En6=r7hL{=vUdGh;b4RT zCGRx$7>v^=9=?Y;l=IQ|P9dLfil zFVfiD63qb>>kxUzh!F2M|Ee-OyP8Fk4k5BwqkOrY)#xVh*&~OYil$jty8oclVN|R` z>>GX0mSuokpHa?-lEt8WvH&W&cB`jAFaCg&+3Vle(=~b?br2lMB;7UgwyfXUTsOL^ zqi)`xD*fN1+{YL(27^3Abzpm8Z)`Yg2j}|8GkY10aiJnqHr{;px#cO)skv|L9BA#g zTD8n>4{JLEO@jD#d(;Zabw>Gjo9aKrqcSJssRx+R7Ms7Wbu8qi~v;{bXwS}Pd#zJoWm^au|Rs@ z**h*SFTeG#m%Bdx&hqg6pD)uhGv)kCpI=`5iXSR>{N68?qel*KKCimrRpqkhysUic zkNyiIL6eg+<)&BuFm2t3?)y{f5df^`zT|t#;}3nARcPl{Zy=C5_u}iz-d*3|XJKn& zEYOFj%E~q;L6bds{Af9GT(nT+^`V6jB6=z?B;aUg9c=0oh=d|%5fwOVUR(|=MA0p_ zpbEA{^jW1-CStj;%{Ok|S>EtN?kM^9rD3z3Db=t=}S^)>U5d9YxZ^ zxx^l(kx~~lZdR=gnX8}>_9o;s(j%nTMN`MKx+gFIXLY(q1yV&{1?FX|sE`cPuGk(U zQbU5xqIGl;q{ITL0fwxngSH;$M?V-*ZMQT>qi0|QjJWQ~3C>K8{%JaK!DY{1(!{uu zxv6mQO-v$w2Q;=LZo z9#x;(Spj472%Wjd1cqbUuAVrdRO9S1b{}4QGagpp*T`uFhcTt zY;W35A4}cL-WINLGJ-HanZFHc2|R>sQ-Uf_pIQDe3}Z}3PQ9*=j&)2s9-}F z|48Ic<)a<>^0UGb;Y4yr1PI)iUl3JyViuPQX`HwOzXOs#$&*wysw&P zMPQ|9f}Xc)-1UWY2telOo{g3qJ@6i}Tv|?=1V=0*luEsaCbC1n>wC{NJ@%x#3A&WI zDJC|==$(pcUXHk;DKu%kF$eJ6tBP-!C2^o|T@r;ukw@t(8HsKj+>gpQ8j=b|K#xU> zkGwC=L?QI`&6#|se&#O{EIO~S2SQc^i!oT}{2k|AMWbo=WA~Q%lPZLeom_1{X^+;T z6wEwL->~m|;2j=0RXaJ*)GmMfv@{P}zM<4h?6lAbx zRL1|a{n2(~T&d~|JL6!iZQXep4V$MPzrW=y#t!XAeEQ(Q*BPSy6P%ByAYc5Df?$; z)$Nj*>TnD>YK{a&Jveufo8?Go)rASsa%?Q5CnHjh^I#~2L2Nm4L{t$6MZi&LX8p#k z1TL6kRMzx0VLzee3@U&=`RLagUEKOI%JXA?$#`v*qv0rGK9niul{GcNeSx3=m}ktr zgFzk7!J=a|cMX6-l}}rb#OPIriu$Kc)KdK|GU=i!4r?X?8-1 z5*s?*jw7>KA~3O%eUbwcveKe&whJ?cz2_>b{d1L(MICM~SwBU-J3Jxox9Dc9Qd<2e zi9L$#!1kc~UdLvz$~(rAxM2`t(~>_8+7T&7;9Lu&%1frQ!3ayU+7qLc;FAZRn}q|q zQ34&zxsqiy50gwUXP}Q7AsvIsIbJzJ6xE=l$P(?Scd5Lv_1_8o)w#>$_r;8Y7a6#-DxM0azMr#wvxq_HvLFsu@fB~-2+wXQ-K^AJDS%D zz(ZcWt}GM~J$wWJ9c66>ZQkpi2mUq{BYB+-5OhFbIaJ(%b5(nHw#MmRU+3w%uVT$J z%9Uu-ywS5CMLDXWX&E$VOM7VugpXgNmDgwRyUTz@&5LKJTB#KfEH{?=e3G2{(Ln&! ziG&SYHO2^|Wykqfb8U7%4zQ?dd7?N$FRR=(*Ej%Io9EW=(7Af`P6KmbpihbtKxR<3 zNp%LbjuioC%CRE{_}_@fG!DHpnWK(=Bmj6OIEWEhgbvxa`$4wiGVMMWB^uFnZVeH7yi%cDHP;2-l9R4hZOwC*&Qgt4 z>n(?1P^v?x<$1L6*`lDLn*k7e4$NGt?L}POHu5}WB+o?USBtCw@=!sh%otL{MD2)b zssr-6NQ09T2H*e@Lr}F(9zV=TBKD|z-swIn`~^7%kl4HXL4q?D7)$9NJO_9dIL|P0 zwLDL?uV6&^78h&bLr^I>uE>|8QBAoIN^UJYri$o3qiJ*_myA9CL`!9n5l}}NX>^s( zXpQ75mC-uM=eEFO%#-DlhI7z;UHFEo5jl`5c!P)@fEDfu+0>p8Sf}%`lyd$hHxdI44in(t@RBz%I{As)|D$pVXJ*UGUi(-1`A^*b zD>W_Swcq!T%ER}6u6*qaALP2AEySz7=f}#IKl9%5;Ju&bep~J)WmvbH<^z^*gf?^6OKakb=qsk`rN)(r2-GP(G zDF=`TfV?-n{T=20dp^$AC9KLB@`^bUkdYoTz0-RZ-(|tQ$nC`Y1coc&14KeVATVpzZep$^6rZanF;^0N zZwT=5BdW}F>IAvqN+3ohvoLBL?dp`|9&cECEW;;uU7oI7R!kv$|sK-_EZ&-*j{JBrO{jawAZp?XH?n53-vRB;(897gZhM+kGJgAnu3 zfP-@|BElSr(0(rUrV&^SuL9qy(XyaOk*eTGdj&n+A}vlfuHuWsHk5o6YFLj%-3JO$<$01UJp1_{qI-lQ8&)0t zR|8aAZ}c%^C#tj@fEXHk@AJ+(VDNn zFv^1#3IGinC;G60CW$dP4-x043u4sP5>e{kEhn;3+-wK8IS9Hbs$vpofQ|~VsLHph zaHwDCi~^RJ`0)I@pF&2KAPcU)RN_&fiaMPSg< z;l@||Fbm4udHb)ZHN(Pu1*4z&@UN*b;KXEk<#+#G-tY5wzKe1RJNdRB`nht?UGFbn z`@$UrK9GYq|K)#C?)um}%kC%cXH*f9>DT|jPnD0o|KGD!1@5(F$HnElZvE@!Gava4 zfR*oHehP^#8w=E6r z1f74*=fpDrd;;*HxXp(VmEHZIY~v{ILs^K3IstJwuNmuy{LRcU^-2-)u%DNZdpQ>X zP>v8dsa+fh^91l~;F%pjnUO)KISUZY64WvZ9nov=H-gPn-B^w{=@Yj~vhKxvVU8fj zj)+<}+7V|R;=Rl$K6Qe7OUCt6q`h-Y#Ccv*0nM}vt>0y3NY|Nuo70`4F-;^l4qP?m;=`fcf77Ya+1N_aRJF^0j z5Lj#$^$9`wVfE@lTM!5)HX-}eu#cBKN)?^E>QW5O9*q70-Uq`z4Dg!^ofK6wbeh8I zu%_ylb0iX=H+73Jr{b1C}c==$Z?wQBe}85JwK_e9z*0xk#vdzzFuz~d&81~Ws072&qMpo* zP!2V58cfm^V$0Tx|kpPz|E~^ zV$Z}v=5wV+?|RIg;n9aUREJ~Bx2tnsH?L`TPP9(c zQ5c8w`AT6ysZD3?Z>@a$rxwhn{eKSQ=UcErl!m0t*Y*SAiLb#akGw?KlArm=uPZt`IYH2d>c4mY z$-7nTYwf0T%lG|5Qt0s-))##hU-jL8r+oGEA1e2Mt1wgx&590jE-4EpRaq-8_E^ey}Z2dH-CAe=#{BK*vOCs}j{ za|^Zt#^*g#bqcD%&aSG!(ywE!5dB7BJrv-Clw%!LrBzjL*`qTe-*71K^8j|FX?uU_ zFs`|a-tW-^-TKHaIdUpkP0NU4l?JCSrYPrW*q>27TP-z=55($lmENjLa*?y7zq_`N z(sgX-T2~NUr@&nugB^Q5`&(p@@m78bgM*?+?jVW^0GZnZJPi1jJJR%C_j|(trEd(c zeAUrU*n8zldMFD#Gd)YbIYR63D!8Jh%37);+r z7IYVPFfG9zUU<@20-1`yJ-J#5WaTrMZ!YhZn^Y^9rD7_r5wVIi`I@f0%5`IeTh+w) zSQTK}$Ug&v_6$H{XMa@QJI#s_didy`<0}GV$qTP>!w_;r-#sB)ucRsT*s*yW-{l=K zw?R#JDfks zn^PxIk*+Ia-xjbK^3ajhAwZ}TucHs^A46dNSsWbs@b=eW)S`6;bSJ@b^jYj)HUq{Q z2DQSj$iBhDQDShFQJ)D(->-BQj>@+@2{r`!-^bsbVpz^AuE4bcLtooq&8#9D)OOU# zc#?w+@&IF+1vqF-qZ;a!d~g5mhY1!HVL~oXbENd;UxrI_7UJJ6_uOL)sGf?_bU<>V znM&(9UorNcSrVp8hGUBnyvXDC{;DH&tB|@zT_=OiAw|JRTP2-Vy1DLEJLak&_4RiA z%}9iRCn6u95~66`(@#BG4m|_IKT-#JG<@rDJ33)Q?6}|>7Cr%8k^S2uk4!_+`NybW zP#60)MT;<+Mmj@UA^;b1+FZ=Uj2zerZ0|6CLbT6lP|m_nSbu}X)2Azal{Q;ABMp8* zy<@Zp05ftPY3xTYyc%hY^GI}MvB~IE=D;VZ!w`wRLUneMnlLL0-mhBgpn{WG@<&NL~#d7Gt9#;K4|Kc0UOJDa_S@Z=xEb(j? zU3nvm-~8ck{ZqErKm_sfYrnHR@1<`oxBu2J@P3%{D{pvJx%zppVh$i8?y$G7y#D5L z`E}n_{_vf@pq%>2$#VURZ!70rbUmYwh=jobbN!3oNZs_&_xvA~+IizEf2eHOw5@#T zcYm=qQoHF@e~I((nLGYlP0K+=Q&e0zAUbC*e=|_HntiWSOp5f;Kf}j7gw=(Y& z0CD4%oowre{Qz72H4~*=001BWNklJ`B_B0Wif56V5!DN%fb6 zQpRt262jkqr=r~7}^1m%O_Snja5R{N8{akZH zGUs2h=U`B_wihFj-U*c*#=-s6WB1BHV6LF@{jyLA*bY$@qj75FmN}wPDQGFY-9PLN zE`4pud!q~0P`xXRlG%cTL&@j-tU-2oSz1)1^(AB!w;skW_Z=mL(Q5`ExpK+FSrJh$ z=0+qiUJK(y(|K0)462cxBnI+azvxNEF(jB)!}^t$WQt8IQ=jK+$l&&d9xe)!163xt=t~-F&2PhZBYMj1DJex_hC zW=A=F13)u_C#~T4$l?eXt=H3hf$p^J+{?@C>|6qieTi(conSWfb93gJ%Fu+0g zLv9^@Tv%*qd8GTHQ$znowLqOwa>&&)sJ8TI^I+quo2Jop+33D@yNFf=G=F9#z}}XM zS<MRA^o!xGMM z6skf52H&TAhs|QPjT~|)IH}w#kIzo;d@rm4fW!I?TUpW5YpozdFrA{Piftpv80nK? zfD@Re2&5`h8dRI;vZ!>E0E^CLgfS0L3!98lOFT<0P^8A<%2!8WthuuBtR1Ybj30nN z{2Sj}yY4I&TEzZ_%?F`_GXrA1X8k7Sf_~$kPY`6IAj~CK-Nf{!&wc!VsIPA+<;Ac3 zVYcu2@?C#OZ~`!Y%lG~R=JkF46Yt^}5Vd;M_xxQ(6;TieHqPob>&q?Q`wz>#U;Ie< z+T9=KS-5t?S>=}R{RvWD5p9GVpykPHzwal?S3dWFa^Kw_2mj{-(4QL z|E@}p1&~9g@e*E_Tn|*Kj zyfdrH8-DO-%AbDhon_a<_i&!puG?I0`{AD}AO8LStvtQw5xxeh>l=Ug=Qx%g z;(D+9fuAh*&~ zGjJF+XrIj)|E+$uZ`{~3itCBisumznj0l@ER}$g#Xmsj1fD)gdKVIff9A}w%0!b9! zi7>sDnGFq598Dipl!XdBMb}27M3IZ45B5C#@hyoYk>@N}VkHVm*FE%d*K0K3FUV{7ZtWJ5qI=+tgtobqwC+{wfZ zC8GrHmILbQn68pmBae0j1PE-szWS?@i|FJ~UCIef<5-SjskszY?pd(>x*OsQ080al zV;pJ`@yLL0NQaGcBAk)FTPCttzn>g3AqY)Y*~$V_C=5=*3YzQ@F_KB2iQa&*)+grJNsOW%uy&s6b10i4r+$192{;e?{iXl?xwQBAjdTt zO_0t&R`NwXh8d1w_390z?6T_R>3O#IKtY$<`VDpuYaz&i3xI^y5coX$34(%;UX|-M zZsGjF_Cr5GP)9TK2;d8ag;*Ho)N#I#^q(*O$sh1_09y1Jz37S?35pKx-$gk(=c4P% z)i=Dd{NX$QSro}xC|BO_N*1Ge-*5gri`Za%*F68V<@y)Dp}YsZ29HbsUV6=Ulo!7I z`^$TN?HzO=Kz=v{+24f9^TI}gU8JOIs~$T z))vamrlW)m0JTqHQKP8njYuM8j=keu)JDz@F^G^$JX@oSW)wi43^3hF5SW0GOa~vT z&8*rS_;I?N>?i41=vMq2g^L*VG^5RxhH<^;mGv2TU@!0`A zKp+{wxZx93Y@WFGMYk@ol2%k3MR=Fqgw^ZI)^jdnxE_s(5vlTIk2hMHhimjR;qOin zxbfHd^L=Nz=u5tHhxx?neB%4k`%WN<%B^Y`tqA4n3aCK0!9jWIBzj54@A(rF)&NI7 zKwMc+AZWbdHRS2c5hcG5C5MFMy-z+sWkEr#cCw8EKk3k#4I8^75s87QB(6I2Io&Nh zpEww1=0X-H2mqZwS)VZ#3xcP};4KR{b}k~pjz$`|Ib_c#jYC1-6SXoMK((B_eEl`A zj>VCp5~vgRl}H~sJjuJBqmQIKk#gCkQ~LQmj`sHuNNR=|K_+FQeNGB7@@DM3$zW!H zvX_A`S0WWmYV!mmOr9ls^Sz!nWNI`$qKTZ#$Pr;Y%XzlZFdf%Xi=6n0aXOE&JztcW zP8(2i)R)iZY#Q3f*%`e*Jd=m%1FW7y z!Uh7)fZdOMorcMf?it$a%iaEro~s(G$$GC88R?MvGvG)WM;q?S(++y=qoDOH0_ zHfLrcD9{!IgL2b(qJh1do{|+%eR7djJgvTs_HV^ zr$pW|z46iF!zln_RS4kH!4*zAwZ@^6s}WFF2gS=AXVAHuT1tD?>zQ&mhvd5NY_q;; zfYA{~^^LCQpBAR05@A~)XKT}zo&4N0Pwyi2&QZ!H*ZuQ*P=oLqu-VSuelhbE0hmm& zttT8ij9eDRfpH!! zIHXkKtPVq)-<2bRbM69pi>C?l;2a0AfP)`%k0=y!IuRArdIwm~MW>=zlR1vOJxoq64gYfP{DteAbQQ(&1H5DZ7dXAShw+PzK+NvjqS;4MmI4g z>vn!0YlohXX!G&uKl(LZ5BGlM_xv5& zd7z9cGF8g!zW*o76OY_e?*7yt@a%&hzKf^IO|Sk-eB94|^f$u4 zJW+0X)sJvZ5FG>-z`n-O^09Hv6*m<+aV0t2<|4t34?Pk|Ta}YH*K4q%k6! zrjFv70fezej(8)GVb+-)WCG4&@6kT3y&QE{&!2UahGN!*+P!h_{gYq*;u3Q904e|s zk@$7xcjA1rb+ zPfnGc=Ur8fp!d?#yE;)tU9WeYYIL-_HLvrSD9OOG*ce<6jQc%Da9M1q(u=xjt(>XeZ+_ki3abY-09Q~(X>3I9o};y@%qYcE=Pb01D#hxs z!-ejqj$wx{<%UOf}jWK+o?r!%q#a zosHGrx2%hH+6CZ>epbUNJl4uJjYB$tGlET*#}DJS7SBoZF)B-4fwLh}#W}=ur3hn3 z5k{Y(aT+GmJ(s&~|NF{87`^KMFTi5x=I!TPPER{Ly^L&(`56L$-jf~KJHrTI|2CGZ zl?pi3?+x9jI<>~@GDn86&m38WT*Fa{gSh*X^Lw>7C5Qc}-pJE**#d)e;$1of7vnus z?}EnU99vFe80{~o6dFd4!VU@xZx{aLM z(I2t)88h>z*Y3pQ8v%AB~;RWbH0S^=vbOlsJ+;sjZ zBCrxz)cZKga6R-cHCR_g@mBq{Z#(p*6^>Yd3K`TeVij2gX<&6$M5}OtuVTF{btflKl{<&Di7WJ85M?{Q7$2X zC)O7j0P=g=5C1Il4Zm^Eoz<3o#T)-t+4bmG%U3@4p|XTMJw3~);(`5-l`q_>97f#x zC9nBQWZvEN@&6Hy`o;2+*Zfaq{f4tyF_wB{X{lU$<89@Vt6oe8$!91(o#A1qU*|Q-uz>u|Yd&ItQ|+xN z@@G94^5{O%%`R0C#B!?K$|yV-1qGRZ84=N{H~kDQs#Tee{WC3`MmOB_rlr;EHWdgl zyfgR>frC;&V|OIA0_|V>!q*Y_JiYf3hNllcy^HjmQzw)dY~`)6D4Mi}p&pyDon59) zh6gb!vyHVz{$GE?zKF)l7-tNP^S*OV=p~(|0znck8qW(<%3I~COAJ_{DixxUCyr4# z;dR1q+}EBMf36=nlhHC+cAz};>3Mpc8oQ_qa@*AQz+*Mq&m1U9?z*4v&PVqict$E~ zZiJQ_m%WjuxWE8{SA?6b8VKPHcWy|fH!i3(iI3F|l_+{V2A$SmM#eo341qs;Qn4oX z!ZezWHla%lhn1+ixrBG*WBMRs&p*zM=AiFn7(^B!2bq>TxE11Ad1ggUYR9mKQ3ZNX zZoQH&lnqDCZvyOz_EtS?InvhyyIqf3c#ta>UY=(e5Up4ezEexYn?vvBwqX=zu6~|_ znv>|oc0^_%C`0+wrl~(GMHZI>i~Vc$*JcP@Vh%m#GXk~WqVB8Ji$mlFWhen0$$Og{ z$N{24pmQOzNOrgDdw_xjaV6L8boxBnd-PZyX8EFx!diupa? z3RoPsS8ZhUtceb_JCsC6S5S7M7pXkjNsd_%M%AVBcYUueyy!y3F)_?KTLOW|Gj4sD zO&>I!sViTa>9rfqCRjv2Iuy%b^}YaIIwvB3ujYokFhuOs>b=(^={qu799iNuQY$Y< z996jx-;z=0!fCQmP~bv6W~-BuRX723aUU671{BS?>8h||dN?8)6Rv5`U@@GS`F(yS zdNbopLk0IuTh3vVb>ws+A_m7yjf^HuwbCBS(Le7Mq!O*$xRo{l0aWTWT&cd%Lc@%y zn0?+3z*5FF&S^17(D!t9)m%AraBoB%Cu{2mFPY^c>uu{=?ld|E+#g#7M+k~JmN*}y z?f`5~NAbYq!e?Rl0yJ#cyp6yM#yXAuuo09lwZQfsELwQ#L^*o+X@Vc*A%Y?bwgl*% zXgz{+pD9G_|EDVX_;FsO93$Ryrbw$$Vl8gRD5RoVb~5+(I@U$SRV2@f%!17X8J$uD zvGyHDuklq?2f!XjWYb_BpPOC1mS7WpW z{&&Iwr;alx^0puP+483!`>pcmH@;BmjJN%udM1AJtDjU3-Q+ZLF`s<=J{G6Jx?|j+ zs-o5g*6CAs{MT~ynf(NsNQHA$5|eS&b6;7W`_i{iUm`Mj_`p-j83e!&%BR#z6mPQA zI(8`Jflj3;^d}&vb+dh<%C?gQ=}D~0i}jC4IIe3ds|)Z^P9pCS*9I-u`k?CLuyY9N z7EVWQQO|+R<*Wc{LV0 zkI|GE?_Zm8J9-=jMnZc-fNfb2)&qat4~tq(UN+p;o0@ z^V9Zpc1Bf))u^zK0@NnFn)C3~)6h4A!&JavVo1EgITtzzudUy-l|AE*A3s#~?|vx2 zihJ0aQrg;J!B`eJQ9G-AMs?W?jopx+Iny8w6lGXxzLb}wIcm{S6oQx(c+msbXyoXe z3K(!cgPz*P7!nzVm>r&4yXd`)C_z+7$G%&?aT}w4II}@F1Z~pSb3|?kg!kpQ4-zHe za{iok_W7iu?%n+$0TL_GM(;ru)eA$KED%scZA{j}F#vCo?;XZBivUhdM|w**7lTf0 zx#aaCBGXc9l%n9Mu++HDY33VFPBA|aR8r*sG4jTW<^oXwE~wgxh|=kkCpa#oPazVA zJVw~7mc2BUFPQ2iJHlFax{G zv0Zri3;7(FOBC*bBLj1Q^*QgN>&oXp`Mb=|RKLb^Sh*C1Y!2*uoOUT9+pl@+-)H4k zQW}k z3%>JvNm<2s-}mc3%i>LPbg0t39iOf!OZqeRw?R_q1a;AgsIuiU(@tX@&6rS*p>-^P ze$ca7tyH!pqLrX4;|Ke#s?*Rf27zV^K=u{U?AFJ?SWOjfffU(__)(BUI!pPD6E*h| zdz@kr(NW19s9FLOMQYJ3C;>LQ)*sz4b4IzOS>70wMB^X5I zCkP1u3>F1KhrEQ%TQ8tOf(HOaH{j(^8C{hl{`4LHjRpq|e?*fI=0%^psL<0qrtLJ# z2gUNys%L9*JiE`I>4Ban`poapz+yH&yM{t*3Ji}7Ha$E@P^gSbqKfP6T&2&Ls^c&? z-Us)ahg=xo&eH&q(s5g~7@pug?h#o~uNcA2yr67YNBA{_S84}n`E|ef(ghy=D z*KPrW=6CKJ-Tj`TTA88wADZ)Qu-NOK4V`AV7;GjFshb$nLlu>M(>hVPgn=y&Xj@YQ zXL?9k=2`M=g>7TgUNI_bP{}G=uR9N-rfCdPYRX~s>-cn|uIV$&&&TLa%s_1yQ@Xg{&O`e^&k>FT zeXtAK@miwhLYJYMBXZerO#nm`4^(x;(D_NPwS5sFwJul#ryieyS{+05>4R~O)&p*z z<#YxXX$vL_s-)|0ffuiV$3%IEf@{#{0E}2q=XT+I^qJUby`Xr)P@fh}n7VwL#Tx)OWghVy>2MEz{nO>kpM5{q^VYZhlk(ub zf5M)PT({}ja?`7SlxwVtaq^3n}WCoCDKBn#(D$K2)&isUt={yqBH=;O<^;|x@ zOyQuYvlk7h28xDZ!@}c>yifn;CL)bMrG!NR&<3GLGv&>W0%iBh6g3s&QVWs*m)dAemJwOk;V z?-zYTR1JIb1-1>)(ccI2G+G7Ka}x>TRHSk+(ZHeCR)$-SGA%a`Ueh7xlPMN@1{KPn zF+w9mo?(MU-FLLbOrGyP;E{oAY8zcORY|AdXw$pjF1=KwELvxXfsJKu>&Q~|3PkY*F2rXJ=<_Xue_Tkigxrj#7lkGsI#JFl| zjwEKsRQ!8{$=-b-&>_73}8A7pkIG{ZxmqRn*Tg#qG!Lyy>jl%LCt07T8UY`w4?J9>c4!;w}Y z$6FXHp(C_}+IQog&p_EApn*++Lpwq(TQs_Z%5Eo?>8Lag0fZZS& zV>h2+4J`6it(_whkt<|f0>`>qIczBh_dmf13LAk3y|FQWObKsu)o6`TCD)NqNp7Xw zN?&Qz(60dNIOCAJW*ujs58XH%;NJ=x;)rtvyEw}#Y1=F>%WQ_&|C z9cD3@+0{z1sgXQITyPcu6rh6W@uOm&0Z_RG6wU`wC)ryOzkOaru_M-es0DT8q;-1) z<`T{*?-7$g$2g1WMc!W&E&bhd(`+IddzR%Yu^f39Gc5|nAeTY%}*Fk@=rF!p|zCY~r#CMc3q7&neWmx2drcpdZk{e@@3@4jcMY#tenlvyM zO$NJ%YL>q`FZrQTR8K&&MKHVT*sj}m>?ohZt!W0%r4-5S(pj56YKN!_Qy|~&+Xfbg zB9A@CXwwCvMj0SU4K|N<_lzEW);u?T*%^7Sx6j-9ingVEm{@tAT`sy1XF*rb2i>U@ zQvSAVyO7Sx{ktFL*-~XKjLmTd%hvB^f4IBYgxbq;2GyB3X~jqW=~X|4qY4Due!^6@-n)n zI!E~VD9WZitds`P8>iXw0s0cgH)I;dx#*1mBLHKK&Ss|^>;asA&R-`zF$`KnG6)Lh z*6?u=nWE7OrykGZB|4-rV`_GPnxInk78YxDQrHu?x6a<+uFx)5wNwJO)B22zZyCBR zjS1`^^p8WK8C9+%Z4d1eW>?F>6wz^1fyehM_(U(gRhSpl*@$$LXum;VIi-8sfkjz} zygH?ui1KL1mSjmnfx&xR*{y65(^NN0#><0;Z4RehOtH{-iyiJV5E$=E2!F)zajU9Olbkxt6 z^_zDvxPa6%T#H(lj`?u1#~EP9jm(9nhkRB`TW7kwby`%X4QGlS44bx`SDyE>x0Ww` z<~>|*U=IApwsou4aNhXZ+`6*uyvy0A5ydNtyFba z&mk*Dl}H61mEUN}sw?tF72s54(YmC9JTeAkvntp2gurxV@^slz27lDKQF)(09+gbv zJ~_B#2be)81W}R2)O(keq2<_bj^XH8o9wE5R`hKY>z@u->>n&Xz>OPU9I`BOnmNbG@)TwRD03=~( zqKP%~Q1(6f04p@Izy)bw5zQGeX#0kPpQmq35U36ST8%rRh26!{p09>wib~p1maAh{ zebeT=g4vuC9fzf^ZT5q_&v3NC0A+!jKWk*M?|iAPK)O0H%a`}dsDrc>hU>F|9Q*9g zt*>hXyUCpNGNVG#D!`t0H;#7Ek-8j}g%FiUy*ua_5^b&aY2JEXIdpJO+4tmwRVOpn z5uSAB>(I|HIjs5P2Bv9!YGl4g6SZMPFi0ne^1Zls-OxIy+ybit2%@CQDT&riDjK1* zf=cDfV6m4YI;3wpPPe6{vU%J2^-LEW2YwNA8!ajqq) zlhdmhsT3s-IgD!*Epl6%$nj!(4}xV?7OhlUGe{^G>e;9^3N6>(&DRB30~jwxKCEjF zguF@qWUw>mGOp`=26@NaD*~_Rv4Jz>QK?3&35sNAM1*eBwz7WHHbyO(bGUjv|5gsE zayvn%HI>e7VE>`dT$IkMPSfEYA{a>w~sm8bVUUY_3bFa_1L)ocXxqfYh)_3agT z{91CTgi&-sSIDwAGjB9K$g?#G|7@QhLfHK)DumoC&N1XkP6w8+@$CeQp0gaqK=V@w zq;f`cD17;Op`x2siE1?+ouqQdA%p8dnXyt=^u)r>s1#Rtx6q_@VLmF1+6;MN9107o88d1>Tn#E(jSL-9xDxgMA|z^RezI9RQ`cT0Zi3J4Q~-KlVM=`sk4Z zwOTD@$j)#_-Xf`-6o|;dum{UB$zD^aHi!3}gr1YSqw-!ZhEV5>z*7oRI;Nisy7C?$ z0_0_4s?5yHk`{L8AWD%dfjxhgIXpHPgCed9i(ulbU0sPZ+cWc5n-B<+6c zOcdW305UW?%EK(tbX*2!iyX?gde-)fSg8?)zQAHoWl=J|nQ0qr*c{`4rjAkJczp zj@Wi}v}8uWKZ6Au2rJ4>))N7$`RpEJa{cj>Ei_& ze<+Z5=;_^M&+Z2b^3(8R>Z8ZOvp-rhv?3B(SMD}ir>zZ=Qx>RI!`Os_kKoS^g&YNq zqB5p(sR_1OBCTDLjWS1+oDb=_GLvL*KSkBS*vOQd3od&ef#MU7e3ebc5&4l`MEZjo zfs>vV)i5g+murHk24qE79nSOc(Vt|!XL6NlUW zH)Do1CGbAxUC|2XM+s=2B8Wv~QM6XAxd9;@&G-xr{dqBW08H5+J=zbzwt&q*@Rcg! zLf!!YQK&=L!*73Av{yOt1Y$d2aUMB*t2ts0G|&*3EK?y)M~o@{8-T=$IK065x8CV4MWf0J>3ay*WOjrb68n0v`g2 zuJ}8{IwE*}Tn9iMG*D1u83aH-@F--1wi&F<4~j5y4x^>pH@|vkdE()(luNIEN!f7L zPUZz7nh7~V>Jo}qBBhLZq)1(2)EZRcWA#}G=A+kgwlxgMT9mIFD7xgTmz13sUQ_<$ zj{l~pFN(IXAF7<)va?h<^-Vwe3+3)lznl4u_3WT?x-jpsQ@xf9v0$vkS!|{gok{iV z%^U*h7UfeLT-q6&gJKG{2>hK?RGbv*U^IjSNL>)rCzPxxx2h=W-Olu=uyG)7J~OqK z;hg9LI!8fMN=7Pz=E$YwS)a8-2-kwMf@xSm_qI;M=Tr=+74vG&;YEPO7mT-LW3!+# z-sw{(*>4eHVN?6YfknUG%}eScJ$u2hA(SX8MQ0RmqfmB|LBo)${_}e+KVLVh5QjT+ zo9uz|1cw*UilBm(x+KdCcpMsDc8O|)HZMBkMQn<5|9Tsc?qL{LW`*AptHeL@9A}`QP5=2cZ#btFHL7*ZIIP!r#63l zxC}?eI0pm9W&hc&B<=b0xU*3%<4gx!jj#r-#I#O%x<&o16q~YC;Ap^lqGB19VC0{W z<`B_qjsY@7AOU)gOU{QO7m7X`Uhv2{UyhzIP)JfGGma~~X$Eih)M`m1H=!EPEA5RQ zO(r6o$ZMUNm@ex#Z(|NoZZG1w?$2c(ERNGl^?Pv`87Ourh4wT&3-u*$dAI#X{dxk6 ziiVE)T#mYjr?KkTaBAQ_Tee>;u(VUUkG-SA>^)=wAB#Xnua%!>t-<&QVg{ zZk!R;mC2DX0Qz_|Hg`6TXhci1q8)Lw}HoX~LabeLEH!Gs^0wBMORl=9TyW|0%2z)B!SeWnUrPP_ zB9a(wkrYtv%R%H9*%`^RQAS_3yPP_qJ>#+hj9KUg1 z!Dt2Ga89E2Gjq3Kth316sY*TdTGdtsK@GJ*?nq38D>*iTd(ucniB(j{4arq_jt*d~ z74B8RB0!`lri}gq#9=%g8Y+M)D8zDr;loonGeWoN*&(M%n`3?=MMC#(h1Lk9aJ?x| z7vU5P>Tdu`bC?uWsxG$#0$bq{?VZ%auIEJ7*{1QifKOkaHXzZZRyO_B9Ru?pnMPz5 zP}75Wwz)avUMh+SM*!?N1O_&reQx9#u3_OC6lOx8$e;($fr3EDB|LWc0Bt&?FdaFx zUqzeHx+FRx;4>$V9%3XDIv(pKhr&O*V5l@45`F0fQ%uc90hN%ZvI>YnVB6JU@+vC6>wSPX^Bpgnxf{k zhs0=*EVU}pP7kDx4*SY9aPH?7!Q#|xIcwVm6qLsvyqnMK3TD|e(gzqeX0vdInOw^! zS9)Rc#`Xc|2tZiLn0S`&4~^T0;0Rbu#T1-#WyR&lYS(L>C_|m5@56)aJgX~wE)$hX z9I{F|WKI}+4o#J{>o%7Sn|73^c6~#Acak@M)DUiCa^Z!|8;D}m_G`FPqI?!fByXZy8 zoI#^=wTGMn^)bfC*m58c-=(pP;tr&lj@L814)ebAMQu+5>V<~BRgA$#xQ1F-or46;VglCpumkNb}|dS-voM6gtfn3 zQdVQ1Ive|SFI6z+0#N#T=ZqQviB*I2#$Y{>Bjy^`_;DFrvPc4TL68LF+6HO{k-U`w^8GQgokAeF)og<-cF}-$ZI%#AeZ^f z&FkVS&3rBBg{Gm3nG*fQJZ>9Fb$)`%8kIWxv|r7osQhrEL1wOb{w*vFa^IIfR-V}} zdb>WSC`Ro+9YE1*SM{)Sv@L0lcvbp$s@O`39H^$Vs^VCS)ws=&TTP+x81ny2gB74; zE>!fAYtdunS`suOLKxK*m0kcksoDfs#~T3I4sztU=@jRddhf_4a^9GkD*2q(-iTC( zs38EuSGk9(mP_j9{7DtB2?JR@^j1X*g!c}fHGo4zK$Tk-d0^CoXomu)XMn~;&7-^! zxVKabvEy_W+0mwb+8A?QPwILyPpl8R5v;C)@V?Y%^7WdW==8!P7EUud30-k;|C43Uu5U2neB#(MtSn1=kTo<^ zlyU2hOUi4%?;n-l`_Dg7jvd~wXNb-UT*HX?Hl|~)hoGw8m5y$QM71kIyE~;J=}J>N>a zTQ^ax#iW%(kyTdNmP7f=viI@%Xh9eAAUd|>&f|8_K)Ks0C`I{S2`u7^NO*-1A+iV$ z0upuG0W@rpVDR?5IxL+PV@LRt0pC6N+Tm4^N;`+47IPwxwmxT%ln>S#IS#{#iqD7eU>;mkqMjK((}10OCi0jU10HKM zmR`MP6BRLxI+Xm*;3*r`dc0h?sA{it*{&YcT-rbkU>)*9u;ps81Aqt5LnEMtzvIwu zx9jg;kC$Fd;=u4~Dts~W)4*c9og!8kH}b7EpM5?H9l+REBt|BnE87m{TMo(pGT>yK zJ|BF21&~+gWF@eeFW$Q*=6(b$o>G(LvCr%KtpFISoQ9}C_ls5+hGY*2W-vMe7~26_ z5BnjR$a0(?y8%hbw&gWD1={@^V6=|tIIMDXGw9;T`J@4e$l|`o(_WV_=F;BqP68V}{dEe-ECP&(E~eNUHfDII? zzoOGN{8_UcV-hmwy1Vk9QjKVe8V@P#D8pyWut|(Vtf3vFgo}OoP6Q479!T7PC5Vh1b z)|KD>4}VvCtmg75XOMFng|0#agi~8{U-vpeW~4oYtuF_N^-lo*_>R{8B<0F;s_L_% zE!SvXI5WI=NWDgWW8~>OUlGnW13Ad8EB%`dAlpGL2F=hkeO$r1aA3H1Yg8JB%xXQt zfdHB^ut+ci96dCfj#2n1;w0t(TE$2gd0kCcow(q#=W}+lAU5Mmh6XA&p~*W+U>`oT zhlYKli?$;ue~(@XHz-etxNihV@wa8|p5rpI&IH(WJ&wcP)BKrifY&m(V=b4qQRLA{ z)PnxlYdZoNiayxr<&4CBD`b1s3_6t`mnx3NA<1D?PpIvdCe+*P>_ zYIx+CedXZ(#|Hx$2E~?vzTutcsXxaWNgwcZOpJ0*)hKkq1!ZrO9gP z$m-Bsjuo-`MskqE`1%TL(E9J~lUgAw46{C7$h1_0k`_5BWy7ZJWE8;5h z65CaA#d29uBHN1Xvj0e`Qc0C##kNYaY(YQ`Wd-wZ(zXmXrvcRH&>HaO>_rCY;a_+h3q89^#4W^CU`WeN}M?e~t689tdy&CJH zQ7f8(CBY_KM<>~G0w2Ay4%!ETG$Y)$)pQo!D^&$0DvKR-d@x(g6-t8!8O;VzuyEkc za_Rhua`Ehm+K1wxfOf;ZMq1!jvHJ5$4*L({c9X@f6Y;|u{#eszdLO;+Wbrn?PiV4} zfkuCdL0nd9ioCQ6e*#=Va0S#}%-~^${?Fcn?dN^qp20t<==8+v-5B-ozTuya4qvN6~e(BHeRXsMd1~p-~HvE3yp-$(8$nCPFx$*VKKhsuKV9cW#M1{7k{T#&dfM) zxyIr}HL2|>H+QJ&!JrUGrbtvtpewj~hOBB+4+9FquKKEg`MYt zVF#pWI;Oo;6>jsW6Xh&97xDh6>hBS27^us=j8gdrBfwQh?H#P2Au9@Oh2WFgz3_c8 zj>SL*tH}Y71qfH$6W;jtk8YtPtXVgpDYPbg2OcOfAH3s%a_#CR@`NdJ!#`aI)=4r4 zTyv|Obnz%xgSPYK-2mJh(y#72)9e(t3)cG%wu5R_gV#-9`zUYTa7Oa%P+it%!0T}j z*nlzC!9kfH0t3jHQ)Cr7_jOfNu1Arn_noS;^=WKvv08_XdhqB2+`OkwJk7BgD=SN7 za~%!D%~^J1onaM}{DYKwC8wAW zPtMHokfBQCLyWaqTUjpa>(}XIL~&hZA}M7z@W2yIuSW^uLAnJMmCw$}W(53tCJm+M zTA(>1=7?3AXg^8qEN@E|y_Q}_C&1jlP9$r(-jGoD2U)q*qCYvw^!{x#yd>=5#1Xv# z`wrb*&YpU%tS(>eAmlcHxNPp}INF^A-O8yk9G2DdTA9^7>OL%*6VD?=bbOY&OVenR z{?3~viupX|W^T`df+E@Og(Fn@MKix%9}YTKONP+<^sF(+SAm)PZ}J>VC5D<6X+eve z_;<~x<~;ftc`tjNvYi`t&$dslqEPqgcia3gzn>1_Ji4dl-n@l0{YbTpcm0Z*dC53+QvY zc=pwD_41jR6{m_A_N5Z4Hao0V5o*=Vy?ee24HWmIG@@U_5C=b2+6{3s*cZ(+)E_?w zkC4!OUL|U3-w;Tpic(bga^;x8wgAF~{m09j-uY3+PGA1aZ*YVGt~Lv#_=25iwxG`H zjY=+@=;C=vP)13QfE?3h18^fVSGJSMT=Y5BYL%0W@H_BR?pySIb1hYKs+2~9)~HCa zRfI$w@5nCozR}m@|6N_{_;MkMUil#hJI4;~*QP!;;hSN}qEsUN$13};J6Q}+z=>oh zS;QI#H5FCImUOqiMpptgas$e(qV6eKZI#KOk%=-(CCznJuk&|=(z=rO@Ec5$^?D>A zwF1=D9==dc7P9A#W_mnrh{UhbKfAN2yQfvOBK4=W5*XW(czVnC5!6WyVKm3jV zsS4TPymD8Ae(wTbcjL`(*hq(z~dgx_xE>V?vAqjO(ir?nhGb-*{ItkS3Oy8Zn&s&p*n<_ zS9oqn0B{&p9UWs6yXiK3eTc<`TkSl*91smYYp+Rro;h(HczsF;hVGk4EPNfhANLK2 z1^@~JuGvalGdmY58jkx!MG{Fd))qaJOyGl`jReVaiNKe~9%qFT^Pq?ZDfsoFb0aK? z^)o|yUbk|CG!O*L7tg*z1vDa^{AJ9+)FSB1!r^qSe59RphK>4b>V=ZWHnyXo?Usmd zA|LwPpk}5u?C;58!8Kl^d5Ux8`nAiN^_9-!?uElj7MB)HfE#Yg(ocsuQqC=dqh?=& zsh@3TTTaBhe};XLsZljqOxZ&`@q}nMC*VDYVaMoIzI6Vi&Ue_Hp~;G%4F%!h+_VTI zW!K(AWFi|T${o$G+FFZHE$!4t?Tr9D~rPvVrBf>()TKhSVy3- z=((#si?>J?>xmlzD)iUiY#XsFM8~WE#W22b&)K^=F+7nJOQ-!#HbM5&qb_VO8n~oB zv!G(eS<@2fHG@7@J!J;mxK~r98wn2vYJ=f|y~Eas+PkOuWQtQgv#zQ7>G25lCjB#P ztL>6$Zo zz*tK{!e^v0A@sd5Ox|=kDK?5$=&H7py>BI1taQMjwYDBO%v~0(SIMGgFmm74gj~UY z9SuTSqQsDt2#VsWDi=OSltYT;#3+~AKUqgO#JpSp2kRL1VNoJ|m;ATXU@iW`c-&QQ z^&y1DfO>r;>J&nMrujxph0nxX+1>l^C@+8Wixj5Gc8k5eQBA8>A;blpEZ@p$cK1fJ zzt|7&`oNEuox2W{KlrtOD(jOAHo?YGRd2Ms=fnRc&-$l-@1Mv0nl;ptb5+aHug47- z=Q0=_G8nao*>uqwv&AzBZgx$!Z3``erR1$K9&9JslNrnc>_yz4tBqz_F}bC^Z2~h= zMGks#wEJLf;lm9eTZ!00NI7}OwOCod?=NfLWIX>yMGl&N%oXQ#hBB@}s+u_Bz2Elj zAKuyn%F)5Q3jRik7lz$eaFgcFMpkMIBaIh=*Db2SL*QDZX)Lfk6A^&FK?R8 zL9V5d9JK1+Ex_nt<*}?OSR3}hIziXqthA{a47HU6`Res0qAS?5s3y`uj!!UI1YH`* zAP%jN$F(v&yNAi6XM*8#K)rxL$7fNoHO7A6y%+-mr;YF6Y)KBgg>q}7Hr6U%R2JOi7RZqUWbXVQ%LFZTQ)f&qW_*OVoYcxq6CyQP~U?+!)~? zaU@KzK?wN$9tV4N#JTEWq_Tl~t#Xh7pS*q*;<%lpF(->r?HNdhlkLdjJp;|Ixmu(M zrOL3wDR%^JZjvl^5~*yr(&srTbRcBl%YiQcyYu?KeQb%4lf}V3I6_)DY@cUhBAABV zQpLZuH?+0|*;WS+rY6}FHzq>Y=dzb9_3&!{#d(i@x`Rj-r{~JK(=RYtBrat2y$JF- z@ICsQ4OHT@lng{t*Qrj4S%T{|Em8Yd%9;2qyjQ+U!6U0JRzOX&+lbYNpR56R_z2uT zePkr8j4uNu!|c&-d)xQ2^8TlP{3}$8hHd1yh)s+KvTS~SLeY~L31J?xje8NTQI)1j zE6kb+QQ>f$(rl}ebhc$gHL8B=NGTg@Yh`?5LUoDgk>>j1KA}Ak-&>W0S)ml=(Y=7R zs>J66=2;pr&WeWr+{~wUh5i&9=47#2COfd&mZIcYU_k5VL!wAeL$zL2M3Gp%4jL*c zzYUm#-KAho^h)aTB5|+DqDEVAeecN61j zLQUCcRe>9$Zcg%M=NHP<^nBU1aJbCP@1+4o;0Upl2j2MIl!r!e?O+ng4QLn`!ixk` z1|31Q92K669zxL3tR|I|)LIbP<+Zz+vjrjT_jwcM-wy_i-6r+CP_5^py+#{CMyb*P z2ZH(b(9Qi9g(7+sh`xX-kQLyd#q&Pnbq-XUVV3i^Jz^jb zmAcNlM26i0k3pNzIpduLYqbI-i`WB5ioTU(5#J%CS*b~@&bJ11+n0O^Es=@+Zzo)< zlB$@fz@xxIM@2z&1>+(OSHe+<&@SvhMpZe0Ctk~zfICPF+H1@=%}F1=W^UJhR+g6* zFO&;sUhE``eTPJ<8d*;c9;1>Ty)nUO>r{!Hyt&mu`y=L^CE%;`*m}ugU)?!8Xnl*5 z@S2RrI!f>%W}wyCf;qeJ3?^8`h~#Y<F_6vC2o0wWiKVRm`Xm);v0%D}SDqb5juF;FQw)F}Dl0 z;?U6t=u6I?dY)&?YwLuk<0siC)Km&(i^2|sP4-s`%#As_S%@J(7zd2lU#9b!8d`%i zZMGOEpa87)YvW!ysseUj)gkvD9li70$|G<6V7a<@zC87%k8`991*J?Cjihe)W3#x4 z`kLsUBCvHup!Olwd-u?C2<{+A+$^IUi_;QsZ53CXV*i3_wyFN4R?RTr(9}KE7w19r zO0abIyz=>X7lh&U~i{=_H@?OYnVlI?8kC- z7O^1OWjGQh_NA!fqC~4l6VFWId={l~58c@4geu2ON(Gdt`X2po0n#9GWxr<|B7K z$|M9r2ym>}Y;X=hxWM5@H3D?jOBYU35e-$E>r0}6xwOhg=IGNQD(E4=J&t~+WNJZr z2}Cr0=47$|a2RBfdeMSWd{V#JRS%)tBamsSHZU|$;Z*cFLX^~$-uidkQ11YN_Y9OS zDug;5N|u1!@iW3R;h2Pi+>Vqh*&+z-ha^zM%lwC`SrF zgbV|`iMf{iI@vVCEdWv=Muub&`_8c!6Zcle)9g(rxscS3xo1rJMs|?0j#-1tS1*=x zuRT|nufH}qNn*g@Oe0Wf3vY;K)4;e^^_CB4y&XAV?45(UZh;o}lCEI^OHR_dl|0$` zjP$y-;`Jtr*n&)0#D=}xvRXPuOt!}pW+V4gL`z-t9?=>)J$J~7wS^f+A6#LwN!nznhNc1A>YoQlAVCtb!35ASAr2)_S2``#PkLu0xBNQ* zTK7j*3Z>PZ(`LnE!Zq=KZe6NEeM;0?OOBGG@o@~5*PwIGZ020Yb;di>GxPj@FoAI0 z_!-nRF>L;Yr#@4@`ni8sukV%uH~nOhRXnI&O1!7;F$&A1WHAQDy8`RVo|BA#Vb%W? z2{&n=Odw-KN3;R)`@jT<_87!l269?YsBE1_GpG`&>$KfbpR4*D8xY|ce=1a%ZfO>j zVqAR`I)aC~nbS4r1cT^bI6@;dUO2radZ!#r)c{>bKL;U3d|;F*(Hw*B zmGL9d3pW&KV{0xJlEK6?`U7=XMGM74HCp3j*xYA3RXcVX((x(wm4R-FfEP05J9i%} zd-mPIXM>;Pc_Nv@!FuW0&-3@Vm*u6)>_tLV4AfN8cIr`%LCn}-v2H{@;{{zcx}YgU z!#}PwA9g>EirVHqB+vZx8MTSb>C5 zl-qH>k3*eDMru=VKzy~glZRZ^h|3@uKVcJSzZ zfJe)jSDy~#Kfo2zy~c=AqM88)0#q{{gjvXm0azI9`g~2liF0GeVk)Kh`0GrxDRyce zzfonQ>cm=|6lb)~sJrWgf%5ixzr2r7&BtE4eBoq$UbmAhsyfvjOTo2w6;$Pl&Yy~m z*UG?P0-wRF_GUOB1om40{5f{Mte$M$D6@0B%l^anm9wus#~w{rO{xQr0Fe$mjSO(` z%`-nbT4rYPIrk7`IRmgD?BLL3(E)&~KF&&mMUoT9p-w1(2ie*7Ec*#l=er}o&NiYs zyXXap3Pi2WR)f@NpN#?Gu>cD4AkcEVmBoDK`pB*JMEuFji#U%Cw7Qiu3kS9R(eY=g zvX^gZZhoQcL9#f#lfffcDCa3hZ?OYO=i`s5bbRi-maZbI&j5%S&ueXkamIsh{vNW;P(ZM+XyB?vi)6dmFFrjNtuNs- zJ@+tX7kW>zIvtfltVN~Z0cc&j&Nu~y2!Oh7&A~ZE|L7-w>whUvfB6&LWYPONKu3$< zc!pi4vN$wZ+)*oo9Lo`F#(R$8@1*N)#H>1w*g%C(fQNepxyQIQL@lN2chIH%nFQ%b zmu{6oKNA!m+-Hh4&1$boRPZy;Aq|}Z*!h@I$?pwyRJVxmJdEsMTn-_#i|0h-h+3s z3i$`W`cKNKm!GVHksiZS6Y?b5RPAG;3gdRv>#6gjS(w=8qJq1+DWAGY1_r?a7Y}&g zLZLRQz_yV-4@PEP;l=N*g35M0Vh0kvBoG`)Wv*;m(1sQ4u!D}VTp?!i$JUpcyx7_B zZ=YR-U3yIenYw=FX2~L-MGcz^Mtx>}fz(zQVN@0GdH7xB zt_Qxoj7?0_2wu5-n*EVjb0qAj0`plcUEyaF(O{qv!Iz-ON&~{b;Y6{Kk?g`~IuYjK zX=ROWyqKJSzBeUgfxzV|rni5lKW(#DyIU}l^B62DhXyox2cL_CNLsL@J=~g(S;?ur zdQr&=AsYuh1`klBoZvuUh(%rI`r7bvuHVEotBr7;Nao>aN2!jhy@~hXJ)*>3Emy9b zE1PRjZe3H=5(Xh;k#m)R2B8LklK9TxMh%oxQtoT7hBU2ZuCzel1fav|SD&GQ;od4+ zWpV;C*0W`HZh@6=oY(VbFq>(;R@Dv4bTg(nUqS1zV1dz2t{2f&^@Q4{Fsw=eZKY^L zlF~CfaWor>S&@z*FGM8{!3=;auVX?^hJAGXS)&!Tp~(Fv^K5`SA|SnLshy1#IR%7h z&$Ygx_-az)2WP)wjR4qz>4A#UG8JB&R^U9U z8iGU_fh*|y05Waw<50If5cb2*x&M7RSdgrFcSfLWMB8Q^p`iZms|j*Ts!b)sBSo^f zu>VdfM8jqvS-f!eWwkp*6^&IpQr2X9I^%vUwiSR*zSf+qaydg{o`9Kw9|TvMYqW8P zjy+63>D;O3%k^ujEVjoGRru&bqfcQ%rqTWSDu#WUKZATK z{pqURi(l0$J-nPfjsj&+y$7I(Q34OYc?tQbU=@8`GSd(q;iJ0+cTc~V^4vPc_LSmegys<{R z0?=AESHK!#t#$akjWw=0lLzAXV!Uu|V-_4}E4vEu*$AOJ~3K~#^R zW(SoRdkrjv{fF)@=T5!A!c9(Axc3OyBr&06lbEDMWxNj}`T5hQBpazU^w}6GkG=Z` z%l;$xmyiGIKdrrZ+V=vmWFMtZfY*KKhyPaj&0qK#7Mu`2=`6L%oY{VrhD)0Swc#fI zl>svWCZNPh$H3xLm3bGSkb4g4Ps9H@F1A(jbsG52{gVxh8)Pl&_^9yIfMCI5Oz$dd zAu5P0BA_BF7Dc6x_ZfY$jyWD=B^+lq;(^e3Zf})NWpTR~;^$ak_0ru{PM>&& z0V2>P7z6hk4EnbAuB_mXynMB+gRZ&0%A^E|C4hiQ zB%fPo)Sslmu{?P0TjaXuU}U?^7QHL|p!8;_hmA`=prN6O>Zs--`QRl)%#J^zHXqiE z_OQPxsb5*@9G{Jzf!X;z+=o}MTnObh3mxS^P!XYnNgQy`FY+8o^!$vY3XkBXlrq8I zBdM6#NI?{79jNOnkk&OCQB;VHzEhP?uy*FIxnY9~cu0F+dT{Tz$m=jA?@0Eyg3Rq6S`xXAZe9aT7LJKOD+d}y*56#BZ(fif6prIU}KJKKr+ zh*O}!&xqg@i84SPB+67=ZeFvK-T9ij&oAErVQJRI2h{4wH0eUD%|8v<=S~)Lk6nC5 zKUv&ZU$4nx>v6GqsQR^XpkVuK$$irdk@E7~mEDzK5S|Ao+aSBl3 z6OY~VCRRr=XZD3>9;Y}Nfx$|%52|8KrgRK~gjKY|5}xpo6~q zL;pFoD*oi-|FT>-{XFjl^J!fP-h}T4s2>&A3U)Kcije`H8yT^c0_&hb8(>a7i3B1- zct^m&7L$L7Z++(nf1;dv`Kj`SKmNCTHmd%OSM^DKzpBh!uNYLXWKl_~Y0nmuaZ-Wz zQsFfEAk_*bki`nAtlULKS;?X*k*v&e>`Cey2*rd$#~&eG{Nni&tr$?*FKv_*fvjk=s_O<( z8J~d;0N5RQXU2@daX$XCRo?f}|EerqyHx(<_kLa?dQQk=e`Nb}*8|^C-toTwwEX73 z`f0WH^jHBkmZ$Moud!l~?i2?58B>)_HFe^sK+Pg}K`V_|GK1;5gEqp%Nqb8`71xL@ zr4c3^Ls3~eVtBZMS`$Ctd-zQH7^}w@v{nhcus?GG?lzj6#Y0LmgW4ah2(IMZEXL-w z-Sxn?R}8-e5QB~i1`iMO$eoW;-3)z9FscezF}E%f!+|U9QnmUND)vf6dEdqn3kXL6 z8Y}uR_8d4~Ft`&{0Bmk778V$NX^R(5YTU1FQ-f)_mvAeP#E7JIdV7ee8Y0dgFf+Q*%TgEwrZ?Vi5D7T`Kih#6g?(BSk_| zFPfBVN6X~oG@S{MA*vNqv5cxwWfc`9&}i4!*c+@-ARA>9bWS+M5OcV(8GQ^{jV_L- z`ZP!Bh_M&YAA+hPP*ns3Q`56$brtlV%RFO1i9JNR85tSYjuA`tV9*$~1iEHM@%mxU z_hv?L`0s9=SfbwrK*{2T*D4J;R{(Enc%yQVpKS$qY+Zu>VcV(zqFd=|J(~VD_dSFt zhDEc&t2OFwBpQ(!;kqZrXP7Jk+`&ENgdm@hj5f+Q3e`4+*vTRQAtj6Ir5^TNazLwV zbE;M!X1BQObH^`kz3SBwM_-lyJ0r|a<|^`BlSR?q>h(DxNizJ^j`V(4FAj-72oj)= z2UUIx1?f^fhQb0v?Y~(NEuK`M};Ank?$N@OjwBd-feG6Vo#U zbI@vl0MMYF{FW$?{M)o?o!EMAD^)3G4h~)is%5Hjc-%z1xomE2mbsmK%Yh^4cV1Uz zcIDcTWYIuvjG4;U6G69@FYIIdn>Da444R(^7KrDNwX@U3dXk!SjD4^@42#P!3S4feSHx`E1|F$h^m5I%Yr0xM<}LBRL%2gT^)sA zMsK8CQ4_<#cXIAxhwhlhVnp)g3N!xJ9JQ#D2i05&Y^Zrg!jr2$R#XL0iS>0wQ`N}v zGBG(>zWXEpb=i**YBBZ!*Lrqt016-`gQ%Qnq+ls6(m#4nqb+7*W2Lo_Y(_#8 zVuDbD=8WT1ZLY)S5zB3Emi>qBDewN!Pcjbu)bIRnvRl!50>IUMS~*!njDuvI0Jnt} z(T_SlN#GR;9(xF*&lArGItch3d@V*IdFG<%ogq+!lM@?`6l#p$KztfKk=P=vawSDo zu5bET?MFmqoxSBqR42H zZ+0@S(W`psf|9$W=(1$*}!SpY3y+%&foWAf3H0Al|L$9 z{>*Qdv2iFGTWCzFSgqWbQr_~eA1e1e`i}D3zxembR_FjwHJT6KnhGt0F<{rCHAp3i zfEh%z&ohNH>|{=U4Gw^U8gR|4tW+)(2?jU8O zKJok$q%+p6x1xp4J-tD1kt{|dy6B4%7eUjl9k}}CLO7yG(jSfUJ9jIInVsKT=Jy<8 zl@kZdGl;}%zf6IVtBV&n7#RNz!-j=oA{mNaa;91|E>xZam}r+YV(~1xl&iQ`1}j1X z?ZEr}li*qL36l)L^y~brssB-`P~P~_{5A{;?@?8 zE1bobKl|$(=q+?ri>69UODMX6MhaM@!YYA->i&lyL)#@2EwPl+S00m4ucF`c3 zRrdh_BoEm3Y&d;Y1tsdfYz_A6*X}AZHwWq-s7L~0Z^A}Hm%3iDc+)i5}1#P@TrFJG-l@La=ycUg z)iHm*_BDJl`ew0rkSxO9_)kmb)n}e*^VLUq{$h-x!lgM5@gDX)5AK6>joxqBXIFY+ z^q&U}4Yu#--EU;&3~ZXGzw(K4_42u>_C#P-fm#LKO1`z19V=N#gjL8;@HBYZeLVte zBrr-=5OdW2HPc~H2_yY71WM3zNTHY}Xi}?G(Q5@?Bs!|-X7B~tLt0(*gYOuN#E4*k z5<^gL*VdNlH)_(G)J+i|OwI0QKtHx)yiCmOWGse+3RP6JVSuRwA7uRsfYeI98lXW| z(gu7GMo?`M+$7k%cAfhL|GjeUDicb8pGcI@pNK>n`+a(D59jiMHSxKB|BDn&%wm09 z&$X3CHD!fbVopjHmn*;l&;*GWm^m7Kg7YB%iqAmIL$Nv}&=f#Y!Yy@Hjc{>AQOT&1 zI93)@8wx3@q@POc1Z$4(f_(wVj`+;F5vpcFR{^X#^+_@|-rOu>lS*D8uE#T#{6Yp> zw+C7yS#-bZjvWPkfJnemDfYD)h+{=8zT0a^I&2giBn%ZGM5x6IXyu~QzPJyw#>){e zAQqgP-(UXXU;XLw>EHcl<(2235Gx?)+X845J35&|WqW?t{_?S3`G)~`Mb<+57WB@D zkzF}QjMQg1WuMsma{{JPyqOCR20UY zp**!hn=67rPqwf_6I~GCLBXFgTE-_Q$p}ED2#FyaAsoKO9O!%@NFX(Vq8Jz0FM=xM z*u+HHdk{*xFHvxZlGB@F5i~%=!I^@Q;i%N$ebqp^vn0KW)UB4Qg`fkk9Of|d^YI(7 ze(1$UvWUQ-HMej7p^xL1q&&w!ip)yCQFoWq#UJ8Y*vkm`5$tl*)%lZ& zLfRCt@fl4#1r-8F;$mDx05>szQ?Kdnb6<)p$`pa1*p%WR(7Hk6g$;)|5|V>{vgj&Z zV+;@s^bRwDUzUL{D$|>Zmv1+tA^}k;Ghho??iYAoU5$oVN-}C6Z%H0pXy}bDJ z=gK#~{^=02u(E2RXJ+uT&gn}%Qvo<5(Dt%5uup!S_Z$K@N-ohN(OO~*ya22v^9MpW zq*q4J8GGO2VU1pi&x*djF^JRz6|#=24p529qW}?p3~L2{z`^IJI?|R2EO6hINA_@u zD>xvUCBae_6?7I@1w&HHaZ4jio{;Q8r5v#VlBDUKy9;Jk&d%;4ND2Q0#u$<$of&+l z?BvzOGi7ZR)yr#C-^X?S?!WmT6|W-bjoF*{ZzYSc<4Vp*XJ#Mg#*kzYK5mMjujYzJ zvN$?c)>r$8qGQlI&xG9k(7e2>k1p}DM0r1wQH50jJ=4M zn(FS<2TO0y^m_SZ|^4gv4xoxr-@dKU>smf&U9Vm;JPBXc!J&+OI zc~4@E9cPd-9aUBU5*#TKVuRc(sE)EvSX9Xjn6!jZ#fc+#JyPEL(Z60k_HTZ!T)OaD z8A-x{PRv}i!t;FJ_x}yXCV%|9|14~cY$)uHg@ruvz?D1FqK8xot1wTtwMn76`l3)6 z4&DXrf{G{rNTrA>3A0EYGZnXv^RQB@@|=DG$~_d+=;l-6oJF!|)26?zWzZeLbgOX5 z$s*1rY%}L+VwXiit$DAlP*d$bfckMBmMgO!j#PKm_CtU;hn)fq&! zO1)U2j9KSF1-)s<|tyZ;c zR8ws%AV_%l5FGG9=~IF;;^JVezX3aF4-BFMSd8A7nkDK5IolO(qJi8%9in^fLUhC%PhFH7W${;%WBj_ALmR#S9 z09)ND46C3+#47_hQS%ib!v-c>IE6}BG=TA-+ zbFs_`PgWB2p0$y;fIxS@)Fv=(!%A;eu-0K8n8DE#R?&4!$rH&U=VP9G<+hT=oS>@b zdy8l9(6NVjZZUYg4myuOyseX-yOk*wFM94F@kZ zW!i6=2zGXLB>H^-Cb^;rKJ{JbO-C>ddj;S_$>M7%kcn|XwF=yN;^2c(wE@K)XPW@( z(#488%g!~xQ;9ngg>`~R>d)8upgje2MbOugEJF0AUGwlH*?!GQvMURnXTzma5~cuI zdoL?8y6Wy2p}(F!Us6j|u>8OqzKh8U)J{=F7i|sC*+F=)RG27<-NVm`{vXjyHAuV0 zG@(TR^d2z_sES#A)xfYvAmm_^D(e7hF=r2cKIZ#Y|7`G<3B7kHnDWj^=2%2SUTWAL)fS+L9xLS&{XJ!_`N~+|d`VD~?4VUMddDK8u z*kG@;mI#<9%f!T_m@}B0jCsei0{W5Aqcs9C<%`dJjsPZ-O!gF_8p@;~s$A?dRN%`h zdGss}Ru+-`O=&iBjJmR4-B?{IV;BX8wTjUf_zuLsc)b%sC8HXxf$M=NqZQ#1zv5?` z>nkz(!b-6cnql=YUXObO>&HnJ=RF3C%n2C95@TFL1yJ$^uP4y|=%2NAUa&UMuK+U- zBP(>YqCeEhBHkY2LKZ-4eV0fs$AfOG(H@&%=CFbakU|tkR>hgPi%QD}9c@xj8Ght# zA1uH13;(@l5+Q0PihDq@xP<5QN z7fSko>^8U3v%U75qW=@T3ZWeKJ;PrGNL%9^-}mwR9^1-+Z6~PZS~TT7(g0?6mBYs$ zr5e%Mlh5*@5tS6@F9b!jDLK$RsC}$vfMObB25>lhsDPs24-PdBmjVmBG#5uD(Xzh^UV!XIvOubvMuiyV$M@}CI9euW zX3N=EpA96W`ndP7yc;|!S-Hl{?Y{wX>BuE@VgEBoB+XJ*7Nb;|5u9m4u zjEE4j2ZOJX7NEzhmGP+=(n~-u#-0NOaxLcn_`8hsI5F40)jouyV&Xb6Lv&8yhY)Bu zRVeRL(XLieO)oYoEvJUV4HFJJ;&|Zr0xdzU0c!pZLVF_m4nLR_ey}8Vw zO@5V=#cN9!%j)vg0Cyz1ASv#a#L6KwN?%P%G9VNqEOKGU&s8)gQNSzZ-G;;au_lY^ zbyL+QDu=n+9Z6Jo&!9pyRt_G2hzbAs(=QGri``0RcWvwM0{B6)2pbDET#0fFd%gSM zf-Y;}oB+D2&{C?38!fhD@7kBvuc_a+xwy?)3KXk8wX=`f)3sf6plcgZgO-pMckple zC4%mK2k)j0IrHi>QCVy#t}B1u54tYXps@92i`0KqqxS$)(n@tjzUU=JcHbIWzFikd1KFq1{BGxjnn zi|Z>)3;}vuhz|FF?`J~DnRmKwC5xe&8ogvn4A6(FXHcp2Q9UCiHL7&97I;0LVJLhO z{KZ}jMpW}Vjm4ClU;F1!lM*vlqX;5a(H2>OsQ4mIjz(23JPX7&PPTB8FjDOM zf9&s-CqDD*<>@Crp{iJ=gJ0zCOMTO>zw`ZvIw*udv*mL-A?*-=y_Q}~d z+Xs&vzwfOzn(GGxU3;tQ9TGbX+{GoHeDN!7*y{Finr*y-#9RflgKgeADw-|fqJt#2 zR>3D8xcaKPy^tI{$wQ#oNlaETwm}7)RZW0d^YFM(Ek)=#4lQWND_8vUnG0<_R zS*0$%ht%(h8B$46iO0GikZ6I{2x%Zl{vc3;9udu)4E5h_oPQ2(xQ3knIbIeH+(~p5 z&lVMVNbv*J?b`u&bcfT{?e~41vDowi)&F@$YdC77iTedf}WyK*Xw>3XHwpF^+(HN&b)^ zFxGZ+lS8`ZoHd4cYpZ9RC zBS5)B^iDv8Q9!9s^$h?TmHw$GvbB zgb7)F#A=9RR6W465={`FH->5(&OU=$jVp3xj6!EjT6GScU}t+LkrO2yUVG~^=q$68 zTA=6&!57CwenzGV%5Q6TJCJ8vN^S2^+|`K@BH3o8aP@kboPywosz0opuESpqOBMx8 z6CfddRtYuy5=3kS;AspRJ_E|%oCO-~I85SQB}>&SSB#LjJ4W;zKPTPxDOMRKGc4j% z+m9-IY3h>j|F*7c9M;Sivr6P-& zXq+Gr=B)!JsnzqP1PTCFlIDvaf}&VU~nwI)VH zsf?SbGkR4!KuA90Ob3AuAMypH#@q^(X$FrZ9Q3X7P)WWb#Oih<1 zBoIrN>70=u;5yMOK-3rOZHaIvjQn~jVc`$u(^I90!G5Yt87Z=H9yAs;qT=Ur@b1{S zLMo1|e9~&>%m!XcTYrpv)IfiNg!?5f-d@t`8L0@F!Lwhsr@NgE8 zX#9om{V&QLcfUzO9P2A(>52qbmaknb7tg-RBpj7m^bV8Cc9Ue02((p1ldO8ii-skO z4T%dO7#;@QXLVd7BW2INqoi$KyLw6NhY)~*145Drbw?!WP#C><_LYGik^Z`Fmnhzz zNmtM-;D|e;IX&8q5c{$ilZ|>HpSX62i{SmN>IAi?_M@=ZRkfio1{p77!;v(gzC`f>4pHq zB$G~1yU!v<=uwv&jklk0_kB?aFL;)6pa81Ow_ZD)mm$fbZC=DRu#_{?^X1{Uez5F4 za94TyiI0~PFMcfrA z25j@38K{a1HTJA~811`trX$gc9#8vGRJsg|Dj^axfLaJhrjmFLk~)C9Wce_;4E954 zK`03e&?S5w_M+#sGMQ#Dtr>wD{H~v|vPeoODvO$BNpOL5SPQsB6*d4_s)M5P7GonE zc<1xZm|<*Oy@g0h!fsVX(x5{kE^=kjil?@PWO|_T2QU;#VDyp#DC8QA>bg}4Li~Z) zNMN(0X@b!q)T9_h)kb};diKb0!+htlcyF3f>SvT`h<^T3BTeiCCyOnT@A~X~!c)<~ zzFBrfNjciE0NSoBUk(7$@pEH{a9<~2O8eiUcCAIiAf{~z_c4>+ISLH z>|!4qbg(VfnGDb#&&?{tojfQhlZWpd){k%BQ(1!%KV|#gxApd0ooC#$>%PYJXgzMp z0n@GGy4#I9#DL&6B@iRqwvjvUM`iK${>Z`TkOJ94@c-xgM++cyK!LuidbbWr@@>Qn zvCg5g&m5G6i_R zl!MK*D?j`Q`(zBlIW&5n4_0KoJ;b!Fg*nrp%(huxoeFUna-d`fjy=dxBcL5{=2J9A zdz~c#9m!U8v^RgknKFx4%9!2=ftneIMD6cHr4#R8lo=JBB@}_f&wF(5XzU3eY~R1p zSlkEtPjTO@4&}_FQ+DstdbQU?+l8SgjTX)7n|Pk9LW@ZiikX4oxJCa|(2ac}8nX-! z9N^k@s3*3e#zw1!RJ9q5l_osIK$ueN1Wkc$qd+#)jCWBff;#Apy3>O0?l_X|o~j*$ ze~)=q2%14f)GRayc)X&4B-AJ!s-FlRF*9{~eh){o0ARuh7bIYymB48Khu{DCa{knF zf#y4C@VB?B86?p?BaBrJ9*sb-gX*O!fcoXCk>$QJ^`y;eq>YIgXb6ǃQ&aVS#+ zj&^dMB#?jfYJx)Td3)WpA6&`XO%`26+|IUTBsMl!oRO#!2I3x1f-ga^gkjY2%AV%TN!inVmZmr((Gw>H=UJ3S`rc9Xx{>N>At38C zV2_NAu}{vUE$Dj+eBU}h!@Y9^;Q36fODhjS!1Mpp>LHaoaV?)$Y1Hd#! zq%gap=rIy{4ib2w&nGht{gF~tb<)Ot&T$)f9x-+zKnDAL#oS30%X>a5d2Yq(+vN^J z%@w7nh~Z3q*GK*u&*nG2@Uhl=S7QvtovJ8{@{Tj+eVdaUSKD$TB>e=uUesg9Z3gl2 z-vHzOqaXRZ9A~gZ6Ga45 zxGi`@po`DERmgQ;0mwKxOtT|#4xLnn@nBWoA*I2A8Ygu`ar~Tup;v{^EHanGBNGU0 z+N!?q=FF3va1TZv-@;D}q_Kapv6ZsFmJJ;(1Ic2`B%3&a%dvKt`8D6d<=w_x#Obx; zccpFk8;9k(PC5t66`e$@qGa9SrTKpSoz*dM5WA{72!1iF97dRwN*Jn!HC{z=rYlEPgMKIn)b2Y(o%152#% zNK(6vOku!)M5FWBqOa9I{pysf8}R}lw=}SpJWdGd(9cNdYrm4&iu*N%rcuM%W9E_O z7@4|qqfAcE^S>d;QV(4mK7V$lDMs*yIZ)_HL{Nw%0pc~Ngyv+G#>LJ5s61l4#Eu|Y2Tq2Cl@7dyrPXz2bS zwT>#Z`aq$c23qY3Y3}MVXrxlC`Mr<4iw<@1(itkEt*u-yYuA@3A&s@Tv9XCMpb9cU z?Q(yit7vt8Q&50SQ6HNs=&{0i<~bf6FRLrdW$DWKf<8thNv#^(DB`y=Vz;y2*`5xw zIk8&;H^{b32yIrXbb<=IfqpyO4_E}QEXJYGTDh@4kl$+KLf8Y>j^OFQ9S>3j0hL8O zClf-q+fPG%N6f`jOs`~}6^5`gb-z?_O2d%#I#f6W;?-n199pHORYxA;4bjV}U|%9( zwx_)ApaEt&R|^i>$O!Cv*mjK0fV6(T=M2X6@7ck;_Kd68W_>hYrT4Wew=0HZP25m2 zA)71^unMaLFd|iHgEb09`ZUxF=U(RAyAJE70&fPMT7Uo%H1sVZ$Ub*k$)W={-G8HL z`Py5MD4&J*LJ@mm|1k>esBgAApxZQ0kTb2YOrX|1MF0S>2BF&RJ|DFYD9JJaTYLJW zdcf<{gJ$If*AGzg(6NWh!*70HId}Sn^3<0ya`{sOeP5Szih2k2?lO#9wO@zrP5-mpmCSYe5=Ax;|cUgT+hSsAJVT72=(l7z{=w%(0;x)oMxD9OkBOQ4>f-!30O$UVN|)j(RZn=2d87ra zx`-k&x>*xPAh2@-7w`5Ug zf-V-F!x<>7jnTYOi^KgP{v2R8IJ2fAaO*-nHd^LeVHV zEH(NWP-#^)a)Ol@P%L2p#z&{9C`&q2Q8f}lF)NaoIfQ<)&5h`v14=FhOE(3p5w;;4 zT$>mezdg#}`)>gzg*^5h<@KF`;u}R;vRa|a`Xia<7pQDq#~PeO=$WWpHQ>zhbbHTQ8O5rIC^ldET> z?grx7oJ^{qyVtF*?eOzalg0E5cI`b{cI`e8^X4#OLuhyl5{;szy%tUu=RoRl*9n{` zz)FeljT>cV=R%d&#@fKyu3TT_bC9zg;d6S!w|}_YanGC7k2*6)G?rpT%a=K)YkB!f zIe+?va_W_*H0C3H7p`??=Wd=^T@yzBOqCrw#`!p5u<@Ri>sOf6!m%q6(+XBhorq);MROrQ$4o52QBmYag5K0{6kI}zsugVm>J z=ga96&u~U<+k@V?de<=fsr?b_m%*b7@H99`u~(yy=PHzwNkh98prEY0uA@soR~y1$ zKWMgzeQ;1>R!XE5c(Jm`Ig8KLWO3ND8J;Y=uz*(Phm`R*r*a_b=88SDdrfpQ7o+hfLP{2!hXl#3HBRU(Y}3p%0#YSq_+%%D@hvgdqK!J?n$%!d6-hoZCw0~YVDe_F ztN=o53Yc*qzyg4T7GCQWJ;=H#1>Y7R^3Qa~{55Hw=>7Hx4z_bBF>3Z1&wEosH(K}( zsO0ekSz%dcr-{OFu3@eEsSi_?NU6oPWHI?IBnqh5GBNhNQTH)Ih1Ty?AFf0f*MpX+ z^`jt=t7icc80_Tthq5Hah=PX8)k*zq^?6khl>pq+I%eP>XY|;8j}b7%cMynOxz4?Y zb0Pn=O05Tg;kb4H8tTW>+F-8mLvMM1`PvtLw_Lw^sj*e4ifI5o63h-Iv+L_~4B-3H zdRir330AG5N7W2x=WXx#5%$*q&cFT#QRxey+LcW0kXr3}>^pzB-1WfQ%CG$&f2Yoe zwSU2Vsh1K}->^$qPYUng?6^{IUlq*5+!n;I>sHp9ZO`In!7{4}W&;mwM>CVc`9Wjg zMgMIzh6z9%(&wm`H8tjH8~%*{u+Ow7&o*zn+-&67y>A(sRoPJHzi)PZ!(QJHDBJq9 zvMlr3+SAvJs}mu9ZZ$*>4C*H(qtk+x?NIuB{ha`3SjB9cLsEm4aPU@NVj>a-3YA52 z<*`u%9dnN!=yy}oyO?Yc^@Nzq#u_VH6xU&IK_Ly2hdp|Z!~oe$jlZq`%CFI4s5gf+ zmili6hNz&-&F^DCZG=RXhlU zT%JT%(0?`qiH~0E&E82CYwxR2Dj;$YuA!uLBzjk`oTIowU1uk>HEB*kZMrU@(yD-) zk}9L_>@Th>s(lD*;3Ox;r)u>NpaIq&hE8aCo7e+q&At-^C!?Z18&Sq(P@JL$HL>^T zoN^%CJ=$&0Cn@+&bu$7eH)4;Buwo0E=EZX_v#+nxVsp^iGYmev5>~){wI=;$h!lL( zWV=AAc7*{IKn$wRalR&!Ydk-Vg}^#NKm&b*2uSxIzPs$iIGo)FsQ~)NzxThF3#eu| zSsW>>VjemE2rESn9IjnCM`|g~9jeOMA6FL7Pyv=bJZUyrLw9Ak+Zl;@e^Gt!CrurD z6UpFqhPY2%?IhK`-sSw-EQrHrgJg04odm1Syo$=A=CpMK{o$472IwGJ9A{tG?EFGG zck($>3j0;+PC&hlbI8xT9qGI;yMh8aId@Q{z`W6Obe#&+Geh4==XQRoAKdtL8WV+m zC%PIw6je6tLG;|^q4L>r=R`5v&Fp^$5nAmnonIx3jmp(%OrjLW48Ana&w-=IJGg%e z0V%-1`Gv#uDF8n(XA^ycVMsf@bxz3LgM@oVAc{Z|Nd`tW5o$*Qe);KB{C+;2*C`Km_kG;s>9pOgXLgl{;%kIe5qY<=8!MVeI(j&;BO&8j2KCb9>m< z0fyAf&OH@u@_H;UU8cG`z=+kg>t%gqxvWE_lr2C~)92qYf`V&ELC0Vw^#q72Xqc1U zU?tV!2G6Fdz#LstMQ+q$_B}uFH_OuEx$>Dm{8v>hD!<0GZJyN|H_AIc@Z*eK|KL~u zNu{6)NQ`G**S95$wtGS$y6tB^A7sL@436rxD)pk>#*9&`2&Xt#?JlC)*7%e*NtJT5 zS{i%BYO3~oijLXaYC5{<)roDwI4@d{`hAkk2H(6W*7t=u2CU#uufI}>?I0G-WU)E@ z5IwN`c~YdRPGvh!oPOR6K?}5VRf!iIp56inT3DIF9Pqo^p`_79Jhnj!Y6qNkEb?t! z?(mmHWYbSPNiT^2pPObB^i%yIR~iUppz|IKPXP}a22qPt;ZiRKj1>fS&`izQLZG!y zOwgqSoQN}BHa1pN0a;mQP|U;3ks&Z(8$peTN*fWAHiSOh7%7(v2aj{sB7zAUF>kzD z^YK3d(d6$F<;kj1RG`g=C`E4yFd{@v)eK%sC{5N#FC~j9)f)a>Txr&d#-+DIn<;~} zmf-4QH26a(z)q4zJnvms6+7S4{VsoQ6TJ**3pC1J{y7s6xo>+imh-X z04mXt-JgT&#PbK;6~+(aNt7sP9LOa4QMPVSA=S^Nf8hJUZ9X%+!)mZvMFbTp1kRT) zyjqqP)hp2Xlg^2M?qspO&LB|F07V7JXm3PU#YE2ySO*jE#S@dp(&tRbq+K%QCQys=K2Yo#;0Co+2I8dbYJ z?~L5}zH-twY;$jy%v6eLto5*Dk)It8916BjCB9j*7)N?21H-hN+*WXL^OgGSw0d`bD)t9J%JMXodCFyyc2axb|9YTO5 z@s0oty}I}=^!11qUB5BmScB+$13ueRum7^0>-5nYe8~7%^oGS72hSw}4JUB&>aZiA zej?d}-2k=g^7)guoh;%zaL&fo7$Py~Q^K6bM<4qjsjyG}=^wC4TB|0c zK&qPQDwkpwRN5Q8+xcWc4i`f^!w; zHYbby^|LL>XI4G2PTG`ksbXl~D9SJ6Dpn^|jct`hB?F?%N_>YcJ|jB_%ySGx0?geX zN!D0O7C9=zl;EKFR{AOFq=@~{quBPQ#R?tUX8V&tv|KsNKGUzq{Kf|4}*l($~t9U-|=0A3%YHtqC{y z_r}(SW+%ox&iDVNze#)YxljCp+7q~0G&5RYZZ{dMMW*KHdS}sgH}!)CFlJyu&!Sr_ zsQ*QPAPQM*H>z-KfHiS}1_z=y+(1=r>8N31jaEC?S$$i?KCPM>SI0A$M|TV+d42!W z?Y&N(&9Pk2?)$M`B#WL~Rm0WJH!69Poa!)#>q9>bQMCi{qB~JkT$7tQo3ySPP-WEW zCXB_dix&3^E2#@g_Xx?e@>y1@zv zdimg_Bs!33pMBsaCpHdxvjB|HQaGFgNA4?E7SA&H6ip~4jJK66%INkJith7khM9p| z^tFIu*6ejg@|rQOXTNvul>o#(3KY!L2nTo%8u2JoTcoit)tJk^a zNZ3*FmpX1#9}JTC9+PCZ5yZSF1`=+qjz9vHa5{f-lAjZ!{Mwv|q7n>X==8~FG^4Cj zne0O&>Z$d2I%qa+9TlPrXI`WzR^RFPzlE$v^L`etsq50U_1h)I`aDzP8|rQJzV@ly zB(QxwCO)sF(PZ2U06Zj4SgD*W_Mh9}eT3LbRKB$5TkoP=l*i@>u<8VtvCa<@B zrBUBTBUEsvWD&{z{!X$8@I!fg4yKx&bJY%Oi;CdP+yZ?Hl+FQ2nO5oRWMFMS8u~ z3TvfwiY$R%+D{e{eo0B(^SiNk+Ho}i03ZNKL_t)R00kl7b-T$TZi0&BS^bm_xy@QM z?T}TbT2ZuaKs$qZFAv5sj-N)TfP3uTw{Twd^G|)Y%+4*8-FuIe=b!wHSR+B(^=D`+ zH(#$I>)r7iwmV3aN5`ki)buRJaY1dU{o|!?i}aKq;$ta^b^Kr z&%1r&NU}fhL;p=VeC%O91JGtM`+990IACK+eXqeh7*mcU?7-$FAN@85H@6KOL z)pm7VB2Ow%GzDB2%H;q0g*C_T+EZfLG~duYKS~5+|D?D?AXuCqvS%dl=XhvXA>pRU zqMezYKQ~8gi28RgSoFed_d0K8Z%~(LSy)dquY^E^CRPtEM2`=7B8HZI@jj93}|ht*60U(4o!Si zbm_2S(0eoLGR}>U?Z7AkbY?&yZoo~hgaL^!t{L|sngLw%Mp?PGM2e^mOH?L@B#U;4 z+4&7t7mVFx%5yvm-$#t}&}}xS+^=3V%2n*M4v-L|3?j&H^rIBa$o;oqr|u^`Tn3aO z@m-y61g%J7HrB6~eTVO(BG}T^^Hh8Vbry!T${cTPmDSZ{(mwEcIx8A6(ona&HwUjz zd#zP&uqS{5?mv1z=Q*PPNNRTOH41kypy1WZcD#vg%+J_yZ zlf)s3Yu>B2Z(MUL%kF^K&ODp`FP=Ril#X-8+Kg6!EbLJoneI8kswmNbjk?7b5S`vJ%K4K! z_Z;GL$H4L&h?*JV&#q`?qHh~Sauv6k?jGO}zmPq2LM7Ek%tgcZ(#ByBb9(LTS*QHk zL0h5ouWE(Z9(xbnMcag`YE%7gfm00%xK~1Azu(hU1BYh&y1_)8AKTe@KYnU|XmHMo zlUP$HBZipp`oUyzv0Og?8Y|^y>&UJ)kVrO3{XAIP{fCe&?&gRnC=@GM>>}R0u2kV| zK%s04eD%R2_md8H;mj-L%B52s)E{e)_1$;q?lQM~Us+jRD(6qVP}WwVAl>YVzjym& zF`Z$ye2noN-}A`3%E80;m2ZCiQ|08#-{{P1BfuL0m;2sKIp-sg(K+*TkH}_zND7w-=dj@JFK8=w_50mmq2*=+Rpw?0J{BU z{{78?n*bXlVdgk7+S)+{ckC@w=9Dvo1J-KyB55>ek;Sj@?>f*vQAw%F2>{$f z=F?a$CY7%vSrjGK!cB^Iv6qHb76+0=#A#8r>{J$GjiksL{g6?W%t>^A?JK)3jwzDc zqj$ZL`}*Z)zfeFYz4QLJk|Be{(Z!nqJJ>6lG$uwDaPfY?GZ`P7DtA5fcJ}sz<@Us9 zeLj=sUERD!v3CU`BPBRZ;~wHR&ib!y9aBb+84%N zF?uP4Fn#8_K0MEt?zWgw;6@8ALn%(SXQ|v?vZz=vHISsBjW=sqbU}p;>CUf9P5w1; z;RmaKi9#?&HHTIGS|swV#t?(=%imK+K2#jFRumh8CnK6eW!_7yYyS(HAFy~%llj&& ziA~xq1_*ub4cIoKg~JEYmWk;(4wc10gpwCVLLhmBF}!l=4AB|{2uLCk*eVGaEgNgs zS>d7~NzPLaR4R1M88lG<{+{Y$L8*)+(fw+s+Q86Z%mt7>d=^I(pkHWgyewb67?iIO zQ4=_Wv8{u?yE(+|lEq;ti327h)T+`2+8g~30l|l1>?Zx$0pz^UQliX^%Bn%#&d1$ zTB?w(5g7+~pkh+%1ry5MdKIv?2HJH z(7BN+R-?!6(Mia9wL9q*!%-yON_EpA*uwGwN=jwZv5j#lV3xZB0 z52A>VaKCdzO~|nK5zlsxh9{x@-*1;J@;o3}98)p_+kNijHv@Rlr)0z!Ng|vwM#MmM z)U-kGG48Y~+!G@QV(mNkU^;eGXsci7#wdDHb_q$u2j77nY^ad7$|91*lj<|BjEP~% zqNt_V!%)ix$N<5N^QWIDDAhU7Df!hJTFj;GT|A>hcRX08W_J-}SiE#PVgqApIOU=;fP(uR%P-3m?5S>&$%+&%_E|q}m_c2zZ@AqO; zTz@>xNTPB=>v%%5Cgr_s1YW88tP!O zsD4aWo;ji+Dyggjc{~ZPq4khvTiEqgR(&pIVtTe5Jo+GQ(aYcbQ!4C(G4|k_-b?n- zE6+b6`l!Y5l3nS81@J69ATWHXTJJJssx8vkO9^P6uJGt zRXeMvwuI5_u^bTddV|GfW{dz7G0X6reWnqAxR)G08l!I(4&23f1lNi`*OxApOXp7( zDnBn?D66Z`{=hgp0k-Z5tucCCd?(J$*Qy%Hl4;M`b_4JVf>yI9q)9!9u3m>1NPwUH!4r2wThP6lEsV%H<|%=b~r;(2(9-BW35p3_M4A-z24aOlAKn5 z1t?n(=)uoscJ3|HbGyncMP3eeLKeX=hgp>^!bKD-;GVuS8%Ry?j-1gGpHn!b6ZtvQ`I2a0DS&y@RtBM?4{ic zN6P%dq4F9lD;NwddY;7}3=T4&3xO5cW}Xh&y^)c!u2i+-U$EqDm^zJBVa)W}ag+uy4BP_7-hChHQgo50MM>N5ZBLCX4cKHQ|n+AK#2; z1W^wJhL|6G&jW8~VhVbm`V+G#Pk@@y+tlcD5`xn>4y;ceI^Oo8ZJaa*k{F7`a-y|C z>X@KFjbJAM$^OXHdVWqFebYme;~eumMt`2Z zFD3Zt4DPMC3wYA<4*tvDoE%=A)M zWUIPs_)sci#<_8_$XSXZC`9Nqs=1;FhrJ4c8&$X(4b{DmPHshojXuYqpYop4EbA;t z)WTe^OPJZtavB-G<8oBBx36U)-S4= zSZ|CQ16NFRds}+M5_`(wN&c2iRtNT;nMRa> zT2n&UanhlPl|*Ga$s&weR4$xQD5%H|NdN9rm;Qf~EY?jFj=PiHN060%=H3#%&9hlL zHOC=Qj;SVTe|8U4Gqi(9N$WwVym>*I>U-cb*rLz}g8x@v{0a>L8lF`dndCSDj441P zG!7&TB&e|H*P<-*@>L?h2(a-tg?nn?=$^WGj-gzA~dQQ|DveY#c z&50(|+aN;j->H@4PKw{7bX5<;-%NhRrIZ*n!LGM)*!ikW0MtUs`cI2WUz^K zMxO)%WHh~t&o6NRR)o=jjz3gSL)AcNAS;_m;K){_8~7M>X)3JkRH%n9Me^;RbdbH@ zcV3zRjGF*7L{3pv8J{Q+g#o>Vy@;j;bK|5v(67kV;7CcA4YTC<(RVBwhk74yJ|e&y zDOA_PnxZcm^CmIQV`6GL&KwZd8yq+dS~hw*AlyTRTu@shk<^~Yf1{5~AO-gR&OHaq zp1pUJv!|Y=qs06@P_3Y~6S@uUd zS!^JUfJOD(D$tc`A)M9`J1pnf^kvhMzTH^y&(tM_=1|5KK z!iB0qj#ihd2x&u|6jEC-s{Ne*WFKHKtR{;A6yqaZnIi?;s*tGM1OVn_#>rv^l;H0` zA19+J<}6nK9X;^?fox;^e94YNRWcNCU9}{T5&dkWuEwYr_flHbk_nt=I70L$Mx?kX zqA=1i64to2V&Iz5GmQOw>co@f?8)c2Y)F+uKWZrLV!cGemEMW}bnm~jHPUMgK1&hWXGW@~`dqVeu(klp5Zl7n?LBxmZ6Vk- zSZaVr(CI+c6sq2+Mgo|nEr_1})^gQN7KdG3KMo8hUwfhLg9HqkovHpu0qT8~>%KUT z7+)6tYCgg3Z@Q`qqE&!0$KLX*EzeSWjYny@aF<&|I>i;;R0rg}b+Xu=urAPKuJrUf zS!h3?>b>7iJRh3DvTEZ64`jIiZ&VcZbO!fH`tC?`>uahb%|Ee2X&kTNCu6&x4pE$Q z)vT+!);3SbnY>Q60n`^J4-F^MooOl0``UBU#pGL^Aq1l0{vy ztBVTOybna7S2eyeEKKPR3L3|Va4u9~5{UqJ3_X&V-8w#9shD&?L31@?iocQEtgWw< zsY%dk5Ab=BZay}_eh@fQp6hX(>q*`xlE4dRUt;1Tkr5}Xt6eu zUkRm7S3Gsgbx$+=sVaCFS2M*?9tc>mpKyI#myL}O>C#@ob8sT8wNkK3;3twrS9t6@ zEZpGltRUHtq+S9-0UP<5Zj&tHhOkEZo?r^x0A+rTLAS-t%#6tvp}YT7t;qf@2TFGK zP7W#nm>4&<;l7Sqhp5S^t`PvAD~n7Pmls)mSi#KEsOoxuI@t_lisu#f0o7C_i(n-n zfkTjrKQ+k@+btoMra+j3aM&BnPs8A$v*p_IC7nxX9IPy{ zYL4$j!h_d|=>R`rmOvY2=1OT@w^Yuk$zlR;`fKcpm03k}9|4dKB#U*nA>wZhyJsIG zE4K1Qx0fsiomEd;-xtXufkaf*#wRqdFM7_fHXi*UTC4yYCX2B)P~(L?wpywHf>s>q z?kxf0crAR;p`#C$v#))#oI3GTP2>%xAr3=j@r9>8$3zg%1lIyBgMEkZWnbgs9WKK$nQmD4AmEtk)oP;8Z`leSOXYXi&- zi)OVl2^cn-l^h~Y*-*ZYf48sd$4@%BJ{Ot7jQgLSo-e!h9xglQ_j8`}uDyr&GwhXX zOBdPmxQM>)WdSJ!PB~qm2?CiBlP|Z8v1r8rQ&@5LV%S77XIf{BH0ywcq5WX>_K0|r zke5E+Y!r)SwQFfM#6OdNX>qe{n$>{)dnTfRwAy|TPZnk8>4&zPvpDc9T?KR}N-tT= zPO{#DVCs&u^d_qT**2RdR~S1l`Tsas%*76oGU!2+Tqb0#{~)^5(c3#IuFlF4NWI9^ zwAYg?>adDJ1AaQHO$gksAOK7QfBEl77HbLJj`PM1CVgtsNBw72h08=_pk~%foD2W$}?a46scmkz5{nWP_AFS$m9am#jBS<-CQrrON$jn zh0so2BPSKLw?cEh+BLPaplW~&ovU=Fq211jslj%7@t^_hev%B~XjwRTXIZ**hI6PY z&C|WsH~DgXXQr0~&=oz!vd6vZWS>%7Gh>IK)$}(oKM-;%-R>AA%@2u~1Om`6IUVd# z*$AA!mF25UKA|ed>LmJ+DgH3Z$`9UvfCK9eFaYNh&V>}`xdp1@p%)ARJsd0gVcC;$ zW0RGu+MgS@=jSS#UEy3;%(p}Z2-kw~8w8u!OFf~U*^ocC7#Cg#q#MC3f_qe+0Bj*q z+l?85V-wtOrmAkiUO1q)4GxvbT4l6oQ%)8KKm?7SAdQ&RTv2NA>|o!PuU_ho(CAeS zI}Dh-|0-3myNN1&&5VKAC%JEql{(TGW8i#HJ!$*XxyQ2xIL6T#yAIG-TwlISBwf`c z&AH2ggiKi*H2{0L|ImH3nRvFSEGk)y9yqoUTjjIO&1)4Td2ILwB#Yx?6AU`lGwCX; zW~Sj;LX{hP@X94UU(n!f6Y5xyu=T1MtEB>GbN9ZZ8hebT3k}g?-$lh}>%Q%}Kpfb=MeL zpQ^74UEEU`!fSpG@jK3vWuLJsSsn@D`?6i+-x1VuRDuu_CN|J3c<_zyEpK|q_m!`H z?zhSdPkn~ecech*+TwZI zeb{%*;KZ|qe}}JJ#m^y#ME@zj4?jwO=Xr6#=JE5b*B|#7J5F~`BPdrmr*Otp;@BZQPDd<|5s@qMV!fAh&tm%AT)C)ekh zuYOWJw;QY6&lorJ!ZV*QOP9|`!I$gozF$`tUHQ@+M#nT+-Iu_5*e=?!&_NmQN^?{_ zq)2l!|C``Y0VF4Ss zxdHXiR&lKNT;oB_YQ;VQv#K!!n(vpLRGh~3NVcs3nezYcvkZhyv$La0D{;ZN&#>#2 zS)epgK$R)i79&h;AOEg zv;KaY%A%cgcT2Zq(Lu6eWHqvPkeC5P#&LBw4du3q24=k?0%!ydp#I5Pg@fxNq5Xa$ z9acG7RDU4e0P4*7GcPhg8my%G&~=_d3Q+oik1Bke-Gk377=(^_k<&~fL2*SQ*@Bi( zI$Yl<>#I<+lIkIx6R8E8LNi?vtlvh_74(Hfl_ngmkVT8{G+KxJbttx?FApP1qOX(= zgUPW)Ud-ng!fbko6tNI!1uQ_GyLtt1y{<~KYCAb2d2iSiR(}wQY=+Q@6tZghpR_vN zqLeqM_&2IXpd4DwO2O+G4VM%&Wwg9oOz9bR*t6ni|2X7r=!BT_i=wX-!6%#tssNw{ zPtNQl_3QY(Z(+q2$qK*%R35R%fl{L)d3|ZIT)uRwtgc)w%U3T`KnYFfTN|k2qTe)7 zJ5mTG#M8tdV&M@)n%jYHrlXXJplHL-~3+~1`NXwelQF)V0ftN zg1frATyu_8LZZ!A6L+Yga`#Ghs~-TvUlU3#LGy0#{z%ITRsX?n{ptNLkF&zh*s?E7=?{Y0}j>mr^dNj9`M5IG_F zfXE3B8lWjr1`;biE028xV}ZTK_tnoVCIj=olJ?Y{8=s}SH!q}J2cAwRp8dL#8?o-{ z^Mnej;m@lIm?XvS{kWVLbM_7{HH*^DpovmI6^4;OWphJ4FI*FWlT{0bq(B%{C8Lh| z`F9{0Yi0pprwy<7XuW3j{tOCa1d=6lZFWDt%2^LupPdozCBWk37N?;KEMCeziv^?< zYHY4XsWRy;{Kvxp03ZNKL_t(E)X_;jcLR$ya$>W6nF9-Fi%`)bfW?+E=aYGl5zL51 zy0$Jry6eEnG%`G%9#Gl7@u|~5tNX3gKlu#yHTGxkq0^%2p`iN72R~KSJ2EPk-M4j! zYG5RC0gIgP5YjP0x6+r$T4(C2z)8%0tSOYfzMheXsS)gpVD4C=%fY!Xob_yZwKIfH zyfr71V`UE%KO+E3f*3%S>8n0sCz1%+6Bt+|k@VcF|2RGK%0EhP{rLCO$G`lc(HH?P z?Cq7MqGn6d4(17c)bca1iAGfwj^|CXi02N=2>*^2NMSA~yJ^a3ds;vmc1L+1>q<3!3 z<{rk{)N$#r3@ldFPqCD+8$%;DbJ1fz0a*v2Iceh#nCE@q$n$At$ANVD{9EbHtxK}O zBNNl<#OZHn?MT$^J#Z?Gj8CdZZ)ssZeRlp0B}|ApsFDFBuYPt$wwJ2?g^z!p_8xrN zeA@hM+PdqI`VddQ^bgg?N8*kOB}qcFdCRiX&wS~()5q`rKwzny?J#X-Z{j>##WO0V z&1ALt=hi5$%9i!?Z2*WscfXr3`echd{^{)-ot9vcao3j_3(1Ne*n9vZ{f}F=?$zIU z4kTDaLs|s(giv(NIJBb*lv>o^}EVQb| z^_y+;Bwr-Oa?-Mnh1&ORKdWh}CFZCFEA8XLk6S{@daMv{fzzjnWAJttaY4^q_)xy~71l@cm_C7gRcAMmSS zOCVrCXHWBIMb#bDp2OKoG)v-H(0RF65_SEa07wG7yg#4KUc_GsP!j0QKN3g;G}E^l zv|;PHE=sczbJ>>~tjILiSR4g5N=U0YKyw)?yuhNaHXO&=}N2|mN?NK~-UF>}- zXb&IUb^vTaY}@^Yy(~do9fMSVccn{&H4yM&|JazT81v3?TW_L!uPT5~>FDXNr|;K$1cwEnmBgy7RB4@R8>2Wxw*_<#X|3>Y_<)$v7c2)QnYI|9gnG_e zqt1@cCwcVY+kc+^{9pX{dj2|FP)7Z1M{+$^R(Li_S}6l+KYY~SH$)pySGrFG!$jSEVuEiS~!nGNX` z0Q7n0P`kJ9I-D+^eIxBT{H%ne=;cG{^u0I!BwhOSoy=I^K1cv=*|skofA;J8dG2lV zKE*nAw}eP{n-uX#GvSrNK*N^SV6^z~3NQtm(POosdPccg6}NmWOLDo>hPG6)tDKKf z?8_I|Ju*I>w(mTsab??fA4=mB+w>Z!zs!z>vGH*BmJ)GFPQsL<-HCIgmI>2w&`ef| z9Qlm(I-Y6xgaWDsJ}szkB_FwHOZ0j=sj8_yS=`VKD|7?Y&6v`y>*u1O#tqchRcG=a zbG-#*<POLvg<4VZ-1@s#W!OK>I&tg@t#it z7RgQpjmjI#4V2qv%%QMF6?$&bvr%$AF%rSRA_|)Hd_XO1JIz8Z>jKt$Jipp-MDJKM z)`lWjF16=-wkl!p^~qc+gNa1`05c@5(k8?0juASYQDc_U(h>qY%Q~!l&pyw3okB3j zGJDO7wjK zeRH;ns1i5c%lF&ksx@}Q^}g-WKiT-PRcZAref<{r?>(jr^6cFkjrR%=9@*ijY>+%6 zFoKF5U<=SsWdTWY?u8)4Xpu(MW_^~H9?9mAI3d6Rpg|vn9;<%PA=?WigixqspRn#! z&)LW9Yl3Yh7Bn(rUR7y;V~lg@OPpiWkV*8Ago#;mrMN80nu~&nmgnMDR73g(`c#n| zr4llL+Okz(g6_kgHUed|qA`YgWYWISbK2NY5(^MSa-(K;M^_ra(1nK!8{F3eiM?)~La1>Jq{Y0cY3_MYpE5eHFuj|v^@I=yXo zdgkTdmT&mrt-nk+u6(2(T&|lSxWo`OSPWapXnCwa5wDg&(S7>G?`Uv4G;;h9 zXPYlr9~&y7Cs84kNEIFJlgn|}1i|Ff!I*a<1nuCHm&MQ<4EVB>x)NzQ8|IHT4DuU2_a zqQyD(JPK{xS1iDy*jbFiC?kX#G}LZjk$@exLQk*=c%_P1#&(#>r~yL(OsI=aZH+`| zz2?~1V^4oI?c94z{kH5QwF%Isv$`S*>d9xmneN}cE&(>ymFG$|n+olvPu~@*g8c!g z{xqVT=(9?&!%1bj;Hs2@u#^8 z72;wwgP=zkn7?iIq9tnNF})?;9L!hq2pjRV1s+zFbGz86iYc*VfJ*jE@v)tK+b7{W@>Eq-ty-bfI(Vi*q)Hcy3ju2kHAsR(y_hZ=Z$e>zY2i7JbM@Z%g- z*U$uk1*dj(k3Gt(kK25I7e9CN-W{YC*Wy8{1(}VQt_xVS!ontjLJds20LRF#YUwbH z>Myi~lmcSZKw4SnaxY~)EQ{!Lp3w>oY2Z3nKJtr8WhO|QGXAe&JKs-7JkY*$GY z0FES*_f1Cgyg;uGO@A7qS}-&$Ix9Uc>d``A2P3a+Cp{Gy*;R?wFoVcOYZ$FAj7;#e z%_*7ERt_>M!(`W3hQF5zp51f=TP5hKsoa(4QU^vP+U#De=V%~JOwMS~J3tZ#NdExi8CYLH>71RdB;pq8f-u68&0Kf9qhf8^DgF zNPMdHk|-jk@>_q!?>A{Ao0$1JiJ>=o3|MS_nx5s(y(b(jUTZ#_HdWFeT)nRY9H6il zBSr4tzLfe0N7Aq=>ce&>$0oIodk#FM-WaMZ8o99aNc2vq(|jC33RR>VS3gdJ10z=1 zSX5E;52a?Xq`HP>dhXPfCT-QeDCd_{@)7jBJeNgsb15{f^K3T^Pb36 zqdM_eC8xsn^zaiy!{h1=otUyLI26D;H$O9)ZtS5=94VC`z#{7k0Hc2=?57*POo6Ji z(b!SzWdxx2%SIEtavpA6IcwBJpFJ!t2V*{{KDNPP^kFLJ$$QzK*qvuz{a#vlbU*## zN58KgR?ZmXVX*12FQkI))YGun20FdxbYx6b7lOL5M>s?u&$vs+9fx zX~(|f8a2T8pxsG4YnYaUah=ykvv<>jyH~|Zp!!aX0H`F1gKZ4q9(oreF(x`MpSWsb zJfWItDzW|Pspr3)zVW^PEdBJ){#R9nEr|q+A;6;j-ID7z`hjFlBy~gd$H1vo7RBlb zYOnW!<>&1VA%tZ%2a7I>qkc1lX$(}>BRHb^L;@;=Ycg2$3a8XcQO4~G7K09302E0b z#AKjpM^aoMb7dv1QUq87MAOpKC$TB0-6W%_kbm;w>*@UaKUNt0$+Z9v!2yScRmO?e!Io?N^RrpfjV(go>Mb_dF|; zDV&>u+-~<#eJ>x%E~jRy}6#GFFD_Dp3m8XwmW9c@r_)-lmq3Hkt& zrp5?O*T99UkIRe7a$Elr-w%m(D6VkJX<`m>6*KA~qG8}j-zha^uR_{)`F>QCY@V5% zM@1>nwRkm)-UG7gI3LMdFU`xy21Pc07a$Dkl=>_{(kZZfrZwhoXgDpIN2)H_n0bHZ z;v!-pE{|?V#`-J?@IrYu-&Y7(l%YHp0MR1L+_@8JWob@9WNmcYfl5@A1&V3<&U1~* zE>so4_py2h28UJE0Z`D-G&QqFffynv7e0C;J)FI1()m$M?=s%@XE)cJ`4OC%Hl(CF(3^U1C0? zI{)-C(sKA_sMpB_E9tNlc8yNw4h#)$&FdN!%6Lc-L5!Uq5f8)0YLY<$?$4xm@r`1+Ca zIoK@v%wn{PjbLzZ;QiRm#9|$Qb%MqA`{O&H5dzkzUgU~ErQVuXv|=oT%`)?0wkKi) zUS?w-EQX*8EK!@$$uv2+O+9g(dGV-E1|zfU>{)7lcwxeYrC;(qqU=$ z0%~2FXe9JpD$;E7Jr3cQ9Yr{T`G%Bu*kJS=jYjc@YbJO9H#rU+0y`b{=W% z65~|!F=f-er!}8h_u;vx*GG$ml5WION?_E~*>*vo0*kqd-+@;;6Fa(&fg!a)Pz}b{ z(f2qxvnve`jVOs3)kpjzK%Jxu32zbt5f{eZ&NwQBu`;eO+v0&iuPESie1DTe@(Yuo1hJB3O4>70gIj7#el$%2aCDdS1nr`P9vS0s(2?no z699;)GUxLvt9}UcSIXhK>nfjC0KGesm_#ldO-yM!~`*h>7v)b_|; zY8Y*nsc#!AYtjZZ^E+V-gF_$m)Bx9^d|M2>HD#|tGxGjQjVtg`BDHbax#y^YGJ^C{ zd3Abq24=Qi0dnm=tmmtC=Ik|$zF{Z8&6s{3LL>!~7m04m{<$if?{0$1kx>LsPzttc zl6q<)`-w5u*+58VRjP8(9>Yngmq69nbp=TTx;0pATz3Ggj;db?%4`S6*p~uA;@$%Y znqz1wsAl1msCo(dcRzNu9Sw@Q12}#`1J?JQP*#)5M^w3aE>>Z$Y(kzFSAc+BZ=bT* z68?E`Q*^oUg?IU9o zS}Rm+xfa%*>jXr{e($!KWXljMnJSeQ?$*cuEAojOoB80~YVzx@cfgRmydVXno~7|4AC3+OAfK@rfBFk<8X1BDNwC z4tiM$&Zw>c-s#Unl@s7d&nxT%6DC_%A_~go8i~TyGMAJ}nOX$A4>)YQo>frXYigSR zoumbocY1eWazui&Ii|$Te{0TQa~;a~iLhIiFdax+cOFs&y(om&l|^6GE`pw70)R2gY_fwgos*U6+6%Gr8={cm8fcdS^+v!gyFvgeBo6PUB2H2Xp**od( zjnC5D+&zKPFMso&rmGjpG%d?9Fyx2j`{E~Q#1Kp@z z1FH5Md|J;GWz*O*Ifiys_!xIZ|M32!&!^Kb|CSPfqoY$|b#R}|4a6qG0O2{Y_g7J- zU7S}Ejd{)&fqHdAU=3GlPma4798OLjhIZM?Hcz zm)AmJQx{d2zhAqt&8%Igdv!DXc-#L*v7i};l_1X}0I!BZzh?B*&i%*J_FYG0$G9$h znvJ8ns%QOh_O|RKajC^##A6=kSAM-NR%{xN_xxceeu>zm9f#}L@l5?W>Ny=a_9Enl zo^Njm-Go$1ZmeCiDs;e-X_9)3o9w3QPt-Zx-BFNkC+bgJONvPa6rFa z+uxs#oP0HH-FZM%dVYo-Cb4JZF<_L8st;{=ltJ7(()9EWB?bYMQ1b@7I?SE`Xx+MU zHr>8?LG$QH&;e`+(AXc)rZpbIX9X*9=lz#T*trNxB-89%19+$Ond}2LtXL%S?=cg& ztZpPD8a^q>8+pqp{ilJ zKOYC85j+)$lJJgbrY*3jUVrGHE3)YsC}cHQdlKqx6m_)?7QL4++BnQOm(dw9o3R@W zRbbJ8p?*ie&&Lw*HV#Ux5=H`)7809%sI!r$0N5Cwc>aLlLnpo@Cd+5%-fYBNVG-Et zhfjVv?LYE-y8Ox8Y4_ffX>R_$p7-(sGcfN-+W?U<`pglp0YFOpYiwGT$GwN1kqy0l z{eminTmxr>M2ke_)K_QKEfVIZHN)|z0{nFxs2P@=-GLBlGJ!QI)$%>xiz-pL=#M2v zJqF7ZaZA8!WSI-+*xFgu&mE_ONS-ML5fpI)v>0OWnrH@?7WXkWCWK^)?}+yfU})oY zEPl?_NB0YjL{Zzw=JQsdK{p@T_%%1Ud^W5Y?A6HVl!Sz4w(nIRH9~Vzz@LApwvl@R zkk>>#$Db0PNIWNF3QvAETHIxS-rZBapM=7GYbSs))3 zgvhw6Z$qk(RI4Ur$N`bOltbIi;|ooCWmWUIG{70v+LEsp7#E0C_R4530t$-k>kD!JApwn2X)}?c zG6xTb0!=j&r%e+qu?2Dr^zfsiS zqAC`ku@3s%i4eUbTGd|N zl4phOeg@L`)Yi0p*CD+Rij@Ht1H>IV`DFzz*ROmeXSjlBO{g^L{Rt+91UON@yztTM zK0Mp2zl`G8PEuLa*ai>A zG$YJ===dz|3(+H}bchepFUJ@c)*oO_CVqT+TN)ji(CLHrs7jt@!r45?01?`~{rxs4 za1iS9us{rZii96P;_y?iTA%I2jQWxh-A}6L+WXjegpDLb zMo-xq_hc;(5AI)Y1lHE)$$CX>`G`w&qujRvXagz`Hj zNOci19o|w&DU}ne6mkVre)(*`GeC|r@`%c-2kLq5EzhB&LhliT#Iq)ph~fFjDk3-~ zjBMh0dZlKQPDxy4o_Va0bz**D26KqO&|hqcDXxpeBmMq1zmV^FkgOIN#70J4rIX|@ zz|o2rT!8k0`XG(T5-mD5mo5Zw3Lq(JsJ&^ZRz)-wW}c}jd{Ygz3RbCr8e2ovOevq* z=q<$smH!QqDBkzfOW#$}_~Q9DJsIGMLf0uBL^BhiP(Z zdwTb0|HfEW>L<0Cyy3Idj~aRmAppd4i1rG=y1=rj*V@<Or!-`ch{)mqy& zHp&L@YXIGnFh+Sb=9K8B-rE|~P4z3rjO&&*L+xLq#mSOD^u^k>>*RQqF|MQblkxXX zKvjF{^7ls4uX;(G-SD40TM{?hcODX@oz@%HoOPk=HRP-lld-W>j00n)$t6jH?Ud)1acZz+b7JHh(K`u$Zk<1Ds50>Au0*)YsUUvEU(aqinewAIlx=XmgkA;XwIx_2{e+jCUnGz8BAQr=IBW5AFb4T~&T0IQ@x zF|J3MRb~7K(!kK5#7t^H#{Dx&#HfQtAJlz8YlT|FvvW*@vE;d_m(xc<=$Wpst0#l! zuk2yWgwm`sJ2xgofTcC(qY5N~D1*akYI?h}?J>qd_DXb0XqBjNTF_z&YEIYn%1rKc zQx?v}cX9w1RRM(%jbN;q1n80?+oazu>_B@xc`krO91K;kOkb(8x4O3oR(1D{^{le?27-)o1>iVv{H65h{!JxK>^_3NTY7!Nhtxo@ zxkg_7sl*d(J;El`^y@NYzVuW#eQS5H7&O!-Sgfxj>;`|TKXvC}tv@t1XvYmoWmNgI z`f$nchrMQB5R^hOr7FlX#5U>~a@M@Zo_-$9`dwR5^%KBW@0ob60!f_n!C_JMwrt(4 z(GUD^H#lyfV2dtmJ9+&Gm8_NBC487+U0r9k-#^f zgt-W?#Xop%BqPMqc*y*|2Wbt_JQsJNPtN>;oeL9#A$jOyEPMu?0WWI_k-c%{QUieY z``BY+ftXFQq<|@VYCfuiMFR}9J}k>081S&FQ6zyZu~+pJKVfB&&w_rbikXl204&On zXf9_NU8Z~Tk!JGd{`vKJ!$%rbbSa&9_FL)Uz3UnQql65A2mj}a_9U&3J^flbdirbW zhkx`x`IxcMbmEz>YsAyF&pt>;pMFi(aqi3y($2jnMFYlm@r7RlNWuf1HNtg>)(=XZGmRUrRSGf0!u><2^M?JV|KsH{^8uSMzj>b6oIh;)tkfu ziI>^C*VDZ_SJV9L9VM_d9l#UrNeLpy_W97TZCQ{kxsOu=Gqe0y2(_>#!b0HPgF*P-MNVU%>(pfZ+Jl zOjc@@M7gt4Rb?9(R__b}DhA#_4@1IjKs~8hMgpj>CeO{Xz(D8I=c{!ySaE;d3|RjF z>ak<$7gHv*Mf0t}d7bTQJ~JpQ(+a8{+`f{w?AR|kcKXi9N;jNuP68QaNMU3EkqC71 zn%d8_-agQ`oFFotHk(SI5>RfkhzjiblPO$oY^_Zlt`@mS+Oh4w2(KEAVy_cTh zwm`#F|6QQkKdXp~zBy359f0%fGs zxgSds7!8$Rfd7~gh9kL*Ac8XKK07f6c{unX=sk4ex$i;o^C0HG=aSj2|XdpG~^zSag| zDUHw=v_ymGcOGmLXd%3#exK!qbp6W5qU&kBz1NvJe^eT;UH(w(YSj-<9MnjqTFJJ9 z%^=OZd3hWmCfE3$SE}?{LNm8l)oXqgU~y{8t^{3}_af*dt1Xb@)Ldf%_?^^=UROp| zfDT<9u(;=#sGiJv6AiYnU$f)@WAsu+e3A=jy#ep0o-|J4p(%{}U5iQ~%JA5)b3!GwI0FUvVZ1 zGe2o@uu2Soav62ehxgK>dp9)Tn?#n97W&z|ss|=&wyea3&XtdOFq-QY^)y8_-Kvo; zpymN>*kSCC1;&<)v{4RLE$8p@YePe6uzx65nF#C$M~t>u?2c9C#K6$J`$A9U{-}It zZPruz^uxbNcW+;Gd){yJ61{h91KX}Do6RDo$`n0n0v=wOiy4aeM8Kd`3jwtN!^M10 z>YLN|mTdHmtD#1WBw#npe8U13tqS$UD~kaZ1K8LI535{SUt&}?jY=6+$f$^wM4%Z4 z))6KJ?|c08SJSmiA9|0xu^VEX58^gQPkl8VIQqQS5ZdUr9S4>4;vP9y&`3E?e5Q>a z*^qdOX6MpEuw}dUC%*ICnIERDyACNSv+wY8>8&6Cfhzn|s<3$|r9u;CgoovXiq1e3 z6AEqAl7i}cm47wx$mhcbz{au$!~q!?Ms+Y+c5(tApl1G^m?9{xqO+4MfTk>mW7-^1 zJvUPb?bLb`gMDF)9gm;#JX1?Phg~s~YvO|j_U*Uyd!oFWpAPDLx1z~F)Nsvtm6Yc9=W9+F;RkNvSM!+ZDfV zpjcHH<1k?4Fm~n?tREpVp%~TR`|EPs*Vn38J}z@&ZxQR-T3==Hs#wh%dU?i{owS)z z7Bra?7Wdr^WK;-os2FU36@ie6DkKH9WZN{8$1~dN8%Aj*0M$4EpA#u+E17F%^a!Au z40UbfvZ2d;lHEZy*8}ayKwVLktplWZE;TT(M{BS)+zZtm<|~qI-?96M`qKcR`Kz@) z(OX&@o3?T71%C6oSHYZ|tW!{8Mj+P)T``_(BpM9RLu*|#dPyGv3_?1VS`$%<$E@Hfp)$La2S?+;2^66*2E|s_$ljJP0*+54 zAVauOwfQ1IvCA2u5`vsJ=Zb2ZGQbE61dD^&W>f)6b6|cBkpyE8lhI^$BG3K$%V%+GzNA>w%+d*exBkpj zQy1sckdy{(OpPiZh^~xJr4!G5D@{zzsLFQj(g*4C`F9ljK(U7A$+IEjORx_;2$_2* z)wXY`YR}7wLzC1QXI>q9ERQ*|eP=8`r@nf^#A2M%ZZJQ&3K#+=+$M1{BP*HEm+hZ)t8O2nYlDgj>FD`S(Yz+q1&>EWB&p`-^t!)65Cb#d;V zghuG2BFDwjD9 zaImU--K1x+4Hf}FK{Kvtu#reM{~5jp|6;LMPR`QnNq_$OdV1zdzn#v%_Y zUFh}nVZZg0f1#OLK2`Q*%Q#X2$G2HOqe2Jpye7BQoUElUKD6J_;he!ZrEZzpT#M>VTHMmTqqzi;%M#-6)vdss`=n(a07DP%uh~oTc|VMITAWwe$pw zn>>Jra!XoTm=m=ExVo%>)Klf&8)+3xjffZ- zlaLBkv5_GQFeDNq#kN&ZR+&>r!@2q*Ip_@P#aIW;Pl16qnRgRDP^F{*&0dwoxT7!< z0TyF_;n<*lA#G2UY4^U9>E^YwqFF^SlAp>G&>gw~`x?lXOjtOq;<&o6uw0G@h|%xp z!MOi|HMSeA#sX5Kq2d5JQv-wX=dgM<2;3rDDg{m-wUSA9a*R;fjJnFed2=%BX=rf7 z`gxY-vPcduj>?qgH~JptbyDBu-#MYv{Vpva^lFG+QvPj`Q8NhwZx_$M<-vXT`<&TvFdaDZoY{a4g2xdHT$dNr{7*%X0Q}m;_a#*hSS7m(?UA7C z(d^}-ol^V0mR&Ysj;9k_EpJNKPP&%gG2>FBAis4woL zcYh$t55c;qfbZfJ{*{$i?KkL37hp0ufOG>I~F2@heWh%O}r)s*ZAh zpTPUEr@x-2W_H-DOK(3I7-p`a%`_BUJ=xe7p3BV6LuqVmTKfrs5*sn{R2t|@N?@@c z+2qd!cl?=Doc7Tpw;8G`?*+584De&g8)cx0l8W>PNC?K4q-1+zaI#-9| zJ><*QR+QM`dKgs#K*oNM7!&)(+i0j#KL3^9OYgt=rvii68GeubhAKEV@wqSmj_d@V zrP-GL-0NMRM`U=SNCGhedoesdk~8L$3Yar`v69{%t0=MJ^j!8<{5|?hV^(5NNo(L; z{vM+>f;t*W^#aTb=rP8Y#egLdSCZFuFLqBs-7etJTCCXLwI)s7oYpa9Ox+2-W-^d{KJDszvr8$%Ms)z^{n7DB>KE73V^DR|!!n}@( z8;%}u2OYqCLk)7grzu7h)D+vCB_0&m1e_U|3=8xju!CR>bUH+J1Skm#5L^hs z4)qF>fA)P)t#eT>JA?wu()bj_i%pMX|Jzo?^-~)p*f^{SwGi^t`X`T>r6$tC~Nw_bOuFFZBL(m z^tu31ynhW|S!4Fj-ovNU%`4|zm9M*3;o8~zCQ)y+GxmEV%d9WRR1^uoNuaQ82)@*x z;CD60ixVIYm9Ib)gF>ts@klrX+#72 zgrExn6pg@P6weCJAmrp3<6=Rv`f90UYRERdw!?W$M6e9FRuV%JS6W`see*L_Dx>m~ zD`8fdHmbU@BLEiLb{$mK84vyoo?VhBaw3_zv5~fH+moJq<#*NlN!7;Ahg&jdtHk}< zn1Ue_2ZR1SKB=B=z}Mu|&NMnPCHm{Ar1*CyW@6H7DJtL!Bba8>#@dGdgyuRwcQ4(! ze!(i;Yc>~A2}jZ6H`2`ZJ)-e))%Y0vo05?+Yfj1OegQ#RD0GibX{8U2wLEzI<#g`d zAEra6UKNYt()oAv`>Fut{x73}8pY3;6kLbYFspfr(aXVJV*~31Y%4A=Jd}1i-NZu7eIaMFTUnA1z?f zDDNb6m`@8>gnlb=wZ4IL==hh??1LMk{L5a6_R8nl{*oQ=eoG1PjZUQPI}W7zx!H94 z`gx*TVcG8`MZ*pvT(8h zH{19P(33M*eklAiimz@ad(H0{V~+O?b?*9{mYAYhf~jqf?!_*~6O^GyUtX1cXa+x} z;#-5oxW76ssbh#x~k$q3*ZVDDdW&C<6wce9Z#D$bfz>u;}mB;rMb^*$i3x ztJ~}IVebM6^SwR^;B1~;D{uE&+j{wfa@DQ!>W?tqhkhiu*<{ZMNZHhI?3H1{=(uBz zUKxwV>#r~lE?FHJlvwM!`q4@P7{0JflgyI9tKf*!8wmpKeN_=%vFZUFcvE7v&#sM< zU0K|ugSK`>sji%=f5pZRK*bpunGlr;${ohQ#)8;@VluPzTB(8|wbdp6vk1}DN~4<@ z!+3($Upk<`?!nzFi9Sda*T{H7nNpuuO`&T){p$HP09?%Z^9ohaNfZjkT)Y;&#axaD zTJkjJ)9Uw)z1`TF87%sD^YaZ$T(XVoN!oruforDOw(S4{H}tFa4=SJ=8XOZmkMpen zqf+Ce`Zzd970Zk+08F%FfeH&ULJYu$&l@GuY{jYqC*BY07}WtO%!S&b9l8t_>@x~g z4FM5;4p>xgMjl_#%$&yaihavyfX6#0x= zp#1bp{~*2ejsGxBP3=fGuYV$?Q!0zl!U;%mt^~7Gd!}%@6P73dpmJ}VM--1&muxUR zS$rt7P-i(SfHwXf!{B*8&24pY2P!N02-pdBuSpd&06%L%6_~!s=xyVC~Z!I-+0OELY_pZIkBj zWOc&Sr=FUvyAH}m&|4LOt_7>M-|3%%N=j0O*I0F>fJL2a_Yt*Hwj~XQBuGP*BvaxM zNvX!I)PY(vxNX^t&4>#X2n^HR?HL%5Dv3vP9qZ~ddiKk|tt0~j(XV{+OPibPGk{Ie zITE~;GAcA>6>UsS+kBD7Vm`}HqbmkS^bD{=lhZrXuDvG&LZBj(0KzW-C^(m>VDgL~ z+`BFSuX(dj8#R*;p{H3BW%E9H&N2IHWPB>kqQjqQG; zk1)nK!pCo< zxd*p=_N28$AP9B*nQx?bUjHNY#Ja;2XgG4}H6^yrpZSp`z@o?1eQ<{!LAC#Kd{CK# zIvL-Hz`7)Wn@MATqW-%2+_u7r#y@MY=#I3ROz!&2<*+y7vX))Tp+Y%x-GF3ou&B+I z{ZiZh#J|ly)xNmX7&Y;SRs2{Ap10Xw^NH4C62LwfWx9&Y4j`F`y`Z0**kE$&ZdI~L z*kKpw9j8Bf_5sSPb4pa=8{}hMfUfVrv6sBVs`-Q?E8p#*Y_^b_{;XT|;O`S8=18eK zSS&yGid(x9*yCoS5)uY31BY(+S_9Sk`E&toVSq|i%(4(|u(8)q1ZKglRCW zDUL>QCV27&{K^OiJJRvJQt8Omr~rr_209D4b+L?+#ZZ=%u_s&JZTH_Y6~5djh$xB^!R%(&tzfWw732rfnQb(*9`2Y65> znziQ?Ban~82GuqKN1h*|DfFpm#+-TyBS?zpx4GdBgH~?U>D9hAa_n9O4yWJTC(+MZ zU2L_%axl=cGeNJgb7-NjTUT2<2W?xn?@Nnwvr-+i{o#NtGMEmAJQM+)001BWNklN&FyULACD6{gu%I-6J6)=e4hI*_`T@_oyd9=PY%joh2*yg$ihp|mXB!ol*ePUE*xHd#j zkea6gM1q2Q6XlhF+takH0kl99FtLh?{#3=r#7m$w()UNTj%pA<0BR?FgO*&dpjA~& zRhKLPh(0u`o&*v|xAO&9L}aK2izfOIK;3(N?Ld3*Zh;T9Ux1S4C*HnX1d}4v_5>8c z?9$Sl_NS0m@ZqQ0aO|;~jRCTv((=0#i-hCwH@7*wPpx`NT6;W-dE0S^CTRq;t zMz9C~U~~a{i{R|W<+D;_l`<>Uya1yvASB!1AU*_Kum|#k175Apsrz87&{J=Ih@@p- z-(X@8ILQTs$f%UZ97M)9kr2SPu?MJZu}|1L>^YJgoG*H|=N{fyb&~7k--z+>jPWm2 zu8m5(JAL@}U+9Xccpf?Vm2~U+dEFJ0lgK-G^u_f4+f*+Nj3Wwn@We~9HVa?Q7NescFXrq|Wg6-6y|ZV|E=DJZUW)z-E|laXM4v#mqX2|NW3l~6A8DJ|ypj9CCj z*V(Y@so8IP=ClJ$sD)&D%TD?D>8*Q|Xp}!$m=kM5KIHx_&7_4r(0B0o%RyFcJd0lo zSo~G&g}=-9$W^F#&|bZIB7j>UV`M_KIoegs`hMzc!)9PHH|)mSH8*#iy)b*$9`;?n zS8rHR162`%=?Z5vDC!1* z;^f5EwBo8+7^(S3v&xvz_s5qSrv(O3s&tv;Oku3z?V^cgJ}s!H9_&kI9l2<|Uor>k zUqK@ZBbj@QA_U?fyQ-?CjZ3z;fT6a5GP*$+RA@&yEgVKRDjryw*a2?NwPW#Of>eWt3F0}kqxkmH`IxYwmB$!tV#gH=Q&5eK^ybR0MC>FkH86v zVSIIF0Bf3YWCnXgo$U&Gw~D%FbM5m?K&jAQ8KiCZp&)Z)M1cepHw?W=%lq#URBmjf z+cz#K=p>+4W%2q2(Hl#Jhm4^;|3-$^D@8_Sf`ZEDuBRP)PY9e)#i8FJf^w=73>V&a z=(ND1=%VGJ`DNK>a6c!X`wfYv#GKA>mi2l;uRH$C*97zcivT+IC_sk579h;EK%XJV z1YAbNoX>xF|7O~MWb<@EB`{sZsFL`8Mp=IhNr zRKScV1kV=603aCf$2npyA7B(Yb1H(ItFUdHFV4~&yv$g*?+Jp2{QRuG&-3IAV*9WMB+k?m=apW9OV$Q;Ln^v}1jWB3 z6(y!Jt39sDEaz!;Rg4XKZ|Qa63sEGVWh5c3Drh@`^~xemv4^||jUa}8#p#(n>XD&J z8x&d-=RhcIAZ_1uSV1z+{Py)vv{qJ0GXbcm-$*oNXhgKj(b1_iJ+o7L@YeND1#Zj^ zn008=LF3%E?L#g0QVe*@_I68Z7pK>J%N~_Q0Z@t@fm52v$h<)= z78`8+`8GD8um-Tth@W|Ht1D*^hYIfGJ6fyEi`5d`bG4c)pxH z5=fK&3@0YHr(OF`s3)BYFY8Ydh5d;Q`uN@NEAfC(%IzDU8SVPPOP2y&p@w z1hBIA(CM`I;OX?~M?cfv%U~`mRJxs#Ad}I|Wg9eZ!oVW_D}zO+#cK3|W;q(0rv{5w z&9k0#?q5L1`@r#ayw>yp3@m1wW0|wuuNE}b0E;1(Vt%~L5Ut}JOFkDr9@XF6U)}>O zvd+)F`a6mrpot$i@`BhbJY#z%%-9^)zGpBypU-{h%z6(eqGOyPR8oW9OlYKjL1#qm zKk~fR>B7gqkiCGpaQNh_vS(-C{k}efN;IdM`Ooy(lU%?q@x`99XKOuutd+)oK#xxw z+8fwFCAU_W(w6C+YKemD{qbON zv!X^Z33aO7VeSeiuXqldRr-|3fsYeNl>WJpDG@~oi;%x!u5 zCt0e0r(e^q^woiHm&#&ny&UvZfpa*(nu^fNK}8&yhoH8y4zaoFpt{#aE-_olTm--{ z`&MW^xf8oI4?hEh#~`O35;-L9na1Enazx( z3TZS$lY}3U*hi+kaAovKtu0H;1TH&4vI6PFIb|~mRPNon;|Ee4*ThB0#d5=1P3VM&J(-z6{_Fk$J5^*`1KGw=~>NE1X8CWE6Hn3=xDs(Q_uf~df~2L`6%~B83jxb#FueHeX&$S5Lh{I>}B2a`1qFeaQ2qy zbNdcIpKf0}r$CL2JL-Q>u&Hh=JhF-~i6lVV)*buwnLLY+2#|)y(^Jp=M*7k>|EZEH z46X(!avlJl3zrH3wsF|S9L!}bAuJ?i3M@5P2W~>3Kv=(67ELQ?Hts|A8g-7Yu zwQ~~v0m!1n$@^1{r5}pDFV$C9Y?jUR-WCg_lc|wzB=s#~)9Gn}?kOs?#I;t^+6rPk z1m#d!QFQj+TDcNW5>koYZo{Qf$h2#qr`P%_LphXS1Q8yo?CRx8W zYob}I{iZI=bqO#lk>x7SZRg|XsI~*mglN^r-16rgzTBK;v(2KN2_#y(+7&b;x*X>DaiGX+su1TYX(?xH8z z=T4H~U<3o_@zC*?m4y1mPkvv?Q)6cIr=9yx>P(*fuvmt&bM5%Bpx_D6WPnJ2BY-Q(R|i;R#%K8C@J$&AsdP_&BfXT2`H1l( zH5J-tHU_=c$XtxAF1J#3eCw`NA({GXxZ|S1_~E znka}QIHWkcx+1`beSt#HYw`c0-H(h}g>hv?z1pZ!KYDaq6~(EU-J-W5?u4Br*@Y-s zz0r-WV14z*9s-Q_0&Q*Y{-poj?EQXSV6m|YoOxA7uyw>GJz_R9InCluP0{Zb@6;ev ztx}=Z?*fjBI)hoHM7-kyi*l;uy}i37tZf!8Ooc5odj%f*zWY!9n+>wEY#^w7WTPlk zn^GI)eN${Rqv^CLH=?yAXjF~-j(*i!;7Pa2=XqV-htRV>vz=+I97g+A{C8npYe;k2u>MKc(j<%Q**y zz}GwaU|Pe3lK?|C4x{QFif7Z!Fx80#IcZum9Eimj0gMAx8M4bb7=l%0H5VSqv4p}Z z^eXQSI!eGeT8AP2aSyR6?KRCHCL zP{3pgqJTV_+o^z2i6#rI{@RgI8!kOyy?am}se4*@!4c=3>e!Bb$J6SP^&Zk2 zcjVMp6zH1B!=wS#KI_jSL4d&4{KGp^kOO#=@mEG&BXK5`kOCl2Y}uaYnTZxZU?Lk_ z6BJqcCKn#fO7IGbmx;SDie^$Ov_@+gl!%=nAsovl19~Mq03GPzolJ{XC6T1h z5QF4*3rO-_fW4pp;C~mWCJDsaK_fkK@)cE8AI;tst%!3B;1}TXUKh64!u);BWP^sy zv*zdH6El`@fRO<>a~lcWO~Ebq1#lHmnNzUHo&XqeZB()p@T!ugREPDRrame4LTBWh zQGFmG#ec@$Fi|h|GeCNd3hTqWMbJoslcwO=(L*SsTOBi&*D|&FJlkLV|Jch?OSL2c zww@m;VHM}!JemdjwX$lrBytr1?%Z=+mFu%-eyHa~m67j}v@nqtDrwz)JBh*JVOk0R zKdXt^o`6q4AA1SEMr8=QOMrg;;`;*9JQJwZRQB*!1pfr}B)~3TIHRNk!ZbIooE11Y zeDce(0~gP|sr}2j01S)_kES6ij4rAowgC#l>+3p`R1uNpzk2aK?WvgmDLV7k-RYxu z{z~e}MG3QQ`%Kl-lt@j4N}@O38iBo77p>jYHQ5WH0*ODOA}>0oS4M)mY_ku2bcX+) z`haV&m}mSV3SulSKB+Ey?{Jv~Av|t-S63G*b&t-34_>PiD zh^-ww@g*f(&b|L*C3(0Wz(3~`@H#X)rnAWRxHrxli30lTN#^We6wd4|-4zLj@KGd# zw(dM61_7T*a(-obIZe*&NNH_VHjG}@65~d)-{vSP>4RvQ3+r?fn|WL;->qO$;-8X) zY*RojM(8Gt)5+G`{4<(~def^g+m!u!2uJmZYi&OnJHozvUu6LwE0#ojZas?CY*_cB z?ENV2sXf3)*@T!-`G7Vuvslg%M@J8~L@2qRQ!jjH0|Si{!IJgpvW{3{Y`F$i?<7l^kd6BvaMiwopbQA|x*$l?>3Z(g#mwi-N+0h!0Mle6DUWf zrQ(_^Yt@XsE+0^z|7MU`0v7cp_{_KQ>Fsjf1X@(;Ody86%-)IocZsZ{M^sJ*djO^T z;XM~}=@YF`LGIwN)^Css*yy0NC#eX!sZi7+JC+TdR{GMKa-Ir z+kWua%Q~x9F1%|q>C%SIC;RRGt;_OvWZH*EM$_W_BUJ+kBsIQbWK5ut{tEyll`^VR zfFMBc{$no*d|mtOJq2n6S_IWl90^{?o+?mXTQ&N&123v48i9d`kAoC4?h?OYOaWlf zXQ<&n>953}a(>9X^E34+F3y=~k@}sN^n6KT1-0EOG&Zx9dk35X3Wi4ws6t(go<}LC z`nVFRc%Odox~fQAH}5$=dq=%cRBHKsyB`zf0T7C2>k6(H&%P;;J-uyr28(tsiTMD# z7GSE^j-Jdxp1DzH$w0Gbu%GO8Dz4B*`4eiRM0M2HZL9*Qxl~)3y*WR7S5;Z5N$VNY z14=(9qi3jQ8eoXP%cS_rjNuMH&{igOu$a$IZ7(FLA4v_Xj7nKL_J0d3#+*ml-2kc` zRmLJ(0jQ!P!yH2F&&bGFI`zVL6rcm-MfGl!rbrl=J=Gq7G2mipdk&t`-wEi6&BQDi zo3fUK)Sqr%Ih*1sHXycss2dtslQKjG7@#rlhx;@aT8-w-vsdUT2-bP zZ#A`5djU|Q1d#@#Z=`2m{hhRD|5NFwfAP=L?Q7>v*v-8LpL6W#*CeXNoYI_4%)Tn@ zsVj~8NP`f)G0`6q=JYI9K+Z*&SeqD3ZwwRb(NjWq-G0v$OvxxXrB&k~ESap>M)r^D zn~%Y8U*A^!3=?dzTj?dUgjy1K)?7&vR?Z9x0D_;D2+bgNayZXNwBEr!jWL>-=B!S6 zUo^7`S1h4J!fO709&ZqSa_^yM)5zGkX1_kXcSGYuuvt3KY5^!VwRI_9lc1-%h#jKmHNGNtld3gUT(Mh76c|Iy;+o=t*J1XVjeD|%z|-mBu}P^~V4 zHk%ZaI1{SITNN>XUOSfT5|4L_ZQ_~q9XR%4^;FDIP{Joejj=O+`iO0M4&w@e;i57h zHnYR}CzRz?6((q65yW?Xye0b_Mpl)PUk9-42+UiTQ!77x?#g0aDT`pY$`(e`e%Jfz zLTNRzjqXpO4i+O*+TK+42Cpk}0aoKs$>CKMn*g6dxyuH(1s1E*)5u^b;}!`64NkRz z!2xuh1S|^h<;Lhvb=Pi2qH!P93+(esCDn|*1K`KqL!bJp8M9m;LA_d#bCx(ycNd6Yfm z{gHkT-73;u0cQ=2Vu115s)CfQ+xMlL&;Zw<%o&Z9{y9}6ojRq;fcF=wLa@A`Kv~b! zM@oodv+Bd?T{$jSwp(LO6f`*%xy(!~`^%^-HtR48&qOt|0*dv12{0c)A}fOf#mSL1 z51Dd{CCXYf(-PfG>*xDkn*q?wFqZdftW$Pm)*++pb{`qX#14W6z0idQtfh!MEVdCcqD**l; z+`C~wlaVk3Mzd6pEj@uF6B?g`m=$|P{fH8pShs52mL2K(#ShhsJbUkEc7}jG^-}u4 zVuDvHd!liUPDq9I)QjI0<%^pNu?VRz`e+)S4d8~~CD0~gu3_&R8@d(%5x`SQo;wbT zLaA!OkWmHkdpth&G|xfeHOi_Zz+!Yw?238_C%2@DNrFY|5fj)I_@WYF1GoXQWaOc! zF}8ysUVv>QX=wKtiil$qT5EjtgF9E!yFdFk0$n^S)?_Gj#0zNH-&Du}=~NbtY15bX9(*R9c=lV? z`{zK_?2EA_R#q3&%A%?2Ql-{Mr46wJ_8)seaoEi(A4^<@-zTU?$&@NQ68W4-6m2E` zHb1L`$^IkHYRzw7`!wx7aMD-;SI?)>@d=~%F3qd=jcPJ`Focw5b{^0gYkr?v7sk^5 zqtB;r{my@>bN>B*`9IpejNVDFz(4iewrM1IrT82TtjD)1KJ`8?Y#6{XW(Rf!i?%mpTRod+mBvb?Qr{2#08UsTb@86hLCb?e|qU_|0HV-&|4}y=6;o*7 zOFV1rCD%g&jzo@Cg01Hb8z3<-s*sQFEAauVf%^s^PB7z-pUvG*i*pYeN7MirDz>Js zYkhgBKLZ{s##D_FdK~h{fkgv-{>(josH>MD6k~56(+XUWOhpe9FJ#XJdo5ytw%@ie zp~MMo8&%?QwpxjAjoo4e0QuU+br@)^_oLYod!2nhlHm1wn!sVrdhE?&@Vjp(zN%*) z*PziEIpl}~Q|h7C;45ykWl6|%Qh}5b2b#=S*Q)Uoe2c}V%So6t~uJ1g&S4a!UXOyif_A=UxuW5HtefgRPjJQBk)Vf7}9 zztW zJT|L~-R`8$kd>duGjD@HJ!?_c=x1{Q08z=S`A@wJa2J)&cqyP``<^2bPr#V~P-Ngm zx9L}wm(Sx_Vk@BUVIy$pLwry4A#=DmA30T5l*J*@C@)-X#K?K zq2mhXEs0RmQJOFAmK=!tBa@A|2w7{g!vp|2W9w_G;*|ctIMQ`rL;;JneE{6+xo>Q! zqP1=JAxZWt8RS*lEnD|W)f4GtZfWNXBp zu|A|w++%NzjE)INa!pj|tU|)r0K|UAtiOgpk;))e&wL{dk4Y3;f~!$EurH=S2i;j69^h8o^4i?k8Y=Z)&7QMR;u7XyUgB#IV*VOJE)KUxlt(V>c zcJC|7i9V}Haa-!;X74ln8m59OeKrdco6cS;l?!_g;cpHee@Wo(+}XPl3vnCG7)}`j|eR9nTyfM?#;9KJSH1 zo7%!m;7L)m#S$4AS5m@kZ0Y4>?GRD9bMuneHh`l;$6ija{^oz0u6+8AK*0OI_!A}n zOj*~y*!!oR|4oT(-MNA4aUIDuD>YU*EI>V1T;#iK-7LXnA}cm-!{#X(wG=n8sy<|j z7q*szrtB$ypl07*naRDx1NvPIL| z_oj9FJUJu%gLa-=bV~DNm24_NrLI=VUsrLjynDqk!B&&V8s;+@W5n!D4PKu%I{WyP z3ziizH1-8gSi*aK8|mp6zAI4w$%j7`Xrv;azx>SBKqa3e;b#*5WH3y`M}Sykht{py zPvXT{5Mrd%tRMdn^J8VUp}A4p4`Lg+g0y;96EPD&)Dt^T02GY@X{y2iVWokT?65e4 z3N49AUKiExxMmU0Np1{|WStf$!Xz+wE%u8yHvD3CE-ImRTTO&g`{h{YIzF}MY{@VF zUQaK`tV3twh&dD0Z?AB6i|^uj+UJ!0TKX3)X6yx8+W|_i*rI-2&pC_j>QzyP^aJjj zfsM_>Wdjo+sP|xyO>T~yAVYM9MH;Y;{$fgAX4rTz7|C!tCHUGr-fA#7HhF0Vi@gSj z|GL0pm#SlarY%ZaFMwFz)@IO-e8t_>5rpkzTMXAse^v;cId)y{(g5>JHyl*dOT>LM=1^%DM;DF_xtziOhX^rO{}sd}uSXRxY4BSnS*%7QEJmIc_7W zH1Rtqc0?IErgheZ+n+pd8iKMK_`bMzj)9y_Wb-2_y}4Sx^@a(Exv;L1`bU-^_#%_yy=Y zR8*{+PS3$`5^h_MEJ;2}Ko} z*5u4C_4C2LQ7`Dg01{X_%K&32Vt`Qsc)+RcMHFF&Y>dI=jD8j21S4i{A>Dwd|6yr_LPKD|w}VXA2Fzx8M7 zjUW6Us&q=y|I!Bn8tNfWecFS}sRW$Re?`2&{XO^U@21`RPUi6&d?vtX5_}(F5;Q%p2{bZj6!l>eISlfa| z4K1YMVdka!Y+Il2X$kPkPq=^Ovk#s4vb@Oo4}PlqXC3w&IxYM8@h^YS(c^9QxJcjE zJ`}J@^$A*_u_#OrfO8Ww*39NdCBhmrq=GELD%)ECPn*lTtosQnr&3^{YOWw2uy`Wf zzV?Z(6QQ1O|KtBE&CT6Qum8nAPXOT$-uiRxF=HN>kE06p^h@7W;)3LisD+LA%AS>g zap)RkA8LK72Dqc8C2UbqdSrch4hA?@Q=jOJPFamPjSdzCEUQ8D2BuBj)5L6I1d?kn zkm&TJfVnK|?(nWY+wJ=6g7VFX{Sq6yGv%)q1jH#3vNiWGK}>eY7Jt%{&i z9@%S=fV1b*3c(`m@HeswlqH1CKdhyZk;ybMy+ew(unssA%)gB>JP|k5NqoDi;;gdY zbVbz~?B^tA)~PURa!wX^IKk#ON(^ZAeWRwMQ^1yBHWnGoEo9Jz#J+In(193i-}|7 z;Fb+Jus_e5bPF)UD65ajgT@Rb zeEv#yNELrODq!*X-GE@%^>`A{U1f~oeQU7Te&0+#Y*h9-!D0~6cU_dE#C#+B#lRl@AB^XwZAtjWX&ZK=NMI)f%BEpdfbmb&pUnzMGA z2Bv=Jn7>u#hQ{-)sSkPGiV4o$*;_9n< zs{Q?m$|4{s6!xS%tPCv`Kcki-45EH4)>Jb=ttZL)!0fErsES2b&_h_p*3zh4v&!1@ zzEtCaS{N#bI=}Q04UMD&$6iRMU;c*@QIWFe>>U?mL5Y+R6c5wtiUBfcV==dob%2%y zkmTBoV#*M3L?`IGL;a6R>$)m8qAHVd<~7SpX;@V3F;ySNqkRLKHWW1h4yuTYHoju< zVOm+7m()B}My(wxc8M8~)2^h-SdD3~G}^pJK975d-aZnr1gXroyL#b0B^^lC@;Qj} zAgaO~Nq`~ONm7RUv}+-8yDA#mxiddjzZBv$02A(?UPsqu3eK0(hCME%r(|Uik z!2m2r#zZOR+Nl~#+=!~$8hiASSPsMxR4NfDBFRDJ*JjVTM7;WVj4{HQXYDNs8RI%i z|1=bPfla`bU%%Narz28falmNF%@W}&sOsxW2akVA&-l_OZ|50;jF#B3_h<%-7TtIi zQD?K$x3Skryh9;n{pKFr7Vy^jUPrn1PU(Gg+Fc}Fc}LDCNgC+Y>@mP9>wo{w)ec)^ ze$aZ#Q9!(Z_p0{tx4!pZ2q^vOAN+S3<8u7jZ>A64{tL6`LGzV5@w6!4%nw8m#d@&X z@mqV2T#hs{@MtD@J@G0EWoM--sx;B37QI?QAFRP*RJ0~$cBJ7!SaDPJ|oUd=~WEy>;AgcUst~k&-T=dznN}bIj2!DuoQ!f$bKe6J*M z?7f=(nwGh+HTji*MYD6EjA=5;dE5Jksi%fYf-Az=OrLSfJofb&y=Qq*70Ae5a_}V} zAfseiJY}V1pqtXu<>q@lwqA?-Bp|2#yWM`LRnh4Q6vMID%9L&OdB9>T_0$ed>kZw$ z4sAyD6#6E~)K$NhE>+LX09|99KZk{T+#ZrwB3w9ymxWuUC05?0k9Ex9N**25^7cu~2T4{43#&48ioj{tk&(1ZF> zlym*HQ9aJrTh2`5)}CbFmyM*q0o;&qCmVP7_GRw@$}XePlbP?s1CaK8Nnvlu9HkLm zENBWkN>rFceRn#msU|}A8i{)Ac04tzemN+S4f{{3YF34XpQx% z)=ck^vY?FT=#hXw{qlFy3$OkAs$O0A=w}jcfHJ0eQ4`auz_P|XTlN|EU_Fke5;}YTmcSU5 zLH^CNwr523cDMS$_-xKCJv(xsPPHO<2cSho5Gp$ry^s>Z-=Q`La3`qdy3F@covGchPat6CI zcHtL4`h8;>3=SsdyRr84))B;+ueK_2sL-OO$vRLGz01s2j}bINK>*Z)EMF(~F0q4# zMh^_8Db!@Q?^lJADmM25;N)4#eyp!c;gi1;^iyeoQcl%}b&6O+ePt4Hd0>@39~*@5 z3wxCPW7oZr$DK%hk|foNQ8yzVG0BY__#L zWXs^WEmP#?UPuD$JMx04rd%82FX#c@vUOkj?A#klz;Io9y;rFg9^DfKnMw=nfQ#qe z54vj{0>^Jo}CG-Wz}F zy@G|sM78GhOTVQmGtb#H5abmDR%}`^GXGhE;ciLb+K2J;UIWhqj94s+co1_&86ZEH z_8)%U1X-{_nn4V`_o0Bs()@$8xHzYZq$usnOG>0Lq6c;Xww$B}Nfl$ujG7v-#~s)- zzDS^%oiX~dvFcEAB?)DUzsz%$pjI_pz2T!<|L7KnWj|wvKl@Vis+J^eKgZ2JgP+M~ zKv_m$%xC_^KDF^ZtE%Kl+oFdcW8*Vg$>>;P(K2&ip`Dv20k_z%XI}Z9`lGS!jN1A1 zqn}G{n6W%CSMaH@SMaNh4SDm&zc1l4?8J?$XEn-(L={QJw}0}70+-kUDAX_{QG>m6 z?Nc!t!vA*k8uomUMLaOytG~8X_*%k+)mWCAvRr<@ss3Nb!;g!l>&tBJp(sL>>T-!` z?0fa~_Z>L)67=uC#aE{}sLR*ggI{x@64N2uO!X1qhihY)i$i}2s%Y5(&4~X zm~G`sbfQwEbyYL!3}3#X7WnD7(TqP0OaeQ0eIL zMivySxg!ctzdh{S8b?oJ&;+`yTHLB`YXFWK#*~5q5zp zFKSWUjJ^qQY(GY;UYm%4L?WVh#$RanM6h9%MU*k4k{8t+f>lczTaOg)C6GA9PafM-lq4Zvi=9MRvL z1ey@n;MpSC&*zo3L&(4?0%X-~LsUptZv#P=JlEy<2+;C3>vewUQRZYMKK_2e|Ako;Ip%FcM z0y!In@j%o`##sOgb!Hb(iew*-%U|(3&~T~bQHkMv5A*>pRx8m96O^z$Xnl)HHu>HL zz~L7G1PItz|L=&NffzWVlWr(LjVdF+jL{~n5B+7l4zPIi>DSV(eNXAVI4i2Qc;BNc zrqE0m9;Of9`3qG#C$}J{576&V`wl%LJ0no*f;a$O5)_)JwzQDmd-G4yTR;8-B@_Zg z0|Z&sTUX8+1=)jGoonXdj!&h%ho2Q_g=PvREbN6;xU+bJjT6C65(D7(jalHrT6|xi zZbP#v*(W3pSW6Nj~hE}~|JY#@QK!c0~H0W)}Jd+Z-|&sNyY z&46KNtW@R~2hg&;W427}3Miz2GQ@dcyN!)2p2YT%^wPMiK@;NB{#sg8qU!ebPj%hw z3s?>8rTe!ps}hc_yL0nm+P?b`Ffcv1dqrnl75}BVG(L&)sQEBvsz$GTROm?jNSWIA z@%_73j8RY}3pNYDA)?mB!{^^Gk%_DLW}^EY85ApYl~Vff_x&a7y+H`MRh z1hSb3>mgCivN0B+MSwq zlXEmVy)~VE_b2Jt>93|spS-0r0|NrK0!hU4@BLW4w#-DuC!T!%+v(=jbLzVd5x(5p z+KOMhg->;|w`*+cxsy8nF1?245py$E)syJ(t&vE6lJKqTnz-l9d&LvD@!EhGHMo=- zYAbB}yr2JtUSEV~Jib(8x6z=ikHZEWL028+$jP*k=Whp1JNv{<`M-DrJQm&#&^(K~-PbHKe%Ab?MI znn-5@@8?@#zY`NPl^m$m-j2p?KMp7vM+OgsAUxi>;M~pK~dWK zm^+8kU2|Lrmt>OScBTY`)H_YWX;^_WeH-+csm}x&8)5+iMt3F6tlp;eRS5#92TGuQ zSp$#BMw+4>RJ9mfkE5!qjIFt)HE8$VTY?qTFCX5&?Vz(fuKLc`#uvy(C8fI zSsKWs=L>L#ty`l<3vk(QU@0njs=T@=3Ud(&!U4_%yU_KF9=cVTaXI3CvfaZzd>O#7 zDgegkL6M~DpuR2uCv)x|-qF7SjZj`A=nIDi2!XyS`{SYoA?fbl)LIePGs{uHS4n`V z!jth|No&xy^(LMG@!&FE+bf6y92|M-70s0U@a?};5N%^qta>=JeZK&TDtePMJ{H92 zW+WWhE6~hl?_U!LBSCQe%7+>~z}}{EO8*x7gmVnAH#JxDQ>r?-f+^36$|{uz-cw=; zv}26Y8#trD6RIk7PX&#vh1ADK1RkMf5_D3XWOf<*Pk_|LBv_-F9sAM*)v}>cDYUZZ zsWP2;{zK2{82|_jY*_^s!5=^$)GGo(sbN06tLq~`-h248f+wl5 zF3bwl0hT#4Tej`d2nec2Kl`iyO#m(I8~bkefv5D`Ze2a6>PkuUnQbG{v1k7&-4jA9 z%%YU2i&Nb*1xsgOSaTvd=TP4x(Lp?*Jr*ntXFce7kB*BX2lbM50?+`iq)6%ei!;D; z)7}R-(OWq&khiO2*y;c(7iq2_rSQev%plz^hBpqQ`ai*@x^o1dP~o zRLn`N-???sZQz>DeO#;AQdD`3b{Y31%I4aNz&jxF-1|RCvv;n!pR*(?m3QWtLhB3R zsR&i-Sg5Pdi2HSa(sACgy)IM~K3I0e70#)i8o-7MPO^t_a8qV)w0=YKTin0JKc>1G zG)N^AMTK8d<)1_Y^II7a0aJlB=XpbKp4oX&aVAM4KGTGDj3Q0HGwa3k+p+hU_ATdV zX2$`YHDCa&2!J)~hHY0uvP;pTqrgy$&;4pbp~kxeaIp2UHKr+{gPma0E#NCgp zv~_|-j{)@do+PaLGlPN9%huOm8NiQV6yLk{+52gH%QlVTIdJSn*|{56&&y6?udaUf zetK~CYC3rArF7-9GrG5v&wWew8wLX6Y_KFg{rKk^vvl;SucZ68E~R_-uBAKIKC$HL z6U0p!B<8$`CAT6`8;K3Yp903buZbW98`JL5LcusQN^A_cC|A^vbMp5wSfSfKA-+Ob zsL>y6$-H1N1;dGJkL&(>1B;#aP%4z!fX0jbrUF3X5KPp-vTs(_XMDrD4l$0AiUQ6< zftI9yi$SEJR@hx1X@<_eI;%#X=S)6HWwCvLIs{1`2NnzD_e=H)U1X>vOxb%@V=>xJ z4XP`V6=mV`+;{!jCplDQSxa?ME8z-tc`a1Mh=HNqKyXdd-2CV5Yb;IFJ}SVUYh5*r zB#I8SSLz}V6^&FuwyAB&X$dU)T*VOUabXuJf{u)(v9T=zh&VBVDLFj$X2TJ9`9IcC zVmvuTn=|22#cWpcJtFcO4#$`yrO#_yoI0p%FiLFnD)slN(qzF`=Nks~PDWAqYIE)a z?+_GF(f^PiUm}2mp2y%`f=N{H?B5KKCRi#s)_^m?DghmIGln{oc(Pe=)*Hu_SbwAe z%b0;j&|m|w8FRqN@2r8|&>U_HhB*x;I}cGx^6>%W7oF`|0|OoYe^!JZrv zS@S`gs~cY$^gc*N-g^rfXYv1%_vTNQWygKrt-Y$NyL#`Qo|&F~FoVG|#6m12MS_&V zR9Iorq8+vv3`h7E|5bK4!ita-wrt5_*c2I{2vH;;3^7;+n8ECrrF)j%_v+fZ%JKPr zGtWKuzWZLi9sm+el>~N8)vNdJJ@=f<{APaho3nGx*7jY|6A84S6e4`m2aDw_M@3lc zE#U<_JE>`sP~rV!Yqqp)SCgGtM*znR5uSI_s{v^m#Swq2wWeQaZm~IhlKF{`sgkD| zVF2sxjZo60@^{;PkT)+k>$h)c-892*cUwJ6>{F5oRBH(E0F@|B;!8+QYCOcwwyKTl z)4lSc96S}hoL|R&zz#rhVh?Fv@e)*8Ks?n+R{>Lg-hFkRN10SE0$lb1fj-y4zZ#FB zIg^cnE!7X!Li0=S=~@7CfF1e+>1AUeI`2h=i;)V?eD1dtur4kk&%Y=&S`-{<^^l+s zHt5#1=Ix(;TXt(@`JnnKmsbu;4U>u%&yzk%-kbS)BoJPH@sA~DqaG~!tr;Xr+{y6?DEI&dYHUK?wq73)Tc;>(Z9&p07SJ^@j)e$zOkEE z1Wo{H0HGBqwFeH#o)Xv|K7K}@aqZIi=746}9c(t&Z>o|@07+#C3M}B2z*lEXVn>lQ z46~L!ZK;sxnQ~C*Nj` ze_~_-%C-{sQnh*6)kkcw+N0dkVDUzaAaRCB1Q7@DIaKA9WZYbLB4YQR{>28dPyD^B zz&sah1ACv!U0Iu6k>ZnsMfOlNI;;wQ0*4HSccU#gd(FWkrv-#zzDQImMA)n+(H1tw zKHpA!P{;U@Zp{9i+sIqT1krN<&nJbAuCr! zFBrc!y@Xj)i0a%Hm4r&9n$(qf3W}lmZ=GJkpe*~E9KIm|wC=nP3g-&Y_nPXME7MA3&5p|-PLH3@5 znJS0n%;)pUYO1J|IZmObS-XmpV6o-F=PHF!jy+=YrD!*a&<{)Wy{_C5%-0vY?QA z9_K=IfSxGNlBJ@+SIVXH{0LO2D!-@r>i_^C07*naR1+w>U&%w-EnQE*a#wpGfq&W~ z?%#cgL9dDX&wZ+-)yzy(78x6GD^wEmdHL`9HYNXFKkuxl*MsW-EIx4dSt+|R2t9jT z4L0pW0llh{go3r(0AO&CfSVVvAh;%20DutesyZ3_ynUW6l~mVL%@HjE9;IKiqR9tU zm}gJlp256(Q3(VHs8U!Y)oG=MsIeG_rCJA&r<$l|6IGuSr{T=ee?k?Fdr(iZ)c1Bp zUjlMjooO0|R8hgyI35^R`l2GQRVI{_72k0IGCR9C9q1T*Yy1WU;D zvt|xRSDFvr`Em2wOWzVj5MZvs-gmAwC(k^kdmvyXn3nv0%tWR4jJ_nQbU*m^zY=8^ zP>6qg^rUqEaj}6h^wF)MM9tTJu@Dli~@$N-a4<5C7fZN=VQ-&wR!uM zZ<`GPeR3K57obw=QM{pPh0L-WX_?3;ExHp-ad?-MN6VV~*prts##d5z=%^esXS zwi+*$H$W!OA*;*+9N4j_YOCKmM;ioybix3GKzzT6gw0m$mq?`T7yVCB-HK>M_p3hn z&X@UolQ2f>o&9VW$3zb&>?bG8%?c6t3X!^QqPtyZSIK(GWFt)XF_$qo20n`adVQ8- zLX2RiIFTXW2FpV%84Kd2SQ}@EOHe;ApFy&R%02>iF$33a2g?B#Ie(1yLJ5}^h<#%7 zDt707@u!E5JfI|v0V0|!TS|y&Y*;AXk0b)BvoOdqwqtb!QK+f@@B4|_Tf5bsa^5yo zf`=mtKZXBagT^=n#K~?~!p{_LRLS5ZxHa2fJJ6p*1Q&>xwI*Bo;+0)Aibu6w#QZ9`hUlfLDHHG($`x8dM$UOP`~vD}bj$!(-#-+GhePdrsXW+$PGZ5kD2}E}x0% zm#&8LD0vQ4@Q^?UFs|RZY2X$%kn0t_hU5Urz?kEyeo1=JbdYAGMkoq7z47XSTo8Rx zdsP+xn*t@A7lFU6&FC}SG$@S$)n>IU#Ei!Ss;mi!uuf#Lqsq0l3H5Kj+1z4O$Zb7$ z^((I5vYk>j!_{DV9|3ggvkSoz1+5Ic4iL)vVRuxq+}Tov4oV!=5P&{F6-Cd_eEILI zx@>Vd7!aEttHBtn7)t~7^}RQ~CtC#|Vjlv;p_2k6>Ek?e_A{bE{`kB9y7~TJ{a?*p zDx>Ah#xvY&^x9*m9@GBk^^8#Px$+l#7s@rG7zi*ge)zTksZ;_hx%_O8;Ae-9oX~l@ zdE=s<8TSBy%yZ3iO*$b%?GbySU+mrvHqw>?+CKov6>XH*H}pMc6|fB;*0VQ4jcc`S z(3#$GZ?6)9LDRHyaRyxNnN2$hWswmR=ihs|xpfWYXcQcOr@3|gpOFjm|})@F@{n_7au3kCUTs;4}KJSqyzo_vAum13xW)&3SH`}W0y)LwBdMcxZ zK<8MB&K3homExR_sd$WF9M;6@nn0dZabaR?tT)##zNhbVyhzz}kpLf!iF|$PucoD; zVio~BWSi@`#0he89%oU}WluQ%P&}6HBvs5N0GY$n>v`4{P#&V8jyUKke6NesB$D@J zgRo=R7%H%^ZP-iM&ZXFQJLU?iCwjv+o>3rxrP;aW@G)8>5bwHf|9~np<84SHqP$9F zl|Jg2P3patbN|MG#Z&-}WMNXBO-0Y%`rL}$z1U4ObYH`>gd#mZx6~}HV2=-l{sHrS zJwwq6T{9W>!{+V!=QVVb@cp=yJwRN}`a#>L$C!D&JU09%>y&EKwTO+ABle3v1Kv-` zGSJz{F)RI|(|v-)ew;4*5=rZ9D@wc6zdwV;I0#ckkAK5oR11ELKuNJnO1%r)g8w*QvXa^3_hS8Ou5&oX?|vCZ%D!sP4{)?#z0T(Z|>z0+G&7 zd!YhT7}KoGV3eVnlC>ghOh1DJJ7lu!SwfLvtyF}eLDaMmTehkXx7uq7menjDyO;CgkBIyu8TmMfxU@<_F?pZ=YU8hkyi43ticB{7h zIRYXCiSqe)ojjXRy?b+1vtr=zy?e^MBNTySxgE0RIQnEJooYJ+klt%m_3QS>X>P!g6n01J?nyS1+CSOfw0SdE|-4BcbZc zPz_$I6hM^;A#9r} zH1~E?=|$M(&YkP(^CCE^s}Ah9qsJe%s_gE)=E8?>iJ4Ic>V5yH{!ppo+IJc>8Jr1V zL;^$SiBTr%0cFNBiI97RZmg=?Jc$Jcw{NNkh@=Pp#)+N)w3VQQuO-GS6{|@V!*fUh zEcu!eSOoweuHgJ(@9BTSPdxMaZ)jx2r4Qd!(oi-6TY(M(mdV*)?=jAZdbh0*EoO(* zTDNuPNFHEwpc{K1xhjgC!3IfijTVVu2JmzCq{M5~zuBw!4A}Ld$v~Dq~LjTHFq}Wb@B!gw0{heMX(VMlqNZ4kuKUn7rKbHyM zc=#EBbw7Aam9Bn~{U?-us>>_QW1sp}*$d9&hwuMXkNt^fzM}CotR1ri-9tRnT>9v3 z^`FzLppwE2i?<=wBeLpMq0j&sEK7PkyO`CUpuBJE#k##Pw?c1m}zQmSLfU;uj zsRy4{a*P=G_Vr86m5cA0ffQ#T_i4Ld?ORj9x9b~u%B}86{miFXuRcgj8&j@9ZyyQh z0Tj*aX3jqOg{tzrzX93**!<0YMH_%euUgPX2&z+kjet=>KQt)#@siQr)`KQMzyK52 zDN7LjX0Aj!`_+kCs{=j+EdSEegnc-5}3QPRm#P@1Xkk%nNN_@+WIBTTO|$7Y=O%>0mERE@%^mwOFmUjz{rRt}23 z2S}`EK*_;oRYg_99Kf8Fu`W0&0a;Kr>P%A&e(Oh?jufF2`j7ZbsoiZNZV|nIQk=Bm zndYk`DDL}jobMj~>V0-3tFk|3k|E4wgfFL^CpnTPR6)C#?&@qPa~RZ< zbe0OfspK3zEfE*48Cxe|kx+KMdhuLLAkAu0CIcdH51JW{+>5A7?5Y`*GohUmoZnS%j8t|3 zDxtoq(K!fm%rB^#$65g<5!c}>`|i0X`kfH2+1y%}0FJ89K|O?q3+O`3N4-(&H?^;y z|Jv_K-4`&twY4FT%)Rja4s!|D8OyODkq5vel|il%F^&h%J}2QIsHNZki~qfO>AQcV zDxm~lvT~th$!eKOi^3pldHLdd&GpM4#K@EA!3(AY!4ozc+xqbbZ|GXnv{6>X_rS@H zv@96g1z02Q$6Y)2pnMZ-lrxWhRze$4j#YV^ozwFu$zQb}d;cV;BG@HafG@>=vL{$` zSN9G$9?|^18C9gA3^H~_yDhklJ8TbtTGuEaR)xVqgG)wFy}qrF$#xy_5SzJ~ z`R1X=KPS5LyKnrpk_`A_iRg%Bfg&mA#69S&6VK%O)sLJ&+cf95JZv9G8c z9zS(f)qawt4?Xeu=KMQ9(FQqo{H!YbP|Wcqnq|6S73U)-ACkX=y6+Z;ZYxvAUzanS zeYwMJPy2zNeqp5#-eA;x^|${}*Gk118_2ofyzsks-uUb0wI6=dD$^6cx)sGVRDIT4 z4Hm^rxpPB_IX-Lc$OH0Gj0wU{J1lX<-wZ)!Jo|Ip4{8Cck{pjUZR6pe52KAcFa5JK zv@8OP1z=23=AI_N{2Tw8oZ%M%mQZsw>n#J(%v!1+f}lWw!2ty?{7ufB5qMP903dl+ z*+2C@NTC%F8BV7&e{BL6x~8bc_pUwp|76*?1k2Oc)7wW=(Mt5gGV`Vmu%`nQ9phbS zJjtDOuZo(-am0KdeLqOLoAz`>fd!66)XuxNO2(1Hgd_K?O{g_?^l`~jID|&5O27)4 zFF>c8-l0$I2Nns+z5kO6HBqN65Lw_P z_>N`NgbhZ1p5D-n`9T_D-|^lCm!@ykNq`Y!stPR>jz&~8s;Y<>cqZMh-#-G>{ks;r zr#Hc3{&X6k+0w&f|4g|*M-m+g;H$qkC`z;Kf6LjZqn{pFtihxL!UzOaI|vYO8q;D+ zF3ZYZ2(t{h!$1UwG7P^Krt_I5s(7S)ig+|KAa6I9vE*#ZE|KL zL8a6bq0vDn66G?4VRozv$h}CUBeI)-MGJ|%<6bBfW~CGw>qiodeI{zVX?AOePf5Ij zdAI}wH?MwJ1R}0pe81b%T^@w#!cJ-vIJZy4@d4Fb3+&9!x*7@163{I0JVynPA<$M~ zEkSvRt3aKjhYm1BMjL=Z0tA~2nA?LEs+I%OqTHY8u}o6AjBGneD%R%C?HkSJT?TDO zj~LZ>iTk)p3(JHIJGLJ1mK8j22lp5fAXz<;UiiBb0}_QX6gtVy<1eW2+Gngdd7x1Z zuEaq@g#rmpSXIRvmlf0qjO{{^JkYGHavdwpkz)^PzM>U>Q(VO=!LNM(Pn-ANd{N8? zJ_le)(hTrO7MsK;$vWPPK1HdZBI>ZTDggc0-}>j;Hy${CxjFsd)6D~CpA%*AXRm*^ zdEw9gi7Gy(@@Bdcu^IPTQF)-6%l#oj0!Y4c;hj({?kXlT{|vy$bGvZ<4cU5q(E>35 z7H$1%Uzx%7IN#J)DITAUmETtqiG7L4lNkfWsPvLu#qKKEWXqHPueFaE06RWlA3gl| z=cS@~?9`*pwTtfyOl!nKs6DF^xWnu^Kt4-hDxern2&5>{VhXOPs0)jF?(9>6VuV;U zTh>%nkJa%ETlQx%6r?mCRCAA&$ieX;av`<@R7DHIC>0j8TQey4LAw&b_TtYRy)mWx=sK<;7S|-O7=K;U14n>P zMjqjpJl8T41$i!F`vh}~J(Co}Lbr^9LiStE&AGa5L9`T%>fO$LfJL38xrOHRLr;or z@Xl-BYd-yjzt_C+Wp$gv`+s4>hm-@XxdlAARae%?I!OL?Bc4ZxUE+%lDm|%k#Y-NVG3$&wT+@ zy?sNxh!1=GnXgDp3nt3N4_?=K#IODAwHKOqU;A#U;@20GzI~c&sexA(AS_&XQ$+^A zB1{mR3hPV)Eotlqi79NAttswfuB+7PKikCD$Tq+KAB5m)GS%ugD1GB7we}`S{O1K0 zdk1cs4PnO-;co z!J;WJ&J6Y(W)A?41m7d}$Bu2%+@t&5iTx~3N}|g#BYXf=C}y0gvZLYLOVJ~`t4a)O z$*o9OBe;=i&AU20MP2`DdFW$ImG6 zf$E011fmEGrFK%m4%FM?UbAxWn1xa_|8qTPeL2!0pOMmtu3{ErT0tCwX!=s5D(K9$ zX8Z;1G=aSFPgHYylmQK(UZr1(9)jB*h^@c({%xyp-9WxP-?4_go5}i50T#QSrK0Bs zcu$aR>S}eWYK7Ul3R#27sA`**&EE#CJJtUJ>^mDDyCnLnT1=ExjOfuQ=Q3rmBZW_; zv%CpZOhk1&1C2`A&JOC5uKEEq04W6j(4e!YCu!V(Gwe*E$ZPL35;yVe$gSq^v4^xr z3C{SPk}>lO$|ked>F1`BNs>#nxA}Pij^n2uaqrvay68*nIfAG@Sj;n3f~sDBQ2)7U z?^nbh*(a261vb_U)afN$T#>XqK?wm3*8<(sNjpI1q9|5LStjrS%%CDGN-1k2CG1d@ z)d&>RvY0tXfNQ!e0kG#SsxNhyd3wyyqvvhYU^0ST5>TSmGHYzXpz?$C)UvTNjVRwFDxjB= z_&NWxmzp~WSuG!Gj-Gl%mBbI;eMS4gEd;YVmp86`+&uowS1pXT*XU;?0ie@kgP#7} zH=2*%`$@C8wGqnN2by=^c(J9E_W@m9{BYn@);wD$oVXcI0Ogsj&n{~vigM-G>!gyB zDGSTZmw)RYt8Iv68t;$4qw-hQIAZ&(Tn~Z8EKu~XZ~F>W+Podw9xMKgi$b(DeWpVwR;IB$i>Dy!jpN!4Hv#-3MC z4OK;|p6XNF-BBMAnNyFjXoC_eLd@sm*^U7C$S&#{qK`l!LR1nZb`zN-k;*i84H_g0 zYpx#YY=*-XSnOo)0G6gp6SQ%?h+YsdtEVHYym=i%=X=N@SFbCy?O4cZz@l!q)?FKS z9@~f0Zmqs!se^;~zP_de9}-?c+$J;W@r;ME!=wAS;$!XedH!{~3K2K7)nhqA2ZA-N zHWLg`vZz+Gr{*NI6?CZC*=A$iVihGgD$m;Xh4-XN#E1ZTt~I(v%A5qAIjuU->M? z7BE+F{knSkl)MvF*}@?J(PWbtywZCalv&Z%nr3s0F$rt>jaAgE1H{l_@t@=WVZp4^w3FFl3qm(YM*Ux-MplEiS)jvz|9wa{U6Cc{nelR z&(U+uh=8aZXGWZzIyc*_9XTyw6IUS`*&!&g*Djv(jMNY=aj)A>bNtj}nia`45UO&iyH%h4lEhIo^f8bB(BFi+@hsgG?}$F~l903Y zYd^#D2S4?>-_kjK<;8!axqFovDeuerh|*5{AQj!^m`i$3K%Bji{v!Lm-TUhc)7e4! z73Ncn8BsEd`LZNBs3tEgE7?M;gnFxD2B+!Kj7edn4xlboA@QrbW<1abALp%5gGui2 zo=QU9X@2_sKUK1Jj?pw4DP(ZzWU(o}<*Sp#oDf~qF-}b{9`YYm^{KDYIgyDK*D{g- z>s^*AzmaI-Y$k0~a5~lXE4yaET!F<3oCqwU)Jbxf8Mjiq_3KC0C}Ifjo8B76&kBWD z3Fif^{Uc9*xjB0L!REcUe%LH7uQb~m>jF_{&OX~*y?kEdV;+C@tJ==zfA*v1$gwlB z8`xNcv#>$14WKqZ`pmD2p>X@=RRPHd9)3=}jpu&$QgfSxM*j7mNOH}Lr+0I1%u6nk=@{K=ee(;@tspJ*!iyh3WcHJkMNrJv@sQq01 zy&p$?&Yeud$FdLTt*7EnLJf*9y`lJv+Af&QHrj{S1;u{W{Hz9xLq2vKnC)M8y`@!n z8u#4dh55c+uvl-%31|0j{I5PKZ(+Y1%gp$YL#s1?;VdM-ECWqX({fY^=(V9wWxh~O zI52D^vcCjw+fuo6X4;fC9Fq-8>l9m{)IX4uoMD}{8Z?X(z~+9-lbhQA8Z5ec2nb`` z#39Y=DHN1YUv1wv4@Rw+SizI1=;W-!1ko8dWPge1d6@~XHhdnq1YrcsOUnloXp(VK zrDbzN!4+z8I*FKeIG=*oH3PC#2U04t8) z8D3~=R8vinYcoCJJaUwXdZXr*wZiceI+86@e_d1~GozVRaR)oyD&a_FIssOIl&s)- z35T3|Ect!O!!Da&M(kL5ns@d?4AX=I33SdQHOGeu&0_ubpbHU2M^gUS~60dsl( zl>RPCwr%F!Dy6Yz5fA|K*h2Iw3eZW}7HV~BjAeDZbr9ZHDG?t@oS-Mm$O}Ze8aF#f zwtKl*JaEYKFq2+AJF7kJwPE}VL*Tc(XHaTYm1n27Kv!TgMp$?-HUp>E3{#T8 zz&J)U(aWwiHC+`dJYX_=u?a8*{Fpzv3_X?VGQI(I-FZC&)?IyyjM2DbPzvCuGRU=R zhS=<^#zU}f2#P?>H4SxHK#YArZxTTj>#|ONB8da_y;)+O-Xz|iiZP=>L|!w*o9O(-458{v#^7O3H4lO3$-Q8}7erSsCMeS zn&&~XuA@iGwGv=2T) z9CxMe*XGbkw$%^1_JKnQ%sOx%lUQXR96WT?Edc5}UBI9#fz9(|j;haweRii1Q&ip! z3RQVeuqcL;N24UbuEA~k((<0^qtj1?ZAx3pkFoIxbCDRrCdtpJA9hbRl%H`8*m~)5 zFtbtueawjkY z)R~5Q!`;ua^|LOvX%2>Eh!iXjS1|iVramwu0Jl^K4d4`{Q;myW#P*t#D%d^^3=Y}& zl*^~jf&c?!Np>`WqNUs;s4euwa9dJtM3%g&IQD>g#7&o>iUc9jI83eg3^QkwXix zl$2>J*E)GH4QL(ttSMLz-Zz}DxgOQUPO@K>&wVD)rrs{kU$WyW#QyA>YJ<&|v|K8v zsbVHNDPkfL0ohfc2(ZXNPU8+XHzI89(NsH_HYmj9jI{g9Yum0+ABef{Z&ox;K;-2M z?|M{3D3+4EqWVTaTBuKZ^gV4fcc3#KJfcJd)pn@Z3Kyv7KQI0thC7m-9!!+z<@ z9!M$-BuczpT`e^(i602m;KYhRB_py_)#-e*_B1pp81rj=-y)bB|G zMSW<{a<`It$$VXuXg3`kOCFwq*i=(c2|Z+L<%-9us3H^NZ3OTUhtVjFt6C@bD$-uy zK3AP@=vqMb-+6Io&Bc%=a_p*Mql)>@_tlHp{ODZ za#ukKl~(3Jo_q5L0)2;%p4L48#0ZW~KJa+6N{`~oT6665qXNi09bXgl+u7#QM{hMR zz3@k}In3juf^g;1doi<*D)frhaW1M{7D@>!^9=pn$HZg+pdxTW;Cb`fMTwXISS-Y2 z0W%)=i3c7NJsN5lpPgW_8`CGa2vy5C`+Z-AEo7FVss#cwJFd7B93#$j{i1-kj(!M3 zwaK7<0x4J?(Q4vAiU03J1c?fSdE^_zHoIc9tMyj3JNkUGFObWYXpYo$T`5Gxl=n8E zZ4+CnfGY_wr_W+fX#^C#zV!9ZE@;gVoC2^b85ljwEey_zs~H7UtFrfzYffP-)vS4%Q9Y-?+VlS=5P>#sQblbBuUV*=!4tkLoLgGtSx&efu1V?OVG z!D0bo2^I(Fr@23Q7N~6UtN{J$5oXlR!cv1;^WEDwEecjKcItae+U5O%MSXsr1MM^W z`x?|_%#aGRT%*<9oy4f)tv0ShN@7uoD@5@$GO5`UOM^aB_8e#1iI@I3vq;xRCAFnJ zw~5+L99TVj3qhH-sp^^%WoAU_+M@WPzILepBrh3h1u!M4u0DTekGfAk;~t-@?Pm4R zk><;P=N~uc-u{79m(^CV?cz&Pq-j%t;X`5#N;e{gxusgVXDc|Q*|uD7^!KNJL4q;< zhN>%l+a%7IIm-H9`uJzf%_|>;_C%|Kp9%eO#hqNcx-!_IjVh*U`(}rLrQf6d%pp9` zwpB%YTkf^qIi7j+=`Zco541Gn-VZYPkM-JLBv|YLyLu7FW<>V8&q1&l>XRcQF8lyJ z^TqT@f`2m48OU)MH0MpTAx+anIZSf?TN};YjoX%gC+ishCjG27BK^xYSb;*}gGLbI z_cr%_$bgUA(EBY(2b4r6D0_QG8+nISVTUp!X&4s$j=yhLP1LmE|Ld3&D}>k?I}7WRO5Vapo9? zPH=uppUL@!4ys^%%alw;@yMw&3gW<81l~&$98j+#Vlz=~;XdwZ)Qo#ssJiJ)#n^?c z)_4Ss`$hr&8ThB|$@>O;0)AZGbk;rvnGl0u~hsqk3N`)j8Xi z0ruEeS_wR^X-2|o5)}*T_n_ZWFzerR1LGO(or4FD>ND!TH7-QJ^yXz(l=aNpz@ELK zs*QSSBL@{q#11xFdz`{`Tzk&&%)#I!KiT)}Q;D(}+Bpdo$;eJn8C24o)hJ&diRM~q zJpaZO7H;0^$~B`Qlci}>hbnsoaD|=ftZy9`Re(WpPd$@wG*IzRB6(K=-xPz(q-;N^ zjsNZ!KCEzF>jtzR*bl-d#Wf^VNCrv3YV}BSFt4M~w4ccmbovwUEwOYW&$uNVm7A%%{Dn4JVCMxHvhuycmvn5-C z9pQWSB0tYw+bn(fQML){j5Vy}YY@ZV@&2aVMj}^w6R71IAo`vb2En37QXQ9nSy)(T zE?+p;%*@!1coycK6CZo`G)Bp7JG;%%Q)ip!e&z2qFaG7f@W>bvxJtb5Du%+|N-M^fHu#BVA*SHd}Y;Lqcc;kpu^ANoz=uP&Qohu6qW%&O}UllC^W%4@{<^mtlnV z6|-jg#%|o_?FZm%$D?)YWux=I36NMrGOwcG$>>^vPDU#MVr1ADJs>b0C3y#bZC2W! z>&jySvIMK?=padb0yX&g-*wiDy4e!gS(K~{~b^)4AqskBCRdy?|qCq373Q9<66 zQzB3=LL3=11fWXbo%Alt-c!|umNL^UE-y#_UL;Mt3T>q^{yWz+l_{;5yQ!)H&Id!x z?=0|P`d0QBMVX`1C){QPUCnTXxMd`i(77KJNg$)GfOekIUZYAA8DrEo-7n!}N_$oV zkXGw+VD+e)^VOISSiE&vgXF1paApK5D$2By6wv>It|xjZObCgyAQI#LN%q{mpfhC! zoSQvz{A~02ul|GP%-K&jufFu>%_}edsU`KJAH_X{i|V(5g1U0xV6(b*QsM#h)*z^| z2pv1<{+vBPAU%7Gn7DcUqNLvG`9f`yGo)UyyA(TjZ&(Tb8`*r#x**rleXFFlVS{LF5^aX_s%u^=*I%uj6Bg^qpEsS z6%YG}=s_ypJ5O&lE}*DkXCGexG*#`Z>kOMJf0IHsNh+8`(G7~60bnRDR>q+gaZ%NY zBoD#6D(TT1rTM7#E#>DurSoFb`W3k;D~stf$NHI0@;ya4qOzNItgckXJr;Y~s}LrT zXu&|cC{uyOnlXfWD0_Wwp}BGGBPS6w-lz?@$Hp?nFFTfSQi?MG$VvuKfW;WrUXr*y zV5OZcdT~^RD@_B(ebEycG}lh`DPkGLkqB-{0BNOJJ$S4+c=&j8=hn3{zK6Nv+nb&@ z-iEuaN_$~5Mb+KP$rM9kPG}@6^!YI}G^=6)E~=0vn<|qnd(G$D~Og)z1gcNFCn|RU5l;f_HLv&SLKFDYE!ugU4U?FUAFy(_C}? zw_`wM4Km6D-0!`o33hd=d(@Yqzw1{-3b~^ln3iA%WJM+A#;tDL{#ATEtpr`?9yjHKtN@p+onW~FadLYPcZZgYlRuqrm z0!5a`0j7j&6bP+aRhL1)%Wx+lfMkw;sfiD}PK?47bpl=XvBd`z@Sf^++%R0@n&7Pgd)b)He^Pb69venvPgA?O5@cF@0JlA ztS|jKUW;X^j51`~R7|RHB(k7qw}}ubL<1go?+H{x=X(BY|4@JPlNbIUDb|q)@qEmr zxdCw71WhK=k_yB*1uy{6pwDuht7|8u?nyuoSYlt0Ip%XzkqnU>fXc@Db@dscCJKmy z%BZtC%dFPbW_g7k$yI@60Htm0vTTNXxNKjQkw@{GO6v}l1=D4-A30TAxdtevqC!QI zN&S*LJF0Tl1IZ0^NJ7Q%_PK>-`G7xP;8=iVp?Udxe-S5q}vpzE1CSyl4b0>Ur&HPbF9^)u-MyluApL z{wm4FtZ2ku83ciy%3?J>YRKV_0gIhPaNmE_fpIV1Dqu19N_=LiicX@Tc6^>G)$C*J z8Htdru;p``6u)Fuhu37Q0?)k`T&erv%9w@N6YAGXI%FR#)=66x3Sg0W^jI{9#F36( zw0J%KlURgvy|{8v_JJx{&X(T3ds|?u?k}$IF#&6?LtW8SEESYf$62m)>NPRXT8Yd6 zW%c{69Xs7DEF5UAUOv}6aP}FgE<>?L-SztA^UeJ7fo65}utzx{{J z`)~hH{erC5)l27^Lu)6MAft~H`-C{p_Qr#>6y%njXbPCxXtW)%}F&?ZE0cE(<|RpAvQZc&mUlIcZjqL-}i`0Umc3>^F69>{*Y zjPGfcid#lU+OT3Pt55jP4=koJssGIdDS?=?dsXO`W_r907y_c>GHli7l{Xv!q%GY; zUZj^Hs45C&P9WK1fFttoD^g8dqEATz3N$0n8F)Y&(x7QXA#Tgyc{r}AkM$<%T;D#y z{3Nj0{>~1s&$;*JjCp`s3-@ewmvuad?1RPHXxG^^2T!JLW+ko#QWc$**mYAz>To=?hGHGpl zMvQg{s#M2u2EZwTEJaN<`|u{YumFV9BxB+=-GIXM4?C0???Nz4wls$g@42DB^K~C! zv6FpEL8*8kd?r14IpjN?n$K|re^C4ayqQ+wgn$Rc1JYyeU<@5M4l`YbDw4#i=9im$ zd(1LKz~pY}BQAYud2=0rr`);2TFQXI@k;x%SY?r_&lYP%DHHL zCr~K5u}%pV*@Ilq?VFe6@BmKgLn|`z_58fT-78lv!6E39Av`3C;Ob!oBYaP0ma!Oz zk37(v``M3F{qz_Qdb3e!+!pw9<=jfroEP=700e?gsEQ@*fI=d#=2X!$HaDjP8a9y1 z7;_V$K^|pp;o9-$(Ao+0zUUcq=JsZqt!+kzTu_ybdxw4{aTq8|2;9K#pwDsjuqtT) zA{0h*W~LP==ah+uq6uBoeS|TaaSIjJdnM^Gzqsfbh>WjTp(^QWrLBsoWn`uaMz%I? zX-=e)egVGUdF=)5Ye2EV;uT%n7k~ZtRVmOjr^30j6#~5-+Zxo^@o2ZFpRM! zIe^F-!Yw<@?}P?$-TH9 zzfrfhtp#x{&CYZ>Gh~v2TEK5-csTpfVl29r6u^jTk+0i{h1x$9|KA65ZJDa;>_@J@ ztt^&n+{c}b{JO3T4#j2@!D9Md$0j6PplXt2%C?2RV92=3t650-eGL-w@4RNo9P<95 z0-TDeN;j^2Xdx^j9eRI*Wiwcb z>i4_`C?s)P&lcp`1XQwDQDRKnuAED2!mOtJf<=d&ra#<(_O@E4s1~vgJJ3_9iY_dw zFL3415wRDZdH%PXm%jT)ZVA9{Zr)V|QVI8J1}1&YfW?D{PBb^Ke^Fx zY|(2q4T0o$GCth;KmrUOck0Yjs?4%Z_>n6gzw0E>%&dF?YfWoYGMmgkF`KCtz$wbO zmB>uSxqZ={^y?W9_WL2H0gIE4lh)zvlV7OQ+4p<=rhonYR1NBPou(RB8(ZP?iSf`Yy3y=z+kR0=%xb&aBbEgg zHF$k*R}@ypcL0{TH-vVmtP(`sxC%YmRAr@QYOt95C})~7;)szCv@fJMTTuA;TUT@~ z7}K#uSMftS8!XS5blpIlnCa_Hu5^|)&G;qpNRoL1## zcIRxfyu2#Y2V25@#Uv2v&orf6BU=_0W$!%tVz}qOzONxWot0Vj`bN*2U1A$kh<+G? zPo^S9B}kQ2fQkJ;fBoIIQBfo-Fj=y}Sq&Q_;opKzS0X<#SnT`2dSQA2d1o&KlP7%| zkCgL;FrkG@?2|LuHzf3u>ym)22*BYxL+qs=(D(0~|E_6=lfYsEeu1?Vjfn(v_71}A zV2lmy31U6jv%Ab_ol(Cc<1t8FVW;YO+5K~p_bnh3Z7cKs0M>8EAJ9obV6CL zkBVt||6m4jHb|(^531zf+>&e%2`+3V=iu0hhb;uPu+W@+{8#k*H-GXMqNC$a@H5!& zoz1%{qOf*UQn^=&Nx|xf7Lsh&&{K`}A}3O4Cvp6yK}Q8K;`eQ@QU0I@h$cCm1R#qvFjs7_e%z;;R9Mx5`mcRfL-5v>Nl;lm_4V{9O{t_bDadKopgR+zUh4=a%u-<7ui+NOR9AN zi=o1neJ@rSOn_Ebr+hIT5U*T8Rw>(xsxQC$+%V=y&f^@ccIkeyteEpR1hR{Zs|u|7 zIWrFl)Y#Km?Oj@2Rh5aaGP4jR%#FJmUt_0{&%EjfsGsi?H0rMTiE6tN6XUDru|UZ$;f`=a7>0u@bEF86j-Su26?4l-e|-!)hJO#7m$_R7(b zsa4;w`>RC5CMY1mwE{cB_6a~|8s)sI{+6p}Ch3MU!T>HRZuA4DP(x9TCUHZeLgEoV zn<>xamvI09AOJ~3K~xQ%`>yR5j-FKo1EEm5bf7tOXoGOeD{t;Nt8*B9&+_HqL3@$D$`?AIESDH0UAa)?8aCIDw6C`z!3KeFlxsq z%rvk4=+6{HA{3M~RC;ip`_k{auRVfHf+Oq+vk^Z&|623myRT>fx5j0xozPPvAmiEN z6I`_mntmj{$c$%DsSyy+XQgbtrx}X)69jTdGH}0clUNb3XMK;Ke%#8sG2^W>(7Ys$ z+OytP3A0Y;1Y*h0BwZ^5;VMNmjm^BT*NjWHb>5^(?pAh|y-HP`(@hXag@h4FBx(VV z?4`NIMfnTFv5uTLt3F-=&ewkQ=N?}p@aP^;){rCx`v>NUX~X+}4JA_BN(-}j4aV(v zOx2gaqPJFbM)%)#z+%J{3al$&VqfvM04&BHONJ5a0i%F_Ns4rRR?J3D09?<7jQvxX zAtA;h`%|r3Yc4ZZ@OmRaDWJ+|}d&;FK_n6X2|v=2V=+2-BXUT8je?;>x$+0O5koE zI^%PeqLM+!)z4#Jm>uQOPF!PFWaT5PWKAX!k}c))+Oo;CU!2Y;+oMei4HtO&mgH|I zSe#@pqo+WdL$B*nMn)ud241Q$1T)N zY~bf}y*Pc0$PmCy$@O%^EEcpsDv}s9vU=wA8!U3Lv!7vf?bldwmXQ|U=jfyC%`iU*l6w{z>b7dj33H33Y&eO50cK)fIZ0!Rqv!Xv<7l`ZRh+BpD2jc&4vHo8C!Rj*>zeGGRk3~6Sx-Q~9KDGE=Y<7TIUTGbQsZ7H_9@x$AARRv>t3**EF9uK zRLLKB=xGU|QAOlBPCW30`b*z?^ZQcB7#P~J%# z@;BHl{tkf8xD)8h8r={SOjjA#)F;V$UAy$Y0Au$2413XFdicT*gj^qVHBLllV&eJp!0}@0ZW2PHvZbubx>aF)Oez z4lMct(ze#insGzBKOD=Fl>Y3m{+F_e%u_{O6g!Xb)Kj1NH37eG|LOmtHXIdL27E|f zv#xV@S769svG$RsEsq0>B++>Dte({gyjqATlMbEeZDyufJAAVFm0$mT`RVg-|EM`} z=85LS=_i`EfBIKqTA-@^`j7uz^U=B2l(5q}WdzbW4>8+2l9}bRqi7*6N{lzFt9&Vl zNY6I5`{aX9HOG!Wq{Jr4oR81FURpOq^Hu8$_8ZXezGq_Q(yCLG?L(b3Dw+b3h!bY@ zK6)ure?w7<5(Eexl9kzqY2IM!*Nii~eIqxH%2jXH z8gNazfB^%VLL6O)(DpU8YE*4d8)0nFo9?5sSYO*G1$$F0a0O*YU)`%N)q!3bHF|;O z7Z+4w7j3D4I`^UB$f!1A1SDXA^4#jtN>B&R^|mr8(DXL9*5we@dlbX2y~*u>>aUX3 zRL__X4|xzWT?8Ryi*yj;S!VV>mA>ljVk4E*ftFraJJRe^?DmlLrG?vyO#W?4v5CRU zWjurX5dj-~CB@NwWR)0Bb<;L{4n_s8o2EJS;8Wt$LrFt1(LF99pb#^}_B+@eu-IK> z8_9n5a>6+p3dqI?wdC$@iZ;S}_F4f{jGg@`9Fj6_J>60PI(+9pS{c=_y)j>}7 z`9$EU46P}MQj}Eye^0@A2I>|%DloA_o1F;Or>(HX0u2U7lis6mLyBNfzkhi^N!6Rj z>953O{Fh3@GjgN=3!c%@lMf3la(#%UT>h9*3U^~uIY_6#B5arJO> z?9?MlLSDaouDN>2b346<0)URB=OR2GiXZy+>z4%<`vv+5{l`NmKt67Eu326|)M!C- z_;|+jcWSO(HKz_*G;4J7%u_|}{GHcdkWh!H*SlMq<#*@yRh>^&yBT@VOPsY7`SBn- z1(wpU8Cl3=l@K}HXnW|kt|7Irt^bJ{9ed3{vxa@j9y0*rBJM z`;F%0gHLF#t>TxNrg`(n|GxR~y_Y3SBkJWq0jlf2>fXv0EDD$eQ!GJc5k%@e>yo&v zeP9*8c4PL|+hb23fA%YyxeB9#1Q_Bs9!EFVy#3Q}Hy1y8OF9GjRpQ|C{y`b9<7KUR zRQ3v0xUDYMEg76=Vu(`@KCSt`BwTJ>{ZM0|%4af+#Kvq107=okh z!7`Q46jp*3^;gh$gvf&=yE&v*kdq^lacaG@=D<`#WhFBWO-mygP|5RLD{bazz)p&1 zY3go?qD9oEG;3FVZ~fqi|8~D%S0o_;r&JStH1(RCx0Z*mH4>GYW7TtEy6SGTa`0#w zHxPVO0cI#lR5fHEgo15s#(fQf#cF@<=fvvw9h<%H@BN;v^U!;=Ail0Rk5Wm?`d2i? zp?e(xm6?sL?v;I!nLB3%L%<~E@Mq>k59ti_B@mBUgQW+hx`6$7{)5^535M~Lg2kEw zmH~j{?RO4i&v0F?5my`#OL$ z90}U1>~rIeu4K2@X4?R@*i+XRGU~#`a_w&Xux!3LoEOtg(I5AUvQ&903 zv7?GLfoS+a_8v-(RQ1`T1iR{C-DPbrhW}jG7#pkhS~%q3kyFjefkUmJOr=O#i(r(b zY>s70TARlDuzjrZXd1W!QvW=ZHzh#AYn))qpL>7sdhBfkxzWR31D(3sGz1!QpY?;> z`sYq8)N>#wC+=&Zovzzz#dpT}yu9A}y7RS%k3FdKFA8ckc5JBn)?r=5ekzIQ;^!(r zpEj=V(`xaZF|l;tFP3$V3-1HdOn!ag*Zz^H&9A@ot!8QYfZ`FvZP){*Sz2JM|25*j z>aiWp+D9TNM!)2+VS$e)SXvy$`lJ|2-*VH1WMtYO@7Gdf!wQ4d9Vf!}6K;1s45RS> zQXG?^MbxJ44=v6Y4rFHhD^tnj2P1pLe=N+CnV)sDZ?6w=KVwl}DU~*Y9#jLNK#|#} zXG}8T8svOeS$sxFkkz;9o++$8JIHxQWhnX>^MI#;#;Kxon3O0E3IHwxIo?Y{?^S_G z5tcUSOcOmW$mjQ^>|d&uG-5leo**(onge$FuOh&S{bzbv{rL`Vp&OBH2J})rNJTtz z;pt!5R$msMWx7ixn2-)&zw=XN-$xu@KQmuF;2|ej(`Wilc4!ULnT&wDC3q^*^kW6{JG{GT5QnO$o->jma|(!{OB3)=MPtq7Y~s1q38+^1rM<5Gz+!&x6nEm& z+_POH)q&9i*ZoNcWO-3lEy!7Hkr8&*(F}p?`6JLIyQy9{^&=Au%m|zuJN-!MVQazS zdPhP$ufGI@)7*4*zk|t$az6v?hd4V^L1({!z9kZ$@0FWdY0CGcBR}x_oKZ3Reja84sAdVREDP6f^qQt(s8!4_L%|p1`3|t z>&p+9395x&48D9`%xIuJA*JiZFbOfPCqDga&DkeD-@N?dpEj32dP|~4TqAyyJxN9K z?rqO=TtM_=-XlEfD^DwCCXs7=q%Pl+^adS2_mz9s`Ix&srFL3>Nf(i z!e)OWus9ZcbgMueTT=UoG4{r5?zzetT({4`JFiX_nrY%5cFrTJzf^ijvXsZ3Dzfo| zu>}HAHm%8!m9(}Mpk+gi?9cu7f8|eVKVAIWKtl~Q@wH0?mIFiW7f6vSqZS}HlbXgP6E$+UTa#7z3CKzdY`B2dl6S_Ekgn={QUD@ z|F4zQeEG#c9t|xbCaVE+8`FhIl~yinQzMr`L$dr=oG zhD#`ldt=ORUD-;bTW{tGLFmv$O)~Ozma*=y8F41{n~bTZjW~+lHIE02@#d4Nqc!L& z-%kM+`#0Y^RITGoBNl$nJIuFK0O|Pbd%K|~t#%g4+6L;OjozOB(L=fUWXWyoy(?F!LlT82ovIJQO_>kx)Go=b^ zW}lGM|(R2>Xa(=Q-0)`?p11`y86Cah~?Y z9T2Vkmw!1RTvOSeT$2dpqw3^JT~@}dGCD8t!Ov6?n41+CU?0-(FYr=SSpD&U#p9SJ8hc>-tw zq_{cF8Vh-L*2*e)J9^IB!G0)=j>wD)@PwTa#Z~=fuqhBrvXZJQlrb77`wk^|z$g%u zrBP4~MumG5-Ir+EU)vX518>=zI_ad5Ar7umF*ZlOaB~E(fJojCah(Sqezy6_@BE=` zA+%GJPXV^ZU!e{()2K>?ZA9vw5f%hns3g|DvYht}qRYdv=mPgle-5_P)zm%Dd~9Gu zc+fbNMdp}MmEr8&UB50i%l6JjbNlAC7zKiGT2y1T8^gYr3QY8}<~i9fQ8rB?dFVA# zwT^oUF^Lg7TP0`HRJpqBD)uAXRA4Q_@tg83X0evk4czUl7fWJ zg%96oW@qO0tVF36ZHRX&8tE;wc7PWsW-}k{{N#?f+i@v|<3VXCk5xr+p zA`>i*gfHz6GS=X%sh>Cc=^4*-V0BH&4*ZHokRkkqC{_xvv`n-S&{)9Ytkyky^a_Y6 z)yGOy#)fkrx6;NNS<%bN;t*RS?csA@{N3ir@iWbf|NdVniGlhvNr>CGuCy&fy?9=y zGFn=u0*n3Dg9?PTO1zHEIw_)&1Yz3BI*sHc+wqf+G|zwi_nIGk`(HMfnCCjT7*);g z(zRf*)D|bMZM_%02jUqQu;0keV>?eVU-9^ZN<=e~4x2kvku7H>=f$?p&}O$9J;Q(d zJbBEQ=Kv=_%s$m%<<)u{aaKl^QiC~A=&o@_Qe{=6R^0cfSgEk}`lB<_eAR);zzm<{ z&9acC)IAO?jtc;KS@Cg4;S+(yNylmu;LAg~U&gV1|0!PES)=_NoHmOG#%DG~Svzl| z^2wzFnK5|Ga2j{((}2ag@wJGrOjyf4xUe5=D?3@eOvvnvdeC@tfHAY{0E|n^&Facw z4TQDo;i9Xu(Bnj9q5{dRu{+V{waZff zVr_@x?^Qhz4c})e)iec~XWChj^bVm43P`cEefHC4-(8!SFnI6^QiWx7hNy_8XYpqS ziviF(!AO9rvB69~(AYQVnYBY@^CvL>kKL4PL!kfJ=v5{c4Xh#fiO zN}|e1H>>;F6<9%5pIJads3GgVB;gt}I_G2~BnWn3O+AY0?`C$Rq}ENnhr)_#p2Wd| z-kN>gvYb`FRNAOa1`0?q24j9v@1uabnNhFei8D`1nU%l4aqU9$;Mr%JFMs0?nm1qm z%jVrT{@N7VdBlOB*jmVm_fHxsVh~ooURSlDP{=w}{I=5Qv+e&jCH95^NF?f#isfY9 zj09b%#t=;Lg_0`s(ERsQG;cNQ>o@fI*jDVi+Z23{_vm#7@b8$KsjvNf=`>(5eSZCZ z(F-g)mCwCW7p&K2WVaR|=waT@L8_h@;NPm2JVVALaqp}hYm{STNa%2%S*e>}Iv}5S z=k}Fm^&knx17_k#t$d@k)Ipa5N#ixG3rWQU4@q);*7>1^g&Be z?TG}Vd2TxXC}NSWk7{F=jJ=qjdi3N&iaV(4q8N{#1|UHD=Hn1*;(SBRWjs%gN8s8G zz&USi3r3+9O3^ZCwZTX#Z3SWDWnzLB?E7s&Ve8X#B`P)Tj*!^s=rMY*Nu+({cmAL` z|Fa+Ke>^kJE&c)pY@gj~m8<_4iYNO1zV25oS6KOr5?2I38Uc&-1CAtoT^VFw(ei}- zdH!qvP*wKt|JDB)0xtK=BDzPsH|VL`7Ox3*q9iD*Hnr}3&M4W&o+Uwd=*UT(W9%J$ zlKs6pvPOLy){Cujjk5Km2G=|vE6Q@d%w9>Gk^U?D8*8jqk~9GjW%??x*d_v!ArW&^ z$5j?P54Zh~*smFMw}F3o93$C)s^U^Vvji1=%1QoxS;RVvRAo=f!5K6e!#|wHd6ddf zyhTOH7~FMZ99F%lOSAcqW7_ZX>wdYB&#KpUa^`6ouxL{>EU}-PZ@wcQ%W{+cljPES z1{&8zaOrzlZw?$hE=O?(it5&8$$)(lusH4WD@VN!j$};+vbnwUG!7hgj(t)^KOtzy z*@rj^0$>mPwMY%Y<>vZr1xPqT4|r$zHO8(@Aj)4gmiFcgaKYWt0I#ag&+#=37Ne(5 z7cp?gVr>f;>s4>5FeDfzYdJ^qVgX9G$4v+(OHvJb78jNz zj&k_e0|6GVX%qszY=5J`V$2SN28nZKRjIU4MI-=67{;c|bFuouTIoE!wS(eRiajkT z>c%Usnhc$#4v39Ci5(MF9!mbos``OA|ETbKJc~kN0VJsS1pX*WyUEd|QtX`ivQ_!M zYkZ0*f)ZmWE?d}!krXH@^WV2_UTz-$)K>%!fB2pMyV<;Z)1S+n-KABJkXd4O*-~@& z)>VBJ!aIOPg5m^prD_mW{&4=$6Y8E<{+7U*aUnTqnscSfVlqCkmp8A7MhQT~HghkB zk3U$(q-aiNRGT=<044w>wo|>7o9lXiDws;rb!cg04(xu3;rz3H%#p%TJO@k9`f=1h zpZMO)kDGV$p(tv*ca=2(oE<%RwmJRa(|Shlz4gQ9&aKN@SCR-kclw|3UnFVxNsJgG)vuEXwf%=wj$OAK!ioWAn=?CS5+@WU9Z4mGBNTzWw4n8!d;Pv5@!IK2|2(b zi97dz(>me3(JC}{!6Mg}AeDO)T|AODsqR`=A6WxkTl5GICO^l-8pWsee_xHD@M~-U z@{DIv6BZOnMF2KbZ^p~O^5I$FM@abQoXZ3kyjDZwnT1)6%_*Nk45GG~#X?IhRp*#% zC>nAAa``8!z!Dq^AC+?{6M)4%jK*NKs=EQ;*5*d@^k;sfdHmV0HZOng-!wb-EJVdf z4O)cgK^83?1?>HjGO@tZ`2V!G<-}IW#9H`gybF#b-3)VAm)sxNG|d-&PllDPU0-9*lu%9w=+WXRIDN(VTwh>E-|lyO|lWaiH>!1RhmS zFxTlsfS+gmS^e*G-P**xx367Mj;G!m41GWAmaiR3n3y`6)rIzq>ALJG zf;N*02PZT%jGICAQg)jynN$ovf>b&7!4yE>hb!xCrP8-Mg`J3z4Nw{h z>t$eR8g#lWzfUBi6bwYggpnLkxk;fa0Hj6}Nokd_7Hj&K-bnRHBHp#Tt38d4Y0IVn z03ZNKL_t&yBiN+kt@*Z$5sE%YSC%{v5`h!IA~PUagImlvyhkO9e#Betwdp(<9I$`X z%R2|H@r0;$Bv(*Ir8hF~!CSLaUMN*CwGN=rxpz+>ZU`)TPO8Bo3<};mM}F|V6Kl|( zTq#rXhe{NqO?G#hdm0peTZ8FECx`Y|Y+-A^OHkIgS3~=9T;i+#Te|>LYoo^uALQUH z&g;-7jrTxll4q%a5Rjv`f^8s=e8Z9B52*^lGq`f$z2@QvZy0DX4&cbC=HVxvmvZU{ z@BUc5p00d1vIXauaoS zihV0|##U{%ltCiK77Z8*yk=L1a&zb&`0pd>Snb7@8P)o`q!dQ5;K*hc*2!k`cYgPO z(ukY)-}-@k3FjYH33dbDx_a=aX!_Wbk+1p;4V= zQ^jQJjb3XWf99*r1CM^XdHIDuRuVtQ5Um_MqIs`FR8TKOFZvy`f69kuQn#W{^I61h zB!5nxc{0?qchs*)CA#xD;s47Bj8I9==T^6Q)azCH8?*Ws$$>fvnru&3u)Dp(T!W~r z5o6S`d8sIl!x7cbXC8U#i+eTCd(cT&!JH|P`$DJ5G1dTJ>ioeppl-}3d}6RzZ{T_( zRf?!3I_Q7)zSmn));$8Xf8Ga+ZI~Aux))4$vmH|efdy!GS7(xdK*?a#_gVwi}GJcvi1zRX52^6Zn&OZhIel^ z+l;4xo`q0+;l>r8MYTt)^KSJyZ0eS2BGX)bxvYYO|BCHtx+`+C9B%m8|TWyoc1skL{ZWs;8w+1Vl*wKdSLn7U$fVa1Dg7N#(+h7s7P|; zvr4NqmW40|{QtZ_(f8W3cUAvan~-ZM<|7HHdOOAQ>Aq#$-5AB~{Ct2zihd|TA!TC+ z$x@Ase&#|A(nugv&IC9_-?KWZEhY-70pO(8x}wnv4*a+E%yX`7s`yeJ;QgprwqS8r zDvj5!oR68f29)W$l7^p((PZcOTl(Ora02QGz_39E;~tqL>a#9XR~n)#B;^Q}_Y@de zc)Cwop`q9yt7HH^x* zedChWJ^lKzQ)ipCBWLtn5tusv&X1bA>$l`X`1_O0%UoV*ZeF{nN=oi~RpLUm6#t{( zu=FmvuRrJRiT)VCu~ZqjMgc)Ut!c_6FnLdb&IE{6g|ahyF@YwPMFByosWGcDs$~d~ zxcW$iGQnR|8ROZt)k^njWrD^))7A7E1P%JY$_5SDoqjUA4{p*YISFY>G5yI04;^nV zU-UQxuC2sk<@4%3{VpvqH(sGz)@@wfT2S~lClGaQMYX+`bkxy~cs!~`2I=0j>RV5{ z8Q_Ey#(12s{?7l<{Pn;4r)u4BEV$PkJ@rVly>Yi$zjICT4bPnYIr23LEG8)G&}Vz^ zFaQ?EG4}?+VpQa4LHX6+{sXbJ-hJ(RVwtg4J0#e5Hq^c|b=*EBSgeyRZY@}EPCfJ~ zjUnMY)A!9>M=?R_=Tj`P`z$-SYg~*!AT-kf+PwfEg{JD&PGHUR9ceEcjuhn}{``nfl5UfE%c z1b}jL^Nv8FfNeNSFI}5pQQxA(DE10a-Pj-)aP7ry0GIZD^VzoG)p2#mVuwNJ z?5RTDCR1Grr5eq=z4?U@eXsxtd(QIt(5b7rony{TCxGo_oThp*dJ#dMDvPQv&8o8a zHwi4(calNkNCGp3VXEQKL)C>*+Z9PJ&MiG;g>6s?ekq`KWsZuNDkuVf28aa1B%`P} zIHwY#ToR~>pfBgFh6-lvRtLpFTjc!-j(Hwb9sw9oNJ%a!7~0v?0Bs3@?QAMgQ6*sa zUUT!>h34Aj527m6R?YLQ)PXYB%X~7xB0(c^@4O$j5}O7+)gokEi)pp4{uy|9M%avc ztPKzxkU)*~np=q)YAklqV3A(hyHZ9?)_?-?JVs^CuYb@713d3-=FzTSmv9d6yTy8o zJp#aJ=k1Q{eAyY>ia@2^mkd@LYTrDXB%64;;`6vqW+I+>9av!DfDYzs*eCy3-cWbb6#1DN9)+A3S$cJysRH`!TgeFdmNt;R;*ymEnw z(WSR}q)JxDjy=(lvY#gf>3v^4vL|~p0s9*;K%)ebg6=L*+w6&zMbhz8pZ|tL%)a|? z{|S&%XA)XEb|01ilz4+8e&=U2R1J)vq;vB1XI0N-7}e3G8Cs9(I%gh!;(5$;ryr_s zoU_U#lX*WNYWf)E7yHU_*EkIz$}1VSk%q2xD$p~5GCJjF6{B9=U;b>UFQ;5;XJgjj zEu3)$PTSuG9j?CL>N@KKFp`zC1u1H6bs<`NtCyS@IZV}Oj>{Srm>9;Gz#KYf()yeo zg+_v5u|N>P8UYyUau|IL!$#RK#w!rW^V%XtvCW`vGV`W|rShCJ*)vvjT{)ycicERV zk<6-B5!MLcAV;~gU3xJk3NbUMIcrkn+_U%r?@y+g3@kySMvLsykLD`DFBa&GZs@Y+ zm9gyXJx9T%LN@O3*3Z>}0RWxAI;+oBRdE7X>^ku_(?56=CsYrMqYhYE(+Gdw3aw5{ z#FSRKi~y#0k*tIIS(Mly^SdCxA*p+Ml(f&bqleNNco%4T^IiKluQRSYY=4vIHR7KA zsv%jGNU%ttK`?&x;(PA>$hlY<09V&k*aGSJ1|H5YdfyK1(>mZ7vQhPOHdu_AaI)b0GaVY*x3L| zqEJ;LJEf8-_QHY^S5!EloboTAiy_p9k3Jw&>GQ$vc!?Ne&e5J~xefpjPMCen9 zbwI1T_~DxZph|S??kf06%BqC97=uLOjXrWzb~W;7r&+&!)%{eeBrT|CxUP!aym3kI zOGQIqaeJd#JMut)l4PMoKY8i|#Qq)j0p4KlTff_^-@dMOU>ws-v#ZL2Qb!f=G#HP* z;c<%ZL%tXhBP#Vpy1%!%t8+HUx{7Kky`aZVKiYis-Ye<>mH>cL}rZh&NjNvyJF--R(H6(hpt7S-n`P-Z6Cy zG|qQ^lApI#&PqToXz|OdhZ@9sIK!;}=f3g}ns?v$Ui0>=-;wZER-9-*Q1WGKy^Nu1 zE0-0(n{D2bdD(Ys=Hp3OFw7&LF{!dx zZ|q*3tkjBr(O}WL#Gl;TApO$yXb?XbrNvtfWO{NFW#H4R1dgMsP6Bx43aSiKyNvAs zQXGdf?>4+seHA)}7OBhw1NSp3g$COQ~!K~UOcUx9CM$2px0IwoxJGxrjLNd07&_~-3OY=pdN`s z#enxgU6p<%1d=2m6hbrEH*C9Q8)S3s0L|~0Kl2hvpeX0O4hE;Wl#}WECHRQonj{tX z!oO4&6D;1kcBu@amcps#*qU0X(H52R9Rc{M2cOd4qUwi&pGNeAimBI-`}15bKr~fD zs)8uylKjHv(d(#D00@^vKc+xND9j@EfZaTNg@JKdlxb{@=h-zDxCkZez8@;@TL(?)cf$`C%JBVw#pt)MuRHgeiX^*FDj(WJusxb+;WWY<3%_xs8g z&YXSX`AoI7%Q&t?K9n(-P^z62+x*A;UE33wMq!Fi?`4&`2RO~kq+{&A$ZBi`Q-hy8 z?(p>tXZhRe=N-^C^ejTOB@J4=fzzp^$WR%;T3uwRI#+vQzuG2@Tt$AX1Z_CI~y*aRUthsgVqMRQfGF9cY zCbLk`=o@oz#4Ns*gKN!!14m0Ak-#Sz@=b=C-xcum=Ui9d#Agw7@%aEtXj;2X%*)9G zz1K8k{M5U$e8BXwtxZ)g$ixCpR{$6EzRb)v>nN~N>5Tm{%{q_U>4VwR>cwL#ZM{7? zv=?fy=xS6WB}Sf2f}zfJ4LO$yU~cTS^=@_uJQlFHpTq0D*XU=qv+5KS>;1wWsPB+* zD+}rwA|S!RsUpS5mF?~39)ccQ2u}piu%Q@vTw|T=mRK}*DjuG zZr;4)s&F>Xb5^k};X%`pmY%aR1bBZN*>|e@?OFS;Hu2?W(*=v&_iTHAR53(ICa9EI z9n5_R<%&REeN_ssP3==9Ch4OYNDtWC5&NpYBXQ8b-p*kgdG<*utgGMt3xlJq67xFx zpO2q@tU=I$V1*tdevYCh`;F|kss*AoZv=SqXaXvgryqVs6$f5(@x!-d5BZYPu549$ zGC+dwg)t>mBgL!;I{5MmGcC8uY`_j!yz-$cV22K$lKsVALvd|6*=-P+fFy&b;mTr_ zWJKt}gRBnWULPkH6SasV?v18Tf5+^%?PHx0Jyfvq^CHg$kk@w_Z zm~E)U66b1eUKK;00iZg8GatxWKl$9(wU4MuW|cohY(}c-_4t*jp!UTua!pf>kz3Oc z_Mk!+)$*dQn*E14gDt^g(qHM1WOPcU?3n&M=EnKl#;AzcU!~tPtB<|d)4iRpbh6Lr zS9fJ`K?#hcr;_YoUs>7OkxW)sX$@IgTvfGf6u;{Q$Mc9X(8sqLoubV?mgTS zEqitCXmjW06$|kwspr>q6Wu|9?8PuTK~?3~!C@~^+S^}suk6sq^RcXCz6Gk>8(Y5i z_L?(~KG!_=rQdBXe(U*DV6F)*p2e=Fk> zMEz$Ie^*9!#j|9eVP{U9ezZA$>T$(#*jU7E(3mLK(5KRmE4=mMpb?ui?)vlR0|ll| zRd~|mXABm*S%v!ri#Cw=b@1XL)xn1VO{pMsRgY@pF!J2@ zIlMKXZO{7ffgcTqMt9jX!5p9I|7N$=&v^m%d5@7)uYX|t0>wbi|^s!TsM4ou8+SXKp+T^iXMFe_qGH$ zxnQKqB^e&`7XOoi#X;ZEtym9b)UpGlliaA^t8XaB&`AeD+wjTi^e+~B8saZQe=^ia z-`e4pKAnzU*Ai4lXSY!;HGNUwFnUr6R2lJ-%B2QWwjt^(l5^@VY=<(Mi&xfY^!5AO z`si^U;|R;1YG#yOK5_anB}=H7Ge_*^^$Q9Fa~7P&K`gIEKbxuC?$x8=|E>g2*wZ7n zU`*C|-1XN$XM9b=cGS^yN5noxyk11%uW@qGt5!h5*dC zBwF8Qb}FJ3AhF4FWl~CzB&-&w)^zFTzMh!Fiz48`!_Bc%j|%W{4>zxT)ZDoCu@X?& zSU?%{SY+^_zFTQ^LqQ_;=k!CLGFZHGqq+Fe+h$-?qlUU?NAa}!!Rg_mQf`s2c~N6G zH>n!#C`p#UoM&+T@&`H(R5<`d*nGgIRAd9}`~E$*G7|vat^*-TKd?@J8GeKF!&>lJ zs5??^gl21ME&+a2_ks#K`0V1@w1Boa<@>9&)Y~UiER$BAfP;G^5vV}F>cXawk7;0-Ipyk~(0KiZ%Z3-j3!g9zFh`sNuJ7U2QI&d)<4Y zH)3P(dWMQp`>k*P`ip@MT$0I|A-qucU0ERI9Ly$hV;d5?d|Bw+e;y>aX2 z{N4Up?van{fiq)*o=aPXs;m4F1INf==qAK)niA-~4!%4g*8ak7GB|LwqB ziIicG;0e_mc@j~MrN$f-Ss7uJ({M_B?@V3e%H!Qz)x0*-eF(0}>`@)ixDQo3@5#BLikH1o zcc>av0l?5Rs-HnWo7vwZ;|xaqcZ0!N^&x!#I0zQw3=Dmq_j6lW@JX$}P4!v#1s12s z_}7)jv0yR5UG&qWS|6{s`mQU`{Le{=y=Hq8#a8;;sG39li*!?&bLgH=1sQ|04{Iv= zCjp1|X*gr8cs{FZ%#3rqGXLtsMUcbin0@@SSO0_h z-$v~2F90mI=QmjTQL*4!OqE3V$n<9dM$h52qNu9dO7^rPOUTCS8O6Sv1QzT4*FRhL z1r{U7BS@ACD*e-_pe_Z&V8?w#urJ7@lQ=5#)x!2`5c9oz&Fb2*=GaNV;+pR7#?=o6 z76mft(_UO^R#px*%d1Dkw%~mc@&Ysh5TP6s4D;MBefYM(e$K#atK|{A>Zp2Hy+m-9 zS9Ep{9zG@TN3cW^j(g#=5b|PQ&`-$EplW5WcFtmSpdI4?P?_!7){$PpfgsR6x$?wG zfsOGwfY{AD*OeF~NCq(IysK9@D2oWJXm)8-ixMo>ST%rpu~(Vg9H5;}I)Oz%rdMsM zZDC9K%#k7nHVHI4V?2`aQCCLoJS#uiQhoV(sUG$!fOSQ~@r(O@OKq+a9ycXX{a*KOOs%?%hNWn49 zaHJ|8B07o{Lg0!&q>V!MLqd3)rF8~TB9dan9th&Da0l|0uyE<^YoD zZhL)iiJlHa;l|aEetBTA8=Q2HNH57y|B`1+QvJclKGPgpJE`jg{C@P_Pn+vkKUADV zocHSg$KHDdS$17#nmfI#s?0K3-k}`4BS8`Xtq4ielti_t9;uDg8uQTa{V*|4V(95Fi|Z0tzVay-8m=@%?M9efBx`+?!b- zB$0}_46v#)?>+aNZPs4@TL1dj3x8p%^JQ7nN`63bCTUGJ_fXtOw!88w)9ma`+2^f0 z?-oUwwR8FWF^Png`>r*Jvl6aqGag;QUw&)z_g%gt>}h5V_A*q(HM)bvo|divM=PQC zJM>w8R^J{6OBn@Kt$f+S_hBibf^vKsK(gkP z+Z*gI!^pULqebfM)pUsT9QvNZXf@VA6A;*DvGIuO89uOv(f}-|UuvY?^5XMkF)$Vg zDVRE!MUFWHD9Xk_57OXP0yPU#$D3EC(u{J;HWl|PdSeHuiBg1YKJxKP$~IC%$$N-)a=+9J06yW}Q=iDE0m$6D92gYu zJTpQR6jd_yTI2w75Mq7PBGuF->RztHHfN;x{i>o%-J<(`ot3T;a`V0SwmYK%T2>7f zyI-}rx7yZa?oH^mK{BB3U{y|QMKc{59@gAN1lj0JM(qp5T&u=s-I-WJcJkZSb~mv2 zUfR`01U2v6(q2H7b)g-i@YCD(X$`YBFP%RwY7%RI&!G>b{r5g8$N$FFb7_YDTr)Sd z#sv%pM-=cl^4insrDwn7cA_3k>ozap*T%Tp{w(@X7LKp>#o$P83eLT$hDwxn`nAog zmQD(p00wHERQp@mHohnN(?y0S=%zA{qI}jfi}{`!A}nq8wzT1~XZ3m23=SyEM%E7+ zDRrVamH;T#HK(K+9G2tts~6L`ldlVK$wp=8(E?%sFhq#}i-@5B7Rdx#%~&1jFvkdL z;oMN$jiRdcdt589c=60T#;_;u?N~-;{r(zGtk>!7ji^^dz&OQUp&Nwm0{}D)xp2ekvOseQ*H|^j?EjjqN4F zD1i?sm<|?=JyMKYUYG?O4R9Fee;Zir<=h1jE$mHk=-NDsf?!UD0v|A5GFWs~SG}cR zDRcviImlhLV#pc4QtYMJV-^^%z#`*fEi}BfMzz45j#*@`yC6>h03ZNKL_t)-T)jN| zF6DI_cCeQZ)BzTqdfEXNa~-Aa@2Is@W-x=SMo_QkeE+mf_^nki~R4THNJiCgX!)^KAE2V%Rkh; z2|%k>)%soX*^S%ws(#U^=s#s!$_ zfiLUfX_^%IwGvqD?U;1&N&9ssu9@1Lw(K~l`Q_FxoH-)!S^}~694y*lQ@^h^V7OYa zxRRX;Kd&ndwbuZ)rB2_)fd71bBp`;@Au40w-1e5tVnnCS>2OL^0nVDvML8DDY@HRG zR~wg2t(3SIs*~BUD0B4G%2r&FcD~jW`ic$ISa9Kh)EykFF$j>?oUaP_)oDVd@#pho z>LfDb4wkZcPQ{#@+Nul;4xVM)s{VN~;!+VDK+FN*L862sqKWc6C^iD-=&57kGklNv zNJa~BFiZpw8EH8LMeic7KPaQAyf11=Fz(PBkV6&?kG^A?&VGqI$ob2SQ2XT=@pBXo2w3R}r_2RWlLHo9zY&b3^rV&{)WkAaF#-q>7!}!EH z)fdAEV0~dzmdm-p z*-{)`^(=1G7TSKX{cGbM!Q~bQx7df-el}*c4i@d+BWqa8EH=R+*+bo~TCQU_$U08;9c=o>-0>23SO9%G%IIq|xvv1Nj%6)cuE>`uV! zodEA{cCwt4=HELVzxi5zOELKrKB864` zTe%RM4t@OE>)(z6#19HCk44FBJ7U+Pd zeqc$5xn0B@QGq3#K_4$2Flq>F^#uY{%IdhtK&VN1|D;fRTeBAREtE(vh~kBF7XXcD zot&xuzBGh^hf+p;p@eT{B#fh8jDtg}6QK5ls6V#}J(b@{bYgy1;E`x#C=LQB0UA(H zxem=`m%R2302H1uYF4{j>1$N|M8r_QEk0RX!NnAt% zdQ_gLu*FgVg_dX8wRpa8gpJ+>m;Bg#9bQ zBDIK@FP>CwTL6S^jyQvglY_{GM7VBV)ihEAIX`ntEDnH_)Km$KDOk5)6jSP~mrVJ2 zbj?&6A6uuaDD*aZD$-Uc#JXeyhlbPUZ3mRqB(ukPC7Qlyx0Y#TP1vHcetR9kk62{R zQt7&H3ScgljN&3r!7LnE)*JTn7S!1*=d5iFnJfB7MvI@qfr&b{X7Hf%KB|72c6`+X zQXOEiOBqWBi=wMXopZy1&nmC%YuiK0g+=eg(#E!dMGq(lf);zLI`iFgD{NYPNBRB$ zbro3jAZqz+F>pn=(fgo@-s8ED!MuO zwL`^izl&-uq6*vJpSJA2HyyhFqv;3V{I_ZL##L_z6oCV;&Ae@3k^T9uY8D#+D1sO@ z-@nIP=QU@4$&zK%TiZNXf7|;X`&61(JC(ls)j!bcQm?}S+EE!$e=lBbHa+`J&Um3; z>XvN>()!K2(y;eEJ$w8O)yTF7Ydpxc(irr5fF5A6M#b;8*Lq#M4Yd0A>HJ+$;ASOs zzKRH6cK+UrS^V3$MguHn1+SHQpH&`|pBY~K+~1!7A#6yaHd^Kl-nqS+QPa9ImjKf3 z+oEBOj9Q%#kCzO>sREo$SL>iFmu9~@O#_<)h&*%Q=R0sD`%VrXZ_g#m{!BM#=xdW zc|}igun34Yah=(8dvVq?u#CCYG~_i>fVGm=n%6@i!`{tsc5{+T=ae-F@Kx_hYCU3X zi|;SjPwy;X@6BJkPVqfbbu4R|JkS#vVJTxmHzbp|4CQ%D;vxWX=yXyr1tcQD?nUc0 zpxeAHcRYd?8IC|XF4-n_iK4ZF#c(>a16zH#1dD1D)@BH2c!I<5HVreeT@%U^?{BCl%NT_caG;!Y}UYOXp6$nV$RhXLIds z**1WH%l17Fr1PiW)T~f{!oEL$>P=C=Y2^U56|ogWpOm#=|F%qj03xm*S(9+GJA^f| zW7(FouIPNdKwufjYXN7Q@NN~xDZp>XZ`E$RA|^O9r7 zHX)qAx@3<(_pN`QDNf=O$bK%THB-}R!zQDl0(guzd?A+?^tvz3hpoHrmTd;)(W8-U zh^X?T69VJ3Bcirxe)fj0&+ieop>_*L8mb(@6|#mjn}=pPHZ~<&hK(ZFh5eb_uw8Zz zryCoE^T%h%WRvNDQ9*{A03Z8}ag!)m+y3hEP~~1zV8k zYYu=M`@?HZ{LH8_#Bo$B(Qdl&0-x~9MXZvrev04%7n+E9&bu+1hN(v4a&0ZWR`*`0l($b8x%G9tAje zmRC1t!~;Jog2nD9&8p@hM@+gey;WW3Z}m+LBlFXM#h8?_@hPjTS(q2~h{IiKplVKQ zG>`HXMciR1aTK6O03O8Irq319(u?x~8ywz5irGw}pmvG4)WD***$A-M1cd?Usx#Nb zBNXW_3W@``0TQL`Nv6%IdUi%yl+CEM(G|#QagcjQRqx8>Gik%7or-STT3^=l4AZM{ zVKxI)^)>V!c77vi(dnre!I3ee#)-<>Kai!=MFVjI9N7>+TyXbALxqw@)>dsS%(>xN zRUb7#!}2R~ltM5<^WoC`0`T**ipKYOLt!bep@KR`-NQf{Lu_JTNJdai>xtB(DoBQL za420o^R}F|xPL|XZ`<=42pCazg*piu!vZ1!0SXlK4G5eu?qnf3+$hdxEhsB15FWHR z0s%owv>sY!JE|Z+Tcm6yuo%(Z@pT(@AmK#T)^x)-{WL(a)23GSK6amxqoz~@#Zr@E zm$=gH#WXZXU1?Hag*C-om@^(iQn7CRI<<&>r*(?GQ>}McOhp>FUK(>GFk>ViK6}QJGz?gT=@s z)xe^kR~@Vc|9Y#XEWxYaQt3FB&RT5(*~?$rX`E_~;GBRR#R&t{(IZtKU#iL;p= zqU@iUo7Ys2HZrj;T{!iY#&PY`76nlFul8yJ?ecrNh#7XxgyqjxZGSqZz6S^pt3?!V zXq$Jb&*F36{C8<~ZbtqS&w&m1Q%Ub7X|aCePT5@1Z5!(`e}5NHQ41I}gBuNCQ+t*M zaH#@57W9~;=kLIP6qWCP>{mq1fBI|xM)pO*U;~5c8f8N6S9TSs>20Q4f7`VEvF7o& zp%ib~ez)v1<9+GeQQ3{MWUMk-ErBCHyY!wO0K8+3RR>kBY1a9gHBzGPw(&?k>}Jn< zh*GOIu-Ic*q{A!LKn5mi~~M&HFm{%w6^)d09y0Og{S(aI{RC~;0?YJ-$K^8sZ_ znfa9q(fg%bwM-q{__{PUx>g1IfCMs#WTkNasmW+t1Z|GLIrbi%%uy|OjG?*?qV|Q< zIvE#eqzFa;oQ%2_^6nv5kE1#=256lS2)w~&_RUcTix!)+eQrI1qGk^fhMC#xra0Nx zubRd&dQsiHBFYoof5~MJj|mhF^!KL)DWxK@4PDUcmbe$u?2yeyWfUi?h`@1MmSHsI z+EPrwerEzUA_MhVh7YF>!3iSrgCnE)Pe2$>6%(fnl~d}%u_Hsmm@#kAwA3?8pe-rm zhyeo7;Vcq7;6UP@aI&OccXB%9Wl|zt@-tP05yODHIU_ zBMWj^hTQ1R!@hnkFcR~5_rp)Ah6aHJWuIoQ3mmeBSYyl&dx;hbS1z4S$KHHS0w`+f zvM`sfsRqs39snZu9C*xH4=97_ZGiyas>50Kx}Je_wc@VvNM=bTcb^9 zr)AC}Tal@|%^JyK@pU>5?G)7Gg- z!&ybbe%<=5nhT!m`(OJ5)dOm-5l(VP7?FjI)4P?m1872Z=UTRpQMYz*5{|q(6?`Y6 zTd3QzcE~88Dk6BX%5E4%`3Y1&D-}2@LfKCLRn~nXc7gv zd0ngw1B-{W_sDz#$YN9!gybw49G0>xWeb!~uvRHoXmzOX)Sp-#QEaQmvvfO?MIX-xdl4>Z%Vfov zm+Q9Tt2i?PK!{&7souYje)u=jYtMf*oj-lVRAT-8x1iR>GAfl&%kNmhk!bo5_R-GZ zl9hGc$StNgyXd*ic@;i)*)}82^40h;t9nnjxoFyjUN&!)^XZO=`GDR9|KS!UJ!SjJHz z52DR^)Xiz0rE#geE-#Q4uqxs@WDcOa4pDbFsrs5Vlba+vuB@dykYr;PB%|Sn$pKu>&r=LOE=QOM zH%<)TX>q|COy@poWI{sdr%*HurwS_S;0WzApui&BF{o@4hLz{0$Cb`|(SV2KpaEu~ zCE%#(zNOTNM=UA7tRl`KFu>cUz^Eso3z&xv>o@M4~PHh32cyG7}RzvHVL*K6!#doK&puMYxgH{VeV*(CZ zl#ryBELfqMKdJWir3XIvs|waod=G_3^*5}o1ynBqnIq}tAATwA*!`fgJg1MnsN^`X-26#H0r-GU%>5U8u0P1D%-JAm+3Ni;cEP32;yUWX$!Fg%(b{J^Kuw%zwD zlSj=Bdyw&<$0eCTGOGlVHg4XNCMGv2JM#Un{XgmImD943*j4N=*Mu@hts{Fn1a4$I zmaxIrGJttB@gY;Q)T+OITegxuVb~o}GE#!x!aB z9hD8R*ferYkkpoes|;rtpL{mFE3jB*fXe$>2`rYGq#nLrb_UmEwI9*o9A{`*A-j zD7|?Ki|A>vepqwp7R=6=f7KkT*0a*b2wO;2@!`imou2*XAFGaeaAeFtmgcB0t)1GW zJ$d!wY54_f*Kg8(=GiHwkt%zr)VBfRwl!P)teo#I4ol@1dfq?wuZ@-YgxHpQ9)2pV z-?UxNLO=%{0c{D&kyMsc_!C{gP*>j~TF=DX`2KCXXEAbaU6ZiQ#!b5wNJA6k9Bqfx zySF}19pAZ{aqQ*r^a6UT1%Y>Z4?L5=V!65XcjLgt>@Y*sE9ZfIPa62whO4SAq+UtY}OjY6U7a+ zFI(qETMS3JG%m4d+nrfAd~)>6kuSeb6bget)*Mm z8V$8JEloh{#p*<(i851%7tX~phjL$X3g@tcTC$wW0z_ow09+Jv4~>os?9gK?*NONP z8u&C|%kx<+D81UCSrJtqN^`TfBvzZw*QY0*G3xsg?*Ey2)`0b)R9>sj0-s?^Kz?e8Cwcn@L}Qf2jC zd4ScZ<5Z>y8u5ZrTA@u7v>-UaeXI7ebeL-QQGvyLA5k}Fi>zZ;#-S=IbQoO;6*cOC z+D{(s39`50*byP-(34|*dnrE)84F9ySrhCs0`1|-A|q1(KuaU^eC6zx2iD`6>b_Tu zjU9#|z!C4sd(;I{_)@iC0fZ1N8Xoa%ytRrU(}5}|b7H)XKGAI%w}&48wBB>}#Oo5M zVNBQyWaw#qv1R+gboS)ow0+Ng%4VHB@{&LtfR6PIh(Hl|+wS|)%^Mff?)~q#`q{zZ zOaava>8&fULHzsWAAUu^VE?^Oq&Hvrj({AQGcuG=63?A_GYt(5rK^|ErqR*0nvc1; zo2uEPZV~Yl_S>0bugOuO9wbzTOIy}9zA=uq-n4mes~)wb<5t?^wm^pVCfRA#M_OZd zHBujhjbLX`{zsHdFj(M|flRyS7mLCzbl0T#2P z6bVCDJyirt51yZ&u_iD|J!!N&Q4nx`Uh}SU1qTXRhu)LWE@M3$xks@oJSe9!ivB(U zdj)g{uy1uW=r}8D_fr{%y8UVMKY}{esGF;u{Y{6l1gG6BTsJ4P%lGBys7`K;FTp$P zH0yQMV6n?R)mtmn*#;f^+wb4%{aqctF@6z5vOT_};1%=7x(*?|W?dL-K(+6|YH9(( zHUFy#z8lY`M1YqXvHougz*USW-X5T&GvjFciISbiKK9#U8oc!ESJc;fcxwfan%~7p`X!MtKDpRwbwd@;cAcSbH@H%TwF?9cO6QT>$l0Cqg+q6 zGgSUpwWe3ec4!^$USMxEzpDU9(|6@`L~kM$=6(BQ0NU`?@bSrH$JnnW#P&Ip7rX#9+GhKSFG&3hBVG5{vapcrta&W65j zI4r}|Z|VRd%49%*zoUvMdXeh%%plmoK9DBYZWBWavV(k|fV%^9GQHMH00(kFQ758JWFPsH%q0ho1aJn1M02X-uuVjW|M5BM$#6&k z=80xhM_&{R?9MJDEYL(PFf;z~Bc~JxT6C*lL zon~a^mg#Y40zQGS%*ZcV{=8U6SQ6`u3=!*!nh8LL*@04QxZ%uO7x-}iGHZlI2ucf>Cgio6^+%@ll`7$ zG<5e)MO{qKed~`^dpx~$pMVmM;hEzAzrM6%?}J+VWHxslcvR1IdVp9t|kx3qck#vrG}$CYsO#@Bp=H zZ!RNuf6bfWjAO&0dRup!0)hw>!){F18`?Dki~G^MeR`!EEao0T`OfNt4 zWr-NEPXjEnZpflR5oIna5237gvl=J~hj=~g<{gJ}`2s&D3r9eU^GR$9023t%qZ0~B z0QP9ba{cN#1^C)*SvlU!1a;V`AF>w6R9aK?BoN)|l(qRM?t`whZQGuk=fHMw){rIT z+2l8RW)OR#y&&6ZqACh>q0UI)Dr)AvVZ4djjcEO=eoT9&B^ahJ@jVqcR{pFP*eicm zjE7}y%mU`Wd-O4a#DyWUZ!JM&+jaBj8;rE5i}b*sE|mZ=W9i@nAJ@5i^zaYcr=-=# z?851~6Q|psCEI}(fLuR+meabatzv7a Ephim6oj8U!=^Z-G*w%hD~HMaG5hfFEK z<)NXJmX_1vZGzFPqpE&U0SH%FH9ZDelo9kDaW=tH+PwW>y62In(lg)qL$N~^5E&$J z>b1`LeyPG+-&D?ggv|)vv2L-~vP;yGzgv~jNIW$}5NqeX4MeWEE5RaTi2rll4H$puTPA-Kt;3kGy>TSh{%b zSOs)fN+8)mpNF9e4zEzZ*b4}*#<=|ypYN%L+H~6T;$F>7{at=fxe!_prg9P3;aUMj z-x!T7nrNl6)=(EMgBG9Bp@dM3Q%*%+K=?%c-|AGpOo=H{;mvupNR;(Ys-i;CpTJWN8ljR3E zOQ~;Y)arNupNn&r-JpP8RAHI`FUxTgHK};6YMevne=!a7OhYDO5p6`Qj;-E+8Ao23 zJZPs`SZ7pX>S4qioLXbq_dnID0s;942H_IgnJhNqdQ0 zCub7%jDd;haPM;l5*FuOQ0KP)jL2q1;c3>&Hcf|t`+C362woVQ%LI%#R0c<4P5}Kj zSBj+a+ypeBaqHPC%20iOSQerQLgWZ6_gU7saDKYcf$McKUN`A`)v~5WmsEc!srFgj zDr13@pgLVqqDOMpK|)qur^{el%|$sjssTvylk~}d@u7$9ooVBKcbpC39V%HWS+wshw~uNz<>Cye=i_J zKuMW;vMv&AvKmaDH`--HFo!W=Utz}xK=8RttM`moSI4WznbTbNZEx)r4dz}MHw1og zbkClAL&7ga;itFlmotfjg;O@Qal6($S-n&5ypq;VZjyrzSX7{E`}eucw{{2iQouLwYXecrEXvk%9+<+d zz0dmxhN@{7$C_(MaHm7%)xUKmQ0Gp$62@t}!Dl>AWz1Mj{R?&SZSQY>j z=?lPI8X2#arTb~wA8N3=Is^0V>#cs?uqK97*Ug%t4$fFd)?1YzGud_iZUJp8Z`phI z2jmOk&vAwja3XsRAjd|WKK5FsYsTIavniMa%Sn3_AB(eQ9zWCrIx7X`$}z1yVF6Cs z0cWf^XWBS(M+`azUxw70;(^CLm5v{IF&%yVSrc;vAWM+Y=%^Vi#+Tp0TIhQ3aV=l} zn&XtT77*>*vi*SSS@C&bYYuSZ18GX8lmb_~8f;u?O@K5yM!E+BvpH^f}cE&dquwZ!%U^KN2$fI9@nh z7*%T_a#KLlGLKdRi6SkLf54t-Luz_!z$8RN07^V>2)|gy$_{=qRz}B+Cg4S1w`Ck0 zYUS2=GxX)GQcG>6)zX-VQSQa$z(`IqH3M@vp%$S>TmnVNTyv1m)#9KnBBxcYjyW&2 z12HIrwPUZb6EN7z^c*vF#L^j37RzhCMD-jQSN33dY$A=0pvqc_t#C`M0riKRrC#v5 z4kE^!x}b;%hB3}}(Xd0|c$Arkn5XeI8#K4nGO#A1ezaWAt2ywR2S?=u2x3X8)hpwdhX6$~;A|g$y5ikhvj9gQ6+>2Jmt3`+iC4o7Ti0K^tsA^vW~a#5#Tc zyPuOfrlQ8)GRHFK6>%`zgCaOqo%epHJydy{w!7CHH*H!oh}I4kBN&H7`)t~I*Td<+ z{U26akcXf6jodZ@z(<`Oj@P*phou0DgTuo@H6%LESOLli6`96d5H2zn7f09@f*?>Y2=boixjN?91$cAP_~qx=c@U!0p$};hq5F?W zfpz0n+O7Z!!lMn8#@C`qPP1%svg-z!vbsveU5!^ z>e~^-ZMjyq^_GpTw*=_|78{_hX*%ke#V%m6S0>_4vJ`&)KIId_0A4=w%m0;ntg;6Y#oBS# zL+Rwvmt}9J)^AHM{@_2!28fkF+Yf;sYR!###WfKeBjbyZUioVFsMYTp^WU_u&G+;M zi}r2!TodayWrb0E-EBMXNjvsElAiz0XVdwUhpo*V8GHG1M*TOoLq%V0%j&kRg^nO% zOTZ=eO)v&H3!$HG+P+`v&9iei(z)Yr=!`7uR_g)dFa&khO6mJpt+W5W8xU-&BzIX) zU4PsJn?3e$GtkkVS^Sv;i?*RVM04(Rpx&$ZuL9A>#;Io%;|8Ke!}~7wAzi=8q?o-I z9)K(sryMNxpR#1V+}4ITOZ8|Tq3HqY>(NXf+eU`6ZKyC-MAe`j=2jfV=2A0lMMswv z-2&KIk1aBm&bRlvN&_+u9vcgop94H_4y?5V)JCsiLoIb=T)!I~r#A7XD4hT{MVR^r z1PZBBBok}GG&7btyuD~tEoBgCRbhZPY7bRNe(Sn2mRtjejtmL+!uSr9v^!R;oG3%ZiKvoK({(YOG~f3|vwa?>+GfnR^LQ43CMe9yA7jBVei@yrK! zHCGlCF{L}yD4{WmQjGY@ZCZsO0e?d^$=X*=8HQd1km31>N+TgpwwpD7&!bOC$&;+6 zvg)*Aaq1QIuVgQ&bA0u=KU1Uma(ruJ?E@MCre>D5K5o5@ck?^i)^j(o7(tH;!d9$~ zD(hpJ-0ger7p?b|=l(qHJ@i32D~#>AQ-`(Q$kbuGZ{56>cJF^wlu-gAv5&DQ>n1m+ z?Ry`Ph|TE4RJwfbsO&nFU?}z6&-&>->E^Zbs#(MyF>lX(=W}WAp%0{^Z$2mB4)~%5 z^vLT^i%w6FVSWZ-su^Vq`A(b~GKPRTYHIf1_hI#GgaRo_tRm!q#br@Y`JS#|v9QzF zM6#PwOC22cRs+lF{HeoQPXx&j&!FxpGOh$57(?nf$+8ZOOlWPGeK!?FK_+aYD+1e` zg(wKWwZIzRzj5=X{ZXSH^4gpjCDDOZ_%(@ZfNa~prDr7VjrhA$2RIOyPgld z5(h2k3BJQ)pZG^<|GiJ9zxe$Bo{qoyg4JF-RX4!0>fm`!w=YeQTkh8gV&)P8w}Y~= z{%iz=%e`GbPX-u;&s*9O&MWB85;=n96XR7(Ow-mh|GiR>(rmOOa%*eW1gR`gt%mdj zD_pRUKsgk3`~cPxV+!A^0V+M4Oo8l>){bc$k@K0V)o{e0;0Ul*%|fEeSld;cTy%cu)P z5R42Xl=-sMs^&{J_I)de^&49qSTqn9smDfO4B_t7Mh;p=OeTDGYl5XNJPVcXpwroRXE4?meR=g zX@kto%~)TpL60&9cqj}=1rV)=PI57tDuP*Ew{>$D8>DRmttJv?(N&KG7KaXC77+rY z94)4G8@5Xx-5lX0Iv|lSGIszdWlDIqMut*R(}AJ1ZgN`D^wEj6UJo~~4Bgx<8zY1z zBGXD+fT&G0MbsN<&E!UXCx8#i5br_dGm$NmI^diDxcUh>tydD#Q09h)RTr~v{dUog zI4q#K^6W&Ftw&)}YYdDwMnd$^qNu$bfBs%&xU2{s%2l@vp$wDMODzi;SzL@f)Lf$U zP$Al07PWR76m%6u@0~gs^wZnb{g@SKK|5UlWO?wdyk3f9zOUaXmOOj^fW~d(mOUD? z)5l-cb85_5z@lzZnb3wK<^iNk$RFc_5z19z(XK7Q>mRQo?9C7dvU{`4=k%7l(ubb< zy>$4cZ>6y{lVUFb1_2T{z19}T0v|+fp-viDysdpm{p_KKJ|X%gLN|aW=8*3;;Lwni4=Db-zrD}N+b0+$+ zI|^hO$oSp=*xwU%l+5_?w_Z^FCmFWO=a0(K+I`@CzPJ0+$)hi+b_knCy(V?PP`${^ z0@QE-uU+Yf5(Ag{k#u!xOj4O50dpoUB$^A8|Z>!3a> zC7^W@HkdWFY4aXs{x6(Z-37FABGJ@d}WQsMuFeOMQ4gYwI`rp*>2I+hd8HQp_ksS z?n?wftg^XQlc#mn0vPj@ck$tvKLTs)LE5M^#dz$zs+Tm#uH@d)D+li5eCP(q?3wI5 z%L07Vv5$=9Rx@ZhAb<#42L<6n4}Cms-FdhAG!yi@cI8aEeC}8}{`QY8=*;+eox1|z zeSKnp2rO>iqX4-vpX_POf2htmvy*W))eol_j}rXW#<{uA3h=~d$cR4ii@zsP9RiI! z`@N4om45upm*vAD3I=d|_FI2!=cFsp_5zEYw!T!;c7{;27b*d}D{F^MF?DM+V(G7#lN$bvWgw!qd%6k#w2e&*uxlk_uNdslH`QV3>Nd8zQ?td!u+td+Jb=Xt zT(vv3HRI5GDBhdjHfgBMiBfjQYIMrzOOBuyV39*EOWDuQDq4%fM>HrlrGd_fJh(ZM zD2FMR#`t7M-WOQ2*GoKn6UbEdy%MSEHBik+Sr`ZoH#XDo7>D?_bo1H;fkkcyDk)+L zL}Y2$OwTtObn_x&Q#yMX04P{QsLA%3k%pJQM(rFha5z-Rs&h!IwyD2A&CJ|X|H2Ru zz{m-30RX)XiF(0#oOp0}+>5?Ve1;4o;8697^VBiYK4U?V{gC8WW=sZ`=Q5!o=77jt zj6>zzmh07>n0$Cy2Dbf0`wi9)YI~Now5Y57obSzb2E_%;iLhdKf%l2YG<)-!KyuBA zF8dI5i*%WVwXtf}&@>{TD{iWM7#H<`-rRWejssG=48e^u(ipW&K}pL?UHid;`EhTZ zYtrA7Gw^=6wbgkx9$=+NaQ*ESbu1G+eZLyW=vR9S0vuX1nosHmq03s+@5nk^P@#z6 zx;GcjLJ4lo$uI$|lG>@}J7g(w@(@xQ8k4f=o`dg`2+En`uS?wzhkbJWX6+4x4>;_0 zAAFzab?hyIKI}d22cSaT%p*^JMj&bHj=R&;^iF|Y(PdF7_N+OzCVV&Z`SP=0PG^t* zB(GgtPeCQKXDtDmKxJdywXVO`1y^LC#9FApU-@>6lzN}rLh9aH{#b@wtw{15%0l6) z$>GGA+Pw2ndi}+3D9g&;g0+BC849Ep=)pdiNCd!&YpSL>^$CO@dhp{CxMAF}ApmT$ z1PHj0mEE*uul@}sOD$iPm(vfw{aLA+8uhwAjf}4oU2JS@U7GS%7G$MyvTzg3 z`fBW~x4_{(P+(oVZdx^$qL7|DCMDWji&xA=IL1wjMRtS00yX6X-k{VfGmfe>fg#m! z(W7%(nLyS%U{_S}`B~L&a&IV26R6{}tdZ#PRt9GBdM{cCh$c9-DXrhQTkF+YMg8<( zvG%>08fGU4Yn%*UfNyF+**7+afSOp_-o`}?2g~rYtnBlqkSbvu{mz*Xs5^QMnSc{C z*T~vPEG(QiZwcXZRPLj0V6o(|*RqVw{gnL&_HrRcRywY7J5~=CnY%}y{LM7I{XqKG zm;aTRInB@G`;=!VOa}s^fCSEYGUqUf1aRG{19wxQ&E=RQ4SI!I&C1Pp^aeYx(Cnu`_qm+530@{UklrW4L$zmk7Os; zOm0@@ly*uM=x>Zy(>G}Z0!m+|>OWh}NV}ipd_Je3S@AY>HYuF(X z3n&{GPZQhc3ZPdku$8kvZuGlRb{fyBWnI={gww9Z@zgvmN`!&>y1ChFY4#?R)g{r~ z)GXc)1RB4Z%&^JP%Yu8vI2N?%7c!(Kx?=|4oI2h^gv>GkC`JyZnH$$7S1(|?Zey-P z#Mp4K;Lt^z41^aLTMl<3)XWpciCP|>11D_F)O4DkospA8%^me*{C#P`nzzRWr>;Ov zuu&1rbc|444N(IPT;p>H)Tz4lvSuuIw|tfxCs#f?2W#+2NQnm-C>W^svMV}WN*MbOSfJGY;9oN9SWb&656qF!p zUabXd0&a;+>bJ-QW=>mP>#8rwLKsyBOwS?V5erc1yCvLYDz9XocJ6yv6jL(cP!kD~ zTsVD1z4Es2yzkixua*|u{WQuIe?XYGeIAtV%syDO0K_(K*efoSamFwf+68pd+P-6)fY8i zWrl|RVop0fN~_*^F)!R3|51lWwEp^)Gg3(AIb+{q$HjQ?ERlg>6Nn<~7xtYtJO>{9 zc-pz|K?%x`nUz3JvX&SKs6cbV;lfenJF$(l&NzSe9XZd|AJxDg%m)LDMxO^P&QKHR zwz?E8Gvm{&}6O{O^$2;bzSUZz@|CTMPI>1m?m44 z^)Qvid5Hk=U9&f?h*g6F$lAGew>riPxes5kNjP^HKF%QR5zjnf?@UqHlr2LnE$DS&`;2Wy z;5lfhrbf%>)B-~5wW5oK7@bE->CLO2yaTDvOHed6 zVt(DwoUn)Rkyyv|0KT_U3rea7)$7QI)D1DG!K2&Ta8sm#tLmyijlYVL&zb|7SUo7m) zxw#u@a>MqtdE0)K3{X#c_S9jWkFNMEwlgS-y7#; zFE`A_zq)oldwXEIYy&tq{(rF8Wq7+8#G)oli>VR0;A+;e9kGfrMV-kKs_x89WOm%W zVQf&=f;&@XsLYAt-%=682^{d6w@_2`iH@jGxgkp@I6q~%Fv_e_11z>i#G<&ipaVu! z4Wq**H{;GT&j@f)M=0?O#4==jN79We7j$sSHUpSNcPSeg2e-Y-+JqPY#sq^${nQ*l zuAlnGwc_W`&E1lt8&Q26Cj@Sc-e*$l9L^XVdJh5ecn`pyO)qCv_eiGE8iEsLLmiTW zaEuGt137`H8q$l-vz(@mXZ^{t6N6E9#Yg*v%|aNCaFWB}D5FD2?c3N`4W=iMYKxWc zVceul>H;(2)KQSnGn9_DIan@A5{-G|ifsmCC9r4@vyy#k{e6Hr6eDpoq4Nj9iZ4-1-Fd1~0aXIXSo z@3BeXf$LGn#G1iDVO_+bVHujLrhf6?UeqA&N+^B-5j{iF!slbRpV2 zKO?)bea{1Fd}5ubqtFDoCK*EN-Ke{`diiuZbNnZ1|9wxUmwxc2G&-@)ga+1b(8T}& zP~`XB_u=%`tKUgG_dk;EefTNew|a20m;JDd`z4t2%Cmo#-hShmTDGtw_}I)`H?kL1 z2DJ%Ps(SC7t#nFXWS|&jYeD2SwXt3uq^ezs(*|RVgL)HFlII6!(}P#^7lc}=4D8&D zDDPzOvCknuCC9)4FxSp?AANmk!{$8_pV)QRBT|c%qF?mmLs9keSpj*RHozi1W^tr` z@RxrmswiV@St+BcV|U3GLv=+76#!b%)XQvjgkr4zhM^u`w?Xt!1B*w~byP~DZ>ozj z;h+bzAv-XBUO=nm`B^W}M`+p5001BWNklN6qUL3UL%)a50$N8;Y0B1&DCnn=%3W?M$kH4S88j%Xc#ecv#>$L+jj^J?sfl2NgO z)oKTe)@C5v1_x|$DKa~#<8rpxo-j)mE0;Z?XR5U+vR;jrF(m6_HcA;%;dB4A2c%TD zT-XH8Gs{ZRchY;#g-_Dc2{hV5hmTNvUs*a4cGwTFcVY9xFck-3<0^T6%iv;Do1u|u ziN1#Njrs{l(+4%OO%^oBLQ1Gh4;!dbe@lXR3v;fnj$$+POatMZtMt)iu4tD-TZF!# z_&ey~yO=LTqp+pV{M8>RIBUVfnDtepGV=RvPV&p2onR6^B=&}9BRFJ&H&)J}R$cfl zBNJkW;FG-i{GW@un}OI80%WN0TB(72QCD)0^-SQ8fDRe|V13p62S2y0C64K6m>{4F zE(!3tz+iu09^-trhTrJ(OW;6#Yc*%E5R%wuWRLM3ANtU*%dh*<_dcINe3^Y~F2c5~ zVHq4R&mP%iwcBt#2mRYXZsiiyv(6+IV3JI4-7kg-6npIcnUk+67;L7Y0<7Gt0>jz2 zHn7M(jo!2Iot7Z+bt@sPVsF-jvfjPVC4Z&{7At|w-W%F&MK7>e4q7%UKZBXYcVW3! z{z$_K>6%43vFtY?D_L9_=28jv#Vi{jZGj#i3$R=L&3=4x#m3s|<$9Bzidd`JnIvSDQeGt=(B{LID<6tg{B^cJSdua=(lU4uur# zhDPKdK(oTp5oJz7A47_+1I{qM*3`bLvkL&ka2d6!PX-(ig@XWPmGQ?};r^gzD1+kd zFvw^MKscCF&q73a7+0cMWE|Be(EB3}05~j@g8{Wddm_UI090Fo*w5Hn7u30tDJs?* z(~L}Pev7_UfP{a@nF>|gVl`@<5j|miaB}K-aEggm2VJ4(l=u#la5qZeqr6R_9_ROtRECe!YHk4hi}fsLG9E%s7blUvnFbQ(>5 zM@=VlN@UXZRI=vT?(o*APq8;$7_%}KCE8GCAaTx^Q{2OzoYp2xK| zHf-J{hn+plI5B4ID*`KI8ClmuLqp1-@#5gVb^S`3-myO&f9pjF4p6rjAPsw#UE<=v zd*!*Wrng@GZp|*%qP2#&YZrAkv}w#+e@ zm?8B{-ZFVT3px%Cd+Q#f*M^gZqVI;Sd(xV9(*gmNJt=_K%BR1*qp+W0OTr=4J$YtP z4w%n1Ad%n;Sw>}@se6M>gXI3~b?Xi1nZ%$y$N44@NXEyhsyb_nT07QZrp~#;owJYL zn=j6|0Fk=iMm<(@k98s%SQehKv#NzWr{i!m)cXC$x17Z{KmtZz=4Jf1725Y%w3hAMB0f?bI02_b! zrN7eNwVG?|IW3=OXe`~J$0{a`+Ac7~`GF5Z2@!tSjcex>{C@C5pH44+@AK)x*&|`}J4<4UY-M>~ zgui30n!IgIQQ}d{-g_-~?BNnHmg|fp13vt=-S=t^R7-y4f-;MirSkxDnZWTb0Cm4D zYJtlVmMVA?$%vrT+g@;=vIu~!){K?Doe^ryhUWS0hUv=n%Gj+2EXKgrBPMrzt3O{K zXl!hYm{|12>W&sXas#EuxZom5(jSnzLpSu2U8W9>C=AZoEJ}w9X=%xU7s_tqYh+Y7 zNa5w1NQ(hNQHG#z4i3p_;1ES*1z?aJodB?kWQWS8N0CcT@*Nnf8d&rLyNW_uJwO~> z!B5XoAJP1xSK*=}cKl9Cq60$~A%mvpKoQ3UgE2aa7|m6Cu7Yl)nngeG%qW@h<2{2T zqiGmW=z;=W^BBI1XR{qZ{72s{)~I?(4ja`p`dAXB zl)y$%f4ui$*qj&#f+qmW0}p&8&EC42j=lLK6Nm7o%mUf-vuR{_Oe&M~kmALD6%A`~ zUUd1rhaO80J^pD|>SG@{tu`+ZJDjQO`^gL6s5|WOo+cxsg`rU%zVUa<6cRA9zK-G0 z$0}4n&eb);!6_rk+V3um&@uikYq@lo_&aK(6Kgl7Bd>j583mk2=x2x=?A-ULL}~z| zI6l}W32V(-%^+F9nVDKFj)TRvy3IHjOof*kp!FMfXx{-`Ijb^QjQtIbc6iJ{p$lz5 zzmuKh{E`y!jHw#4FHnb;f}=U({165K&LQjP;@P(agn19+#50n`MxcW+x^d0ud}QLV z@dWo+o7f2ciYo2R0eMc#EcUq@xtGBI^uT{?!bhUdLqJ9Np2q;n~Us02x zCsK20!XFWw6`ha0?JWoZi)8OP*O1pYks`~Uit4Ojq0{x`#5&`|X^{fyWg~RYE|l3r zWA&IImf8BM-f^{HF@u2CweK~TIRI2LEG~HYBhg6 ztJP~~P*AiLsse7Y)@_We6v#ds+1bj*n5YtgC#cK>b=b$WufU%p)7D2HXEmyyQve8G z?~%v z=!60xnsW!Zd>=uqdmesD{^P69e?6T&{+eMs%2DLI4!V-+vQZ`p)Q(!PJLf>5w8IXg zpC~~iPi6#rtnyu)PT6Q1CB}n#|LV{!ME(3cD*!w`8A{FAP83X3vs$stScG7KYqn{)^cjhhqdjaV%jW(uh42dL<E@ z4dcOh&MR7MZ65@bygt+DnBEB2TSHjQi#h*B;pHuZCidV5va%_Q-Y0S9Mj9SlYe3w4 z2#rikNmUg(@cFYx^e548(H;cem%LXa*_8=7ZgLLhXYH_9K;#Bx)CH>#piXhwY9K`E z7#h|*NXat*qOT)!GOI@NO+#XSm`f6?OI?kC;-IjUtB&KhA%ar${ws}BEx=Pm-zr~y z75n(F87%5vM9bT)76Hc&KPNDsqjb&U^$3c1eP3@zF)m~TJ=JA zKk~_R_QdNF7aHgvN|(+bRR)sUW^50R62Oy;y0TH1&X}!HZRCQe+0ZcoJp`q=#*e=D zC!!0Z3Jq9D{Ue17zWtS!OQQ zm1WsDC!?%DK}gRE<;nN`%YK0>wsyl-6D;Zq7V9)Yi@Y096c9zMW5JZW6})vpHudPe zy^sTr+CR{mmC-j~d-3#JQqg3r02giNfq~72qNdkd=5`Q8YX#LPdZ1YWQ#thBd$9zI zw8n7?TwBo8#e7qzw$f(UAlDUo%D?_{GS%!xQ*Jo`2`k$zU6uo9smwOn5NTJ zW=@OWv2GBn;@;W!1PuX%F{e@_PAToU>*4gFPyUVq+u!`+zf7m4ylg%W>sAz7F>Yp5 zj}Eol{222=Ocx@_?(hnbYeDT$l(lshwRg<`K+~_ReA7;_$ULy`VK!Kx3sq5suVxe+ z`@qNlp+s!3cO_VI<6onfn_uk|PpH8?z+#-268ceTSMh8`2DWyV_?l+!>0E%iHR6HT zinAvV%WtopFU9#&{@l(GuQg_`293Qe0SiAyf4Tv7U&3>b_UtXe)#j4QW2MX7!DpHm z^5<#KEao%CzF=(adKqYnOn+`)-7+9P5M_;mACL8{iBFyyvU&qxHY)XTL}L|IS-zdd z#@4FFgw4%HU~y1CM#MMNOZg0GcZ66lE+tHe$c)hjk`5h&CZJ04{v2Tmuoy+e{R0W% z1VAbWaYQA|k&FyWw@g-5cpQeC`?G@Zer4{U2+<1?z_hTiAP`1TzuHzTEhtkVgM)Fw zF}=Mk6;UE=6jVdO5XBECn@pbQSwRsn`l_f4wAS#p0ysnfJPZhim$BjBQ46Gdy-ntD zQr{o<%v?a@q^6K@ymH~VoFTHhMlW$bIBI7jV+LOP2Gio=tfJCVf*f08EjZS0l2DKJ zdz{nrl5xa<$GD2t8c{O`^->Ab2DK=%8I20?)oT;XSQA_@YLYuyjsU_qM>H|6*UXsM z+?jJ#W<+X+F925yfb7`YD}lvcS;bzTEx%}aS!2Cx|NE2?L1e?8uMm1E-|qpdGOAqv zwFk8_I5W_eO`6wTsLn~f4R4Fm#^J>rS?d}O&VD&~%Qyf~$YtcK+9DfkoM!Kn*%&-K zl;U1I%jnV83?v;42VGH7X;;BDhXBEvAvs$Fo7C>W!BKSxSs>3SE7dF4K^Js(`yQgd zW^)wiA`qgq1|cD<)gd}d?aJhaty+&z8i{UGpTYZg?0YD^@5$fP{tgN*j~W6umT67t z*qhHu!GxH+ky1X z;pfslk9<-#8C!q-+WGY02Y*%T7m&Pb|0C*YM&_S0;M(QWY46=16yQGf&MQ*;J8<8V zqOT!Sf92wtG&ZqT>;~3dupp@O1GEq{c=72kq|?V`klhl3y`w;#+-v zTHge1j0(AwW@oOZp@ES!JT@UaNdSg*6g`gd56~Z2H)TRh>{-?)L2uX=h~)4+e7Ch0 z;u^O^#W(t))$=hv*h2i2N1pim>A}Z;E&cgt|3x~EkQbs+WWCjE*hFgfiL)d~?1S1_N?&V~n&)pRur|GQpVk(> zHtOPw3)TlabTvx-kmgwy%r5+2bJgm-HLJ{{(f?~8uk@*!V6hu`?Dd(|9)ha^i=@Gq z7Nl;;f=5;H=l0bDEH<->aai~X)$z!A0k~jD)Cnl#Ha0GUcI(E~OkJ@^M{%%eVy$0c zjbC3lI+1l^ks?lkV@BPOuEpWt3aNFjv^Oh<4p~Tu-zivR(IX&319)oUFrs8Z*KgdJ zrO!j)fyg<0`kCujGZZvLwO*hh)9ft92TvqJfb!V_<3V`6Hu@k!4a~v)Wj?; zrO`F((#@+El~KgeAj^WaREAaMcR2eaGUjrA0oUWyU=8Q&Ey{os>!#E7%SJ_o-o$r7 ziNYzzz=p&<06<_?#o(6JQGE~%$rp`Mt4tGP?AbxpKo$M%0H9D-jY?|{L5{LvA2`4x z8ze8=j2H(S2N+|g%&r@@`T3ioXfTc#8H`jI=@Jw+BYP`G`r4eWnw2c5M$KKYQe^86 zz#`v*6VBM4Jo<84B$M2r=$3TO%2|ord7m7wl4TZA&$1nZfia_QK@l7fWytD)S%(A- zm`igGP$-S)ULnpEt^loLp3@l!Eu!zGougL2AKk{4J-@M2k z1O*#ArHE}`e>!#SmGr{*{>1HqQ-V6Jse^#ZnaGZ#zqbsK85=>KN5jo;T=-5RsVl8z zKh&8^?8m_eKB`PF%E<(jpru|s_qJ5>08ES<>*?I7H^nsJp0R^F_C2inBI-g9Jn+%9 z|NalBnd_GoY`l5(f@J!m*Cv54J_8jPrj3*Y;^dNmr2R(X*$G(4Q9HU?N6lu!)L zEceyRaWfDxpnHbKN-*uhnIp>l)f63DsBxYO%Z?6!n2g2T+;vy`HX51$rPs%xvbc8L zCb2ippLr__JXB7nSw!|Cb&R<`9M3XK{jmkytTDN@jSBl%vIRmMD;#7PBb&A!P{yco z1U-;r3n`n85S}Xcg{`W%YW+9X9?SM?+=J|ngq9FXS<)GE_S74q=z4yoDh0@wvuvgu zUZj$tlc@2}V3ACzYK*D>H?>h^kG%B4?!ki#;UtC%v;2w* zBsX|i`8?*j1Ww-n(cenn`O3dehhO=&@7c;Rt{*cN&@41qy-y9hn9LK41r_1_2J=BQ6*t)eCx}-%fA5^zC%? zjb}AKmKiR9YMZ_8;%}5$(ER;Q>9ydfYc~Kaok142p93|jC7(;TmlxCYwgYLyrk(P~ zSubZ#y(!@%{0Q?ItbW-_QhdKO0`n0p&U>zSUjR;1{;iasFNAY3&`x9S#6u^9xN`OC88a1JED8gpg#4fhZYezYWL`mI5&SwwKTdLjEoKst6MT>)czgL z0+bIN^zk*5>DEoF`4e@huV0x!`nNHLP*8FLuPU^{QV1oh#3FoppV$P^%Y!Dmc)bx<7CUgwTw$Obi+>*%++Fs~koJX288@;VDpQ?9eZ zVPRiIU7@E>Y`7&XY-JZ)b{>*rd+o|O3Ebp9u}-K_mcWm<-`$xN~uty9TjFyY%kIDfLzre=U_FxVy zIarKZ_BPwx(_VL}Yvg`%iv#yf`1%qo+PN6QMhnqMY?o^7cSt<_{J1XscdVzQ>Fi5)2_|(L?eTBwVHQ z$P~F@D-dW!{0hG;DEauI5ggI{-@dKA#ET66AT(cu^t{!RN`_Lu6pPt+?;L(szLl|A ztUqW36e|(1peeVrM#{BX{ylsiDTGrKPvBpVyOi#K>{DX2Jpb*_$xcRww&|~SjOR*V zQTxq6R@Bi3O;?sD%E_WMsFArOU2;LwsRro?Zpbb`$mfz_(*Rt{=~=vB=WR@V=Ztr}^k zD6a?>Yb1@Pvv(&>%BpwEyMJTlKic1#&Q{G(DFQekbu}qmx#8~k_6CY?IxsX%w%$=V zo7Bqz;7sm5qD-v@J{+IM0UVJ@L~i1`Iz(N(0+9j!%_IUI5L&^xrU;k_FOgK#^o)vX zDsiO~gsZC}V9$1i5h(8wAT~NSp<-vi2@!6xhg^pUGWTMVzX4#qzQHrC<>oLzWABeB z6^k3^2d+8?D70OSx_J4cYZM*iz`%e5d~e>gzD)4!aiTHeIAb)W=GsJ~E?+t&Fu->p zD1hPNIyefbYYhz%wYQ8_fNZOqLAjOMpHa;hz?egT7x$<}*`o+J%<3SM0FMK146QXJ zM{Uh1w$b}1it}A2xy;;@YmCS~fCZY2>M10qK+wU0X;Bxaj3xp>^mbdEttckN`e{3e z+tyyp&x!{4-EPG@0gG}fO_XBS!AF%vK6mPkDr->CW^<&khusN7X+R#3Xf+;CzqQF} zGJgZLMdsdmLCFqyfI#(jG9H$NwCHXe+~xsW2ErY^Qnghd^Q^Nsch_M&gleU!b&B@v zHP1STWjhcniNIB~%LujF&L+)uUpMD23&Lsli8K7_{jd1WBD-PdsZn9++lNY~TFuPQ zN|c0pI1YB4erizJJpce807*naR47=~H4;&uAvoprn+UFqj9ZN|0y=NK`n?Pm12mR* z*PcPCQ%hG9(CD~M+Zt(POlqUlC78(Ylpr@^{W0n|pWAldr;Iqv2g`DV=#SOosrD`R zk~C%HyAFLwR8<@@>IBK4D9Y`0V%99|lu7DKY56laBpNDU(fYladLtAr3B;_M)_UbE zfZ9rSK4;#lL#y`4+}oyY`$b`eHFVy=VyPtQ2WfVM_3!MM*?K8k!PM7gfW?utWyjsh zT975Wc;@X2EY|jSS>ui4x?9gi?IO=a7D*16XBL~QT4;5nEKl`~#O#N3~0)@%D*l>HVvMQ|$h^5w{Q`93#? z-Bg~l0=XP!3!(=_UUgwnhwtZp#KOW!1jN4lNB?u8pRzqg?&*{3WjpPd z(JE=gPOTasaD03+UAcHte`hU_t&erPe0w3CKKc`_E85v$tInT#OP2-o@Hv=K%9LF> zmu}v?tiTHADE}saV2mO=?=POEjg9womV)YS)!MS|@P8I&XVj($J5Epsn+NNTU^l>q zJtUDKDKJ|dowcYbf?dr;8wY*k=W*s}Z2Je&*xC)U$ADbE8@~Vs+r5weQaW|?<@EOJ z&+4q>y%s1!cfx$M5CX$)NT-3mpE?GX(%72yVn4thAz1q1U-~c8zI&fc-}u7+A$!KN z6F`!Jzn9kJ8pg;xH*i5WkQfwLYCrMmW)XaH1{}ZRd7k*i-%CGv;V;s0#DWTTQMVvN zH~*$Gc~#cm9P-flF!8!faaWd|46>i`uAvcUBCI~djy7-KpC;CAl<#oi^xNs$l`}zF zcV?R<7bKt*wfx1oWATKlwMry=B5PYF03t{e*Q?v!%8Hqgk5lz?FXp0GV>V01V9WQ= zT#E(Z4zL(hb=_a98mir$U8)OWul=t1rGHER?x;I#2xQcpV{cDDhKX97cMBGyKpH^7 zMucV*^@}!))ueU>jm3CJ-H#fR&d-Xozh-KSYDtJ3VHBaKQQwENiJ?M3hsZ8ji~eQA zXy&rwpHU91aj&Au{Z>>A=m|PX^S*dL8-wT_#{N1|%h_qFM0M&LG8Um_Wa66UjC-V# zs0%eE)Z{V#649~7wm~V?p|`kT^)1&f8enq)9Visc6&VeT7+DOQejFu?9n@5ufr&K$ zL;&=h4kmu5K95jVp?WFfIIc)rM6TFCIC=ofFwh)a07-q%BH782v@kz!(HmDvV-ASo zQP&0#FnN4La-a`Vt1#luW7OD`<7W{mz-FnW8eYHR38GCF3a0+|Zs44TfC_SBYJH<$K|4pz+whH?b6lla+w(Pnmjjvgsg*#%biLz5~ zcJAbx+I#WcO+eRcKHKc(YJg>a*0x|=44DUeBIr{rv^ZAvC(|J1JTDi>WJGUiLv0+v z0OmUOtg^)}tzTuSy&eVyTLick<|S@Jc9B*U*boGS_-u%BU>5*MIK4RF+ziq7)5l)% zUS?z)hGicCRRk@YV6k*OI?rnaIEa)((cGY5kh)x1AS5$M%-@yt7Exz8QB;=|e_TC?V8*7s~Z z3t9WluuHkId%fRcZkyr0h}pQHe7Z7lQNyKj2zv23g_AXwGmi1aHL$3#g^Agvl zA@d%+WC=2wAF*V;k7#~jqYQfwG8Ud)G zvWoWI`$Rf;|3}idzWlGmB#4$9ZQoHX#Uh~6*o^sni5lOc-yuV8b)S~#FlAy3h}gd^ z(Go&|H?LhvQ`0-rrp)1uCHDYXj#~Mk<>? zuj6t7gS<`xXm%RNZrPWPsAdaTY;!)k36iXO%l8U0H80}yDI$(L_B@czoOn%iA7ycz z+S5ERx@Vg#f{laCI%W-6jfeGni#ZRVU^N&f!yZ)On4h4u+U-_s1!YrI?_sTAIHYl4 zh(t?471d&QSdm#L6C5pV>^T~CrWRc;AdK6du8OYtt|~=TT|XRn+oZ+a7we`(N_vmc zn)K(upb4LB+>tY`h;$HuA=}UUtbGNxVpQ2J`+UEC&ptF^C;#p^xVjzYksWb$$6!0G z#vv%zMQu$45D!rUA7jHYJ`TPYbZ`pzn-Z?gKj4MN@AjY75u2k{D(G3QHOjcAkRA6R zVGCtj&9MR?MvV%e-*?}K)4h*8CHg#T1%^e?519snm}GQOLk%_wl-|=vU&+q5BK0L$ z?CYyCi_V(p7!w~w2L%Cy(B6iI%t>Ef zHv2~tdO7Z+qVrLAj^hq64n@=a1qE2NpZT?+=TA;6kOYh40&O=`W?{4|9}EEi%i`Ql zOAFR^BlfMC5M#5D1tuHR@NeTXE1I`vKsxWY6+dY$XwKy9Vzn1*HoCmA5=6MltF;L5 z+LXMEW2~GeS_FscjwpREovx;Ut*Ogq0O57o*0?=rZ6+*N?z8Z5Y%AeUjB1Utu7B|} z|6J?-ufF&%1>6X14-6aQ$AoG^sK{r}pEpzIQlGM2l)uc+q2tx>9*Z3xg5z_P6YC)}iN~}Qs)P5WpGfE<&f3yf|>G>E-B{Sd3m6~I_?9U-(HaBlQ zkVYof${v#~J$L#o0qH{zeq0L1>?<nwMJ_&g7aQG%zg7Y?oTzLoLj@A z+Vj+Ae()3jB<(r$So-!?em|Xf`^T|;RGW=&Tee6G;L%+6IY5;eIk2_Jg02&gW(_Er z;bJnZXKVo)0t6YZoIjCX{^3_5I#LBxeVuea_j_!>av$aFqV>J3&I7Y;0T8X8(^}E+ zA9Fdq{eb3x5(LVp&YyZS3*QC6#IFpn7)ctQRXu0FSqah8>t zLGxMMhjCEcRCo=HVhIuRy_;ZBqgOi@tITMWA^x2Mi^dWl-3@#CJXhZ#vaD<0SLxw9{W znVoOTmWjTCW0KYLyoS@&%>YTU*vZ~S6KFDkrUXgv!=bb=2Phm>1`lTzGtDLl+80Jg z6jjt&0c=o5=VoLO#kuz$M{*iyF*1KEjgPNO*RGtG^FS0IBS5VcpXacNC=-r|DY1@P zeYxw|Hc3*ZxPP4k>wk&kjVSy)E06zp{LmSeLb|el#aB zFqx$TGI*|o#Yh#IVYhlJ1v&tSgTu-;bNQej6R#IN&}pTtp)8GUo>q<$Hl2j7!`3zj zg$=P*<>u$gw)vlJV9|ab;LU+=BU2Q#b!_3}`Ylqql%T@myjlQIyJIz1aj05P*T@LL z0MP!=wyC_U&Zn&EoGh!N?|1L3bPCG9XB*cN%?|rsu9KXN%)u`Dz)x*z8Eu z_?SYh1(Bk!tLD>t*b4kfM1oo@Z|R`^nKFzjbkyEgVctv0BSd}z*@Hia#uECe){>$3 z^w0-?CEcQJ(Zaj}aR3+ku;Tc?`rOw9VkbB3kkHD>W3PCS+yVopu#S!fNr<5|y?wvd zAoZDchMBkzy#s&!_x`7J;>Zi>h41}ox_t43kJ)WgB=#0fnlkx#1>-5s9SO1zGmXPs#|I7L2uCd$cy*wLomO z-fE1=VxRGBCVFG4$JTq8(yOF84oKxSYl^K$D-p_Vapd**(N1vQ#r(X*l+@G+_@XSJOzz3fB$PJ7MQWB7=Fx4@!H2{U;_ z@v@`PSj=|VdM#2j67SJ6CY}rtKtYkrWqJ#aD~*2riWNCqPsA}ry^J4TS3T`;*0ZBm z0fq`N8u%eI#wKQgAsj)wlG>r&vP%NA=}%f{I9*c?u`+qy3$nR!dh9p@+b-o#pC}@T zw2z=(E~371fCN~~>2`Z6oMjBLl*OpAM7#ko2H1w)rM^@|U52bU*lWu81CXo!j!TOw zEXQ~-{)-fsyVHd+#DFtaY%HRM%JzBFX8ukF(x_o58BQv?6(EHBx_arfoGm~fHJ|YG znOo{UbGF%OG;uhhbP8y|q0=VRFRZv2-oIL=EG=kV*hm<)!B59()RoC-F<^!J-yu@r zpDyRTJjml7n+{017s||5c7967q`aq|R{1^rrDwOMcN~=9#;LboRz%aNe3qSw3|p&n z)d0RcZ#WmW*G&{4Q=)PYM1LO>7y=GnC@w*qe(FFhE5X`bUNo8sFHxW8XH39B?1X@C zHZIvH$9Oi!c%|WMJLtNC#p=7u@v70D+*!2jga>w@-*{^a><@ts#)~yvf<>}H%J#Yn zWfRAi>ubgN@wsY(#c&?YIV|^#@0<+y>MC>1@0Q4zM~Q>UK!Az)WiJvy;%~#l<90@{ zIu^}QUR;_Ji$Djz2M73!6mkK8P7Sy9Re`3UEBVY9$lbFKwE^o(`^hXm`ji5JTvM4a z7b@WXup_d+s5Pq2d@#N8+@GblUwSWDqDa`CeSVLgg+dK62r%l@qq`M#fgct*;gF=CPu4K=IH_CHO3-VfOv@GgS~)xNIk1LJ%tL7N4EtCkvNcLLj2^qjmZ zh5gMt?oR6_H|cDGQcgQ0p4Bpd?dqrIgLojZ+`}2{xvG8c^!1(Ry)w)9y7tp8o2q4Ioe3?|uX$trqAiQZ$8WvXbw-&G`YU@(mg zkEh}B2}O!A6ugLdLFpvhg>wPd8&E?^T6DxlwyzsljJ$>@ac(MfiXBJ^-|kd zZsekVLJgdk)whTU7gSgz(Qi?UI65v+r)Iab8gaTO^d(WhaG;cF?3a3(6!#+2m9>q zS>N*TvZ%7l&(i~K*fQ61J`Nqx&%fc!Vni;fz1nftgX!YwBMAl0d>bo)#T@i0MyyEY zT2DSZ7|QGv>kD>(G9un1lc0#P3M_&;M~_qj8}wUJdkv`51~9DVw#=qg%!S(AHL`fC z-iIZ?>^3L)J#iQ`L~-2j3d*gXiyQEDaGMCe2QK95EiEYsL%kffkY`5u?doM3jN_ko zvNlRvClJuQ*GA@7->0CD*9eu--3I8c9c)=4unGnko52K$xMqk!RqO-omj$nEA6LjiEkB|nb<#oHGu~gzUXM_QZ!m_9>m$1@q;%480^E{2i}(+e*D+uh|JH;N+kCJqXz?Lo)aXrsa=e=T?VNvnaq#imdnZ6_n7j}@d z6hO<*MTaV!CN0UR-&Ll|18hzSW_+MKk{x01ojr9};KS6x`94zxk5|*t4IsoBgiuA$ zikoL%Ei<1lR?xKkXLXPl&B|*~rpk`^8enfQ$7fFbq&1+uqFoRYB3;2d2~Jza&*rRC zd9mgg7wiV3rjcQ@Aaw~AEf`!lvA&-zxWgD5Sd8ZfbX)eqf-!ujbOw|at{_s3Ol0eu z{!v?y$ll{2SHD&;8Ok*s+7V(h<=%SMt2bvz>;nY{qjR+5nOJ-H1?&&>9mrTe{?zYD z>Gcc$@BfglUpZ5>S8B-sHO}+^Z3=ut>6CwGJ{04MuphBZG%wJf;C&X`>{AvFzm@}>3w_ebG+P?RJbl1I)r%R{bNk4h%8wz&udEN_s7N2PA&byVlqxb8v z!_TL_0k5NG-}Eh~JqJD@s`pFJd`Wu@z!q~^f0Q=C7+ZT0{4-y8Ky82Uy$Hx7jEK(x zjhB`|k39Js>CKnFlg=D}HSOH@Xxek|F|}D*J2jnl?0rz*|J--}L*?^zIs0P1YQekE z9*8y_PQPrUElRQ|QxYkX;wFIL1`q_X&H#hi z_qBU^y8BE0{^y+g?t9<+zWy2uwNzR~VP^VU-n;MKbI$*q|M{OPo{mCPk<9VN2lM=fB$DiUVMRP`yi(_v880*aO4 zq>pIKt~oN_jSTLZ4kjhq&~-?A*Y_s z2*iO?7^5&2r63DP#Ti7O83!}2OWbm1+}*fdn{OD@TL3C+JTfw= zIcFGg&4qNzEr6Fq!u87+e0Cx|T}I!qL<1v2CKNm^5uAy#=1#Sx`dkKmWq?u|7e1Sz zy_VUdXUBR@YQQK)NH{oR|58cS&tGt5F~B0uW!L^UYBgRy{6tpS>{nUL_h@Cv{1XOL z!H?5A)Ko9^Q=fA_<5*budSgT9tj+xRn zq9RL6Vu+MKHGAn5K+gKky?1L(Yrw-Ep7vHV*%6>6(+{H!K$(PKDm6xAnFX%1M?~XX zRwTD{Z^m3*C#e42*6^G7}$Z)ogo96`00z2=z$O&AmUg zyuYyF6%D-v77-WOdPL&NzRQyiMWw#Huehf8H@)6928{GWb#t6xLy0aEZ}Hyn@Cgd8 z3-V}D?JHx!@;d-?hpQ4dgh5gOJDq>U(w5|S-fk5MdF{GyYE!bByj~* zL5-CqAjj7~g1K10!zwENpgt28CHg1#FhRwt_TBig9r)JYV5B`AI5UlOay?05_==pDd zS*<`jZn<6S`^aa0Lu1ndfHhr1>{IQ*g8dN6pxnziajB2RDvLQ~62%gLAu?DO@8PV1 z12kW8+g`1y`V~(+?=4wDS+(BYS`T5~*RGdQ%u{T$QB8_yPHaTA-$!^g!Co!|MB;}e zgrDE0|BAoIvsALepG_W_RKykKcdf04+V+InpW2|Wd`(~1%;VXIH%qf&j6z+=gB=eN zEO@lO5GqS#arryhPxV&tkX>K}QwQK7J4g^!Jzx_&2~cMZ+n#Cj2sW-Y2o^?9v_@O= zE3xUVQo(m;N?F5@mRY%GMxwbP2Ib6`55`otsO}lX(`1h)v_1%t0EpnqPa*=da5+s* z&KS3Qbyc&6u3bHsrZ#L5<&*$~fMk(!{>+>xT?DRVgXtZ#p}E)ecY>3#i5V9vxFJAC z&_aMfV8E%!=YZdA=x0vae|3=XVmgKv}I= z{0ihWV}VL#*0xI(t_zcgqnEPF;0Vxjbl`0SHSwFk{@Jzskueq6gZis z4gdfk07*naR9SmF;}O(!TO7;mS3zUz617zpOR(3HIgQ|}=aR?!i_hWeDnN`tl?6@4 z%7a3->`9GPQTR%_UC#Uu4=XE7aG|RF%_Rvdpm5r(Dp^&Zgi!B{eJ}eI_q8TiL_men zG5#!3Jq(JO^&&?_iKNk@Y=Dv`P7jWNr`Pwi?Vp;HEg!(3755&=mk3e-P`BOlF44)< zH{>?v+7%QRHz=@T-Ki?z#Lt~RA_^+|l;0U}vtB*|Ln)@JvUoO~KlP%6zPgR5R~8K{ z62MN*%%-cC&uji+*-ICdIP13!zgidKvetnr*A+pV-M*cP>Deu5=bqaWV;e4?Kb{sB zuBo>&*f?cozb%Loh~#93SQ*Nu^Lx^k9s4ARK{Zv+odjv{X`1UFAMCU5m?g(7K72_2 zl~Z3M`H>T~wF6jrZ+F^3AnZ}G>IRD#6N2R9FFmE_*#-J~9r!`_-WoPK#|}|}^L3T^ z^^sU4*W&qGpQDX|vBcS`i_O_HwWb<2yTFmt{A1|n#*LLU2|PYoa-T(6#=cp zNDwoNR)Ho6ZG1;BzY!Tn;+XlJ2ju7Pd-x-1$DTXWAAjtB6$QE)RpN7Zd)RV)N2j9} zms{WP_H^vUCzYT9Y@9m!w5ophKK#R)3CTI(bBRH0)^NuJX=tljye^TLTkn2Y<3dQX zV-FZ>M%4}xAY!ELx7?l%KmAC$W&b_t{OOl8oAS9QznFF(yjRSyV=q3Tp5|ybFp%Vy zAHO&{A$x*Ij`l#C?IWq^^NXRd%N}{m1kGED&Lg7&fW*lvTr{F`{4XL#ci#8CT8|f> zeN3?l%M~n#vxTZ_b9+?46)sF0SnLQ~-}jD>rsGGSOfNqDSjGG+L2yg8EqY{?Nc9+r z3iHNI+m+-eW@9F8uua%6mOSyk--4;A0+6#Mg5g&dt)fSg=a4JwC8+e|P>Cy==SzDr zkIsnr*w3sp0BkCOj{PuO0P28C)u!F#$L?K&8LN{S2T+aaCl?!O4=~HRTA=i27naW zD@NbumRTPapf$4IQXA7?T!S1v#U>qyq0-%W4WB0#F1*2Sv=!&C_Y{!}}u;6#rm6&%1YYZ}g$d!o7i z#&t$)RN_VbjzQD8m49bVa5m6+jZ$Y-HvXO98qiBHMWzv&iUO1-fa$l-N*duSJgYt5 zmTiZkLRFgS5212!`owdUA@qAHgWeo;6jjA4Q%%)yN*PSfw|dfUE@}+`h*X_LztU_} zGqSbPWC6(AzO(Co8dc%8o~2sFBEGK0c1E_lMu{t!2RWO{MW`RoD3&BD)L)6@z4zi- z1qiC8{ZH9opZnLe4bc~|anlaT#uLo2kLl4NW3B7qeE7|q-6P9hC@Zfs>CoKQRa|eC z3C?IF@Pt2L0cZ>fGfq)$Luqk2Kf@5(smD2GkD-MwJ)dbmU)B~B4&wXD_xXikLpE*O zlQwPM<>Fd1Sv48idiJG>QM{zJ*VvN0OO5&muq5LxmB`dlfJTsLwz5B1q?c&to;&mz zS1z7W007EBHNQk6sY+_rLPf_$-UHN@{BXt2ra#&+J1=nvf)T#MfTH!b30%5F{90zk zsu{zMX zLpz|WLgHW8cFz07E>YR45)f4dlD$hy5PsCeZp`0Gb=Aky;FtSVrFx$ak?oZbrs~DG zg!|w5QB~z0{mgIpJicZk2OIvpwROQ>$@(VAP&%Du}HDYOg zx7bpMJM#G??ny!sM=O!Od?Q`Gc&1{lNKDDrj@aof@BT3{$DVlf-)k&LMIm+`PY>JL zYv0(tm@nFY`-ADjKlMMPFaF7|N;s#YDpxek@PB0mE!6G#9Il^Y1+;b6o*&v{=vOR# zrvXA&J9P$wUR;2^%pfRjXBO?LgdXuVC>1LV32iSeC8cg34V`3hMtQt#@TWo40c6~hS#g-hTl!i znmQzd?WdqR0V+3$9;T*XKiC8-1VW4m;h-XlAj;B(Q&I!O@bG>bqLsB8qN0eB8KBgz z!KCVqGj5eftL}+Lr%K?Y=IjAv)fdV4a9xwrl0ViUV=`vTo(Rx@XJ%H~j38y)y)Oy? z%7KDjVKg@jUbt?mn(P^=u`W?nT|y4a`@D>gCe{g=Ad;=uzz^xCTIX?TnV-H)o#Xn#u~+I*(}i^0r{X=#V~d(0kR`8@C*|CrwOj zNG~7$rip-r+tM*@sqU3vvG`2(hI&;s$^@1GeIll&m$6zSsIFaevwyDmrIJ8!fBgF6 z`Q={da?Wc@AW>H7xzpCtP zwVn}ZZLRYla_IG1F;$HovdvAt|6clM03gRG*ZzB{HDPz)z&=F9|! zLS7$0qqPqzS&yp4T3hwig2ggJ-1S}Mxe9RY8!mcbBUuUkObXbjvyP10s2A_OT3Ebl zbI7vbPXK6UGTOKZ#%oMX8(2g@2C&#Q$FQLLX>DD=jcN&rG(;^35Nq!%H)Z%5?`P{u zG&!{}l8x2c4yBEowk1Xo;2RjKj=)V+tF#7@m|Nq4>9uiaeNQl0orK28qfg5xiKUaZ z3JhtLd(8awu=>{LcN|Qc=B=_D0c?PaD&f@POIxn9?e(=}QR$QYxWULdar8T4-1Pbp zpbo43dc}2KM-yz9 z0K9Fj%J?asR|uulXsy1_pve>a(ND&x6w@QProBMiLXz;@sl&NXzn5KV+Mn>lJR)KT z`uq;u_CVTw>wTL42e_~LB7O1tJQus~)wJW5JJbBGThkMd{C>LiuD9##KKJAo6wg2* zRbTS-CQ+kLz5KL*BZ>1ZJNBpNpZrp~?Tzm;2Gzwg>A7!z(bQx+opk%X@70_|VhyP6 z8@Jq&&YpN7ZQFHF6j06w-$NS#Vr@D?N+=@E*D>HLdtgaF7)X)zg;+e)D=~Y+H6~7NR?Xl&?BGvH|ffiGcM}op5DK! zw9$k43KOfrroQ*X|5-YC*Td=e|J6UzjMhvyE$E!tCzd|MV+o20u+k`I;0vcWZcd$* zRgJ%)qT770o^?@8uQ4XPg(4{3N~n0kOqv!oDtZ*33QBkea8V)DL$eLo5L>f7$L|51 z);k^nLnM5nNEPdw&#NoNt9lvpGJS1cI~wZRo_VcTto!$dgxmTAszV$S%LLER8`Y+@!k*-!3dZLj8Qf8{fu6qy0dg$ z#sW1yDgjF|xVk0#9Gf98P9sq6a&F}+)*MuKfE_O_RhGC$_~$p6Rp?5I2Hr*z0VIZl zijPEYsAN!`6a5nKZB93wI`^#1zbo%iU7G^*F~FXlyj zRo%%A8`IMD>uGe{L~0~PqiO;JcTJdKcGFg$?FOK?{=WdJL7kOcH^7hQqO3d8(l@2h z1}F??CVH!8SOyh%QIhXGBMJQsb&NKEb_hVCk>wWY7Er|K)Y42t(o3UaXq2XCnGutfbDy58vwYKN?Im8Btp_j zo44*xyY}CcPQ3VS^=*XOXhbvFiTLM7udhskSxQqs)eSpEw7I5(fb(8p(SuG?S*=!} zs>)bY+dOq~|3T4HFh+lYUT(cox@xb|1XY@|65=WnYN0o0g-p8jNth}08Em2k+8TJC z(0<=9@bqV(aW|b6_14g*K{ADXLv|am$o?a%J-212RrXg`RF%4V>2w9+3p*CF?E(jF zAiqzbRR)l%`jfyBg=J=4mLn%@qDss& zwF+%8IgA>weoFaxA2)=$sP|IWL^`}02e8CeQ2{m@YDcp3$l^!FxV+ag@Zxh}Vn6|- z%5mxZNd>}9uo$4cWWLD8Gq<+b-2r?hPUdqZwT&fou|w4g5^JZ9J(m`*Uv&DrU!Cvu ze$S-_KE$c!c2`u{+H>o@3Ht6upWi5TV(AaqxP)dEIj)s{P=t5z5mvJG^HNCk_X|+l z*0%liRaHA*j|Xs^sq?3fcF#Pn9Dd31U32Tc(ib#=f!GHzn7jcN`S(2s?@QnNk-wK- zeD1OIxljDxo=^_38SCitWP91&W_%JsssA?;zO|%`+ZKSy%*HKZ2_Z&^#>9p5C#>&s zWK5%f&Yd`HdtiXLs{Y*Ud65*Ba_+Q^9;0Fx0lxNQEcTipz9V731Ghhzp8w95)82z` zRt$wAE`l%g8xz;eZ$BWN1(H3JQybI9Ejw&f%!$M4!FT_dD!6DyAU1|h0TjQ z@TD{9(B1Da!M)M3bmZB`(!o34nqGe4@pSIYVe9jTaY9TxK4m?M!y{sKg;F$NaodiA z>CCAYtYTZHmy1|MU{Ol@!%|b;vUQK#E$d``u%=Z(>~Z-5zQOFj^3Uj0Ol(MRdC!lj zCF!ew_S;Hu#{9pCd231QJ_+5*=T{N!run_;NB-77R&we;{J;NmP58=MZ>(=NGYviQ z8K1zqaP7pZTej{t8;ff6()D!u*fVP5sUCl~nyRsP9H@nv^ZDXNIkgI_QSqy4E7xNn z6CV)j#$MqK5uD7*h#Aq5SdKQOsxlZol(t5QDOsOsNi&ZGvC&&y+^QLu^4+f)4RtLm zH9%!+t&eE_zI33?Ojh1Dl)I7e)i6?nUgu9y3#fwCh>hDak$u)bz=h3~ zvFr~4qcY&mX(vEsT>xEBP}R4n%Gyl@l&lpQCg={l7tm=!FH^4kWfH@hw}g?=XAc_~ zXBHwAR}@95j0}(JwPaprH}6!RADK63o~#*tCQv=;wYh%fqW*hhaY1WLRWC9+7#}J9 zUA?Ga3gb$qi|fJ>0Hl<8>8$9v2;j&3M5=T2Yf%N2$j1$nhVNkLCZ!0+T9}~1P`b%~ zU75~k$4(On2k045WhE61+D|r!>i~;wSzE3F<1aNs?Rf-r#?(Y_2E#J$`p%$9^r*x~ zrfSe?XWy+mAXto^2g}+*_nl6fxwv>ufKfBRn$<%^)9f^>#t zmm(+rFqCL9wM_)UDy7QO(e~OuwzdY$B1o%=U9?qe*J($~m*)U5KYRaf2ON4%5=OFi zhU&+hdOS-5{FT^JmAvr#kdTmzM>wbtg;}b@B(KT@UX8v~e6PkNP0yzJZTr&XhE4Kk zjQpXBP-EQqg|>plJ$LFkqFC4ji;?uRUNmrDK}HuAX8p|sUFWy*Ira0!!}`~NopLt>ust4T)A{w)Ln!z7(I1k;kp!4Lt#AT zJBHdNGZ!^>Bu1^YB!|kRMQOA9ZM9}a#Dv*OuWft#`sMTK)CpUYHGkFwC2M{{?-w)^ zXGO17!~{xibUI2Jzvn~0AdvH^-}z@oPcLTI+MQWU)fJbm6$kn~=2*dfRe3hU-T`>1 ziqCD{CH4`4e3(ttMsq-4?%h7NKK8GI=GBg>X1n&>nNFX4AzeIoLV(y@NST7`!Q`qN z7TNY)`|cKr5@Lt&HtJraK;dQf1-_7a<*ntRv1?@Jr!ccr7xeGa5kM@6}$r!p$L#X)z#XZDNOPOU?u)~X<&sI$ymM*~nHo)-Q*XX0VazCUi-8Yk)HNl-=Q+c&J_oTb>H191L09;p&0bf(Fn0Zk>t^KR8 zWbJQl1B>D%iy3AQg~bB6Kxxx~knD6NK4U7V#Si@uC|f2|$E>-& zH5BiZ00$&F&687yks>Ha(A-4n8Ba?$7X{W3fmvPYSP$QgYs!!T%1kiFL|=k3LY4~} z1OYI>hWS8a6V{(7$$o~)y3kHI9TRsjgTy>O`Vo!txu~E733~NUAw#{$_is?v8L$YD z0?eJ_+*(Z~`3<^hZZ`OP4{wU^GFd%c1X9QNk- zH~ziX#%+SLm=9Jza5-6HLMe7`SyQt9Jkw)`AJ?<$3lI@;0u;=B9-)m;|H2Psr85r4ar798zXQh*o@xN!NKBPs%rEC ziza^2=x=TTi<~p=$wW|`aWaDF)`ZS5vmmk2(7_0BLrv2dDJDc!nZi0S%(jw*iZfO6 zb)_VK`{sB5&2+~b-;*n&*mC;qp?Jbtp_iKx2(&g}!zJ*wawBcpY)Z1&e;qOxeJam& z8(8d>oX*!;>`et>8H7f?*>)T49te(beqww}&p6<_2^JeMky=JpS0vW<#)p0|F_-U4 zfBdWI$*=yA6eo$PJyJ z6fo)uCKYQ3)pTS;@e-_p5B|h|tMl=D|K`8X>iPI4*am0?Sf#J{aU06o07L=P#Em5E zmjI(dTP%{c=61}}M$(KvWBN3qsXqFdUoR30B@McVk7ysuDn!woK>m)m9dxCn`oY^gKXoWt7%DacwVXiWCfK^YU=WzL?`)(I8&R@*Ryt zxM|Ltj3yV`FhJR1MeWD4{uX1kXH)qV8w5Z&F=4!I8e<6+sd%XxCP9-KqYBjBWksB*nXXfu#} z!^SNpW;3->ua9|?7|s}2&OLEh)m-mJ)hLof67``v6a%SqP}~5Dwj+83wW>;$!;9NR zEVy>om8xn^*5&Qh`0VBx=y4``ofR1suU*w(ZUGi8b5_j-Yo#O>gK7CpsF0|*oj-L% zYLM!yaJpZ1OgUh0Bz^o|&0u?f8?Oz=72wg_n8CYZS*)tw0E_v(_Tl#OsMl3g5NjSU zYz0Y#$eb!DE@pp0GsGsT-`1`#=zTTUnXAG!S|w=>c-JVfszff4uBq@yyFvuq4~iVt{)jc>*x54=k?3E;^X6 z-cf*Icc4M9i~Vc>(7=1H!slHP)kOnMrkrg4!=6;okQ=_p_ev?8;1N@;ha`ifCh#q? z)IINBl;BOGcw!6LLj*Gy85rKuo>AHxu3R+KJ$EUnguV)B5oq$wExYevQ9+OI&$7qQ z_KPJ~NV4%`_H9L@ieOnp)DX+!%ci(%VQ{c%Jo*zO% zqW4`rD+O+7e^hL^M|=uNLycq-d#0l*QS?p1UXU8{%>^-5xK66;j1*8JG0*M`CD>BX z&a0xuxfMY2=NIu%wcqPtk@HI>6nZXfC#&XGP_=gduP0b6zo>05`lyI~hu)mt_mRJ= zd3}$4?l(mPWlj0P?}cJ&DK-?XII8M+{DlCVbOyZ2V>S)8MV!}q6*kx~8MsT(Yc*}! zdP};d@n$y)n_EwSHTO{2S7v+NY&Faxs?+QTRREV@D{Yj5uYtP_X=&+3TD*3#`mRBq zN#WnQU+g`}YRa)XSFX-pKUbX3P3cW<`*6B);beO18-JQvOjXj<+HRz5>f>q(Z)TBT z2pJ2c0P;-vACaB!`;ot&9{JOMoxb|{k5%J%hK5b8_2l!G2rn1U0%pyYM$Mfc`j3g9 zBAc0kp;ILRWaZpH5@-kpJ@mexN?-rt@1&DQpE9PI?2G%V zuofs2WaF7?{cABz=}Sy-Q<^1yzge+ADvdQYVS5k}QwH#B_Krg%j+x-r7inH9K%m9- z#xgTNYPKrkGrpr_X_YLwR}B`~^kg*HG`UZs?Et+lV9|KE)sM{#3fXZKp7>gNw*UvD z6O-xch11F?4kas<*Lpi@LAwWk;W@*o75(5I-e628&p2GvaMS$N-^F?IsL&F3K$V>rNMx-r}Y z9rQ<$O$3mu8aPI#?xGI0s-93v5!-O!YBLchtUnQMxR1nO8K`FRnKzcM8P#=SMz3S9 z-~<_TO;02TKWMlDxf3XhG7e;;)&tJqg>x^v8l3GZiHktPf>JwTdj;SvU_CTq6<9Z@ zZUyW=T|~lid$(6(nw7=;j@+PZ|B|as@q##~Wwx$Y(AwO6jq|(~Sd6!4dR;GjkU^2r zYWEy`QyLi_OGlo2%o7U^(Q4VsmZRZ8N7+l3DHYl2Q~^mv(e=+71T03yz=KwEdOYt@ zso`31ZNd@iZ*^gv2$CX@jA~T<9QOwFtPcqpn^$TY=#ofmZpPDx>J@(RH82w?yI~hdAQ; zTK};>D@*G6Ofav8<)F$FUnHMM>NNXNGiAK5FDnAoUV&s(8Z%wBxVMI%X-le*F*uzqf-J$(RB} z_U`c)pHRhHy;CFs)bEQj^0d?<5o)845~?0HUVXv5MnRO(y)|of;fj0-?F;zE7_&oy z6ZVR+AWVfg)+v|~IRIoqLZB+A09C^Dlwe1rnNGg+lqybtX~1IaLpdb_$Nb-2_kC}= z|Ls4VKKlp1qza4W51i`mql%0LC77vJ zU$@HOz&}NTGMEL?iqo`jW|z%pFj{B-9S^22f9lt4lt$t6EJ0&&h55J$CM%y-qwG7v zq8bTcfA0_f-E`YM?@S;2<^M9BKl5@1zr?f)Hu_xd ztmMgT*1-BjVmekJV$3Sh;60edYonhv(lY@TxqifxHqGx5#aC@tOAG0gl3muGmf!35 zkinurpi%ej8j3h0Z$ke!-=|e?p(Ugu0avvkRQo@Jx$--TK1MsTCRoI%xx9`6TqBX? zdo9OgoN#A#<$dV;Od#{sRu>#@W;6{ZfHkm7%#=?$IZBUanGzF?v{2idQxInWnN`6yvR%BG^ z<;W*6XTj^6$Cq{Fem^l*2XR)uEv5% z4J}p%#T-81kbCC!$}Vfr>r$GUoK4pkE~zKPKC5cjC2*utIX(rrw5((dZ8dc$n*#>D z6SY!X5tP|(S{B_i(p)EpmpMbRu&gsw2iB46nF3s*q&hmDE?qdKdjw#@-`}!zuik$R zg+7UetcV_=V22(u&FHf#(}qpkMNg%th#p5#T30NvFs0T>tqc3CtY~pQR9T^C^X6ij z-ncC-Ts^PELR68;HSS9jZP^h$!D8|3S~pT@G<)rr9^Y3pfMo#RJm*b7YGvU@&sX^+ z6~N)lkcHf_=MFXN)87+kr%r8Yxkv|#0n~FP&d-%yX7~BZYhU!8RaLx-E@Gh26n#Z2 z^*~brjaMRY9#wBzMMcbkcVWvEiWRd8*SiP0SHQqxR8w^wzs6)a}9 zLiG&n{ZTcxo{s1fQPRtkLjnyxC)a{|do6+LGFkB=Sz<}8Xj7=KY8O~s%cu1Oi%~uH zr`(pb>0`6YUy(QiEZXRzC8^d5Eau+U#?FY!Ri~o>Xvf|=m5d``r1!KPEc#~@J%f#v z(O;qP&1~2rMOFew%?TbFO`EswQl$?cbN1v5#{O`I0KiMZ&l+G+d!hzl1@YD2rQX@4 z8)<50HtpPVmjpu2oq4Gi=w^DmAsHL}Ffo%xCni)$p{J5$9xM{7koZ7AG&bFUkBy5V zkw6uTwN^#)##Q-z&boS>mTuUrKh1BYYCzCvdIy%2FyE=PptiF0?VmmVT)My<;g;E_ zJz>cpRjs}eM2}yV$wT)ctUve2tT~3ZpMj=G4{{qo3r0Z^FWI;q`#)QMV_0ZaV&sZM z;rL9`Oi=O)pScQfFwKLqYQmmk&FLeP?d*|AYM$F}8)cN%VC+zlX3T|+>_Q2e^JFvk zs0xNo!N5yf#7_ad#mK8TE!jSq-U5O++tYn-|44f2`LCttpZtO)mIH`&jP6^Fd$PUN z?a!*6V|bnOGA?lUV}Iut)47v}(;xok|B~4R{GJ3l)LVLg7XlQyFD2eVREU-kVmIO% zlI4g@VKZS2>@|_ z7Q@;M%n;seJFix7s~8gQ$h*$=s|Sl@U_E=AAKL3#S?mQCi;4um1*5|7U&`({0i2R$ zJI50#RF9Y7Ld*}khHb@lzWfJ|Sm}P2E3td+ceKl2}=9HUwr8`CbYFQei zohon;1p;x1q~>VmZ2{!f-=l_U`UtORga(yPeh2V^)n4%GK0)#s1o7yK|m)!GlJ4k ztK>7er=XeQ#PX61TVH3~GuNidXedNBL0hkl*CRM+1B(&hsAnpuWfsjhHegBjDKc7X z1;Wi>wwbN-AcHCB8`0hSuqTb{d;2Hs3|8R)PXL<|N`*puNAIo0Un;iE}nSf47_WTQC*x|)ErNA^1? z2Hh0Y#%AcX&i=A8t6FA1wSU=%>}ir^VDaQ( zfkPZTl|{~$fkmp0fW>M?U0ijhjd}G!eaL<->jjH(o$=qusOM)n%y40VFI6I^`AAF# z`({-M?oA?Fv0k2;k8Ezb%+k-wU~y*5GG=OVK|#*e9s30&Ny_m(A?6}G z8^TpBU@?wPZT%X6k?*1kq{Ph1O1kC18+FMjKvKPn=a~}_5hplc#0IklR8!)9qirCD zz5^TuBBwWqK?7}<^8-+|>NDqjH7zY%RU80=06#(SytII#x=~pX^XYV~`l2yS1iG#& zd-41U^#s$Cmbpez0VqI4jbQnDfyM5JZgxy<00x|EwzsfpO#*2Cds{*z0$s0OSQXNe zJOYsP91e}<-d`y>dLoB7fO*d(M?~ZImX&JH7F2&{l9WPG<<8bVq?JX1$v3 zcdBF(7oi+VOlB(X)*hsvfr^}#AYo7M*nNBY!5{yJ5|?@WkxwW#v83U+5=VeD;x7PP zFrA2jXis82l=$cM!{cdw=K)<8*95?oNY*lmn@x(dPaS_wV2dAo35l5-a_yvGZTt)jaVX2zodZX=T#;K-4 zPw00h?r^hJ)S(Iv`=9z(1QugslsDB10!jgcmK7)tVmOI7RJnmY=ynBIw9KGq|BGi3 znGzj3f^P?6p;QIfzlk`_^qigzh6rbk!JOK#QPl~7@{UO}Gu)oaMLEBVpb&#%LOTn& z0pAq5>{;;n$VlrumTg3eXcG$hSCeKrA$8PQNvIT3ePpi_^w7JhY$wKb>u!Ap*AkyE z6)@4PZYnspz=wd<#Y)Qk_F98Q`iI7*($qAnzBcMaRD{O&m@RPiEq}&~ zV@GsVRvP=NqBDfeuXb%~wyo$dtNFX)jAO|6+49D}gKcMO~Hn>O*^e+}Z(YC(Ue_*K@Ky^2NcxqB*;?VQ#wuFZKjkdc<+^ z^XXAVtfj%uXS(}<#eVB;NXRZA(Z*wcoV9lavk-(+UauoMo?iL?Xmd$_U#}#Zf`-$hZ_a8OueW zZDM*eX?WE7__%*;KDL5bfa;0n?=GXrzGw=^%S#H*Pab&v)STr9JH267!nb8 z-T%GDa9X^Q_8h$5+FX`z2rQ{BW_&VTICnf8FUq}2%43~Uo@C*UzuQ{fknj!dMT`|e64I!JQB06KO2 zSykRq%%&1aPvZQ}gK5L;ykfT7-tbPHO_KF&om0o2R?M|=^R9I9>`RLAU?(s(1e?SN z6pb?*9hYq*IYx{!F+P<}9D7=4CntCdN^8V;^$?|)WnIP?F+0|GICcQw%2}p2e~xNr zrz3hj)&DX9n!#dG(d$*=HnZCl3-jIWGsjK%rtX)@Bu9LPL9PbqYe__hFROiKFR&Or zmN{1U`Lpr&o?x+Qp?ht}^;95UftT%@Y4^Uj>~}rIqAGy;5XhvMs-}WWIO)@KHt%qC zMKmg9rWn>8hNf3@d6C^CXykLq1ks1V5{TBix+1x5fFjv<%fe7`v}RXx(bfMim*Z7e z7F(W=88#QWSnE0U1N9BCSZ=%ki?ytsS7U4jp=ASeCDMcHav5ZJ{U6LBK;@%p+A5R$ zcVw8kh(-;C+5;HUKy-Q+TvUdS2#`p&3mWUp>?X;lLlG8eR5p9X=EsrUW$@}EinK_$ zqoiwB!gUZR0~DEO#t&drIV&}!+qID`rWZDXQvz9W*K^;74Ku`3BlSXX%B9j z6%THK`y-oAmW>AevX`dZfjAIl(CI7nz8)$Kh&?bLsp^MlcYfwYLzKa3fKl<&z6pR_ z(IZMKME!inYl>=TXEkl!wlD46b4PkvPKG{-x~NY+|DGVK1?Gi;R**FmbkFKD!r2&g z7|O6wOzriikZ4u>j*>zO;=FNuV3U@!%N1d$?P)dxA3J)HRrG6)aX%h72|Q8tbw;Jx)dO)@Dvhox!%Ytw&Y2$tO=n(`y~EZKT=P3@ z8~eoi8C@KusQC7De7Z?-?ST(>HVE^s5TcAlB|&t^~B z7^EQur1W9Z8_Nih<~r1ae7jHB3sjR#952`A{c0*(RJ*+B_X){*S8^uMB)Eso1T`4o zND!_O1LK@YOX7shWGw)XR9gu|5lTa$lKw^h9ni3P^QJ`E2#lkGYCyYt&S)GJDk~tNE0@ovuYLYw0&>`D*?w;?=&@5PGooHm zo3p5vm{nSC#?{A*Pe5OS{YAxAbD2Axw0X-d@`;>V5*pYC){|;E3a)^uOBYW`tP!8U zJ@Aa6oI>3^b@XY0MXHPkZht7v%*{&}2{4I|1x(_n=H_=x#ExgCqRUMZ@6d6#iSo*5 zkt>(ar46%NbnlE*gK4A@czMq7YTCB@HYNFAdhV;PR9~@=YDvf*`=2{ z31LIV?LifXRTe*8`?(oIw|z%TqS_Kd*7{M}`2eNi%gX$7?RTYbXaL3x7Tc)0ZRflN zNQNKnU0G}z?g5NT+h$##OKpCs1!(3c1h zV{XC|Re)g+rMol`4cBCY;BJd%lj!}J7gdtOMwW!bPEVT@F^k@jA_VTb(N_uxaN`%CM0v(17MDGb$>aTIUU5iaYP>p?roZCK}f} zGMX{u+0@@0{D;$ttS9f0h>ZbtGbpi_>VZhx9_#x|dYs7!=J>CA8&uJySC$@1M2L*? zS_Z7@TSK82P%%EKvtW+bq_(M!)00!)YZ$HW&08t>MT2-`(Bl4U&Gvfjq*tPvzEt}`yFZz~30K>pxFeH2)5=y(vR(0;8 zUaj$4ss15ZXS}+uSuvFRrQjukh{sSd4+|Ega3Ly#a z3$}uZC0a67HvTLy%}mu9^_K`N4h<Hb_8WAF)2q*19kI?4erFU*1O}7@)!e zsAmQkV3C=30Q*6};@p;9dM|gvaCpFCyJPBeuhI}QiZ8(>^gvhu*i-fi>e^Im*eg^f z2)s>r&dzpM*1WucNZgh|SR){lBDGhK&EAiuElP6CrxP!ITYXRQ6YPWXD>#FIk6ruT zkft}xb??E(_0%Y2W)LmGQgfZ&m+1Z`ddos_oQexUyF~FOP-;gt))LH0u40E}i*G78 zrTqe-JVe+u3gj9|=xauKb$hJ}ruRas_r9o#sv75&kAbR@uLdl(C7t^`KP_7spf)yO z2#=UMrG;fx$%hai!Vgxy4L+|}b2_Sv)xBiLf z+{|!h&nl7Vz%0)Hz-PM8dU8)x!`Xj~n7Q-*_bGAk^y8n^Ufg})jf$O49epNUxqLe9 zJM>`s!Y6+@ojZLvt&pgO3N4C%bw+!|gT{nnRW!-(v+}79rlCxn&c_qkiO^fsadsuL1(>k;j{oB$&>rv{?YW}GmoYt&wRxb zvZLD1{ESa-Fr|6_@6ytuu4#-pzpE<(w3jcQviOj(CNrDTh0{k&EYkN3*ZVy`^z-S! z9dAj${mcJAOoq~qu5H_`H*jidqmrLgV6i2POyj%(gl(Kg_0#&9Yb3eyo;RmgXAcxf z%1k2--&takMlv&EmogDwT%{+R3p?IxPxd*BJ;7pg!!>((8Y|{zvm3Oug1kOXviYku zdwA+rT8mFm4`?F*E@yi|g^?)3%90JfUR_O>FP+i>scnEhV3F6^s0jl#s@|-uq-$5s znHa>-kf3mJ9(Zo*Fs*1zit!nqy7fqZxBq_}`0v5<{(A>LHG&lY18@5zNO7ea`$ z4?AGj-Z#i;(iE?u-VGs@zK*-t;}INi8F7ZW6A}bcTU&vo>GU}Du9jfm?zt8^w}6IP zg(@FSJDa6ljZ<067>3YI2+uI!7o(5-_S~%aS5d$+q>ZuC}Xk zmhYxWVz~GWfj&Kp1o@mdW|h)25?~P;Dw$W#3ex`+1#d1E|-GPUCy($DvH*6cxEXpsRIl`T)Z9g2lFLU+dp$fr#7SW-zc}(>94f0eD~o zKwTrKk{WZ{PXUYx=Cqgvw>r06SOt z9-GyqoCvnwHH`*{H7L(iOXVFfvG>sZ3b4eYREb($mVsTV-HqPH-^u3vlq612lN~0ENiMXgF4d?Od zm9wh8K)YR7xMIn^#cK-iH44PrY;xkV5ooptn7$PK7%*+XuzW^s0ckHVS-iGPsa9ao z{zM{zHMzhzi=v{m)>(?`oAquhTJS&}+hhsh+wOUHde4V`UOUA-FKqE2bzS|#255D`y)A1wUQsQ9O{(A(bU`6ptKrV2E(dh@);H5b5a za_)6wp0p+zjA?&R;6UA-7!RAzYpLLAG|K2$y2@S?t=q?@uLc7EsH zyHy?Bddng8kTZsi&jeV$eE4xGik?3HoLV>lhf=h^azQ=7R3HJ0*a&Fse3zJd(;Jlp z!{2Zgh}S64z#xnB#<}^MKl@MQWB=W+{MSmJMFQQnWqX1-#~(f?76t&6d}ds3-nz#| z%3ZxEQ74izdAvsH&)V$sIunW|6UOY2DJJWqy{|AwAKg@e%62uF8tY1H_BzvCLoXWY zUuCeUb@sj;R(WD-qpFPIyx43p3kq(sDPa}-UwcwrX0ob?VY5dC6banOU|?7{hy+zA zUW(GFz^^G`-UjH_^*C#0AwtjrY(-5eDGpEbec`;DSIL0_d=va}_?thh0|tjIllA<0 zknO;Pj5ED{7=lv0s#$4>j21=-zz>}gM~Gojzg3}rRaP0)k0fvzXT~chE#>!GP#VZl zqY{eu`k$MbsT>Hnp=bu=d0lFbp;=ihSMQZS`}`?I09YACwzPHSgu#ghX~6L)qhvaeKiq8Rr|i%X`9*Vwo`U?YBPn3xns3=`8kU!eR=L`18f`M8b?EOJhJ%E?8=`t zGrYyKU?1WPNEi`NO9I~|xx*;es`V|&l&%#hlv8_NSH6a7RqeWsV#=AYWfh5WxuSF-7iq>0z`eXh=7mz?fcY!Ca`$$F0d0vQ00O}E3q0fj4uZB>U_NV-F4J__STek02vh4Kn=S6dC{TU$Wu|7Iz zao%et^<73sQx!s(;>1ogG^-DeN3{fxtk+Fs`W<2z3reM&*Gi8Kw% zr=oaEu#5-_pqpwkbX!0!RUi_vtPw1TC6rm0msEu$*oV4DB3s%C1lKngl(aPvxgger z##uxkU-=AdF}iGi25@VEMLw&!mc49F3ka{>9=anq1gMe z|E!-G!M(}!*7yEo+JE~)>2rVZOX=jx-$}D`+m)z5_^G63ciE-2A9e&5#Vd<4h%^Q! z(*5uH5rM9+e&J(j-=X`{fji!ozW$}(Q8JKtQi%bQ?H;ql2#MCDQW3xKM`IRYf35Em zps1pUCKwpI3R}&7+PrPAz#Qk5tf8NGsG{`n694fTy#Dq#eNVdk&EKDn zzVJ;`J|0TxjSqb=oj>)G318h<5CA`V_#2w3ZI93BpTwB_zy^aFi>8IfjY%c8ils|| zm#CscssG7e_&?K=U;U%>xljBHJ6DCeXs^eVeG&_?YHIfUKuss{#C2h}NOV;#RRt5K z?)2+l(L~#aSrRrr2UGnFqG{Pi^c~yt*as+6rEBG;ns5o`Org`}$IvHXR4gA4&}J+L zH7oS;?#p8J>c_uOS2>RWy>Jr;zFmH# zz^wWtMWe=v#{8)^z*O{w_E{R852vA493KBX%YG=BfF4C}5YETI;t?AWGj6{FEK=z- zuxJ&d_^GNaR7UMQV;iFiv(}UARb{jX)jz?~4=m=uAfNjJbPfQD;<^W^9(AvUU3c5P z^#sl>$qN4v?Kkxu?%1yc2yGAqWLGYqsR!w8U@;A)OR8pYHQQ8(&duz!PfG5c%oVp5P5=&?-_-P z4Vwk}+UR)Nf7^rVn>zmDxAWK{6qy4QagLy~D{0h8Y190!v}HS#TzX!Me!xB(wHMuQ zt-W3TzPj}xopBN}%)8Vc;hZu{&et}oI!dSGmn2(>oB`< zt3HW!>XqbLGf~-m*u@D8%Y#_b&fT}Cdmj3s^p(&3M!I_OY+4w^cx zxAr(Ureejom-pG(^fK-_aBq6!Lq8qw!Mh$#kAC*w zN{0Y|rZx~~BB-Lqz9?dj++UyfRU}${UiWGz9lGZo=_5b=KczqUoqw91eC(6;gjC~D zw%PCKg$I<=zq)M~{fhHCe`ij-kgi@jT^F}$JLql65i|PLt6M-}t6yt^#WGIubtn_g zp~n%eT(!&V_q@U4k4ov zX6Cl(l{hXaQ#cerp3x_*ak({{SQxw#ED{i_S7K#3P0Vaa<6{`Gi;~N(A^v!OFT=SW zuhQeSZM3%Lnq}h-g%jSsdhslqSYDb{udDvE5==J1BGe7DUmjvR|DB8w4ws%$fFnkV z?3iNE5e!t=HhWuInROz+w){5wIB)Q9~IdBo42C35hP;|do##=pc zWUe*nI$Tm|WeO?rVr^?+F+a104QVr?EryNRmwRr#SI!bOHC3^iLFS-~rVL_Gh1(NF zy^=8Y6(01rIH26C=siOgn0VEY{ut3pM@{5{V4ATko;0BkN4>gITD9I$TMD}x`u2hr z+xi@O*l6vAe65~^)Zb0m#%{@mXh#4JVBNHBj{*l(7O!4R=TE(;WE<2h`rYDp{lFqO z!1P&7!c%~J9VU} zK9t$#`g!GVR1oOPpI)VNRD(l0-xAnCd}PFQ6I=;=W@fWQMNs|*{7{jE)(VY} z_27A_1!3{Jo)s-73)e3xaUk7=8`q>WfIfqigg6PbzsF!`+96)t&)3qw0t8aSihg3;^`kSB8y@~#L^@8>Qv{9Zr_MLGNRH;ckL2<4Cs=*2S2_NWx z_ksj_kp9~PcRnOKDoIDEob!Dj z!{7JQ>4ES0vGjYt_K!s6ZQ9F-i6U8`xYD0ZnP4Q5qJD1Fz^6@Y2QeLJxa&#|l-D~5 zSd4Q}sKm$fjFr#l#tdj(uS9WjN1~op`%Ga|-Ou#mbzxV{Om0y>@W1jT)Qj zYGLBOJMpDiHapu!U;qeO5jf9!*RF$x;@AzEUcJ{v)A92PZ8509qNapoH?DN8jr zI*}HyT}&h6<7t+`^VcqGT~y7Tm@>M9&lZeP1L08ep^f3aUJ(qHC@FvOI~*LDE-?md zP8VPi<6Z$sGs63BCS^(h{YN)8tACDb*LP?)j1Qy$#bJLKwRMyQs)}L`nOV{t6N*dSBtI6u) zjB%i%nYtpYs)Wlo)#n%Lq#eoSTQxk+Ux302cv~W*7if>i)9utk1fi;cMipOy1^q7) z%0U3a=sN%rXsA4Y0yL_+oHOo&KwLEZ;gKwG(^gpwda{BtPYhLVr1zP5#ZI{ZUcD-K ztpH_E$3EzpYOiW4go*(?orY*Y^ghS=hU~Q*` z<~g$wB$aDc&QtVzj?BM&SpgRDZh#~%O4l?ztjfu*y?3P-pZl7|E2uJ3tciidAywz_ zS96qX8iCzUx;M@DoTgl$~lDAe@*=0$TJ(-ncF% zgwfGWz(_RLoFFzvNw%bsm@daRH4=r|hs2r@+Frpafq-qb zGIeI~N50(IH}r*S`1_V!qC;kScCYi>E4FLKlX-tvJBnv<_x65?pk7c(xBMA5? z(X?N{`A7Pzo_B_ zeh`~*_S9h|wk!?|M$S58sA5s5Oupm$e^%o=s4Sw;of$(}CEeIeAy`;~#n=}-Z{m4I z3YlGS@z2L_3Djrvt-k3*e>qzsh6MDMhI$R z&d}DJNCevPUkltg#1ZV}E2v#xkZ=6Ay)xB<-1jl>6v*emv zw=sLCaj2U?9DgT+&03bdo3C9;WE~H`aUSDZNs4(fYOVAk4jlNOIB4O zZ6LD1vF{6Bj3XrgFzQd6&uTaFQPGMVYFE%BVA3ts-<6SeXTm6x-3RVTmoA)2XPDZUViQ%ym%T0fq>tr=BAhQgEGpOCSwRCQ6ByDn8y^+uNU4k~IMh?Z1sWaM3FneH-y9@fnfi;ooCey{a@rfLK>iwbYA!x{d?AoCHg|)5gu) z)!RydhI2+vM&=4qB_QBqj-dp|`hi6yz(&&M`8~?|V@ERul`TLYZwIj?Q%#H+ zbkU1${Y%bHQCoqHr&0xEWLQ+b$*H+CG}IBDZ_Cy_`ZuV`^e}ODZroUK5uR%9SXnX6 zRmGqh7IPS_a^;mp-&1+sudfpTh_M4FUV18BI)B3Vb`M)KG$aZhij=jsg(9wLv+u73 z4YlcG7jIlk#}9w2O3V$KaPAdv7z%AO+I|GA`b3S2q!tVm>yczo{5B=S5k0~7;zOuN zGS_%{$wml~pkROC*AXP)c_U({Y9;&X;u*zU*cX0hL*=bcQtPKgbusJL_pJhYAD6*v zW;gH9`vCsLDkQio5NHB5WgnZxDxOj+la^6ki8+h8R^~;90$g*pNRBZwD?n?P-RM^Y zSOYBLW7%_Wc<=|(cfRrI^zsYeO#5$tFx~y;52R21?*C@uEv20*DY~9Av~$v^Fh$Vs z;Fsq_58?NH^zW;e?}@K`LN;9E-=>TKrg*Hw9vBm21VNpPYSl9Klpu<#B`r470xpj$ z5DYT^K?VE0ANqxK@xqDp_?Lc9+VcU_ECc}v8&0h(Y+Z*TZqXFXf?^mC`MVKN>(~G+#%+!sK!}W4 zC@DfeDHGaH z$lQ;NPMC3^A~-shrl&Wh^JibGW|dVTvIb%U%tU1zh7xDVL*)OwK^- zFj_FiQA&6`1G0^U{E7jXDsUjH$ur|Rsd_9gFQ=KAO=-C%m`rPas3DB+2 zF!nmtSbBJ%O9xP~CAaf}5odo$#Apnfs!6wt8Yux7|LIYsXfxz(;HG+A%lyUWcQl+m zpkvp8d(zm*czXHB6QbR%8!R*pWUu=v9blL{LMl~VOi0NxuGL&az!#Mn1=D17m#(K} zW*pvR8261V@Pbo{-qN}wBlVqa5 zmC7g8ODgHANZq(r#RtVX&kPdJ9ppZ?%hx2cL^+(_Y5WY#EVZ#9kOS@*el4ZFNpnZkbN7z*V|Mq zIlhucc&}*3Hkh4f3&6ntA*wSse~bQ1e8s=xb4JD|tvW5r{Hg%tjfKl;ap9Vh7$ha| zK_oV)SZZ7o_HoI^JK2n4Q@~UV$xP+ZDJj)nK7S%zzkbr*D7lQ^xQp z?N19RG_dH2%lxeC|HfJQ;E(?|Y42?hq~H9%{+^!6?B?xhcxY5iJArTY{aPg%wgCVi zfgARq(a!sW#gc|>l=PLfefRC@-5>lpiS)3a&A!F6E@|}n<2|_`%KF5VDCu*XcIy5S`$31JX>-mk%sP=B1VzZe0^K3{Ot0k1Pw5nB`i3eX*#L4PyL4I0MjN6#&FlHY(FkPX+<- z5(9h{I63vM2wtLz98k%7Ilyden)B6fCyJPF#t05xX{KS_yRG{T9d;^9Mb51WATa^hoK?SQFu<{W0P_YWCrU(IQG2&aDX#36xITYi8b51A#rp7fFx6k zGl1empqwj}RQcf0E7&$8R9<&v(liruZkw))Y$p{Pobxy_83`S+zEBj{D z>6pC;F!b>tig)bK0ZT>IVNTZ8-J&n6vbbrq*3er9V>60`l97u5*5qiP;UDA#~%fZhegd~HK1)GA{JrqsVW zV*Sv~8D4P-&Fjnnbahpg!Oh$EiZY0@H#F38wqQQ9v431Z3~)*2oaYP3Kl#$P)gPq< zf~cJ4AIqPvXHtM;%cG8nwG#dON>mMzbT}aUa_;nt0s~aox!0UbE|WqI5UYE(Gh<5F zE*HwZxE25zSss{a>bvcY4u}aPVHRqq^@n7bv3F;X&G&(XN8>2C0 zKC_nu66~L8Xs*-N{sSG6IeN^oG-eWZXj#l3{tS3jkL2Q2(Ojc1lDJ`M;hM!FLn&Q4 zdpxb6UOR+X;brfkAJU#OdST(G8cE?^YgF#(*zcy0+7V#D?r}{KCsYQzo={lNGf;AN zWF+l7^g!Bs+ndw3zVe5nfZloUdo?5QPk;ZPE8!!XUKxQ#1+hUvttG19h_9xbjF1}} zOS7AIrJwjazo@ZOpZ?wdT}k84N=J!5VsyW#cFPKugao)i2Hf< z&5ezv`yc*Dn%+2{o_*rabQg@~VbqiSj92oADT(Wd%}{!cD&wH`Kd*a{-0cE&*{0i> zH-G7IXR&Uq0RWcviuoO=ea}nu>EzL;l`M@j-;86{^Xz-Rb^r{qCRlt;E~Iw?WF3{o z-e9qrJ%yGsJ-bPnPJ-;x>8uMbc2zD1$dvh_^FXBr=JYT?9~%+SfuV^^No>kc7*l*G zN3oJd#!!gbp>Y^w#iS-#KGeTJuoz)yR1j(ZH-Kj}fJ{Gj2MV18#Wa+*s2ssXj|xaA zreV}MwAXxwk4LXH5gQF}rODkLt@;SPhmW-;gNzc}^xV8=^IS*CR1O-TZ8S#?pvB=$ zuo%@w6XKcQwqF4^jtIv=#u|lG4dh+CDrG%B7vqM3rzd7&a!NrwPKJOai~^1R1Vd!c zZP2`Ze+d@jUZSUl?CFNtE$Q;blLFYbH!P%HOZ=dIZiC42TAk)KKF6KC<_P9_WpT*{ z7!?e$e??UpR#g#WDFr+Q1N_dZkj-j(^Xr@0>xSWrYFAfqUcRnTHEVN9oXHJy+tdEr zA4q3Un=0!1oVDZ$^r_y4hQs4CJZZsOE%}$Ld*u$ez z=Y*}odqc5u>&^q(pIjSzlS&5clp6D>04OE!(`Ty(r%GyMQMH(BTihS-<$rTqcBc1y z=od6AZSflYSf`X^B*6r5L}8oQ1mKF#W1j=OEuj)>j0C{lCdN;9U$EG=*P2f@z+!$( zd{q-HHmcRH+Jp22iv<8K*0nre2A)kVmURlsz0_^Jn?uZt&XCUl98nxa9LBz&+RKOv zT7u|#riF#R=t-$`j#=NS5|>n+t}7{xt++{*>k4C6j;TUrLPn=0x@GK_MN|1!g{{2C z%!jEhTXjzsjb_m>Kj)T|=%{ba;zbuWY4cZw7|EbXVXhH2l&Xj?Ka-w);`3>GW@CEW z`+qvUeE6H`+h6rmEW zWHe20*rJWe^#r$G8Sbcz6cv&z_TbI}5fJE^IQ@&~Po~Z)id3dJ*7Y+$R^T<;Q2s$7 z_!1Q)=(1EjxKFA=T>q*ne?y5X9cpiybGUd-^fBb8Q8^>{1>AAWpeiccv~X2`OJOfU zHVS+UTtpyffe_C)`d65fLzbMNmB7J9l>p3aShzL1S9`$WZt3vdF%n$zJP=?Y0F|=s z$aq4Qnas5)twTe~zR^R)>$o?9Bra4vm`+jU`w2Fnd;nTi4F&Y09OtxL1P%DnXD=^{ zl1oTUj|L8GNy?kd=CU9ngP+3D4Dx)xn~>4OR;==6PLzOdv@piz^vg3-*{s6J_RU1Q zXv% z7q+k~sab6*qnwS6r)@hAO4x+wcIxG4x@g_~z+$eE`}{Lg;WPzQSUsGN<>i$$IXSJ$ zBL0GYN?1Mkf@p&%`;%+mSAewWIch#XUf)bW1z03FedAj`sNv>R+))CZ+OSDO-9>kl zAdB^CL6Ho=1Mna)`U$Z~N+4giDj?5~IEVx<{y~+>RrZ|4Aok3>x)l{` z;-8rFr>a*1lATnPbV8AhF6m+PUX02|p1ZUOs;^ojLh} zu@NGA?Snzqa~6BPwr@hmPFT^LGBDM=D_P&`0(yM^x+;r3fnJ|rv6;nwMPRYl=QsYn z%ouU-ainAwsVG?kua96T9B18GS!GV6F~+CF#W$6&1*2Yi&qi&H{{ny_-;aTjz|72M z1uF*XMx=I0sh=t#V2VHu2MK^9qsn35IJZLwlM1VZXQno$8}wH#(G+Z=2ANVoU@<=F z>Y1y`NUQG?WvlTio4YnTZU9c1!C`?-4kspye~(}b1FnoDV*^}`GgAf>bB*cnl39fE zM@E_o4m~tvClM;(z6h>}&d3hupiXn#0Hupc5>PqifFtU{b#m~zUw|>kjcXyZ$q)2o zTc;WE^jRm?MPMtcK{bhP`qW0X?qsH8X5m^Do9`xA=5v;eCgOrJE=Mm)MsbE} z!CGm6TM{HyMY~_qdqzD4Xf1k1+rVO>7${8u03ZNKL_t){vkb>ns~Q;9W$TWEqN5&r z@mr=;R{+2@jkUj)eZig*Z9NT(HUlWq8Vx0*l0r46mrp&LtD1Qh!ZwDzyfWVWQvZ%- zsNV)`%mEjS373R7u^g+)iC!ABF98??E&(<=MwyCia&;*spSG%*uDL$>kqu{>B1tH~ zB7hKT66cpHjLqd5QE~1Hc76rSEU@STi#=$6{-J|j`nsseaZP1# zZ=y>uQzm7{#>VK?p44*?s7DM)&lrVQ`m6{ztb!{Vw+lR&P>fYNY+WMRSS8)GE+NF= zilb58s^{=4>ymxw(2)9zHY3C^JZjJA)Dibp#d0;yhpIgjQ)$O7cSwZ7hSxu*L}D2X zwt~g{9Br^Sm3Q9HJwR_GxkvR#eQu-lFHR`oz!IE2`MfF?<(%Dol})Ab#?x-AHuM6E zyp?`ThH4`kLPAm1t%+$dMG$M*LS=jlYQI};jD&`h+luo%0UY>G(IRi&NY|Dc=!EJ)V?`m@77E+JPvfexEeX9|8&CUhzZn0RbITg!$-}X1s*S`4ibo|99(&nxE z(mOx!GwJB_Ur*0J^`&YoRQdjrA!OF1sBBjN*1tM4=V%)`boV>b%!c{&j(Z;`s(LDmX198mE6P18Ow=%s z-@5#{kMChGkcf(Qp(cggbOIPDv0{qNW0N}f#Cw25_71Te@$D`9?)Le@BVt2nfLhZW*UrDVxXZy;Ay+5|x`Eg7MbOQbeU9X;_XYYu zZ10C*J`8;O5Png1AGvfn^UA=rp03A~Zcbx1Z)k=C`>6hZY^i+m2 zCyI<@(ru2`h@3d1K`?e44vZiFt{GBSF6dgUuk5-$msUO~88}TY*8r#miyC4(Je=uu z%5XXz5kre(2UuFbU~Zz7x8#rhy9yS$67@rk=D^*yIW!?{Ywu~a>R8#!nGJ1Gd0*H0 zj~Dw{QFYk^p8)q|hC9xmz0K9}TEJqsVUhuRZ@o{+gHy+!EoLSTN(5pbZ&KwrGR+Fm zSC$2M1pWoWRz?4e>sqTaXNd&@yeRm2A5~tw($Q1`Cq^ly0&W0bbRbu2i;BFm;-SDA zvp#zm^=>QQy)FS#dsU#g9x8_fOa$3v^66P5h~;-wv!IZ1y#&;NMP5?^jG(FkHUoIK zfswpjUURTmfz)6|#CMg~X$dP2dIi{!c%LyF=AvCO!%o#@uT(@LDFmas_O$zzUT3EQ z)g4t&=+S1)2w+HN+2`lgDR)u!SpgP#CfLDv4sG8V_bgTH$!XE|v9CP0)5o53h3e{^ z{lFquhJT%yn$`S7gjuKt5vY@#qgRcfoO!zlCGnjk8$#4XRr$C(2a3JE&$f9>@KVg% z&98A2ymi;1v}N0#bmZwrU5ztamu%~(fQ(H}D=^%B;7#&B^r&mb+V=hF>Q(w2uj)L8 zY`!W?t2gBnXlam2v@0BwY-L8H*$*nkQOWYqzBq>V?0sghdkvm9l?_G%smek!BDVqz zZri$^eQoWA()iT0d?3CIIwWV4;8|5}?QJUFH#O=e`kXVXM*YoPu(i8bg~RCfmOJw# zPyrIl%4FTvH(F7A&4Lyva6h+I)M2qFygdS+MxPt|48L!5)*b4LBpJXn#CL0^r2f1i z)8DBm^Xvp3uU%Ao5%!C<9vvG?XHOqhg_7q$Y(Xp4!onrZ_@scqUY9SU&(FtkH47ji z-d9V8xi1CO-21iUniwpCIrUeTd}k<2kYhrgS|BSS*tqtO>Ca*Kyz5Ka#fZI+Q;1 z`~O@Zo3qO(E_^P&`~2x6ik)(TA^cd`qq&CdEbTac=q=y#AE(3L`SbL`(~mkcqrm|5 zGZ2+aRkoQoO&shAy@l&n((LSf+P>$uG&8$Z`|ZTh??^$uD+U+@pcP_pY;-WG+&Lvc^Z@$OMn^>DM4CG? zfhIO#y@X`v=ts0c;1ykzAcRa>%&CM%!0RquJgHF|R+%BAnj|hG^-wpwI8)XX!>yt2 z%#_PB9HEPv_zaaqQ55F3i`Oo${m5wAh>ERO6xH*fF&$^*JosLW57})EmK~dr!G{VP zlmgaZnTqMM(MM3+0zhE|$Vl410}Myh%*?fuk&FrenN88DplCQvRegPOs5YlCR8ox% zXyXTR)va0iHcz?cvwf{zAS$XqkN8%eM+81NQYqP@C`WcxKHr+%vs15C_H1@z*FCIZ zIAx#%;Ap=QkQXCMO2^QwHa3Dp)|P#~`{2E*_`LM|H>@{xK<5%`YwJ?=D`+1VSytjs=M9F(pI*t>vC+t2C^ciR8xECXUzMvs}|DTpeH5qKQ@*K8XqH=ZrBJ0=$28uNG9f(S?~BjU@`c6$ljhs_;3u76+g0+FNN}`E-qk2Wp9sWi%NFOT# zLq>FQMfO&O3_oHN^C8(``qo0c%|wD+yrltt%Q3mK<#n z&MPaXYXLI1N4MVnj`WfL5W zO$N#P1-UNky|REACyfCIn3MU#SrgDu4a9IkKjky%QHXI6R4jO{0)0U3^0E}y_#QQ- zfG{gea@_X&Dj`r&Yb4D*1SqDrh(0Dpbl4h8fTUxF zF#@%&%6CLwgP+e=^~(5uje3Z_I#K8BJOG&43s7?nfE&FgD!;J?79aEfqaxh9ccCqC z;X0~$O(uii^QQ@hTEHUL0o7&Ou0!eAk;f%mF*sPPgQk)S7EU-*i&{Wfoc5mI=fQOD zD^&7{^>PV%0TTm+vP(IeZ*&_^W!|3sp`@ObroToLD>wuVWy#9@IE7jC`w<0F z5(e9_Npv|tj$Nbyg&3<50llrkke&}<(Gp#k()rUb$@YZ}YReKg!Q#Tzi|WgP3YMvo zp7@IU?*fp8P0*FNXb;y3<&z%*Y=G7L&VvFc2#{ef8G8g>Fkf4b%A(mHeNlHWQwwcX z`;Ga(W0PtBp$F7{!ib%=KrgDv{C6t@xVP=oHA7w9x%cjL`q;DS_>pg!uYm?Gs&~@s z7|DU)%9#_-%dZe8;Hy{z5}G6)qwf*l6ry4D@aG}+_)92}Fc~`5x5{e?>{VIh8LqAh zumFA|u(mVRqMJ~j{U%s!*bUAAcf&Kt32<9x^T|#Hl}Ho5Sz|0*Jzf;%nH)fe9V6Dz z`BggzRY_y4STZ%Lk#>=#UorNo`6Tl%mdF9L%+2pf*DjyQ^!A$VYpNC(43O1j5^OF` zL`_ghAgKICi-$UG6~|ez$7biYE4cxn1Y{BGkmLZ|k^BI#l6b&Y6Ynfsy__yxIF=UG zGkHP4k-k@+3!^spcYdf&PtMEzdAgW5c8v=2&lEz09OE2Vy94WcN-Y}c&t51`z_n|Yg7cWmsS75 zp4Cd@4R2#H)1f!KBOQ9fJJT2c=>Jhgj=is*MNjsVFyd?|kzInt{AopX#jz4+``b22bKvS|ZLA4P0r{j8Q4L=bC!`$6w-JSR$c6}vQUd5!BU zV~hVEELNVczKUyRy4Q+odi=hu2Kq~?fVkSoY z-3@jKXG8`*vgsH$j3x(*%&7w1m8CQ_HJg?Jgq>lhc`nIF(ci>pkzFOr$29`_aFQG( zjIlWLs!pafMxP^N8*VPCvdjDQ+7+YDLT?3TK-p3cktDR8f=Ulzr;}zk?NCM(o;lAG z=PNqd=%||2O(?{&?h?4^bQC1Tz-f)zXat3w4wQ}!X<}+deVt^Ws6MdPJO?>*^;r(7 zk}b-bS1w8;4tq$Rg$o?whM-^aXOhDa~7`-wYdpc)tLq^_$wo01X zkWqlk>f%hnlN+`wh>PiDnr?OeYByA#rIxc^tz}2msy&Aukm$H?i7&TQZpKoZ1iE506Z4n34#rh9QA<6660q+R?F!-xJ-|tdQ|Dbf1c8_7Sdt6E5`A6@P zmc)3|`T(gnJLqQr!YWYTG>MwwA&oVOK2Y1MfN~N!1hK9V>w&mf0!}B33P%*r+Sa@l zcyuK;teRqHy$G@zzD86%CC*HtZ+dE0^XbT7!-gTqyLkS%b{qF6HRw>3RxoV=H};2q zzyON`u2B6|N${V3U~$LpJ9PGW-&w$-EB@JAi=;|a8$%wy`tV$JVy^?zG(usLKFjc5tz+yqGvm?*|vdJ#v9+yos_QBxk}vHZpX?#<8I&r$8ZYkM_%W~(G%-B0=XEcdNMUxsy7Mki2&Hc&n^GOYi?k}z90Y)l+y zX(3{w>%D1Xm_#R462O&9-R>Y9rX()&Jcp718x>HJA9;9sQw*<2-{<6=+f#wmuopfL z*S(b|7HyP}?1=z_i88W>h%ZRoK+%@6|Ax&-u->A@PNceLzRyV!CwU zR2mr_Nn5rb(DOyuiFkp%MIwbhTHeburXq_EJMzp|YU3-MOPPxS(dtrxj(X3c;+e4t zT^~gfv@48KY_ls#Y^$Zp$G_zx>{Mfmi;RX!PbGtzGO zuA2>|vTD^=YzJr8?CF>&$JoU|7%$aDSAWV3y|vWj+urvqFTA+f zHn3;`v1Rk+@&F*7MaxG_G^EM_nJu;7LT>~ta=5Nuq0#q(Db=+|^1hzWbdb+B3W6Iw z9||t8OrIVD!O8G>pJLFaIJ~?MXBcA=g65Db8@YgCgUB&NI7?`tqRy;%=FT0xoL8qK z13S54PQ8*;A>**;_u7JwXL^e0qaEOS7G*Lgt=29~@g& zNLE)xr6sUhUS1U43&%#r8Apj@12C#D^4f*8yyVqcH^B9(cHfYFkViiFYl^ByeeXIg z5rGDYIZb$FU^3=5&%X^3g-~?q6ogaZe$%`kzjQ9t@kVY ze)RA+Ela*u<;(+dLZk|OgHNlmcv(r zeH&OVxT|fpE=!k}zBGhn+Sm|suGll^ zKo9dYTMTzE$Xr$B&@Z6@@*)_ogWx(9g@DR6>z(5FM(@K8 z**c)o8)}^;faNn{RwA|$KXv}BfyHibjHLz)DAErfNh#s}}^csowv80j;>2B+Wvh3IqC`m)B}x=~ z?-lG7jd;KRxAs0~pId+n7DssxiA)l>xc8KO)?VNGzV$8E2_VG`S8N6_`AM?xL_^wb z38!-8l$qvHup(_a9}AXc*08N*y~-^9bO&S@AlNI?5ErX7<@LYxx5}hN7{G zm#|(QZ1!&$thFx?=8M>wD3=t{e4I<9=XPGnR}xDLFjmoQSzBxNTXOcr*s8jZ#)wgX z5|C0Xs*nPTpV24DYwPNf%i7#ho+tHi`ZY_=M4vZv3vnbp+_FP1-pKeddtn^W`W3Ib zLzt*wtkltJMr!KcG~*RcLB(v1sG*IYNId)N`kKMV1h7 zegJ-$;Ji&Gat}+Ak?sIPZV>B+S+xA8+zlE&UNh!)Y+i2bsJpLdgUNeY3>N+0t&brF zi&kL`Nv(`%{8~;OKh1=J!c<@o6<-R0)Vz%`N_u>+S&&8=OI7&f?EMQUG@0RBx$Zt=K41cb>k+_apNz#MxY!wN&t$kpI42L zhz}n#UCI5RYHXQ%QniWn$$EPm2b0!xNUz=}S~eY`3oQCej}oB>38Wf2$4%=2N-3$Lb-+^4?5 z9X+@^uLv0mD50ooz0T&=%6VA7pt)DbD#tLuYI%f0jE`ilK*MCw4qIX_-$k#)S zjqcYpR1W!&0QM~U=QymrNQKd33Y-(qAa?Hm+}E`3fAY`&MXg4;s=-1r&{SbavCV`E zW}i_egNBZmqL9&RNKko}y4^KSQi_tX-TSfqk*@f$6Tz+l} z$&8XW?{1j9jb|3)DzU1%U1zi@FeByw{U0X|CqXGsf^?4e?R@-t2$BSV#JaqyM%B$w z`P1A)Y4*($I`rrSiGgG>7&-Xy8+woog(}GRYiPF3vlGq!k*q6h<|I6S;WwKAG6{Gb z8z6&++E@ac(+Du+-c(lANwQ(Al}USOy5~VA38i99|ESndUn~%4DX&ye!!W@TM4z0K zROwu^iYh*n^VLWcSjS`rkPVVf4Uv3;?jJ5~V%lWAb7A8U^(G+SgaNVMh8mmYm=q@B z%_`*k=f*4+tE_jM_(zi14C?R$kYPsEdm;ASzQV@OpOWX$>%k}yFGB@TYbd>!GUq0d zdB>9rm~w+>iC{6jFZZ>+f0NjNgDpEHKS?&BVhMeB%wkS_F{!e5`Qz`tS}w3yVZFBY zb~ZCFjM%XL4_~Yb3A<-Vya3v(9z3WiaIA4Wv#Mr3Sj-f;3T#A$`u~!TDzstfJ<{rW zE?C5vfNC*4Cww*u(7-`s)Eh%DRv4>M6fE{8*m<)AC6ndG*sIDexu|`G4O{>*mkBAh zmU?px`jBi=Q}ow+2^Remra~9%MdM$@nuU{7@GZ15JhNjzClPEKG{!Xy9H!R_EW#|3 zbQc1P(ExD(2*bC{IeNc(7K6ideBLR5P-^ADYD7?L1Op>pm|IpW)`i~*tQUnSS_&xU zwd~#O+FP;6kNR#o=|W&Jejam1{1kq?jmaN2>LMk5+czx}=wq)5;K=I_69$ugZp`G% z#fDHk+_vFuu?c~>=J$y0Lq<(?!^g~UExR_lP3x8<#o6#Y*VNSu6u^dU+qg`?I~Zt% z`_MdOtQ$4)GI#9I9`&nH><9%(_B|5yiPPq~`o_U-@iX6an^wIh)&%1@dh-F2(`Mc5 zF1hk<^<}l}-{ShfHbW->03ZNKL_t*6HK@o+5tlrN0x4}G^qD|jN*W9)XPccYkQYLUtF-y;bB;>Vj!bMkWt|I4#dpE#-=;)~eXfSw; zKcmG3r%)AgYU*^ZNLnc(Y3vsct;_{Qy~I7$_zz>A`7FiY{af{XC6e{>GVjdm;j(ww z#>0VQp?IKTcYRah+)I9lJRKH0jBg?SGHL_>#l!&Y~0sd1qz;SD3A zALW8Y5?hibo0T(Ebb3;4^65Nc-+r#FtWw|#>5cX4Fr&-6)rLNvavbUECGR9y@fu_~>S=IY zdM{W#0wuIbvQKcll#^jjP7sCMmemTs4c>j{+8)pF)*(66#n5_*9LlE`ACLi3xbE}$YdaGCxc9LLSd7`&QfOl30K#!e#x%QcjD_@g|TVOWWo49^MMon?UM_=Stzx#q)_Sz#l zcJ86}p)%)2j-BD=-|;Kj+h6?YUrEM_DH};U%s+s9=9PE3DHktrJGZRR9)#Rg`=lDQwdcdQlI zn>2Htq|6i!I46n$tbq+HUX|-^z1;Zg#LB~dlMiWh7f$ySipr}5-~f>t1#;?`?y1dL zHDeq3N_2IqIKaIPquMzyb?!((u+0*K<$Ym2Q^?DRoQXcT3&-N`23>eciu1 zSj;)_K;_%BdH$f3RWZ`pLup=^l^9qbfqgNowe6H2q?+8Y)O9Nyqb1Pvk}x)7h-3sU zd$%T%hXfquBwKk2*V*30v;4iVxtILwIh77J0h+nlI6~rT@>SEeD=F|c-(s2k+`iDi zV%qvt21f8i{=g>6CJ9)yhtr(iki!r-2~uow1UOg=F;`UMuwCy{FEC1TI|+zpAi^}( z^;ghjBP7Amz~`nB+I$I`p;^6Bm3l&oe1aYqJV#Gl^dJee9Z0^=$WA2nzaA1sx^~14|hQ3zyz$K8|cVb3BFS!?StcX7^ zx*nOLS~nX?F1r|ih8;{W70NP%g_c@2X2g|VGfxT3D214&A!Ee4kdR>5fq4PHfs`B9 zJo-^cI*_RHET2!Xn4FgdknW$Fs92G_@N75eVug!Rjw9R)|JuN$gzHLytERe6g((|T zJhw!@IVu6gW*7F^<=-1p)Ljr@e=Ha8ob2UNT@z zM-o?DFS8^`A3gChJ*`{UFI55@@&K+Odj*Um(o(?ouB|KdoTSfCx%MyA56BQHXz`qw zlemEySTk4|z$DD;YtMdDtsdILe8CQB?X|c5g4oN&&wkUbS^koNHV?SCZ$m~-aW{SB zx5U0PLI76EW*0Z9pgN#=qz1v0ymK4?EB0shK#j@JxENTLc6Z`fi}C>!JaO$m1M}Zgu@DAhtan(AEpNWXQ43g7Oh*iAp>J(efI!+vbJ?n1w#}pla<`CzZ zm#H=zDP^j)o^8#iEMT`vi||}W@q#tW7k${dy=O59&25Jg_yx?CTVFNu=0QWpxp&`q z)HO5?li?G+uk?fO-?d)3jOP7e%Ga_(@?(>lpK)#Nr{!!)D;4M0*fi4hZyYQ$CgjLm zD}WwFfW8gQdIo|7oERWUa_b36N?|kUeH9ytM46liHCCDR`EsqfzkD`v9R&$0D_Azx zIk^!z7jggc`5)Iz%GMLdb&Qirc-l6?FRP0apRVz|rbQJcr zJkZ!3sL$OAiWKV7br%W;VZe0u4FH<-cMcmh%{4R*Q3ipr4Lz2bb@M@E2}|9N{OJ}c zD;M8abN1Bp)3cbjnb`~>vnpoD^x3f~nYZftsW(3FDx_bLLjrr*E z%gZ#%0qJSK#=)-j)JaL(cpv61aX)M=;edKno0&P#RlD{M9OEz`BDptNpq?YwCHFbz z@f|%(BFp^`>x0Jh0XAOc&_2mWxx<=KR9mNj8cdP2?Q~IHwGBXa>XFV~!PXC8wq8(^ zM8)9nY`|i;mvI7KC}+<8yg-#V10;+I)q@Zvr(x44c~tKvQlE&Oj{EKs_Q3-xyV%j^ z=1AxYmW#TJ3Ed^@(Pwd-{rV4bBPYyqEqgX9VM|OKikVRr02RTQp{l0V8zh1MrOK#4fiYT1cM2A*@?7+*H~T=uF7~*46euR> z7<%)0*$b6Dg+f5IyFeSi-ajK$t0|(9Jn@WCr6&7T8+e*>UfUCN|B>4U6Xuwr+z-3g=294l_fN%Zy3@ zSq09TNbzK3VFe(L3x;FDMc2BkZupcy?1ojZN^TYx8R@mBml2uUw)Jnj{d-L29tzg5 zeE{KcQ|7qSCyu%GD_^lzh-mx+ts%q4Ow*Vj*uFhG)_AV~A3?ji^!^j3U8Co3*=s*` z8&)l{nBzz5V6<}aoIBlR^FHcUy!C{8^Tlr)11xu7yEoj!d3XMjn=tii_u^xJ?bf{e zf_FtXw?~e9-23rN7 zAkG3j*w6K!R}ZmY!YB)Pc66GloCmeRB|7vPTK`?@G#d(W$WLM8Fb4{K$A&=-{Am>? zy~zQnq8KunY-p26;&JX?QY_)mDISu;XjH~=)I&aL^eQC-v7yM5jZWM<3PAv@rsk3E zvUv}>4J#J8tsCA^5uD$;_Lk3zf!@1oqa?sn6|pQ8Z$A08}5(;#{T3i&U%AYd`LBq9r=TA$Bk^zuk^H|v~5 z6q24eXH6<|euz4tAQ(?bgI)kEhNFVP0^m?dk9E&h&GZ$k=oHQ$ciPMAl5FSM-|L|U zpZ6g=yf}SP{XBK-VB*|py=s*X5Q#Jexdaj&Bn?!vg2R@oQc8RbjB%~GP6WJ=paR%+ zTs}ca7-v5S9XS>o6F{9!LK{!pX$3ukBmEYqTTf`_6V+SIZe+%r90Z-~+pp0WAXU?> zy34I12yh%UekULjki1e&-QIdbVZda z^I;uu-@|`_c@HjyfJL4Yk^&Nbs?@wEN$kKOqs2NRcY-mY_bsux&%3TYLcW3zjDi0m zzuTKN)tk`Ti}hFVZG&?y#iuG8;ly?7Q{Sj_31boDdKwB_Nt;8?+6v*sgEbYMh_Tgu zlz73U8OzY6kq^j$xgW_D^UrNi1fci;T<~qcP7D?kpsytyjdKY_g-m=Zv`%fr5UeGa z5a&}^A^-rx?J3xWLGSDxtRt=qi8b*Z^9}V7X*OS&!yC@TnEo^<;ZBJ$2ki_MZper! zaxdStb-6nwQxuEIYDw`!$b+6blM0re{RCJ|pM9&l;`)!f zweP*;7C-kd>O+(xr|<3W*Dyq2vU$iD_uM0Yp*U&AFxGp>f5gxm@BN~H;*yuYt0FAt z2$&@wVjrC}{W>M#2lj50uRsSbo05K>6i{w$J1G#t{6IOlV)`aF5^&q8b!o;_t-cqr zJn0*=oQ!c3qwPJI*&0@HU@ZN^#@dqnGji0GVT;)5bctjPuX=j^Lvc!ItxV3Q!LdEF z?pPzqOvrRi+OKJs_uMm}os$U1!|LahJG;=HV(Z!B|e5ah;x%^($UcJmI;SFk`NJ@AXIB z=2eRYo~3T$xv0WHo!(TZ9M5uh_8)If7W(D`0TjpLLPfjidpzGNel!eL4`^_{52Y^( z3jCdOgXyHd6NA2eyEkgxH4PjkmwZ~Ic5Pd2txF&DuR`oWkz>xNHR9J4E4Jpm&jkUC z1TYpH;|!>%o;6r3v0|KCfn;M0Qb7f(&Q4c9pxGK({Se&HJCdK%Afv>wtJ1YHBEk1$ zCDH@W#)O190EG|In(8gvNTAU$+PVe>_Yl0OV)6H?%356q@nO|qFL;v}F1SvGmtqGDjt zPQjy}0n6dyuEpk}$8LpDC1qGQK%YM@ed%Q5B4Kpx7T8`yZqpOrqkPOHYzPc`v+lIbe z5>Jvi+3)+gZ+h;lYh{80SfoIN6Dr9h_r6cv07)QW$^;f$wrj55`38#xT}|VAbs+-p z`2dRobhWN|*aXE*Od^nk(dTRhuAJ&YlK2)X^;uED91Lx)EAE>t2#RF%kMaXz^MU&N z{xpZ_5}OXA2#dmeJmjZ<;P`z23DaiZEY-}q_g~U+8LMNg6#Es-E)vz<+g3|Pzhl#K zcl78!8&)pI;UR9`9iMZ9hD~xW{`4>1=CyAoJ+JB)uc**GNkAS9*b6`TOC57;Cd2)h zb@hkc?71It?<{`Az4_vI66_Pkv*5To@Al72=K9P-Uv*nIyqzTP95eea{gk&n@Ff+{ z-+le3DmZDxSpQ}@m%?r{uae_JiYUXc_BMCA^|<7Y8ofh5?P&mIi#u`rusKI#)PifP z#%5G#J0T8(#Fp!v$X^-T)fqG0 zJOe%lG$n~Y%*-C#r9#1_SKsSaFMHl?S@VWmop}~6x#}LbY3&*1QojxHW7>ch#dPZ*U5Fk3vaskI}8{boJ zHP0;HM{d4%=ei{JU5G8_yuD{nc}es^=K>bBADovti+N`rmv>4`wsPOYOJ8!bWEXEC6h_S&aMytp7eakruy(ceFhbN z-ovD$W->u_i#0+p#92%%TXn5In_!J8fL)6sGP`cUVq_PcbMZ5&VQ%FtGQB7S8e`Tl z_wRB4Qw$s>r;bKI1j&a$zWVm)dpKFtMn8HW4D9$BX~``J0Y5{eW#yXPF4qK9B~Yq| z)m^3$4Dgf<{{(NyM}8i zuc1e8_f}+mX0k@%4uCgf&YkYPHy(9wFM3F74`V;g^o3sSdAI+PiZ-u2_4jVms>MlC zuKQ70>BdaF%w2!?uga|N<;VY41s^jc@*}q@D&+=y^-VwLR=)j=n8|Fx$JpYzxBVwK zcGBhUrN_SEHm`ZZ*v~W8zpv3E<7T=W@A-l|a(Ithv+P9yOa`%2C;-RS&u>CLQ4cOD~(mbmDig>Nl3!APm;BCTt=b1(toeeb7w`F z3Kd{jzj9*s%%83sjHYM46OzIg@wm6-J+Nz+UH5=~ciG}c#9jfuF1_YnU57Vc{5L=T zqSp7C=NF;1_xNIQ9geqs>fLGBJ+%RF?=UU&8$w_;!w%x5ovIc}^2u@g`K~@MK6&b> zibhfpxiS$205+acj}$a3I4wU z7A2R$G8&0fd4&SM(135|XXA!-V!lsROWKiYieDW?|BGjI0Q0WZHXSC7czzu_W6N%@l1^vM*v@cZ9d3X1s3ZX6u78- z+In!VoPo##2J1DFC3(j{dL~Jh!Yn~#HyJ2W%EKDis)CrK5R(w$Utehp>(z>eRN&IW zMc7pIJ(&)q&WdtpivX_JNNq&6%*6>LgQd;T#Uw4=fN(FB3>De{^hq29MC9aWBFj=C zUnc)IM4IXOEE+OkaH?vQz;RAHx4dutmbqWKU@N4Vi*XX<%C%1D2l)B>;&aTMuBdBA%C24Pybk0d%=bM6W9d6GOv$f)n>Xp5L1 zmJw^fdY()YXMLttyhHwFV>d=BX=0GIn7%TKb@Y-UO*F3o3IxGj(w|)BDyDL0Q)j4` z5|CHjN1)HxXT~1&m9s7}1C~welip}tm0=c9GXNrGf@ZU7VNWcUvCkO$#FY!Z>NRzJ z-M}H^meYC3$Wd>TbOEH}xmXDWwx&EGCcdG!C&;GOV)WireMC1Z>Ztg9gmBT0fkn7%iS=W&3MNb_jaICc(?){?9 zVa3v?1Rz-#Fj=e@lT;5=VdKcbz3$l2y;|R}STJcP8IN`PxWGH>M5c77PYS3Lo4A-Z zGcTQMYYL^Dubfz|XEnI}N?~lKetr8ld#6#z1z*TxeS0@xlg)-a!-@ceaNcj&m>F)` ztQ*DTQjnmJanP{wZuYegxYh4Gqcve_rqqNjF7|5NiwA^UyZU|u+^JK?^^7DyKFTS& zCjty42%|(o001BWNklJzB!X4O$bM`L1C$WYC3^8W=Mv7(|b+3tq z9i45Gvf_Ntb4{*g_Y|dzpYQ0|SB@)DD&@psiZz3VPY~m|Wt|myLRjTbnbK)r3m}`= zXt@fbOZZ*lEMMfboDY4Z+=qf{v9PRiiP#XmcE+FIR_mbY9sJ|pl4vT}uu*chGA6Ui@K3KF%nF5nMh~gI= z^9*?z4{R8cYgJ?4PbJ%P52urnhQ8_=1y7BoP|{&;szyRtfaGTyMG(m-_`dpkI@=xQ z0vyB16Ngd?2M9R3uHn&8=6M;?6Ex6Goa@f!}6w(;oQ z3QGHY!G(lG&VS+B+1h5)h4GPPeod|Q9`b)!{rho2l9JMM+SaPL7kb1(l9_iUeX^8Z zFoR9}UM^UK9ctOTMTtA?5d(~|OXuH*T6T!p2@>`=fr-tadi%_T*{|vNpPcp78)h;3 z@ccU(z7uVyx%*6P$6t`Wwhyp%gBqjG)%0OzT2~5oJd+zFWJ#~H9+#Y>@*t$PZ$Ghq zBr%xBVDSz>1fUbw0PZ~7%!GqogbfGzt z&+Xf@!EIjshIcKswWP5}{Rg@+ldlkqj@*+ZKRl~qXDg}&e8)|_QlCSgA}pQcz22OM zYl)O|%%s@@f9u|VCFyk((DQ6PpM#;yrqyo<j$aZxyYTV9 zb-T8$^hE|8tymfidgk5ndCC7?di1Yl9wgS$o2yaSoqgT?ZuZ>!+*=F3@0P#uQ`bSS zm@f!%JUqKs-S}xYe#%vD;S+zWp0lvG1;9u_=!Sc~pwiuQ5C6G4w0D~rOG~_&DeJ^u zGV6{co%aFA83T@I0nAo~n||4??%Laa!M(fq5x4Y}A8Oy=KY%7a1OtbSbJyMapY(4) zIQf79&3YA)?LK0@R_0F9OLy#m01bVyjCBB1QcMqnJ7C+WWL_mcRM9 z$;3V59YRtlig4YKiSk)BRehv_vU5C^FY(VIE%IWkSDJ+V$ERU_w3?|DLZM$Su4PW_ z`$?`REm$6q@|rL^T5~Zm`zxz($;^X zG=;n-#A8X|DTawzH#sp9XdLyKgUYe;`K&vRamVK6Ry^+xko~N|VpR0D6sv?pCdtN% z7~J%v`q5`}T|lsSHjV{LR+MgrjD zPl6qZF0vOHL3mcvjsaXr?pq#%9l`t1RByzO zuaNmzA(@Q-yKK-Sa2N(D2ZoW~Mfzp05A>q1t|r09?weKKEFlOC0@sLZg0`P)$wmnK zE0d#>M-=GAB-@VKt6-LFoS~9y+jQ~E8x{`iOMRnk?&*u68lM;7eZ@I9+3oJ$oi$jD zVnXtqh41Bp#poWJA%_)SRQ!+>$ADmvhg%<4Wzzqod*tU{Y9MqceY@T;!9QEsYY|2c zgzK8^=dmkJ^3$Qj&6q`#JmQYmvTw7V8%zO;FNtnG0AYdOO5G26i`N*)> z(Ynbc8+8r4Od335>`cu%J4}Bb^Yr>Q=>Cv!kua0&NI9WdsD6ejBVfE~4GA&7KVZ;k zC4KapVw{qs9X>g*=huLvu7@x1#e1LjRt#VI4Rj2rM}~It*kQRW*7j*|Q!ZH`gEGJn zvRpva+T|}NGDtJsXjCf$#W)%8)b`c*s=oaODE4FQVe{oM#h{qirq^&i>2IS~7Dq$g zgV?Va?Qb2=%jB8!-JBafuF*PtHv529zke1fQjVH1O9>hU#R<0QC@9&J1_G`E{_Ug|E>)Ji}Y3=+P_m0 zW%fIqN$1?~NsZD#61r~rLO=i5htje#jVi#A5{4Pmn;o0XuqH{4%ge>&+;ZQSl$^i( z*f-qK!+VlPNX68ON&#rV;_78DXe5WR%fA1VwOdu=uDSW=-Q)4lr4Kk7Yd`}9>G8uyyDgNze%nC%66Fh z#A`jy6?%RtBJA3-B9S4RLdi3$T@=bX#DIz&Khvq0LGLhfd14U-Q7dHi)w!LPcSART z>^~4#v~^q{pXv!L`UP`t%wl)RVD15&4^Y)3SWGKER%vI`Fx_?x7^%(zGSJEg*@0Em zyexnOEi)uJe_--|bg-D4m={c~LVyX2#RH@)I1C`r?DW;!AwvSIESgl#=2sfqXvtIs zz>wgR$X9K?UBDOwm%e=)G;EfK+E~XvPZKNs*wrI3HC4}kA`w=@HdW=|i$qE$7G?Fts=B%m_oIC(sBoui+$zhqQY7r6&W zMQ|G=(J&Un%!$qgEG8_Mccm?Om2+YN_ZP6p@o!nbH0xe?mba-#u$VkVDfBQv5djaM zcn3U^e<*hCtpT3`MWr$F0Kzg{Ywhj0-=W7=qkNQHm}_LLoX|bZd2W5i-}6=Q*E9i( zwRLXrut`b`NY0Q8(X&XOG6@`;tVvW`l~~DK#1|I==rp_^ZBT{wfo}GSLQVPI0YcB0 z7c4OpW)t(lvK_nibtQX(46l5TwFmQdYTkS$`osV#)e=!zX^MubKCXr_JxBH@v(U_W z*DRx;0L96GR5037KmAdvSIv))G@i{)2yyhX}+?I7qWB_Ad_N?=4);A1Pe=71yfTGC{(|MGv6RyX^ zi{=UdtXuw)JARbDypwL(pz=kswt9Xj4U|Hxms9h={`SmBvqo^On+Zn^)R{Kcnxu4 z&is$LX|rz;1G;hbVrz4uuUfL`3bF5VuK$#znlC>Fle$Xk6u_5_EiBVoz2oD*r*q|; z01B9~VZsN%#-xX9GHT*%w|Cnbcly*3G5f4||o+ z3$Lu>gZsCelPkqIFWr~ALyWauae+mDpOG*p+t@q;I!!82IWJ)L& z-w(O>aWjl;BJZNeMJyvG!0b|pq-BUAl$r03r`WSFf6*H0 zC1DX*Fmsk5Q`N>r0$ya}?F|il)(hkU{$eicTI{330~3OZv4}Q{%|M|~cGYu1!fOGj zvdaE0>1jnp1}uha4GS3z1b9Qe-ft$xlCW|a#Ze`A&l6y`-#BQ9vMS?T{RX|bA;Kl-Q>;$KLed9UaoTNJF-^XXP27s+d zk$^cL_-xZRb};}y)}et#0}`h9=Xo>N{7M$2_5?0s01^rX<=E#>QliArX?j$P2KG!GDN=2V zmQx|cq0hWBKqyGKlFy9-dnV{=KBzU<>-#F6nDe7Hbh%!3X%ke#KlhVAHO9q?Gl`5o zZ;gW{?uAcFdfQ6*zF-t#bVa43*3h10B|k3JC{xxv^8O6o}fo?k&AVNP=1S zuz>;4gg6q4e|(0drz%iP)^iS{h3pnXEBZNY25>*ux1mX3g!_h>4zjv_0|rUzX32l6 zu|>>z>*#b1je{jW1$Z;wLgs1Sp_^;KH6A@-wi`8ZmY2{jww~y4f2CsSCn+Z9ylulf zia-1=*Mub4z+|(Vg4t1Rom;)~#9~V9Se^kIpilp8Z{IcsFbeCOwpL_e&AGxIqf8cvF{rDc&rGnpe zxBh|~H|;7psABdL5@=&vyIlW)!`&_S{+4G>RimplD!*K5N0=$a6kUN zKNPEjG#+rKeYUbjGGv&?U0YYFpOM%BAOS#7h@`+UY36k@*m-}+<8H;<&$ue~;1fto zPud<|Ug54-@G-}EEq?Bw-LlsnmaiS_g=@=t21wj`-NCQQG^z5d*{+~I?Jto_EvpR_P+1wQ1jn6>dda2yn; zOOo&>g{Cwvh5aE57Co8b6$1e*+IDI=6QhyDf6Ed-eP59^%*z|L)}#Nvh2 zi=qnam_BC|N64uA)YZGwCy}bQm^qak^Zj0ARZ``3VW0ClX)|hr7^tdoRTb5)ysBCz zKL9yEB)}XX*>6Cz?laea&-T^s&6mC_22#wScd?b)z&o%?{tSTj4&d}SQ}jg1z;RJ9 zs;%ws1`QkMHm`k4F{WFvZpm0S$evdqm$RS$jKN}jVjn25m`L5CKEh(=6NNUx7|_^; zW4p0ce!RPs?DB0mCl9W`2}6N>GqeC>yoY<4M3DOBeeU^SOiM@*F4Rj(0gHu!q6IyG zomGb{0fsRIh*ehdcU-5K)9Aq@R?G?xo`LiXqok-_;$+o)OPKBZ*86DEPe5d)0#c4@ zEStRfhgHFb*@#`8Ubbq<6IDYB2sTQ?f@F|ccn;6csj@`KDsL1Q3MXH^S);{@3;7IV zDisZ~QjT2)HQw~W{z@PWOp^gd)~d0I$Syc{1CH(O#{6{v8r5fGU@_@y^ouO?GltEK z{ugsFGyCl`T~=w0H<5x;!|0?eckc$6Wuj6KOqA_z_8ZY>P>n?5MRK}t*M_v`GMfeG z1Fl{K_W;yFys)I#)+I^0B~wZ0u{ma%Yso=)8IPA@hwB>>HHr~1wze-@?`gsHQm9B5 zf3MK_loF?MuBnZF7_Z7bU^N34VI9RRHfbYfv<=LbD)CVzI!TOrbN_n?cFFq(B}nc% zlN{Z<-+{;!Tf*>XoIb4}s5Ps-CS8|7c4cB*V{Oge-Y46h5woRd&sgjp8E|L%rzQH5 zb4n^`0MuM9bCQhMR4TIz`K2DpVg9^ze};}X=2w7yr#pfvgN9D0uHBh6B$Y>n26p47 z$uS++yH!b1k6+lD1LfE|HrgY^4++XF9|>V=e=@gPD_6zCZl{qAkJo zZ_c%qnT^frCHWjUbetPHVzR4m9O91b-{H1yd|Na90E-lcNjgo!S1Y!Ff#}>t*g#^p z4AcNIj2Dok&gS~@`n@~XYW;FQ-u*h@NCy*%%scR z)G=jbeCRrk9%w3_uR7Aer#igLTiuQ<@>p-Zu+#FcIl0BNJXN` zJ=H#{;$x>qFc>6-&G83Y#y#>3aKM3+N}?MS^NC+Kl++G(6Y^DlJ*^- zaV`{}7*TT9r~W_y=BXe2slE@O3ht;p+hZnQ=5BxRKWi)nKwD!|kWBiRhGXlDId{0Z zH-E;hc>8G?t?=0tyBJYIL4jfftTny2hY##fkDM7Uwdu2u9o;Vw%W>07d-C`JF=jB@ z4UI$Gj5&8{SUpl^);#BN?QNga7>2hO{m^DsQxMFFvnni9R=Ii#u~jt!-D1go+z5|b zZjme#KcX>PX@h~8K`C$W#pmQ_x}C;48mnobd_eQabaa+iP8g=PA_B2)%#=B9^temh zyKg=!7LuZXOt{*a&)lX$mH{%$wKdPM^@ORAB;O6sc&O-wj61hUBn8$<$nj=V^zNH1 z7Q@2+GKAu}UAJ

uf!3N~~m7wVu{wFAX_9*BB!sWZm@x25HUg+p$jIbJ*yqZqu4K z)t78+a@4A0iAOdH#`|k8@`)bv`kx^<%srM|M)lmlVs~end%;RbR?K=hmMs;o;1>MY zXd{bHGNTKRD!@d4$ zEtNvo$S2MkKwecV)=-se|9achEYY)ml2AH}!Hm5#0gpZvG8?l|_g`ll5V~0xzIc~> zZutBV^!QZ)I|Xekc&O^`SwsVe0X!N|G_cqqfY{LvvuI2s1CwTkQF@3z3yj8t<2E zu*hN5<3jbbrjIs7dMJX_Mb8BrC&{VsAJxtdTZ_Jj%;vzsoG|0CEgI|{;7W-XqdTxz zYAj0FFng|ecAAHc6Idkq%g9j0EM~#t!F|TuBujMuKtkD1KW!{qi%IPpl4x(gFPoV!fsW%Vi&CEs^RNhBy0i!AerW4jY z9Wu^3M1G3HD5e<4jvjF9-g`+&wIqQ8;g-K~uj={@baQY1c{gVA7D74yzbTqepkQp|J@PfJ4N2mq z;;}to+~hfW4f5g_ANy14+!bJY$1mzy>B!|uh${>H6d`m8?&S|)7lRaIpl zchh~psZk_Pe*cdo9}M0Jrrzij5WD@s|67do6W{wow;yJg^;c6T2_n6A%-NfJ>t|hg zd6ir7*5k?rX}N&K;DNxtdj);#x;p`JJ_kB0cm_O3H>S-yP1#{?2#g86)k?_3`of~}9!Tw}d9 zDw%a??-%ufD{h8!@jnad5Wm+(73u8pctr!x7=~Wsrp|H44()flcdS<4684)kPl+>K z1Aa)?8=6PBfz6}T_bsrvbDd0u#!Q^;_V2N|t$bfSm`HYm(ks^s#e?-Mekn1a=k6^r zK>T+Ei}BH)y9~9vYmuA0l#sCGgT=E*n9?K3Ffy1&^`p)TF1z_*sxEcNHXPlA1Cbih-xh-~pr=qsZS$-m9vt z5>(|GN9)nD3cIm;CPh`HKbX!Wbps11p}E?6EAnAtK7K2cjDZK7#E^R&Y6>!ch@{17 zaPdj3XCs)qLmvuNs36Sr=k zv}7@AuP-l~RP%_5u4&*%Rk4p9A(_ni%u>N(fgl|=U#sHNM_a4D89*u@L@yt`QUFLB zOOaM>*=Qsy4Qnnbrh4^5030D%4x42uSD~lEMebtj?)6^M#C_!aG=FNqU`uX~A9gK! zHmXO=WT@7&NI?Q8R6qwCurU;AA54&P8dy{b$j++Jah0%7B$p)YF#!bm*{BqhjD5F0 z9Rokc465+rrJ~li8{~O9puA&BKyLidhc)FZ=SdRO!@Y_@bV3{!JKt{Zkr{-+W-1=4cn_;IeV z+qibxko(Zf#p|pfL(%5qId`k~Z~e+eZspRaWsVXYwyg-lsGV7w(a5nfE&>G#fE30I z$5z0=luND`YeA3Y?(M5>Mxtjk_VZ+Krn(Y>1qwS+*GJctI@d72_xTBsp zvftDl9j$Kv-p%gh(Srh;$T0WpSmR!K;_oHtHkZn9M=IRxxgS>V zFhQb9JION-{fX{ZX!8k7{IF3MxmzFnT``3VpZo^_ZZT19HUpMp<~6r}?7t|sJon?T zX?A8sRh5sUHcAAi&D&rVSHJFFc=WGiW)mwKSSQ?r8$R>}UB5S;|5p`P*eB_igjqC) z&a2%G_x!q?ZeM-&o7(S@l2T}(SCsp9(dDoCplH_A3#oW+VfpU(W{zujh z`kIrtA4P2V4!iPL$@f4u^y`?yi^cMOh$hng*V0ebxEAnQZ6V9=^Pe0ds@`%n^ zZy915;WXsn7NiRQgcM3@`_JpY=x+0*V}iv53}x82%mu#Oi8XGI>p#Kcd#APZXoT#a}C`Yn8~b0kWA8 z(35259M?cz^*+j-96Q>L zaZF^Zj7$L}MgUaOrSd8@m7773XHtqVa`8PNQJ}#cc?vVn5~O~i7P6m7hZMDC_eRYG zObQE8EC_QxlXJ;Ep4{Lau|r}B{l8hiO4zDu41m~XF!=8Y}`bMoEdfxW$-mDGRl73^)g6vWNBhikB zx^T-k&}%;uFUMLq|W~)i?i~+qL<9_tq;vkhu$hNqu`A%(rWI z7hQInn|H_O-0F9pcZ;9+FfFZLchXCL~iz(0Et z#br66`_UV>-v2vp*qE8_$?yJ8w~e(G&o4Z4MpDC@KKw;!Pj$?1H9K6zIEw*^ z8ZPRsHjjqXdqZtlws3W?gOQ-MpIEyK&jpM-&j9N`{Ys0OT&s)c+@-mlu%+Y|V)_s5 z^&S#tZl_Ydk0t6U4WAv!{ZkodVX3J;KkQdIF)}Ia>qX^m{ zc?M9qTzQ3L?J&pu{ZPv`Nzq}1FQ4~Ojr8HUv4Xedh>Y?eR#MzzL>F-llPK;FMO1Q~ z(3(JjJQ+WhyC=kZad!p7pCPjt=WcoVDa+@a3~qWz`f_n~X`I5@{Z?ji`Qyrh3!~zb zd3EuzE4WjsrO&_ytY+xzj5BIjHzigLE>vQCf!{Y=yI?${{!VXZBY>C#6ak3HO974i z$G_RAYWUOlEe1KN#sH{t>X}M_der!Be>b}uPWTd1g!i9oaX)c&KH{X z=;bDwGl!XuXCWjV3Oxiih%Bw3o%6j&*HRicyaQfvD)kk+ur`zN7>NXxUPT+Y9{Lnb zdfK7E*RYChZTv}vng19=(&jom3(3EodN+-2G-jR6v|4~!8x}*5qd9TmwBt^L_}%~j z4?*z0qAJQNl0+nJ<~!#LRs=jaM{ml=3A4m-?b!I9s@%z3CI4H2k+6GP;5m+hw~9#m zFUT2v|3YRgMVVE?&tUA}3rs-O#eklCETLHymFG;8`Gj%ULxMu|nn{6`Oa zg!FqVT9yK)OS<5_c+pvaMOztV0*Qc?3|Kt0&&(o>M$I0GKR@C!Y#nA6B(oG%n6r2` zU=f3fQR8Q8w9)p>%hi);?0K1zEshVMg<;2}8P|!0V)TJ#vLyquEtX2!8IoM&W&NAo zu#r>TkkM0JM{BEFzha>~0DDIQ%3iIafH{tmsAHyb)lEMq5cAd)5njvts9oQQzwsWv;$y(V{9BaQtpcY0wlAW*D#ZjQ5#`21I5y6nc^UO z+_7o7+(H3WK@!XHVYb8h4jMjD4xl?XEl(U^0bYPQ_N1$B{y8^#;%xWYGv9P;-g_Zw ze+kbz#v9k&@p<+AEqwg%+{V?fCHFMcI2m|9|Bhc)lKa9>VFTatb-8qJAvw z{L)YUN(C6yTkiWE0feW1_$S^q)8xbI z!)3I`ka1!IF^@a?%nFzn6VgUcjE3lWW1PA3JCOivPW`^NPC&h ziL@J6U0hiK3YhUwAPCI%fB{40(oTVAMjNC$*!81E*{3Uw+xlXiU(1YDDV6dz0 zJ3z4xa~-K8H1oSn_k>~&;E`TeJRbCSMxUHIVWWYV4JiY-0&2vb_Pw9M-qbBv zSTqLaf-!{k7bc9NWTuq~Foa1okXWrh14x8fo zDZW%^lR&2e8ts6^-y-L^W-|)xvc!zO$}YAyRA!|< zh!XQcY*SD1qDZANuA>dGr==e{;H4OdYGkdMSl$)&1bewpc`{7Hwk zff7W$pCp%!G8O?CAy>rNQw3Q+>l0Zg#|Kja@R&Sfp4++QeYa!td*)W1j3yzeG-uNW6)D+F@DBkR+1Gu;f5wnFWHk>*}?!>8Qz%Wu;> z#pO$$&~b!;?7R*a&bhaIR^x{jJ@pTo0ZFgE%>TTMmFs}%4F)+2pZI^=ns;9iXg|{d z$d_f5B%&~e(=NTqJ^z#c?KZA@J=sG;nvdFK{@uUg#!tP*EqeMN-RgIqGw>G0GFWPQ zBDw$1{pio#hLx`+Gn+B23Ns#I3;}45f9HQ_ZKbTYtwYw)Z6E#5uBmynn8&@l*K5s$ z_=9sUpz`MXza#+n+{0f}lFxs^Kqribxtf`iGv~XNZ$IretXeE^H+A;SerD!k^}Jp> z_g<}y&1;vq*Pr_rNouWcy+SdQqQ)gx-{U4tzs@ar@!M|S?oDDf>APbc0z&AkWF9B6 z@o>v7*UtTnW zS+L0c9W(I?jSSkkb!Acn$i!YBGc9sjk0#fNo^76Gm}RaVU=hP2iY_C@&Jat@*q_kj zNpS^7R{B;cWYPDGA^~QSq7KiZdYaY7hR4NGvBfZv6lb_!8l80NglCJ9EYl0wu4hOX zLyoat72`pCjA=^RQ_k{5|L$Os)=|u2_$t6`h4Znv8}dV++Nv;R#i{h_ zdP!5%r<}beIlD-yfUw7fkd;9N5S7H6Qb2kspK&%|(I>l9#7TJi)b&ecsE06$q2Occ zm|VEdAyEL~_b8|^B7l1;iFp8u;gaTn#RTA&0WO*)J%y=)RUx?!$r6ADh6k|7=TK=! zaz}q3R{NNuD6V@aYAd{0k&1Oj&k((LtS{J(!!0{CDuP4{GZExoBv?pq`CXWuIX8St z#w?h_04&9bHw-o-5$6P`Io`hgngv#2KsC>8K(o&M*x?o>%X}tMyzLv7$z3*G%629B zEL>fQ3xFlYTLb{F4WrCn16V?hLZ2c)GSerHzu3y|Nry z$4*RKjp zz4Ykc=zfGkXxMwkO}$d1C%BgjpZq)5hMAj}k(f z+U%P(D{{@dFS=Ks`6tC5#qq@FphDMp{+++5*KiF(Ke*(XzL3W_i<|EKqFb@_DYy8! ze@S})=`o{Mue?IzG+;tEuX$bLNHCj0>KoKG9NLhPQ`}vj{BP<@-LUdiNv~Pktg}7a z*Qh9o1b6VrDUv9^_}Dkx;r-i9zDh5qstDz7=m zn*~n9D3Twv3&@jK01gKYpQILpV@LP-0;?rP^aHa8GT(FW&h>8V`nOa-g!0D{ffxS3j&^;7|XeHZFtr(;6ecf zkfUfu8%5KQv5FZhx^xn_J3>P6#m@nJl`t<3qcp`UQ-{*>}FY$zRAQFO+ zF{e&yd~goiq%yH2&-WcJwW8|H8o-t19(KT3SdNbis?-{V#CY{!aT-MQ4M>B z(p7&Sdy}B`E{98n5lK>zq^VY3_lo_f)Si=^_WG(v0I=xqru}UpuqwBX)?C;O0kz0a z`NHK?{f7WX-;ZdlB1|d0ipDIqw$gx4FNCp+t*r(it=F+jPN*belC{b$wcSYDmf;Rz~F{z zDTxc4ZGFFiVuI+AN@S?TE^x*jHI+%)@bfS<+RwW6L&%f9N9B^1jN2vjCRcIwHGFPS zmewvx<~nw_7~%xSD@%G4i%MFv=Li;I?&!--dKUA*VhR_-dQ~s#pwX^j;4lr-#*BvE zsl2b~*pm2MRw3!}=t(e&^={*;R|RyC>{EFcK$RT6!-GZK73t5~BW7afmgR2ShGmH~ zJeX%08``D!hPh(sH;EJLtER5Mk~jbzgVd4fSz>%xu?gG!>6hIq@CN(Vr%ykfpJwB> zwd&XyZ9#IqYujqKf9Ey2;nuHMr1$c*4_y~zhe!)?_(a;a@QJ^3Th}j*3Qq=Lkey!t zp4(1R_U%|B zsi(l=r1_?g{HCj`>+cpm^$&8G1?(gyEn>KayIb!2Z8u=x zaQEo9|G@3pw#FOibh$3?CQMAa?SU^#;`!KjzM}i8ktjZfQA8k7$N9B+$QUt?7_vx$ z>5EicOA`DAANo~EfuH>T|8j@+Z&Lw;eJ-$_0He$2J?JjE<{tObPyX6%T>ZKV3(UKO zi8DaOn6PTG{ea)sU;H<%ErH}tyaG-OU|oFWo$j)EA9YJ!`i^^h(T~J7Vo-Hp-*!nU z0p1i!ZvWVSb<19V#J%y{w`88f?`rn5@~J*rW4PneE6aJYmg(`VqED3>tmRd%s!yGY z-mq>qxAC|El9R{8Mp9V7R0t-L!UpRJM`eziI7c1iHar(wjDZo|jS6tjo9kw&5A?u&MCnb1a` zXJ=QJ8#Z#P>)$w7?Kd!p^jZU+#Vn4Q;kIvn&mBFmJN@K>iXl@K3DbB5BI|(Xf;|#r zBnn2|oC#o2bP$4XGJ}m{T?&vAx?E$ z7%#Nnl$bPMa2YBO3Ja*ZPhVNfQ=PxyV9^H*`y;=;-hF~=$);{bM_bZI5&E0Lu_y0w zmdRfl)Dm*Mpu=ZL2}d`{S#KE7LO_wX4kkAI3FuRQqL-Qi3IT|GucpTTJ(8muvlvEb zYn@ zYMrGa)4-w?F~UqWjmq$n)W8%91j+>!Cb2`nu&u4t|7i?kU>iF+&ImlhFsg?U(8w4K z-osaiL-8c^a(SvW0KMH}x z(4S{uF-ImJN|NCj3D1_;3oreYnvmzthKF0PkC}KVDLr#WERVoqWtF5m2lirya!}P~ z`j>31#u-U%T6S$xFG#`1Bd}b-xi7xD1+GCV{kLO@S*=(eWh#gWL`Q%(djri3CH*R) zOqmN7!~EY;?`==9sGFY`Q%odsNU?iOlGh;@jKN~uvsmbyW3UKI2UtXYmDfv?0~U?- zYnGV`v(?tGTBKx3J?K@n=7j6bG+0*vw#GptR5d60nSR;rVkKY!%w)sZfpAU$2|yw& z7gFaf>z8WCI|eoN{hCy;;#>g;umPMizu!1`lwuV#?&xW>M661Ege1$jo?=#Wc>fN! zWy9N&rUKMpb&j;`bd@!=V(0*qtZyWQs3|C9YObw26nR^x!0fnSGVe&XA*XIvehMH_kvGUsYx}x6^FAus<68@V z;NDsMuv9bJM|{s7rY4xxTr}$@_4B>I3oV$F%$K9-}?-irC{H>>4bxo~e3+s)2gQR)ljCpR>)%S=og8@d$OEDq%6ads_ zTycj+fV}_a<8mdXI2np|76;4S^viB>3-10^xBQLA+-uMNvwGF6m}JE;t^vJ@u$;(7 z7xNl#(v!$B%gQw~@YV;uB*)tq9{Ef4?D2W9bASrs9L7L*eC)q!&f??W{)*z?l$rB2 z>V(;v%r>p>+o=9UEeD^4-|gSK$(=q9Ykx-lu-DxB8P}(7fP3->|4XAu=>4Wm z0&t3Kv`=llyXCa`dN_0zt}*rWP>xb4C~Vzfk0WPg2T`{`41$31>@zhwLrWLcMT z=0AB%tT8c+b=iu5gkp~?E9Z8)DWLHwTQ82UJNaoIqX<|OI5dD5 z|B3Ud$y4pm#68vbJQ_eOH&)Rb=a}YSg3bbx%N{>NCtRRePn*;O{9V|spg#8TvMy$`|%d8+?#sY z$QA3wwE2QcJeo&pz7~?FmVH~aX_2rE9y!VNN9yNb77qz@NQPQyBkd(v^oZ3PpV&}) z`yYP~{KH`3BP5CG*d2P>WJ=zc;ff-5T*4C)^F9^6tH^^$IW@fQ^bi#80N zdq<)JFkyTP^0I?1JKQnPEC#kY>G09W2OFARRbAtI7KaHW?%Tb=X2=H0C7W>>sH><{ zUk;`&B&8ePf7$KdyG3h>;;Q88r;aBegtZ6w%7Vq)#LDayYgZvzUMLVEafhv>my7ka znc?+Y-d7T2uGwagLVpo62RW9$4THogFa`vM2B5)xCK1*U`mQtj9T+dxH9!?9E3b!5 zL8eZB5DYnN4h$Evb>=b#!x5QEa za0mBpbGx>_ucXe#71;XWvxkhBBxY&DibZbGQ~zlFUVM3w1A|18f6Wb_cAGaW)oWl< z(>P)CH341o@BC#M#NZ|hD-m2M^>(hzjlbv`cjLXk?)L6jr-iZ5*8l(@07*naR9-yE zA^n#mm}O;RWpDiO7v1iytKCbF{f$hlc(mdXW5dSGaJSt5Ww~TN^TR)pwA2pSVk+my zI=ubkzb85JGY@^$dc_(2(9!8CtE+W9Lq|<@H{AOhGD@T85t9~JX+V9r$FPZaeEjzu zy@XGE_kU`<2&^;fDKIz0q`N-(2V%A#`_6xtG*o^V9t3OlUcZ6vwg-P#qg#IZ?LW}` zyr2~d{pR$$!OmfL^!UI1cS&bql~@PFG44HV-gUQs-d%dly&7x6Y(WxxOoytgYu)>A zJtc?eQ4?pm%dh*W%#4=5@u=(HG)x5n`YV?$dRQzz&(0MKKH*ls^Q>F)^7mBiV62Ru z8!3a@)H8d}r@!L%>{#a>{kK1m95G2dG-j+^toTPh^CyyqKKxH#mQ>PQJMH=AIx#Bd zwg-OK4H-GrJ^tOVXygdJtH@cANphVj1Tu@15imHnDmGy1*V*pcPM>nej~&o#UDhaU z`g^bcRHimClC&MDKT-u5dH`uZFvg2m!E-A%wW>CfX-9#@KR7Xio&MASza>1$T}$J) zkAD<=kd|Yx!yX@hNf{XS){G*n(-aH+2g%$9CYXDTLoTB*c-CP7hmM-!wr^T)&sBl< zIqUGA6ntRitCEZ%{!Es(=8px;?H!l9OJYNcK!hgu6vQ zA4V%{hdUJ=Pa%}|&v(gV>lIkaJi!ev@ zx3%ouqC}8uIB3KqCGETio7MhZ8?_Nn@Dj{(XMb`iVk&REi&MyBAW~*CM3526=pk91g2sSvj&Jk!iOA`>q8GGJ(r=E zk}(?0LgZSmeeWfA_~0%_1`y0a07XbS>3!oq;Gk+fpa!Udl|F!naS~i}dIx!4!Zi$) zK;&ihTb7)92|DZ$*NTxGNSS#JhF}8R+I-Ae8(;z`WgL;_F0Osk=KF>54CUpnx~kS) zbL(g2O#1Spf9=+6X0wefRb&KeX}?1uXx(@+@C`^*wIh?Vl6iTJq9&lf>6BIdROnDVN?LC)EurUUSd? z_-o0a`%n-k76O#-{P=&Bv*%;q{)*0t9z=TIC>9{q9XMp1yYmyjuk-lnw|-Aa`bC%B zEcqjSlpGg^FeArZ;+ls}a7$nLfedfBMwmY_M&rFDk0~ZHD|6hGtK8E+_+yQ1(Y*+c zzyP3%a?R4jAP6wM?A0I3Fh~_!AAg8FV<*pXANurH#PDJeq_z-0cauv1zy$2v_X~ff zKJrKZ^}iYM;n`%KJ;~Sm^w(OW;P>+5-_X6DF#TFdS#4fxr`Sl=5N!Ltoon62SA9s= zm%eovR+ulq2>_exK^&n7z~2Fz+Ed!CH!>7Wgn4{i3O$b5K$s5}jV-n>OWn&f=7eV# z`89JqGhg8?!Y}wAQZz!=J8 zTfGg{SkoL^PhI$4EMc&UJZ@~>!6?4KC4zxaH@TqaoG_O?e@Y0V!FYz>$d{i260IK* z$qm3Tu!^;{u!|-~O$=^e6=4&RuU49qsvOg(`bTmZ4l|ckjGYm?V-|Zpv;VlSNWr3i z5|#YkfgE27(^ztFNN zrO*&P|1n(j5yxUm(l?j$A>q0eVCHgVu(~GRO;W~8e#D3K%%N4UWqIjkw z`{^m$=645eCM4k`7WAV577y&-?v5YEM5W6$43vB1`;Fbj^g$*%1Ba`3?Zk;gZswdjHSnCz3l7DsE9M?fx%7HH zpX=XWC~039+@4T($y!SHZaou9va95D+B{^e*cRo9T~0mL{2OT;EG$e4U{1Y6bq&T; zBK_)X>;lF!#7-*oZ5Zjaos{z{@>2lg#+8fR_D##QR{=JdfhT!oza}?++SN+na1lMY zf2&EmZDUh{#%E2wc)q{~Ml>5%zM^#(Cu}fQfFMB3t55$Qx8kiQy^}^w-jKO^bK3T z8qX6m4j0_@E0S_@Ogt6ZUpm?ZEV=e$CeG5V$Q_&Bb+0_}cN$#o=}FhYoWiOaF=n^k z|0TC)=Q{WNkN>wAERu6rWVy|r>2!mKPjYvB;`env030NMHdNlujW48}Fpm_&p7`$n z5UZ4`2W(HIKl7IRzvPCFo+c;NjjQ~)k)+^5B3>*^1SMMUQN#`E72z`o-8PwG99EDsqz*^QlYr5iSSs*IPmu7BG=pzBf*2PS&Q z=H*&*0Mo-QyWO)7|Cy3`VcRYPQCx4<=v|-qeOKQw*gf*i-xXtO>JS?*L~aJt33z9I z=M&%iLzxYQu@%9zh=0$z_9J3VStD=0_#O2+%5B&e1CXs!pt<4RFS>2(-qMJZ!9&Np znOENJc5h$hc5Ysw91YL}L;cR8hsAtOoOzuXQ$CA5mGhF}PTxj>FbsA8i+~gQKiLli zERP>j0R}(=f9a8B=j=$9P?bm3s@l#$#AL6Kw;hEU% zpG7_&S$gBZ;R0mzU&0RC?8R~^X)w5<7nIQ_7Yr==W6dp)7tMEk5t!!%pic~M9Bi)E zujY|D0)L1SjEt%2tcfr1T~eR8dx;I7^@bEnp7~(WOEpqt~6Id1x90Nd*(TxXs z8l~aqEz-Bx?m;48@w8_aF}pbhyGUQ-X>Wi7yNHyPf&ApI~Ea_d0Mq`-t zDg+(dI(u5>wsDf&dm|GSw=GHN>30jUA-or68O&ZgdU&7Pw_}}pLgMHBoWNov&&VvV z7=%PW$Onu0kTLy^0m1ZnNC(_Yt`%4_FO5u!S7LrUH5*KF(#RDvKE_0vsBd<^&H)Pa zp3#3q&lOd7=5PT(2M!t|K)~_PV}_XriDJQcm^pwV&p|P;SV94=AOQFGA}h&ErK&!P zd*B((`_ggvvj_>Mm+knTg!tz4tS&hlu;@P_*+>0t3Y$6WIDkbG1QN9ayEm(vp9KZ> z9Fouh7CC+xJ4`hw1OW1JIK)84mV*S_#^jVaNuuZ>98f+cVBK z*v4cKIcEfjAV5e0B$RW`>fHUlf9-Q_-Kwq*!oc{wNBff{x~r@1J@os7c+HDYAE?r2kH}CE0?5ST4R{W#JPZ!Jd(i1mH(oIrY<0rXnsg0X_ zoJ~9C5?eIy8M$)0B-EdWn3cj}v9E`p@-OaMde5)LC`2b&vAl&vHe&2SGQQcoafLm8 z*Dr17woO)0bd+XMtzkn3-MLrj~;`9@) zP(lGv`pUC2g2*=j<#2CP54%A1dH|popSUrpQ;YjLAOa&6+HTO21n?>#k<=SA+|6o} zamq#iZtGSrum^7bp=8A{HGtSH>sJcIS9R-cC!PNd1?Bf#|1Dd)9A@nljoqxr{-!!@ zT3$>);iJ~G&k)IzwKq03N)AZC4pUCQzWok9(+)ZQ3MC5W&weP8C#$YDY=@)wIZS~1 zjaMGg>zts->`Tm1fWa9b{+^h6OnahBY>;S)L8SH1^W<7C(HPzRNbsInVSS44OgFLrh z{f67Y$9+V=AC`}Cq<17h3^2*HH8)X)Rw_21JqNanzcFs{ruNlVvwNrhjw~5-2Ss9J z)uWnp@g@PmzC+(c#vZBj_RXt9?XasT0MhH% zER<`qpi|gW-ccyo&M$QYXXzT0{B@%}Pa^nwkKnMRyuvE0dZ@0P^~JnJX3O`egCuFA zL{D99=moh;ZqCs`SHOPPb}^FdPe_bOFvmIgo`J>8CYRp#{lT>x{O#!zc^AQAcoGhr zp!6l54fgG#ZmI8yT@_kR&yHpx(i7xeACEm4zsx4<65&{Ao@tX2+F!JgpO#s9d8w6` zmj?&bjL}W3S4=yg@^23?oJCApWu#-(+^lvxf$SdK=KK57J;aI~xwz~NC9#AIftt_5 zmfQgXAXTwOa6BY9q_z^ah~ER?ty(%)^`{XmGBa@g zgfSyvf8wrRsSXdoD~68Q+t4T`^w1NoupuKS*%SBvTJ@7+a_N0(&6*?pd)iSK+r(+7 z*;DuZ)?R<{zQm|TfU~$n<2_;OiIPpe`s^L{;*&RejcG6!f|V^OqIJi?cJ%50s(QYe z5B@>(k1^T0d6jBQS&PVAVGP+{?z{0C+qrFhmeV6sty`}lcIw6du5r2ZFIUUKGOn4Fz^?Ev5dj=WebAcjS9u4GPhK|0u7NfPGQX_tIg zb9KhGUzfCzxdV8LJ&XB#p4*6V2Rmc9@WoI&o{@(09LG#NQmsH}1Aedm9hc+|}0zbRsK-2?JD$jjXGd=@j4+lO_Nx^_H-}7-muXnf(=FjhyddZo_k= zFKboTp4L!TXX{qIrF9ouY$4Id9T$+F0gJJ2z9Z4vp1mfMylwj|Rw^!-y|p-FV>}bi z7Ee~WBdZ(dbl1A)8KT1Ancy<5wXS23Qo%a8=I+?GPWu?ofm&CQslz$tyW#J6vc!O8(MX~s9+V{Vo({allM zFMu5asVG+yTS!vMGR$FQm7?6;<-ehRNB<7sC)B3JU^&@q(qJ(!K*`I;MKqBu0t_B{fNdotN`pGkWxT`P%$j(nuM4kB#~>Oa+{6J@#?kPhms z^CQJRW_>_v7Gw=^=Jm(4>Z{hJQIRk%t5;J7+|kFbE~~Q_ZbDfa-yuIhN#ZE^c-M^9DlhQgkv&; zvtu-2k#eJ;S-=}+YRIT5HuIrB*}Rt@^nEfUHHcFfbAa2#X{Xu?Pu^&+K08A|fpLlq zCNUX345uG^nZ5DKqxRgR*Ll5a>>XE3Q}JROG;Cj)(I6Ryon)Rcci01B(ibP*W6t@q z&Hz9OwO?*Xc-fQ0@?3gpZC}1kXp2X#s*rQm00JEY~FLep) z{Q;QrOt~(e83r!Y=^cOGRWe7yXoh+{z#}bDUVZ)!F`}@~Qw}{>y$@+2vwE33m%_w$ z?%rE#k>?8lJocv)Huq&UVb1 z|7t@<>}NOs{)-`@P^2UPtXTw}$dqAVAG`CvY~ITcg?R!4McX&ZQtE8b@O|vGOTMGp zNo2u*N93Z_yLVV=d4-jhRNCHCkC#c+GY|ejrak~Z?wh)3z#`X(gmL_&W35Nup*Hu0 z`!rv)XQ{^2W!BA&O_EL1%kquc58LdSx9RIpjS~k*L;KP0em= zsNH3|c5buXyEfbQE$e+xDX+3+3tsZqwurl0f<+i*YU(+&s96L=!KP6@!C9($`(~4= z40|77k)OSntfKE}A(9AqskO3(HZeo`+>2_g94{93QYE}fE3}s}-(8;H+q!n|6C7Dl zT6kYbuEU*yx4U9xPh_Y`Fc>ZTo6R@O!eVWJ(KJBzFLKEWXgo3s;SJssuowobL(E<) zU@`t~%y`7&TV;XhAEN-d&>4`nz+%=xl%U9*a3V8F-qrEwNK_P`L(D=1V~jMbDEX<{ zUS#?xM#s}AKZRBFTEz^jhyf0g)l6STjBPk{bJ)Z^1c|wF;XSy`_x`2%l2~!``Uk*a z3+5}c09)KsE@*ToQ?G?^z=%sApwGdd*hHAcG+?Z$5u=y@#=1JaUVRt?y9n4cBVmF8 zjwnol(kPGcND(`|JU5<)5sIv14B{d)mjEA+>N5A+QLq?(kAob?G=e6iHmu=j*Pje$ zsPD^SF!BZQsq4>WdXp)T$QAwkN*oHs!~g_CE?n-81k|OOpeWRv%6x`CRk5);rVVMw z(~bb5_Qt7$z!*S5z(6nzyS#PNN@d;~0$2pBkbx%9h_0ILGK=s1ip;?kDdU!y$jqHn zssDDs6IzG_CNF{uZ%vTmWuq;6mToxp@%g}F2kt*IlQEI!0SimP!4!d?%!hEQEvr<} zgOexHF%JqGLqaoLZO(PhOEpLX7o@_^*{y70MWQ>@O zz=Zq0nuhoEtFk4Ndh{R$6J}_dmf7KK4?z08#B+QHfZM-MhDmedTND zm;>yj^S`E^fqWh;PcHM{v)^z#<-)5aYXwZ7 z6p{EYx9P{Z+!a%w*I&F>>x9;BUAy%agT_75-sIS`zoOdGM{fU_0%**M=D+-q<_F`6 zR1tRa)o1UN1X-+QNtqhG!(anC0qQV;wBNwpbgDs~0_&_ZQfGj*6C1StIPH>exl`=lzNO@z_AC;+ zVlzv$k54`F0-Ju!W%kgmKe2hU9~85_dF@iMqDWS0m$L7)QCnkwc>O+~|oDJ^M?qwzT92|VirAlPnfAbG)-b)WC0VBU^6b~gOR%k`m zcgQ$9>+&DiswJ=4tIypfDJ5VXEAvJ&44JYH8>|Qqi{#jUspDQtbdX&b}CY zSTbpi_`OyG{rI5U3)VV3!`}G|GmN5xIlj`SHVLa(R+6es%*ao3>lLH>sro9a7~5+< z86N(vVafv%0Uh2MB8+2u?A$xQ<@e+_^Jc%_1+duiV#9nRi--&q)5n}mB7(*=SoG$) zE=!Gl7cses3?hKBS`yS+wb9_e`I&x>lWH``sl(NbmI{{iUQCQdf+0e(>9qs4GWX_i zQJMU}YQ&!@Q{PG@Lc0$#wK)zPwvRIN%MDfm#Q*>x07*naRNj6`3|MaBLC-H&9^1zC z`;StsOmc8>+HfW+6cUz#^$^;f#LdwI!`dJtc8BFQIKObHWXpM5yuLjKuDt;azYn0m zP9FA(;5A_uscGsxSTaZgKaO69J%vD$01F0**CV-$b;cgZyE=zJ zgMee?_(NoZf}srw9M~VgC=45prZ6(RoMOs#P=!HB6BH#;e`PMx}24{9Q-dL#|o zef+(K65vOzj`t|rkV)|7+fTyt2fUV*ceeGb7bwBzXJT5$;fkS{OeO|s1eCiNLgTK$ zJSYYTssV%CKe9d;G_I+#Gpq^*J6_L4tz~6ZPk}O+ncX|Kigk0QXS)KpsfS;nzj0Ar zx#$(OLXsI>U{qm(X?71le&qI_>%HQ&``*?hIX==-B(b#Qi0ov1W+W6*4vn93f=xgE zBXZlMXQKD`^IoiS-Yh6ktB4cN{i>~9G2b4&^OtJwE*T&7p45L@fpzaQM0Jr3_0{&^ ztv{AjlX*e{3U-RK1UBjD(?2IS(Fbq+ku91#(+Z1u{=@{%UNgVxDH3vK~LEIGTTCG{kDuC;uTYqe?zjUwG zc8squHsc-#kCqEp`CG zalgshR#TXOH9%_&44L{59xEWqoMF%0zI}sg^OOL?>!52d8!`4kTeIR#fkkcKDG!FY zFK2e__72ky{`}npi@6_}H{qVgOei5agJ~XSI^|WudF{5&@ZiuFEe}WlN|FT+YGN-h zt_9sSG&O&7@K6B!PYo8s!(oHP0=TYvS4yHvZz*4ZadERylo2WPeoieSfE1(HCRhv) zE|+_GKQU4anA5E?c(&@N$e$uNwJF2-w5(KMQGY7{Id2QNR+GPoe6oaPB_ zVDM{-^^(b5cN8p2#^%zsB%2)HB-uPu_ud|37JoOcvF2uTDeB%bXjs3>H~+j}tt4=g zngW?oL7wr~*mfa7PkV5iC{_ln;~C&cWg;m!US)DeDWkV6O)(%HXD&n#DXa{C9b2?$O(| zcfVPObjw=D{2AZSZ!>M=6j{q)hwqG!gO|(`4J=vuGZS!{+EDx;JxSzo_;vCea9`>10Bw8@Ts>sqVX zxh*78n)P|Oaq>5T7N1#Dy0lh|Nx0=Bl%CoRae^KR#< z{e*p@w6v3L04#<+gdN?ovsYx3SWy^R>Lgj)01eJV&)#$`z0sGJgRd#8$`?X#+xgBkDN;fnJB_&WyZY-@#+- zqzk?w8S#BL{)fgik!Xg!j=79%mc-zLxBO6yH2?tMs?X+)3}WaT3&@3~n|j#!Hh=cRV#fI$0C(^HBXnPKWTnkS=N?KhAd}?! zib~3D+R+!=#Dh+^$8P^Gd*ii7JcpxwA(UDa7E1DX>c!uZ6Y!%mel97jw+bm#97c>y zvIVD95(c;Z@ha8*GM9Ynd(aQaL(V+;kaO+68^5QyLVFq35eYpRo;5be+~u5){X{OU zIKjdoA*o%zc9B|~uvSNmou>Lh_LTLj7wPj#iR)wg74>nh6Jt7Vzhi9P><7epv&Y05 z@7Nxvva*|9_?chnncx1$s|1*{h!#{fMa6c+X`itPQ;xS8f4SOLE}j#Zb$@oKm5LR2 zH;0~;`wJ|tS@~v;0<|R-rCbgG;y@k0F2^-Hq%;^Xc$`&r?;}u8f|Ic(DFa!=oa@x3 zmyH~Mkia6z1IeLN`+RoETgn(spW}*zcl6Z;Sj=TLTfBenXSSi7$$OsVe0I8=Pl+4u zE3XVS$}ec}-GqB0%{5Df@+&L5+HM9`z{%@>;vq(Mi-J>LpQtqR4BUIcEG9EXGouv= zTmAe$^7u2srbrLH$Ry?FvC(_A-1W9gTsV&ovC%X1BBM%KgM?CZ=LmyS-j_5z_+ zW^EGK<}tOwphmqCk)Wn(5|dg*Kw~07&9uuzhA1HDS8+O*)@1EXl zTXv_x;yYSu|KI)6h+d_3>9p=vRpy!4tR#3?2dZ0aXw*yt+%@2CDk-W1KpEY{nnhT} zni{LFcF-txu|C!>0xs#bSfGZz1XBcrX+X*Yh%&LPhmodX^32!3EqYQWXOm0U6=g|N z+k4t6u*e}dc+_OQH$kxWr+i=SfW?IADP(@TRELZ%^O#_n747fsMf+-1AqTStjY|Ru zBM?Y2SXnzk>N+~YthNOfTfI;1FQH&w0aweh=i5k9Fc2YNLXN+6<0=_|5P-nM06HRA z#0-E#w`KiEdk^c~|9OiV_BNm7A-r$DLZfxn9<)WTQ%ehP^Y6cYeC8-i2k0M*k`KeTn@YOx+LLD8|4 z^P72ygs{B4v&+XD>gDKIL65QR8*TIYmDZ(4U+X_)yk3hb%C;@*+>J6_e~)RDYWUpz zM|SJhWaSlI1p=A-Ix{6bYYa>wX8@AWJ~sK#vjrRpJZb4btx@cKD$}L_YMlwoNQa{w z)X%J9u{Q*`4le!q_-l#;fSI$@A7Sn9^7yF8h)(9&lfl`-Le(-6aI1zXNa&(GKA!ox z31ThPP$Q%nqQJdLHC?#V5?3JW1;lWTm_+f6NVbqz;cr?EFh+nV)|vXLb?Iqk6=VCSmYs)i&(LC;~FIZK#zV_(tKeH7} zUQJ1DodL!n^T4A%q~IR|m3c4UFUhd#QwvE#I0H9w@9An(|K_WYshxzoR@O<%hXfhv z$$;S##FlMXyTl&3?I!~6?13ca0U2C>Rp*{|+&NbY*gtZ|Pi)DXF9gY?uNA&vBI(aK z@xW8%{yOJ{d*Xsi_Al1V$Z^x`xbwa$^BDjTfQv7g?Sy+^&SQ|nf8X`Df7krrT0IHU zMdOcj_wZ9bX?yK^l$b!+?|rA9Y+ZWv7o&*`6SvIC)6cP0OKIA^-ZpPoDW;gYLTxPX z&mZ~#o^sJQCCR<}x_?WYiha&2qoVtxUXvCjfb#{fKjmzoT8!a5%h(sn`SZl{zh(>P zK4lNz@lz?`09dMd4E;xW{^xx3$9hi~JY0xLNU){>sEj-760m&u$^T+c-iNu-Q&v&c zLqMEsr{^N9JYW%^gn9&ak$r;tMEaV#l8V~LS~>HM+4l$;4y|~5b^w#Uw?&4T-l3;m z_C0%j);(ek<2e}DmW--8b+OYf{jPQH(%WwR(^qU8uCjqKjBC${sz&QGXpG#4NeI9U zrcJj}`n0S?uA0P}U203xZ{TRF=-gci5$Y1T4)!j|zMC4YQIL7$-AW3p|WOkQ;{xjDeVuUv975!kz{7!BhlTSI5=REX- zEM92%#2|szxio0Rei7Yd9cE-Om>g_KfGBj#>Q~gcr{pH?Vimw51;}NcWXH`z=4TwN z(H=YZy51A87#~Ypa-UQNGP$Na^lXMA4?(z(OzJjLQj{FP*Om-5SFV_3E5bD-HtD$! zzqJRO^>EvIQTETG{L~L$KWN)BwE-|XP%L+Lv78#kP_GE17+Pf{@>4YEp-#~aZQ?vh zuYm$eM~Az5!QgVDr&AMRF>&YvjC&JoHkf} z14Z4z4K>s+;)q%eXhfD8TvA<<>ZUk2p%Os&`*;&>)hz0B_&a0*TT98emE6daAc^%R zz5)ZA(~*Hnfkig&zJtfg2@J3(Sz5lY4uD1P-G(JN0XslYa8Mapq@=rLq7i!jQ4f%N zPbtQag^|^tGS4+dcgePHIq!bjVk`q{$@+c{Sj_Vw9O7zTT+vxlMd}qdZ(L=K^)-Q6 zbg+ocKawnhj(>*59LFR;yr2jTU_oOLYp6rNK*|mR@W{UY3}4$)Es}jEL@Be}Fhih| z$eTkDopvvb!|m4^s&`Xvz5eZJ2Iijy>jW4iFqb5&*T4iUZd|+6YO4Y3&RnE{9swup z5WxU)vOWVwsm_id5b#0$6;6W$VAS|=HL(|BteJ}PXvtgEXBblzY6ts?t&}N8L7_m0 zx2eH&0|{e+Z2W1I&iCfMbidkl#6639i42GwJ43B*2uPBeMSvprjC>B}%BONNIF&OX&W>cq5hSAA7%^fUaw!@oJ`^mbC=XG05K_(C8&xw5ya~q_r)JX#JMvtGa zWEHi9NO#p}J%I3r+G??@fG71lqvor=R^tcr0XSofk+K5#V3;~p^;FF%Zici6!hDKn z3E<>;(t-dZ5Z-tD=5@An#|AZr$BgCec~9F5k6$mKny3JDuZ1>vlbGXC9sLOPRmK2&!xEfwpVw zMr&+tvb`rCXNRBsNx5x4`|x#EUrUcx-{a$28!%+Nop|BZVz?f-@%v)0GcC)URl}$R z6P>{$Cd));>6^1cIguw2aQb9k9&pq}>MMys5Pc=NUhh3vA`r{G0W_X|skf%M?GIN9 z1Oisyn)8HMMUonr=ujKTH32v=|KU09+`7SKx^mI4wfzn{OEsh~Jb8mX|M0b$TK-_1 zL=ur&%rh_hzNDTQ>Clrj%JIUEp!Is#Ngua;4m`~sxcM4MOf@HigC%lSSli)y9cX7> zevOP~aCzn4a3p2@@jpqri;C>ji~iku4;*cGUiS?pDmr)WWm`6{k|9s;{-czrU|#_c zv5&z(YQF5=roF~}5bAX1UGV8&>2q%U_2=~aQPsd0sLr{dP~h~yqc5@hZ~PB?>$S%- zF1Nxs4z!S_pMAv-m5jXOx^FnUnsTr9kl3Y>^jG9uVy}|Jd9snly}D&INgZWFLycj| z1WON-%$nQ0Zkg1Of(8X2^CuoUa5 z+3P~9lQ`EEo_hwV#hK{2u*}Y%72jlGlC%+*-)Ot%eLk?52j{dIM&(IZ7YrIcF$wEf zcrHsUR8c8eD}bMh%vGm{hPc!ZLOFvvMeerSG+t+8bE=rSh|FP_osWAjz@l#;aWFI3 zZjU}I1X3|TO^T3Xvq}!hA}>tVIj#ZCj*8m@i^&1V93p^EW%rX>h>o&~ae()LUCbvx zbt#6|ibPYJG^^+)Hf2^3*hFuaLE8*i#r*P9KxkV)kxO5+q1LW_Zi`jdXL|CrIe|a; zVb%yR^ZIozvdgFUvR<8i-TA>C=46nA5x_X0!-$4HiJ^aDW0QkLWT-)wng)x=Q@wuC z&2Z}L8mvD2enVY-@;=U*dBBj!QF9%EJ2FSx0E@}m=;$0sfkm#1AamI0{cZDx6}D#i z8(Hf%FAJ5kVJlECEYcyPfL#VO$VuJQ1G%9Gi!d3{`rj{BHR|@Okg_ zrLk@>$p=Oz&!db~J#+vUaekyfFuILK)kpfkjAm^uR$vadsI4rV3we{1K~drh#)I0} zD>c+?#9FxwNJ;mA#1?{cy4bq(>@PP^&RrN?YQkjF5Y7|_cY#$?8Ht;m04&JN%Y>z< z&^oJ*akpGJJ(1$c(0F+QeaNSi(u>UXP*2AD)Yb3y#BzPDfQ+p0t9K~4gbAd50%tS< zH&XDr`s$D<@wy}eT7E}_OB@?LJ6~7CC6%3fO8SQrsjsOJIu#TOFm&rVNTw-UHlc2+ zHNy-j6%$0!QT)C1*$t@Z)o++S8&H=ejn7$o`N5+nAL{CA#GKM5gQOBY|N0KvOET{H zvmeyGBP(Uhh_U2MSXv>&7}z_xuQ$0Ij%NaZ1jLZAhZ*8~9(#Cs4Dwcz^hiV1uA!=j zm6TWN-{qB64wjmm)ZT;Fz@%_}NCGJnqSm!~=Vlq|?0@L_Vr>ZOS1!fWrodbCG`JL& zcnBk&sYhI(X73oW0JP*{O#-8+R0*@8W2V}P=YQQj$KeXoHp8yl$x*?VR%! z$(kRy=^C|fNx(s1t{9ucPW*)2TQSjrRrE(*;AVpXSdJWbu-J7!cb80=kPHL(VCZ@e7^!v{ z+qSG1Gf(mnX(nn5fJ+HU!^S$**PU>|*Q|H{(RSBgziF$M%+Y)Z2c-kzrY4(o$XROR z0f2wu@xLpHTTtMo4m=Y87baG)Zp`01{(O~WuE<8~8|$n{jJ!JsBQf6hz*Fqr>%S{T zG}czT4@H^P*X>r>zpEONhKNN zG}H?l3>$NRo&C`t+v~ILwny*$MKH7pfGtYG%d70fbFZ}C1IO5HfB3T304C}QPu{Wi zNA7)ySlHKQ-K9CB2c0&O40Ze@gociqqQ0^+%Sx++(uvqGPqZ5&nXRwYc=Q>Fxy>Nm z$F_~D)xL!}F8MTl)$42J4!Zy0=Ud-_qs8vm)$X+2JGR*NZR^!a0#MAlBss=9VjPzbWDcl#7b={5Yy*TTMS}rY-4)|ZtC|61`gj> z`>D(%RLJaEJ{C5Eq2oq{%Wj(;bD;bO@(2PbGAnFc99l>&(An#Ip(j-$zf3mncacX5 z1LRGCn?g^a7__w>l;s_xtik3WcNa04*~A9n!7w1+TUM-*6} zeQsM1F*oq*NFW}^K4e1DtRkR}4Ml%&cf;M3dd0vfibVt*Rzzme!6JXCQ;dBTkpob# z*p~b>jzLX*ll^Vh7JFk|?LPw%(cY5zr~Nsz?8q@ycH)FCR!rmNz$EH|qYN%j{i4{# z#^8)vTW580Jq-poH5lF?MUDL!X|3TcHyTv)*q{dONKuiss?V1`!#6>KunyHQ=8kF% zu2UQRI|dyI7;yHCpmx}p{S}Zcefvcf`^T?bAQy)&{@i71&c17d=l;@t;8JT#2SL&c z$$yYfO6mb$W&m=RaFTS2fq#;mO8-tqUY9kL>2Yjr=5{b41*1sTmrO2f^7buj94un; z&;uFj5Cs_S#<^Glm*4dJ2NroQ(HSxUN;&n>0tz8h9nUnK8Hr4&o$K9$JvKG5G7mX- zywhMcg1VG*qb~txK-2To0}Pkf$+52IKpD;u^y3f-K-2t7e#!sg@=%wAk^t!4f21U# z^co`oBDmbKb)AEY@a4&4f@uOom$3QT2ohS%S<1VJi2x8V#=CcJ7BFHTsHxdyUAy;F zO%}CH$WGsS?J-^7uD}p^qKP2Q>k|Q7UI(24(>!0^lX<9~h5-b|H3@ix@gnGCZhE77 z-XkU68Q7`NM&KlWnlZf+9y6Bs_*BRG-LlVv@hn{2eUwXh+E}bjTh&-`+*A^Q*YKpB} z`G##=vs8>5W=tehqFLgIy$-Y!F8Hb~UpQM}7`RFXEQUi3{#!teO=*VW!h zKq~CtV&#iUY{LF0h&g@fsatI3gMSntFDdOLri`Q!&!nZW#g@?IF`?ONaL^UN6l zE&B~}-KmFPX!rj8J2I+@Yay;N<{0K^XMXs5wtedcyX&w2CZLts)BOD6IU#>O__&YQ z-GBSG_6U!=W76B#DtiU3O91O6#@4QS%S|aW8)P=`78A5h%>tJIM9gitU-q!|YZi%# z*L%k#FOu!bt~PqYVOoc*8=iaY%?R_jb;}w7Svo+FAfSdHyo1{@>xDg-`5dLKN!d$5 zV0U9OIrj4P12btgm|I4dKYqxAq1rmr-ziv3ZG8oUM^0)Mm0!_Wn=H%&n+*DG0lu{E zHUt4NQ_e&~BEe+hkfCQvllr*rR;DTS6!T{CTW-Pc@H-*X#HI;=<(iq?;h60Bo8}$t zu)5>BrR}s+hiY=bhQj5%3_y#3f%)MXCI{jzCqULjY2$$_Q;}L=T4t%mrm!P?e%jQA z-@%kdtRgjsNJ>?!=+_ zbCDWIfld#)**jdamSPywch*|Kon9C1F<@DY-<~C%di5V=efp1-xdyck5zxeWnO=Vp zASTJNaH#o#=mH^kq78v_SZ`5U5>C$K?ptIBJw=x&3-V0>#xj~z#BJ@^vcctDV$N!uF+*0@7~%&K)FIKrH6uO6 zfX3YuUFz;2vdU=7!S@N;+_c5(2D7%FRMI84E}GW~EcP2AAVwhC5wPfMFx0&^HA<#N z!URCqXW%H+eeq0qzp?urE!iAERII9;7o9y~TsZV@Qm^>5=ZoYzBYBzy=RmoS6e-Cmt!L409D~{4h!39=I17 z3F7WrS!G9`{(0RiW;7UMMFvn)yxFXzyptVy+GlL^K8LBs@=X9lNR%Wkh0JW!_~~kw zvFMHG)GyGPrbuh}4B#G5x%iu^hr9QN?}|B=D`;7zehyfn_PWo&(RScbm)M+HciHS` zZne=94wwA)<)?2ITR3p&K33JOm*l`0rpKetSA9>2BZOp_Y z?V($Lq}omy?Swj5?bl6BHf$^{L%w0l7QSQ;-To76Ld6%PjXpQ(#iAd7-dAnNsQv7Y zKYz_uEO|}ZM&<{xn-ngMjdE^13l5bnLo`da{KYYoyY*-NpCpW(I6ltOD zweR7owS48-J5*1b=?$DoX7ih@;;;Y!AOJ~3K~yYY6$cKRVAucZ)3$m25>IaB?1{W% zzky@*oK`M*O(hXo>r{!{)K`pm3ktO_Fz;dcNszJLVA);r-56TJxFU%4Fml{<^=0P1 z7&qj?u;sk}tIy5wI^wGCT9eFYOu<}j)FAmcpqK;#Qe|)yWg37>x<&{@HhS`{z0w*H zZDGI5KCq(Xw&nfiizPCFNHzfX@S$UIRKb{i4sS+2Qq`@u?b^0UjzJtMObRy6`=kuIQ{o3kirf2+jYsN7B$X?>zHENsn+8jHS;khbGx@A`z@qop^2rc4Uyo;9hNWxAZd-qRf=HrJ=<-vU+5iH@ zDz*X^<${_qwTS>ztYWbjZUY|O( zOzCcArPLC6pdML152Ax1P3XT!yAn1`Kp*vt0KwWicSWtMtrxRM?IQmz#*yzQ?KCiH zAP8|cRJo#tn#g7`6Et(pFcDd@vV0HheE^GG0~tb`?#P<1TKam@Dkqwc_`Vr}zYr+v zd&>I7d}u~y6Xk5_-;eL1HJ1VsEwY1ItYYRrqPwgg5aBB%>>P;4Ejg7GXh+eI9`alu zkuPvgzn*{!u*ldkhp5XTNF_kTv;^rMfhK_^ZnGSYo}_50tk{!-X^+=+at8YIX*u4h zLvoMbd=G!2Bg&6<4rmV&;=Buoxn}_V-lz>LDOVsPc7eWx^yibAN5&|}_k0p~IB`;6 zULh&n;1LtGanPrX8okK8`uP#%v0=`mD$0}9)7c;T57U+dNnBO8K2}jtrP?n{L9o52 z_oD(e>Lit5F0`6m+Z8;Ki3eN(B48`H2ijfKRKpH72;2f}y7d~QT1dV;;B2IjMfk1qGcYzMZhNYYH+1HyosNWc}0Fzr$>|58D}dO zy(-p>co-Mo+L|4z{X{m4n=ipX_s$9hkZ}$&SE)l}Z0@}F8)}2XI&pQHvt*1XvQhdu z(p&QFc{7EQy%m)wI$-en4cg1jxa=C+v|*Xub?wzwU9(-rYQ%bc9xckcb{}AS?|;0F zn|z$T`1lQK5hYn9Y5?XK3ZTYX>)mfu=wtZ0&A9ICS~u(kBp9};A7imp001Bu)kp98 zr7fQSoaUm~@A6KH>3H8>eTUguANheiO76J!Ym%wz{!)sbqJm69e)F#`%`UAFK?VcK zdjq;@vBEPWDO6iqZAC?{lz@#^d!r32m2ic*C$Wlj)y*|)^vu98Zju%D;TU-6KVw-z zhQNwoGb@?c-ffBLmAEv}TXJwZrb4yQ8BCjrNB1gP#NX zi_9)Qpoi@ztH?deI_VH|#-LV3-z~smD}i#%qO}Ps-XXKdHE`e!8MVKamRH#Fg)d9W z73(J=NYs85v_k2Gj*g+QZu~V-ju)L6Tkc{>56o89yLPM$A`Gl-NcKoJ>Hp^Nh^9Ho zo)Cazl95lzRC5zq=>-zsJ;`Y18PD|Z(*_B~g@cga1q@L2?9oO9>>2eFuyd zE5iHW*hvi?4dT7!MfTuDCbPBq6j^lS=mb#}6PXC0uBHh5k$xLMUvQOz(}j!Nx#Y!p?!m|mRzuyUW5FMYubwO)B5EK97l~i zSOGOa9GMzT+Gzs++Vgiyek+y-Nnc@!6%_FtD-uH_lCJE>Ubp5>%Dh)h%p)HjGJ1+F zdFzGHudYc+FWNK!%*!e}i}4`2BM*r}693*KQGuu&vFjxxkF{19d=N|n>g1-|;p+dbERTg)#~W>_EOraXuJkGRmrPde5*Rdus@FFz!iEG<1qfKk)Ny5ir| z!eVX%xTOCiHFJPd&_s=t-YY`w?myNi=wWMfVoz*=MNjJMC2UR|J#-?pWKb z5!#$cQPI?>WCZICx#!Ez+-fgAaf6s-Sh{6zzib#Sk=)_l0N?b7y!&t8(w@#2i7B2p z{*bVy0 zsroA-J*D?zssE1GIU;c)drgyIFWQYxdhxK0_qt|Vz5VW)O}4$7&9KEteejKcU<8Kr zD6z{9>SJOYYli`PhhQ;g<@yd7V|@pWvDHiGs`kKfVRSdf zNF&2c`5bn+slZ{d$ab{K~5z}Z`5Fji?3EJi>Wq>?e?DrtH~rs~ow=aq8nK^b?x zy!AjZ2uc0zhj)5A_IhjuB*_K}0~Oq6wY}gDTA&&n@5$!}9GUbj8|-RLVIN`dkXQmfU_bf~*;^n6 zY3s7LX9pz% z)Ctf5Ft8A`K)?)&pbo}Q{^;`FLhIJOpA2Yr zZQE>%-+WHJp_K$HEVO#I7jV30et+0hG=rx;ddtIhvbw@2i%) zCeY#7#>oJs#pIgqKpe1(c@BYZRcAnC7pv&pO>GxoReAO(5?pZxEA0#(fQVc%^dyqYL*Dq}T%MZDH zmh*#aRlBodF?YNU^P5NR_?hIt<(1vk{JGN-dnYX+z@o)FuL+rTouC%V*`l&{bWQ0#L1tMRQK73{~Y>LI#~30uSwwIsH{?RQYKanb#~avpR~!-&lYn^y>nbkx=&4+0s+tSKJhcjS?|97TOOOn zuK*UAQwJS)nN2_Ta(nRBAKEL=&hUPU3ALDs2RLtr!}zUVW~-J1;sTSIoUb|PAtZh4 zYim_&$#d+|t)D z>x^~P&v9peN&6Z#uhd>LF0Q&n`c2JnSKII4Gi|SlN7(vR3$-SAR#Ir-AyHQ&_MLMU z(b89)+F2Nb8=T$Ix#Ka{0 zVpC$XBH$zQ z>@DO*v4$YrRcm;p1;~u@Gi4_Uwli{o7Qt3)*VoqfQy?)7NoF$1#0_qfx9LBb;p~>!eWvjigEMqS6&lsrv-+WCcPv~q%j_so79eW<8=Zq8% zNJo{$^p+RMU1*b0kIYmI1(MWytEs8BYFcR2)=8FHTSwiZOHu)tyhd`=dJi_-?1rRM zsTG%0XyZdpCP{iO+tS(~xA(et3Kqj6re0ylsL7IrU|LXsMZGeEK3|<-bQ6)tHpaw9 zX6<+~B%Rdp*9I0M7~%x+cix(S$oj^bL@%;;z$oAsWT+18qdY0LDe(i@dt7E%yeMI9 z0UEVMghM>^{A&*F6=V!UkXlGR8%%@;)-u2-B5U5DgR)a+z+!<)6*eRJ+qG5oF1S+? zjAp>%nlSHjci8a2KgbYuXnScBEQSW$fC~C2GS85q!sN@uC&-KUp}1&0Ci>do3gVK7%?zMl%Gjawe_NoZ$VD zodUc8^mAw3D+4eGhLO4O1i2@j3$2lBjB1A_VnGj3C37w*cgbnzo~mhvk)izrAQEtc zi4Xe;0W{B&7=^t<49oV-0>DE@O;URVn6&w`A9BW1%x8^~60z?fPN|G1jqJBhUs6$N!^a$G3toRh zvQg${^)6hEOO(Lby<@Y+?u?IoUxr72|JA3o{+PeHrZju)d!(*^)}w#5XCJvv39T^s z{qN>x0i}~K`lbyUzOUW>$17!s6qP-$yv(rsBwhLp+DoQE+cvGtbFQ`oi~N3l&2A+$ z`VQVpNhy*7)XAcL#5tHmh1XaU4>c;0BCxo1ovm2>n&j{(9M1d1&n1Pw>33g{8Y3wc z@SD-K(lhg*qc4>M?%bCi^fJ9d)`$1H1mhfd0Rq z9hcp%-TQ0LBuPeXDL|2=-Zom{;L5sVi&$xxNK{->AkelYl$wRiNm3W->&-DuE+H3B z>U>x!!%`Ml!Qc`5Wmy4KRCE!tMpGL#)^XFoo;q$oNFHMCfF4Nft>{}!-i%~EX3^1b zi8c`F+iAn`4}rzd11cWLtuTv;*efP30?1)7Sq#x`H+h@TF2nDw6)@XDu$Yb(ItmuG zXi`rznW(AzE5O|hh9@bc&M+YPSjAYY7=fZoPy?G7VtP;O-!1g=N^F}0V-~;%8wViK zv$J0x5#~^!uqNY<%J%_@VjF8~tggmQZq!agG7rxlBTJQBlf;rF9`!ox)3)d_ zn0?=$WPw>}Nx2H?0Y9)21Sr#UT!MM6zKWRRAb+oiLM$u6r=<4 zU_k+NfN-_<*tJ6-p5UGUo&*L>>Umx}wyd{R%U)Mfp{8cH?wJ6a>%qk7@KZlyi{{O= zNALKV*ctBEV|%ZG8!&W&9eMiabRIA_0TsRbjj+udmZ?Pr>w^0BfkXDT{SUv;mM@-d z58v`*xzMr>k+(AEaQzJ(-Ws9B^g5HlKTSTXpC?Mbw* zASzVTSZYU|@p&6J=~#Q9oSl{Ldd znK!>%sOdwsp%YtE}v1 z$DH*=v2zdK{!?$Um*a0jvge3XKV|zIaEe&PMe}Io5fYoBM2T3NgcI^k5?#0b@yn`- zkBO87EQXeSu)naSZ@=-ZA<@hNp8g-%Ii4U9N0ESwD&U;6Dw?sePf+)YG(2J!)xwrm zW`o7X29Yo4f9mH}S=G~S`t@feQO!~!21Ulf$6juSo%nIP@5b+`9@jy1FtH4duJoP6 zXy~c?e`inL{VQFA%#qBEMvIF|ZP18)?U=K^q_LnDmuJJ=WL~iU)He`=?UtJ>^`@vX zBx4QpAL%p+I9PIG37(%44XBB7GGUQS$fxRT0Tvw>`T;G|DhOtiZ;cJicO2(q+T;}1se5v8LX7niz*8C`JdkODt9 zN_1>Y2fcYsZOR-dMz_$CFID)RH4wT<@YnVW6N<~@79 z?`{b8|Ngr%jiwE+w6i94^Hv%Oa){~>Y{!wh_?iXW@wePjF}eXP>Q8-At5{uwvtD#c ztqH6nf7iO3DhwmiRJ~ubGT~}?Yz3;DmE%~nxPG6RrSx9p(~~-nA(Es}OSNU)GO6ta z0z<+`EPRk_djiA(BEgc^`npL}!aRoW5kl+s!iJOV7iqAV(Q!C147Dr~BqqQRkQg0i z6_`dQ*uf*uN-az1p&3kzoSkI+0j=IDA)KfRlGxWM8_;#rHjF^DH7 zRI{k0403XM9M)tR(M0x|7j*44$R-_phQJ#^MPybAi_4VBrjKTMr_P}siuOqrE_bTN z9)61g{oUKQD0o)0?uJ_1YrmtE2hYKNiYA+Gcf~mlWM*uPepdmrQXTv@!PNdAGv_hZ&aN(?HU{htR zS1xh_){(hXR^C~O12HT?GFw(!X~pz;1n3nOh~44~wv}Wg??&LPzLd<<9a}VS`VHR8 zdJh<5ugttnZA)Ot8>FCtMX%Gi?LFmqu{;2~nGgKICQLm^V*xu1Am@5v!;d)S)0)RK zAO4dht<4xZ6}ihRpT)W$DRBIGSJ}2rYs4&7@7$W~!44Q41Rj3Ur)rwr27(?#=>??k(q|J=$z9F_dx}Wk42Mif6Aj!Fbyp$UJnGgLjX#v5_u?D07 zEGQJ)Ief1J1n!o3T z3??qD(+z8>d0uC0md(>S5(y@fQKx_SJBsUX`{R`YG*M#9{YskK)F=k|tSf$~8r*yT z{%tYCv8TIB=)F7(`R4Gk2PzS;WWfuet}&<(Q$cZ7tgqg!sG#blQoxm&XR0#e@gtz>UBDjMiZ;SY*5>9dfp6avz=XGkfvL zo0P(e^~m8PMwvY z8!~!-?J3k?dLPzZQWrw@v5&Dwa=)w%B~+?+N`(?l5S^IIbYsY38FOMaF^dTx5`u>^ zow(^>S0xft3Opaf9;AdnO zy|BMf5>C)KatGhcvdPg5`u43l>nlhI(zQ>S`P&NgO@YPC_~*QH0cJ5|eJSMiOj!C$ zlQr#9mwLD^X$UMUnJP970^ZXBT}ipIyAm?s#QeYa!%6@UTDl)!Y#%FDbCg5AJCrdY2|riDVN{ejCh4g6 zSBhZK+h|1R(+ChTx$)XXH@XR|V=b~Tf34WXdL*5NGFt$cFkjiI$Qr63J5pTl(<6() zdSw41xFb6`aKye^Q)`#ax5h@?>>Ln^ZIJUI%mcMV(LFfxw_cM47G37e7r#Tj1{(M zW=$Tz#!T13qVoU%AOJ~3K~%Q-vxzYxVdkuc!nhd3B5^A!6}ZMh(81zXxjyn-k(2=v z7*Faz$hL0Xuu@5byg=!Fe*W*%H1puSjU>oB0gd_2tnAG{8r--gKS36T4~fA77P}*!Gbp{i3(Oe$355pOx*~{K~ zF)^x%dmZZwpg3^YzV^zqw`YUJd=oTP@6Z0(f5>?Chb3qwh<7=8CZx-xg+oN6b3fFY z3fu;_Q_gG|qmT&b6!tgo)ycC%mIq5k>xJcuUiOcOYNi+rWhJz|*?5cvF=KIaC675` ziv&JTOksJIZCSr8Bem346P#wlzhl`1a(K*jRC~v>EUUD#PF<~A_x>_C@y6#(R#D#B zO3EpbsR}&|)dAOPckj|32uNm+qyOmcotqTjv2VdvvXAjTFmAB6Pe1TGTe)P8oLWf$ zFsId1u)bc*>#^s2MSVgazw1|_)yuBLNC~Ej`=pL@}5C6b=a&DOo=0If6R-I!VBizQm@nV5Fg)o3n|)a=^5ul9f) zTh@s+RVhVfSFyzWTMT*uy*sys>o0QZ27^WCshFOCtY;4J^$!m z)hZ;}`(sP7#zq@4{$K%546mrk_4C*LVYCJc3aqTO!Y=riUr8E%!~c9%iV#WCRWt1B zpg|)h+L<4@Mso;rAoedgP?vk_L$x`<@xG2k*>)vswr*OZWFble<^f4GnOoI*s}+(H z#2%hdcBPeoEXjum7JYAM65Yucn|+I~G=mlo$FOlFbY;jI<=qFfK$dTFl2f*XU+?&w zPZ-kD%FrmdCGF}Vk^jE}=cXoQ;1rMvBnSO?xC()?ESQs-mSQ2%%EO%G0dz^A7_x=x z307LFVA84kbOt`t?tt%dXp{A&p{X3oavf@;RwZ6%T0FyMK~}G<-0@ln;MCS4^j3^u zF#^FTH;t^K_gBoA+8{w?k^(TPPXutPuVOH`iCHn9Ux8OCFx#}VL8dkvcfL!>fOkAQ z{{Q*KasA5dqN&}jvW!D2wZHA@yK?0ySv*>0w4bCjqdE1PneTEEgFutjg0S>Qm z2UVO=>#U)!!3wAeDX+59^3DoCH>_P`HPwEIq#2U;`blI1MVFPjRMd;W2MigjT94IB zUsogXD5G|1n%Ca?{B|<|KqKpkpGVm>8+-(p4ir6rCqPjkmCnY8{U+Xb8Zf474V_I4 zj9~zaiVxW^nhL$vH0)2Y-qa%1gFiP2K( z=#V#-%9I75M9>A0kcuh*8k{_x=!=wvPE#}riCcziAZ2az!QB#z`U$XE; ztJ}RZyIwb#yTFL_?mx<2du~Q>8;$kDIYxC{yd=J^3P9pJbj<#?W9tT6jP$OCUX(#C zo;Wf3Y{|#uXU!p1&Umm6_yPd*9k`bQaLhWWWg9)=5Sh2Ys;LiT+zVQi@Z7ZHb;z~X4^Nf*F44C2Ih&+r7gu{cm6^> z7@1GZc~6u(=;_&asGahmZz({ZaqZPot)ziMtVx6|hk1JKxjXI2`+lv!oH!5#M`V{+ zU&o#OWr2!&uK$iLnm^Mez@c>l^4qcd9V75cA4B3pWVW#-N=(`__M8n94?NipJLzBS zxkvtNFFkd$t_zSi@t`wo#iH4^Y~jn2KT>Z8FrN9~pTzP=1RX%m!@AOpDOq}|qHZ|L^XMMr;o_dnq_WLg@ zktEO*x4v**aUK1JjF($6r6XQ180US?CYh7811w^=2Y4lE0Wk#2iFp>PC(bU`xvL3S zeg&aD%|QZHBx#s8MWy9--p77oJ^Kz1V3A&sDdkp37~-OO+9lt%*Jj;gkKX>%to_|4~Kf`sfpSCPs108aZ38f`cK_DhOWViGvcE86E={JG!AP4%YVd|rt> z+?Yx7b?w$iuD{e;j+!uCst*)F$W*~Q0A#Nd-l#sIySHsp%{a+3_HJGm)nFuGBrVT? zMbA{TDf1HwC|ewD`Ld@iHjY(Oy>7A8%4wOQdPNT05-SU}iWydsmKm6tcnzca#E^*%V3B)62K3;( z9rnmuJNHOl{65Eh|Id9Kz76M2?rKwqRR&2>K#ZwgJz}qdQ(crcx;rXB0|T2VKaH(3 z+}ws*MwrH$nv7%>hLPU`B$g8}mUvbd`Pi;q+p?In_j<6~0*X;K-J{n4W#+bSSZ-T5 z*a^~L+X0CB8?accv6I|d!6y>06mSgRi#FyYW?tt7v+pKL zg%ci9I@zLm85n%6VHupXWEQy|<`)_9$%ma|Z_IvFV4t&v*GI5O0FjX`hd?YGlrEJH zwTcDQ$dM!|(Q_vYPfG=YW@O3UJie>dk*RL1lcIniQnhNGdnowgzp0VpcL?;6mlCA( z=rve|BYd7DfDLs5lCYwjsQ|Rv+MU)^-{6jy1vDq8_gjJLkP>!W1%ttrJ367l#s^kT z5?-3Jm%>0+$*GWgAz=1#Et9<0Yl6L12U0ISLxvMu*Vwuh3&i>nY|ek>VYP@zx4F;= zD!Ei5mWa6OwdZFf<}-;RC???J-vKPb?Cv%3DAkQFob#0J+O=8krphu$`FaM~XM@EU zz@(d$2T(<%*ADF`)EI1k_@HG;H+#_VUbIC9Tt1DWntzLl>9b zvNv_5_gz;4=e`P@)h|-XOqiE4N%DAR%z@Z$f@ew51DP3grL}wsjUXHmG*=yifd8 z`{^Bj{<@nYg)D(s#r;pzzResSx8Kn=`{~(Z2+KZBb_8SXcdou9>@STNPR+k`CuZU#z`d@xRphxbx@l?{9#qGD) zhK`vkL#9RZJ!#TvnM1M>hx4+wS_~|0c1Ucor@+$bJs2a!=agN*?)fi^SsV*k+^F^_ zGN&mhwzDq(zGU(@{`&K_Va?ku&vcm*9c*WO_eZ_wG#+-~buy`@9}^{SK|#P&GxoB$|dfJWb1%(MWF{1H}3gGB+PU`#<~ zDOdKG_i)~0u;_tGc~w_se8`&lo)ppv`8KDJZA!pqD@E@-lB71kE_#neXAp6ss|(B`^3)ouuFl9%VHPpF zsi^8{MY!_?c8hujBp=a$B?%^yfM(AF>9$5Nt^rT1cqHaMEr zt$4#t8vs0@V^O+k9sYhl2iA@avNUt{(P*iP_*KNgmkt`OoEwC7#4+jrm zkqo@R;;yYaNZ7a8%hV=;9*j+m3T`$AOL7k3%(vnwg#R;1oW?&D3U z0kFn*DSFmiP0JBH^XSrRWdc1gC$U=4?4~KmQu%#=BWDia3lIiF2rEed#`zaZJrW6Y zV}qN66cu@*IVpr0%uRIx(QVv6qEXq3|?{vPX{vb4D#_w z0`#UPm7&0ZZQHU=YnwUE7{Nl8cj_j#lzW!(Q?vI~q^^h-AZu34S1?t*bBk3gu-Ybv zSQ0qg7c2|+^7^d1!#;TF&cy%wmoxFT_>s zC#WBAv4!EFMseesMXG(bWfsD?(mNA} zeK9C4ZlJBCRe>17QRAnJHNkub7O(H1vG(e-&eRHi$o;!f*Q~ikyO_{(PO)5BC-v9m zZ))>!mL-q|d=4EoSuxp;EgP(^zFHuG`8HzwfnqF~H#}47!eqL`bKbpGDhn7&z#_&b z$awF+`5FcGkztEo9*hsN>eDX$o~>WK!0x@_yH;DhD*%=de+Cn?Ne7>0N1gFGoB7}$ z?b(N~btmHBo{Le-K2uM$MQ_fsDTkh;1jjQE{=wEPe?zZ}t#uT8mXzAy;rrRK=YCn> z=+)KK_;>0iBtL>p8N5i*{a2_*^Iwjt@v4MImtpW z=S}Lm5%g%?z0;Px{h|{Rd2mO*{T>FmNAE$_qxVqlMLfs#Yu?rxh(=FoM{#bGy-O{I zc5W5h8D*mM>qI4R)9=1$>sP*&2Q1S2^8iUh>9LCBS7caDtV2EOWna2hlIZJy@d@{b zNw2q1UPk>ZGU1$s8v7i?626< z_y69Wedy1c_iCxqxw}<%?y0jKFipKKzt3EPU}DZOMkqQ^AG83AT5JJCwYgd3$WYS{ zsV9yUdP(B;z?$8+1*|@NoOTU{9E~02Pol(fWzSh8^XGUB0CTu}vr+})O+ji<| z+cvG0EXJ2hffY-Z*+~yt*O&m!;G$>+%B@TC+ywDj@qlr zicX*yQ4FKN3361-ZeSB@1rT8zVHLf05y!21s}-{WvtAA-?s7?b zYgO;kfeO&f1iKjqJ)6zw;7zsivNTYPfxH|71rP&RRG`Z`peguhgJIl+jrQ)XdJWQS zKp{zyOkyOmjsAD6S&WRLOHqR~E4I+ca#alu%E47I?Sc~%VBXFom;?ng8#T|auXk`L znXvb_^!ifj4FQn;GZ_rY$iu%MooOS>7@u!!m%y?LGfqH3 z@jn3}K_=};c-GX!P)`P1l?IFd*i-#q`0bpt!uR3ekQ*hs;qR=LE8zh5Z9C(P8|yy& zZQ2Hn5dbB%BB_3N*@_;3$nBQ4m!gY%z4~4tXZtHSB|H3 z-flr)F(j1I&?C9`X!NAI!E!g-Xm*f_ng&-@0#f9SO3dKQEg(nDT)B1W-d`DT+)KG` z%Y88uG|322m2yXkE#F!vza&RJL0t&b8!yq+^2_K})6z$9yg*TKFc zV_h)kNtgaA$>Y8G;x)#2oUsK|3>vnNnx#|I$<@X-ARSG+B(YJPuc7vcheCpfAb-vB zd2(-MbYPii7eJeXojW$SOdO=*y;#){8D|f4y^JZ&JCP1e^fc_MM8VdL7+(=b#l%YH zS+xZfi;K(E1Cb{2ID&3kyVyqWbC_ynUzvHkVly}Hi9J$0HuCET?#@jOdUi5oY-+N8 zL&n+8XV#s&}l%;H_Hw zAq@SP35V%tu#Y4hYKZxo8`T%jONfeX+R>NV{)eCMa@ObXQqT^g?ot&$N4Cs}H7VZZdl!B7e{9XN`F7`ZSG!+9*52o)D&wXcZzo>x4SV*1-`lf~{x!6B3$5fd z96l~xsaG5|**2_RB&T7iAUg0RX?atl_31xSCRFT|)GN|kmghBJnDM2}F|Ql!1qYCR-z13D(c0V|Lk#D1~(lT z|IADN0kD__fo`K zBWn@a2sv!34NgYR2w1GEYe;~hT4-Q$6TV0PMS(?J<^*z(9ybN!oI)L_9GI|RF*)J^ zaagPE1kde`MGOc-K%X(5akWAOc9M~b9dr;#!lQHdo`$TZwtBm5+ql9C3P|n%6yu)& z7-dl({)AqliSbR!5Qkxn0Mg~^0F2m9CWhc{J|TuL6tsJdBH-HPqpM>Yj&CHz;v}fd8rh^|t z8EUf#x@6TJnxH4Oj2v+C(e5?aLAenm~jII?DXnC+}lqS7O6CW zY(BtGXOoXI+9io@(;;S|fHu7gH>_Q33txXy z?>}MciAuTyxBx!_sZmB9#vtxJTsKKL)-C%g^9be+W!s{;PuuDhZ`#n2lWgjd7uot% z3tT2$y;Cls$QPXRZ~)DlqPm0aS^Mm3ZBbEo;60cH>I1%wm{{A2a?ym{=$8>ZuLUR&H=S!Cmv-dU;JBQ& z=N|n_rlm^qXk8+E^y#11`vIzGtwD(gU$I3`G+O}N!+h~;Mx+d?348}&k)A%HUV}}4c4EY} zzV3dSd-0jDA$`CmNIo7izRjg~vt;9AA~N7?zHCY?ep#Crm&zjh>R)U4_T8|z@mdQ|GiwWm}V8-n8SgrT4lhN5G;pUMafGA7)z|OvXj>*(mtcK z)G8_gjsYyvR}m(rv`m1J%}(Yv#U)`81-iSTPKP&#Bbnvx)%AAW^P6qSMrUO|`1;=& z0S@D-Lo4j;$=$59n0ezF*R;yaoj2WK(s=pIg)Qr1n zS`r+e1%LbV@LI(vJB3vgSY+G-U}WqiO>OYsi8ZKVArpye3Qz=QIbKUR0kihFUVVoJ zuvn--8q*TmBM2<^9U%!9zt5qE;~INlG<1l}RJ+gd{dz$vNzp1;Ol83%@XI9OGP33f z9HV=#YLoym39B4isbu7;?ZM`RtqErhcaW;DWLaT>FrBQpVBTBpFw1+Rhq!>$OLf;m2eL>0s9$edQuZ zpaj_Ddeq)V^}~f?gp{E1iJX$OIao}x^1+ma&w$AU>>-=O71SNkGm#4aVh`haV>$z4 zvV74i0_gvTz4HLm>#olHncjsDAuj|g<3nXFCmwOX&W_msy%$ycf5T;Qc4gn$xJ9Ee~Q4&_l&{JfF`Sf)?PQ5 zWW*CP7t&l6HbT6WfyEp?Hn)tmxr<+_V4k{AWWFTZmn^?RV+KH)L!oYn6mcBuB1#-=|e)zVe>yZRTmq z?O4ZN?d8ZTalWMn4;kW1U;DeZW78A1ee)_MEPna#|Lm=JGVhH_XLzTauD+IIC(PEI z=I5&({CB-?Fq;_oz*7J4n}4B}Byv(sGTKNKvqs+do=q^ve3WQ*p=)r>6*q)nyY%#!~3?`^YAJpx!9{u#yEypuk^5KtBeDzaT{&>Rjr zNQVZMCE)=oSjk4qGmu)mRn;1>ky%R3m_l)_%PM>xB}q}fOQ#8TvZR7wk=KiU7PD93 zy(!biO%|0*6A~1;hRFoSYs%Qrys$iuy7-v%@02k{!ovpdSM1lU>{DX&B4Fka`Yt-2BH2k!rmB5%;~FHU zFzk^qfgv9|ewvM$I77^0_lZN!I;w{#$rWc4LyoFCMgB{GR8GK&xp#Rg0Mnb>XOgV6 z#xq$|QS6rvVgbYy;DiZBw8Zd!in&{@WT*-FxpS?9LxDw^5@C1~(p2w%nK8u$hSK|M zx@9|`9l#=I2b@vihxA#b&l~rvo=yjMDY)g(gY6+W;rEbr2`ok}_OFUP{*TU);_nZW z*q-#(DgGYL4o2-O>nD0{23XA7t9S!uYNgzEJWN6gGS=s~7iSeyA}6a;^z{-l;-O?% zLop9#X{b{qKc?p?uARxzn}ns$xnyuNX0i+?013`4a&D5$DYUg2;o4L?2p~(wZ3KO4 z_T1YkDI?4ewNRM7z=$2#^NbP*5B~Do_L5h;L#~Nf-8VLkR;>_$C_!BGb0*1J*Vt?a zc5SlbNB2wGM(YBkY-HZ|?cSulXzqQ>`5aDAWk<+x3j~!}1kc9}_I{{_SI?h#f?#Hz-Ccy{OnSDjA4r zpQVPguF;mf)K>aF;fevTe|8f;&u#l2>`8AoU>QAbnjJp4+j`Wud!(;IG?w;5-UHx0 zd;a-0YTQ)GcU4DMMwvjhoqh4uc3}4=wM)s)lcH5udd9kMwF;v~tHl~x#;EoYrW)5~ zj66tqT=1Ir$>eAIGmi^U^UP=iA&1P=ZyO+|ap3+^J0k{R#@uB#|IAltoG^>&>O3m; z8|F9l-EqWi4C&W)AYp8qe?mjN?IBnk9);4Ck0)L!JPw?zd9F5-8RkK$|+d2Y>k;d;FdoZNjuO?2L0R)w-u2 zC{oGA%dgaRVd%1L<71Nf;%rS@47qwMQR%(MU;XAk7Fc}fuJ0%Tf?O4b^`X1IE5!+~ zp{^9kBS7*8U;lI4xBHn4EEb6nq|k4A@26DKaPv3*TtGYKPnP5|Q%&ZKdCRolAemN- z{9Iotb|#+TcW`e7z;QiD!uM=@T3CTSh0pXgTqpp2u zJ$hSeV^exDNM^78;OAxHb={YK-@1++&P<&`w#wf0x_ADS%~^1P-SFi<(0vUDi;NXL z6tDi!7t~*sG1Bu$^E@1rPg{D4WXr1`{IT73p>EHgywNe26+dsZvbN?iE zwyaFdH%WsB@BEgM6%n&Ug8x4qEan-!)RV6e!={~}N3HRw0Nyl z&StSNSX{NZrd3v`v9KOm+VDz+tIuB%5R`SvMWr+>6AI>yLx?Px208VxQUe6Ul!2R~hWR_+I~4BQR%dwY_~=n>E%FBob7(sfy202L%ca_%lf#oxyUZ z5HKPzm_TALuBbgd*4c$5)xlzKwArBVB2KDexIzY*H;^BZT^!D&pWjtm#n6O>ngAt=~^R*_e^{km?T%!0FVmQ+?Xa9Mw#3Iz@t`CKpZfL1UR)k>7jNs zzE905Kmy?IU=pBNWO|hxNU>!G7}NC!c)_3oW{PnLX0Zqs3ADKvGVg#zDMX&vXY~{x z@Uy%uugQvX{%3zb0pOHSi{MfLZ}g)}NjLp0S-j_S%H_;T5ELZGlKAU;J}+G6oDvgB z9_fsNA7~jfSxlf7YUJayGv#C`0O;(Lm>Pk5WZq(tOlO~!BSUqtNYIbT5y7If`26Q< zob2+M=U=J*amYp0*H{Kf7~CXdk`dT`G3auTq{a|gDQmh%?|t@#Z_%@U?B1JI*Lu!H zZ(~+1@zEoVnyt<29+W(hX5s|DNa{Kc?UHm0_JrPylV>ea z@^|N!)iPs&3F1tJ9a(wzb*|t^?O;54>Agm!sHya3=`y8Jl9>Oz?^scN<6zN~XCyqD zTgTbHT^j{NBbZ|Bc@04z!6i-9@hjkYXR$+p&5OixuxJ2yX} zb00v3Tj#7ZE>wUCtB2f=*hcR^NYbuHV3D80)FOw)^MHRdz9ggjkRhu7U{RgqiEf_Z zgemiF))^NFbZ=U7ul4{XyDF zE3W*Q%{k*jwcpsh_5m^dm|Pv+zteVXS#5Q77%45c8S~E3`9LcY5=lF@JR#uf(+}pk zOOB;if9M~z*Q{Gb56UVf2LY#m3(h?5aRMej@Axatv)gX?l$|)bKanB1PXhNs?cZzO z`e*jkBe&VlzWVmuF#7jbxXQ3p)zAbu|QAe4! z=aPxZzQOg8AlSI(J|%{j8!vnP@5%l3_Uk_-_t_G5F74~o(q8?$pO+gcU=hZ(_~r3> zxn1^K|IHSh^=kFngrz(gEDqVYDf8_eAN#VHM;uslL(Di&%53_)bL@@p`IJnCe)O+@ zVSW8Bd5-f@SgEqo-t?YN+4Q;R*mYn0sBPWw=*i+rGXr?i{$<_ccS>p-N`T)Suqe4h z>49G=#Ysaw{2)tpg3_d`v29mmwS?% zD!sL8Bw_IhAGXV3tLu^{ZG0(^L1tH1S8qcDJyutT*~yTNn>549%ZNOBt+{2C)zns5 zxeZuNZLQU*5iXlggX$L1yWmKD#IS1yYTHcP-l<|zb-iCs))H_j^hf0;Zr1B)<{-c}<6H&K_D zYVsVQ6s%R!Ci+4^hBnyb`kTv7bJ=wXP(*%R<1JoDoTv>BVv}cfW zW--8GGRl#(JDedCP))VL45fld)rJ=PERGN)MR8i%eVje=jC?S!5e(;Y)R3V%;1jbL z>>_{a*#H(3NKC9FQevJ*u#fRvC2Q65$N{6*uljunV$oY`^kjiW#)W-}KnnJUfC1(J zlMk-B^XMTvkZKkMRMKr{^-jN{#Sk?-FX-(GXG{@1W|`Vld!D2ndh5(dSI;;77j>|a zJVI^>Gf zo&vTHusC4-$y`eAnVcP|b;giqOp-boQ=|l!*9rSrg@VT! zS}$o4>sV2h%&FXEHA+M{UwI7xm!!wOog4BbY*G{<)8nq!K6d`$@>@U;@dE%BP(hs>tsuI)sDnHvCJz8fzzaCRk(Jz}g=Pv5tLuofpyl2$oi+d@6i6gwHI&88AUy-_kNQ1o9;eJcQ)Y^*9{h=df94zI zLFZj^jT`-}eMsg@Bo>Yw+%1OCdjaO|?(&LYUJVRdRc)QkU3js;D|_OoF_Y|}Uw+qn zVKT1TZ+vcO#Uv9czN^F%Mo=nq;H;?;^T=~1DZ#T=OPac-)HAY9>|R4di*@&OTI;Cs zR#n>|wiPKY`?2p81GW!F`q*K;$E9!iFJedu`~gb1T_T&MZ{wi@JJdfCCi`Vqd_?9b z7@NRihdM3{fp}kl24*yScRa23Nc218IRQ#n-gAS;u2r>m#<`c-OJDa9)!99C*Y{}r z>$SqEJrtwCxSsdQciFO+zs+vH=`%7a;w%~d#dwb$Ki9@hnXBHPxB@?KOqrg&+}H>E zZQ_*E1+v)-X)VDx@a5{41pJG8GETmgRW@hw%M^117DI*#>xS&}_8UKCtM31iC*ul* zY3!HOg#s3NrT{aT(;^UznCInJe9X?h_^tNi@BEc&K8J%vuC0CiEPMM$zo_;ww8mi1 z%g+vKOW)pOsa#cKm1R2 zaQ7zr_7^_rrGSMv?OB<{;vl@BLwSTnn?CW`-zL(p*((YfkZ1WV9mH8i@1!#6lHZEJ zEzkO;Be8Ik!@=V4k7cs4QM1WNY8gj{&I>QHudJ!lpIH2YDOq%qYEoNKky>aB4JsQ$ z?E-Z_Y^utb)iwGdMca<*y416TJY7sMG4PGq0?$_OTOfXrSAuDQ;|RvAX(NF)#IvO=2FaX|GXJD;G_qKC}&TPu&&-ybFBKmo?9>e;tL*u_J#`kor^|Wdt+*) zk)%q&An}F~n1)Od*<bX-|A{_14D07YH=}Ys;SnY*FJ8tbsalsJza-gCKUY@75Jz6 z$JBZw1B=N8u*e({Jg_d5l=5AB#OIU&<%Fn0F%i-(mxktStQ$!Aza8u));EF0kfgd4 z*yX8`1XI_TB*cKp;eb&_Iq7r6E^AICIT-=?z<@QkPf&KA%rW&`hY#%1p$jOYp0R1v zSOIAIGGRo4K}N{cPP+e7=Id)&|oU!D_hC>2VbtZKK^v zv|P!Ijw+ZF?u;94ga{xjQ!){-C>Ew5YgKLI^F%vYZ_RW>MICW~#aKtKuBldV&G|rS z17=dN$Nm~;q=TKta(~J4D^&}3a1Ysa;y8D&j*AjYlK>{?2gyzt7}k;}K>OVNo3ppP zTn>`WEu-zphi1T+U7(H>OJ$~=acINq4N&1AGZ~c>ZtB=~5=U-t@K76bC zK2Djv)E>O^-_(bY;Fx(saJymkJ+^rH>vhg;cxr_$Jm)e=@sLje770RSLZk8%#z7Cw z^XaKYP8KkwIUO~_F#Y9axhjb{&Dqu1GFHL42a{eJ0yBoSJmY}j18hl*SH>y?SQNV% zHIbfpV{TF(w)iElSNoa0JJzX>q1V1~K37@W_?b3q{!47n_NQe)Ay$)n5fJ4)Tt-RE z0Qf@Y2Ux(dv6h~ebxm1~w3om1YP^qi?2)wb*pWllGHR@~jhP~V1(+DD@0<;y|dRiSaPN^GgeCTS3o_vTx#4?GDT2QW;|uqHhQY{_H{}UsdXCrH=GE_NDf~9siojd35o1aQ`-EW->*BJ4aSlR6A=wFklm=ovwBhu#~NBljRQo z#6v$$`@XkB3h8sUrzda{$@W-pu~+iQqs#}k5y@&(>u8%X_gt%~ZBnv^`(>UsHn%(2 zltjEn@gH;N__4zR{Ump&yTeEa87d%_+Dg{Z#x*O{&y;67dB!5SwBG%bf3ipK`+=Sv z@6QwIRsTO{NiVqcy|(1MD{b3`Mk-{5#xHIW52*#w8lfGTHODFvSQxMUi4DM)&OhO@Rpa`MVI}Ko%f1& z+HE)fy`=Y<@-JFdlvhaZ{FV=WUhDFEU;L=%Z*~S0VxHxfT%-Pnx8C^o_SlM>Mg(sp zuio*oujsSC`PuiRc73Vz48_vmpd|m)NCJLu{PM@;NIo1aG9t@g`7XQgvJculKmC&3 zd)wDW{5;eZ*Zd(rtFW(s<{IlfMti_Kss9{cF<-#Xi{_s#Y(0gV#Z!rRM+UAZe>bat z^ysZ{qro1g@A*&ChFpY+`R|+#vv;>ExN*<4jcrPbBfTUAws7(ZZMMF*U0 zqMkj%F||>)!z^$G#YvKNqO04!^}qppayP*B#joGA5nvU(VqT-YW?`$9hdeTD<eNOX3wD}hFDr{RDx087R$hGT95J$b$*Ni|=96g86xW(<%6 zx(MdgCZ;+hr`1{O7qx@|Gy)d+v%1O}8k=q0#92zV96z#0^S}6BUZd!(H(2XzE#bNv z8*_jb)-ypKd%$x6nY?B+=TbB9oa)xX)zamMdEJ`EQVT5J+X}ZDbUED z)U`QF9H62vwcrqIkc^J9blKdD+>dF;2+UZMPrMf$=4aY^=08F2AmI8giB6W_Bthhl9x9R@| z5}ySA=Tom{l>iFRg@*z&5Hlu*L- z2j!E%05JjqzQ;&Xd6ku`j~+ce9RTNvnh`;xjQ9WtOKsxx1*+qshE9xSVt;wI7^}=# zbfHX+koaW=V%etPdo^k%2u5+qfyGDTXAt$0({A)1A6Tkq15pYQ#JrJHqen z5(&ZY!(=U7cDaBI(!+6+=Gl+G{g*Pm5euIr)<{t)tKwp>xaMyp>2zb9pG&Sy{oXTc z?z5d+p3qTVSKn$^zUvdJk-PCLA6JWtT#oBbr`&dP`y_kw`#vMdF7BM18$4UNxu*W7 zi~**XNVkc1F`8i>J=ZR;u@uH1Qu2&MmG=Q|v7VkTJG_6pw>=@QZf+N-hCR$Pcs`p1 z78hPD@&mBQp1^ZF|I+u{1+RX$-FCy@tEMwA6HE2!4pU6m~-W9h`z|>e$Ki?0f(8Vbz*vDm0$mNCr2) z7p9`mVG_|76afDUz+zFBmT$(Veigwv7JoP6AyaVbQdO@_DM|enWO700lI;k)*^p}a zpu@mBQ3;^ShFp&7O~}3W5r&cL;2sGgU>K0{z%YtkG_%LIb=tQdI%F?)$~g7; z`TzQr_0{F}{tHLj)KMY(2sSAlULjpbK`HaqWvIDP3g8ehC}7B+-Km`hj;XZPNWB=v zKqe`wdIqXamuxmcuV>!lu+#x5Ao2V`f5s{%6OpJJBnje%G-O=8r)ZVf#L8satW5nA@0GzIx*Emn#$sw0=J&9g#RwjKK14eruRRnKYORt?j0ozHeJ(urb++cw+w9Q39hq?l@24v&_6$?tUM=TRo<%CNfM=n=O&Z@03ZNKL_t*h zcW=&c0=Fi?S`H&c@07SZo z0<#h(TF$1rVG+zDz=42$`uuaPee5)WZ-6B29Y|<+`v-4z1y~|z=2>9w11Ro3?k=5N zC(nSINpI}~h;cJPu7f|7NTEk|NbgfEH+u!9SQr%Lxsg)cb+Gun7kg{lxaq2~L!AI) zCs*1qCQ5rPEiI^vqqdT3Kk2kcuLnfWUa(y9Nto6rSN=?n*Xr+GQE81Wqt$`~NiY&u z7|@Ob$WJ@cnss(dV6pIgVf^U9SKrhsMvXZ`|56NtHa~rTq3?EKQ_7NK&-1X^`8(M8cv`ODQ+rrZ%6J)p5CAErEPMv-UZ_<>^>+TN-Yt*?JN?ivzoRiksqol+Kd_Di z+Z4M}XBs^Qe|p^~tf$Lc(6|!E-Iw{I&Xd}>)sOsCJp}pPVB$5eB(oo~*0zaqV1?<$ zsWsI{ob=2ix#{oWNiV?RnDH~kA_JUBl3?D0Lc$Xe&Sd87U_|k*2%Np}LamXF0*fSf z%53>1@3sps`+(hk%`GNm;pc!_j|; z_aqys+Dc7Qn2a{nG?KYNyIxaWFP4x=8T31cHTrQDs|Pp)^#f@Enw%Q>8AY#v$FAdt z66@DseSMwU@LF2O$Y29DQ7mKGpfxwQT3OkkwKTUv)>~s^lY(iON3kxoNM;F!Jab-_ zdOt?LIu-`OxG(C|RG5PB?g9JyiUYRo(DS%eoytRh@io7;5nz3vHMP#JI9 zG*iyvcW1HqCx3>NGyop}q(`zhXRn-1?8(||bai&QOf@-ks%EaQSHT9(sMJ-7x%B8* zYeo{cQ~b(+TXOm1-vJV%))2-Jun2>wexm#-m){&Pieap#eyQ4;o7=2y%p~hk&Ce0- zw{n0S0VL}4i-BRN7?NpL7NRCeOdjlw41|kd(T5`wBQ?e)Ic_^MIjC_Vo6etnE@n|vW-V0^jsXV&85we~gYx=8f9ejroRRX8 z2xGeP@+zCZ-~DY?XVxI{Ti*d!Sw_p9}rYBISt z&THR;hHT7)*>YXovwfY~6i}C$Co25ii{?nhU@+vGfDzb(>GRH&6p(s0YT?-R_`DhO z&lO_;Gt;r3I!Koc7ZppfFZl5vC~Y<97Y(U+6PoYU&!A zm8{046Xp#j%3B}|3QTgQqh2D=Cyqf4)!Er0_J{Hsz!7e^B#8;Ul`Inw$mbE`LDCv< za%lh7G!SvCitcIrad=WDp*u7QegDw{@s?3txd_{$g89&Qr z&R=FbHm|bH>mRnJrglkqw{Cn)tZZrPf;1Cz8nJluz6)mYW7^wN6&z2M{Ry36oT@c_(iWSz7-Y1p1jGH{q+Qv+l!O&66Z4PWt?0qV;keni~t&g+}V*;S% zyaBLS}A z2i=JO9wBpj%DYwDDpLRZWLz)D%0GE5_VeVWH;5;G}T(B3ea zCcqum(mGy?EF90G_YIj?%mWC{e1UlXMI?2~ikF$yH#R$aq8^G!VtZ^<`*?EEVieub zrpD^)>isnUMX@lo9we8c{qFLb%9=VE-9X9ncVr%1pJXRPgZA?^N9-r7kGv>9J*5f$ zpZg+OY5exNqio?MKL|={2h*jwnSpt4zT}Qd02;M&$WPr7HL;3fwCDjiWXF$nSXY<3 zp*jPJ;SG*`$R_)3px1ky%Kig}G1c1W6J0^}tX~o0u0Fdk`Sf zKaZf1v!mRqDv-C~u<8A1m6!l93TReYRbsVWuI!S%kUB;$#t3*un&4gs7p}OuEK~`b z!gG#(n*?EiMOxZ)cX_=ZZpBLKqy#{}7|A|sZkr%E8w>?9)Tm94B!tdf@87C9MF1tR7zx(w=Dj}F*=7&O`8%Ia zV{hiqhNtdzpi|!@M^~ zn9UC);lW}K-w;QLcl;i`T?gYwiwGoY>!0|gB$u(zI}l37MfeZY)T?(S>;?5s{2QPt z1`Y!yKs-JST}Q3A^MuZP6a>f_Q8{(@oKQlbzX$LLYf3_+PcaQ+1XIOMA8WYyXF}bo z1)MtfEcG^|UR7;9B>VT;diG&}DRXoFl9x+<`{cv7QZYL1=hU9FV%g~Dq+K# z6*9LW_CgK~0HT(W*ok@9+udayhjv=$u@05!$?dufLLiaIV#g}P+D)6iRL=`}BKHO; zo4@Gg0#F$Fc<<}@imX=pb40=<-{-R=V|lrlL7Lvf&SEID;mH-+WBA_0=?gWF);{_( z)ho7)o+wir44?p!Bsl272q4_Kb&c46*j4szz~=x4RaUN;6PHn*Ig;UuvI->uC?nuA zqIQtv1Jc|>2e)f2Q}@_;{E$eBJ=@kv)pp`|huAXuq~3A!XYH9a_X~J??BK1lc%~S? zT>94kqBc7}`quw+32?P57?>~W0zg}!BuOS7-?-*}v8N(kR3lsph8!$L=K!;TzJC2a z2?Lo^4VfJ|u){hI?@^*7eN=i#{$54U&VIu{4Ck|E%zKHw@x6bSyO<{SGJ9=G;J@s3AF-Fb z@}2hcn?7TY+;c-_E}6}+vI=|ERevO)e#>`1VXGhd@rddyR32~n;AaIcG2Y3*x1Unk z*TQozv&*mkZ?;At_7jTtvwiJkX3>Audlgkkf)df&3zmWY3c#YWerk&AS-(L4{(#eM zjv$o{TARa5z20a`QCV%hY;Kue7whv%71uLC`5Ag|HUWR{!Y~$k_k`?2b%TA*q@^YA zPHQz-G<)Wa;1YR&8{ZtwK?DzME^LbEznMsTkM-LZf4RpFce)()#joG|5t!ayZP%PP%9`t( zC60~E=W?O%pEi4d1+_2za$0l-%j*)e{)%eLfUUpT(Zh%AMCS>yS-5ZtSf2%=t4@>7f=LVg<3(-h1HSgcbbBxe@IFai__@KbFgF25K-G&HuT zZe;)|dBz|TfTccdDZA;>PpUo1wh3oRIWWBS%`ou$JV3bgQ1S8cZOFl*%Q*dDlW~a{ zCz4Y|*V-_*ak*(;XWDH&IM>1`3b5g#IcUB8{nm8?3x4{emWc`U{muLLvF}jx0SiJ; zGQi@o!+Y)U0UY>-Y}A;^&McOfD~LSav0vkYL`?l;RpaD6|KdLZ;UxVpGFuwbba=Tm zGG~m21N2BDmdI$b%_mPQ`uhYMb8?UoNl~@Gs6w(_E9dO!r5QEbfJSE#z3*nUSD`Le zNs5XpnI~yZR`}-#n`n+Ez!LrV3c;;E^FqLwz@jTr99&21jI8!I$x(-fa5NZcUn>Ph!{-J)?2^8fZ6myv>8QH+-ZCdwG#vqb#^?K@} z^fUm!2l>Iw`CpU#Gy%JeVH5yyuK>w!(>NpB!*qkspuI%Lp*@NJ%=g5TGg%JOVy=>q z#&clwxT#j(FiPtHW_90=^*aB~*7JQP49EVosPaB*csf#z%l#~)2d9S?2rN^Detfsck9=+#Axm_b& zg^|Sc2S;NZWIb8bt9$2nka9M+j#1K(I>`QkUd;)}0~9J;3na#-wGY_AJ)6}ohOzBD zaY)G*2oKy>FMaEu=^5Yr_5Uj78Ae-Y8VO5MBm@02^qD??nGz8=wR$bK$J!^ym_Z~- z2dDBb*z++HXK4`#!7QP_6OgBbB58u;&K7oO>6I$e4dBB@SMxl^5Wjx zziRj0{*BBnG&_S*qUN&S`mZ*B$t&$A-}x&shuOIvB^X14>UsIr-}$VPMK^x+Pc)~) z_$Z$lWw!K!tL)WR{jsgM?W^j2Slq*W8y&QZF8`37f62S;j+_5c65)tVig6S;;;IjP zMrZZ)U;cfqv;4fx=OuG~tP=r?2{ovWaVr0kzSj8I`FW}eq_kzSLimb^_ z_@U(z0nbAE1~k&OMW9C3o5{gVGx5-TdvxrF40>!Wa7n)aY`yBy5?gi2gGQrYiRRz4 zM+Aj9wiRE?LZ?1}Oq|O!*gL#oDw=OLR|X$L05UdR%4U_zF56if3hZlK7Q;fVZcq?| zBU5#4ofci_mXT5LTEH9y>$Pf;(dbUa1HIPNM1ec4G1??GCE!(?46@?oWO`D~VueYj zT3c72wa6fd1{?x1b*LuFo@|m@f(#8P+XN8!(Gy4Q-i^n8ZPVe!H~#gEz!i&I?7}&X z3TC5ERWW$a3{M8#em|>m0~m_I^13(xNU)5sSe>1iZFEb9irg`CPwgV}oaB>g1K`e$ zV$V{|Vr1<{y5o~r#RL=;z{B`dQ0R~J6fhXfVvW_+)t0b|nfx>XMeoB{Y4r`w*4j2s z8FIIm_qx5X=J$>seME^6AG4W?dnh=4Bv`0lPw?Tca;)AJComH-|B7|bGaL*#!LJ9r;5`u9z+ z<~9e51c@+8UKc{IzW}%iC?*zB@0<0aOo5VuDGy>J_||Zz@y;Zi5fn4VsYWFo0K2`sYqvi0ZB(~~XbdS)&I@3fw7+Glv5O+bj&npo#vYit>3 zr=59;t$q9#G9hx7H&^Q*1E8r+?~|h9E6){ zFtripMXjCpfJ}*m0$M_bI&aZS72Iuq=CR}g?4b4JaNDCtmz4&qm?Xc6Rg9!ku#7S$ z!Ye?Di~#|z>Y7HIG<|_oK-9|}+PmfC1X{-Ql`hzjES3$Gsl5ek1~CM^NSUKZEMegQ zRoQqZwkqaE(CwK#I^{cjUc~*{3g;v4( z)QJ9)r^1A(rzz0@Xu*7jU_3?-BA~9mF>7~1vc9|Xh;fff!Twt}` zT&$7@fO7PJ&RcMtd}xLel0*i{O(d*b=kcQlWroDLTUk2tNvI_->uhu(w=zeC#A{21n@>rm}OUg z@bhB*k%boH`Z(`dd$c>b?5%&UwRz_c|M8@oX1y#u|4sJlH~)z}_>1q@FMsrfl%y`q zLFBPjwRXk3KA|KEj3+MBan=@hRoM8qe()bPR^Pk!qZ+rs8_!~JQy9!=4P**w^5L?G z7h0eAY%)?E0xro^&kspds=SwvYIkz57>r}K@KTWH2Ue{P6bg6ANeU?^$3Z|EU{3WC z)z#K#tYUR-tu;6Edwtf> z*r=8nUb{$J0JF++n&#H3|Dxno1lg)BDU*Q%Stqj0E~$et^cEV@u%|C-8`f+;Y~OsS zB_VIlOBwhpQuAISexZJX|$UAOc5|$JUmavKn=-q$@RwqntBr~n55=bO~ z7g$uiVqUYD)ihRBdA(y|B{2da_*YvS^F8D>))YUt)Sl6t5^4QS>%G3e|$w*Vr!hynpcWB>M?}3+UEOQxcVnh>Abi4Qn zkBSh0Og_V%fMar6&KSCICM?Je6)cyuQ5qpwOW}dHBM2!|I_J_emWra>5kxkd9043(r2=ge$B<6wV=Q#TkSWMiTl`A3u)xT~>qui>SBg!Q!CKZ^%NZ67f8=1R z+I8<;$n~k6Lu0Gv1FVBuFmS=Db#=2huT`v0%JOj0OiJ_2^)*xs9;or&^dO$Q_@#FE z;4a(o%oC}s&CmMMnUY0mDJh#XxEY%pa`j|{#60zuP?ecE8>SQ!r=D)L4b3vML7GR) z82`Nd6LX;F7vggi39Q#Y@;%l=V^fIHqtK|5J6SVf&E0zZ! z4FJVSR4in#n<>R|mHeATJFO6E>LjDwy?u=Uo7dYV7Qehg_dkE}%T%YvUc~%i9wy!gxufE= z>izi06y?w8WEQNr@YC}xBq8{HVnx6r?LBCaPWu+5w~Lp(Uh|P&nShx+Tc48Q7(i|1 z-8ZPs4Re@MfLW(sVASm0_p@(^8GgwtuTk;^qmykLR@##*Z?z@MUT-@#KOyNjO14pB zCkt3U^owuVoP`&uMaDBv-)D0coUeXw@6|W7sWudY8>Gr!CgCcl z!r_sFKgn2o#fW0E)joEHVp!@G5A36M77`^HV`WLnVNZxyqoP9WG;1B>Mq za;v@UxBkM`K7ObD5+MHY48cLAaW|}?XtRhw@e=B@0Mh2u)kaNTCJnT+0bB*A;SY0R##Rg$5Z}f zBS(J9{Zt4b%6^%kyM~|D=zvjc3|eWV#>|-`oS7Xtal*c_Vvnug`=Y7M3t2zENw2+d zc7wfkQL9x|gK|UGuk#t@|Iju0f^p*vCmm7fyG|yQtw6TsoaSZM^pe* z#(bn;I3$&MT07rU0xZTsPGIfM%|gq z4a>DjB1I+8BO_Wg&L}{sm-K?3)TLPB5>W3R5`k`?uK5pb5uPI(_^k^Oqz zK*@pcaK0$&6UFKlB%HwjW^8XH>@yIS+$vA1YAHOqRI*T%^8{i-4wTAJ#E?ujOo#WIOfu?10wNg7U^io* z;l8VDny$#g&$ z%qL%m_idLNizFRj0Z_tg7)w5fIF9%Tvkx3Sc z*qtv)lr%K9D*4sheO&dCG^p?CJfgJ|$(|Ir=^ikZp`{0XHuvpZ=S*#KONPPY@9S6n zB1eEm2zx7%`YV>MTjfOrE~Pj&$s{Z5tldv!;a`Afu+X zS!^JC@uX>sY|FX_ZT!>)HhtbQTld7B>Zv$-+$_ya-fPSHM!6r;OO`aIYU?)qOJ*bu$Fn_eK;aOlr?d_sYsz_d7_n#YF{_i*MXatha~KuL{j) zTFr4CoJq%y9Mn8zKDc@&Y8*!Zi{%wErh=r|wB~-*>GIyw=bdL)z4!0z$(6U+t=Ipr zT%w=0Bwqt%cJbxEYs+8xPP_g4pOMTrBrkaqa8O1|SO4x8bS>Zg=Z}bC&6Cb4iCJDQ z$K)&C^*6R_%Tspq*K-%sB3Pt0^X(t~idb)2UPQvLv_zxaE_}@g{Ft3JroP+lw0E>LFGUo)1o?@%1ULy(AR5|8sWCHEMMASO9Mn?5#FHIS&#sm zo;7E%P2Y}{ZwckK|9_gr7B zvDVg6HhsoSn=xaijTt-E#*d$9Q>RXov@w(HjUat10>;cKl~EcPvVL5Z3vEs^z?dY% zVLBxC2{5VNa^9B@2GYS?0-#A&ND>JLLS$U*1&j+4GgnNEmh2972JI6tPmwgg1T4ag zd7Fb=cAUUus?EyBIn{wCd8kVWsRMKd#?502Mnl<2ml)s_wB~$m1QPLc2dJ9snMny? z$onZOxR*;{0*Z+>1US;K)>{by7Cq4*K&ifNelGDIymt;#3OxWLDfz5bH>pA*Ky-5Z z^gf#|DUH?{PB4cImGy?X4Q&n*NK8FAgJFc7n6=;{Wy&$);Jw7m@E;~QFghs^OBlw% zL9($2RH+A>oU&_x{*qNH)hgL3%$f&as#C1Q&?fIO7Xf9ww2c@g)q4L(VvNKs#(c<=2@VpqPb84Y+U6|d{RN$LHkT=Q9y@Wa9o)Owc5Z$`XRjMd zB_!m#QvR`OXW?Kj>OA=@0%5Z9e8E&*vA`5F;V>0Ny*|#nY& z`WfJZ*v{qagVxtWEn$bG?IigD3;+s#fBUA#)Z&BBrxb_J9y4KfFRZCmfIz7{J1T>;Ei_s zO`oxqxYdS=2WBy}tEU>i`k*Eo?Ewc#C7bxKkXg)`zEsQ{a*UWH>7wJ7{Q%-1bl?WK zLH8^vWqE})k=Z(S$XU@~6-&e|S;Ft6;qZ+h&oufAe3J~9KNh93mi^uaBQmsT{*k;M zIlNa3m5qSKf$Rf01}RZ8_iT(_Ptu<>=w7dg^pyh`LmNy5U?wCEqBgPFTXFRFoRAy} zzz0}_O>AnS0sEjeG&NasQ%h<>-Xtefl|f z14mETKi{$4c6GeSDxT`P`AvKsb7;}TTKlbY+N`!Zck#?N;S?x&lke0R9w{mHwaDW7 z2URCU?J9w)*TwZ%mjENIBJ85qFv2v7i9|Z5wi*sroas-J%Cw2+V-=DqclZ@^Lk6q@ zV;dN8ccg?7cbRE0iPfGIsi9^ueZQtA$*qwYy7biR(p=6YlatCSWybj)&9Y_Dp8~w} z7p?1KM~~Y2b!%<&mQD81gZJCsJ-C1tMRG6fX|o3B%$a9rEN1y*0XZk}1t7}i-T#d<7@_;jevxmDOF@OY>^#T9`EUJH*Omav(r2r`gJd;!U zj1ERTlt9jM0<^tXrDS$H*2##0dP+ZELy{S*BHEE820A5t0;qE>-t*Fv4cssL2A|C% zAs`+*d9KdX9nUN&vxu3L47*8G$iORR0|6e$!aHz+FWh*@3blFGaiK+5W)nM)}VAq7L~ zA1t|ZnyVG%HP+D7ZtW9h+JW6$Y!^l>%1d~Cb10HxPbz{%uI0q>BVtKO9socYyWLx# zO1;s`W#Z%4=k@CO^UM=MJo{<$&Q+p-)*0*%d`+2krrJ-?!s5r@{;Q0g49pSx+LH6G zu*@D z32OFh3Cu!$v*{pfpwN~>fCK$`gStFE%|1Vl`ywb76bx`mK{PT{nLywe*{w`04ZgWX z7A*%YdVR);jRA82#uC#T#;>ulT}9GlY&l@qzzM(@UtSA~NdFqay@ zgR%j4IIXI*#-?WVRqXHW6j%f}R#up`w2ZRBfo^5Vo0{n3IHkaE+D2xyrm=Zt{3}&pNgT>s` z#@WM=og(*yS#(yh)*Vohs;a)xYZXI&n)MN-#-*Xz8X8(9KjE+`egSgVu3cm6)~>M? z_uOTN4&|A?U)4jMKmRm4ciD2Af78w4<9LJ3kZJK(@$zd{v(ODb~ttllo3Yf1@Qmn-Q@DTvow5m@@X=803+$@KzgB*95@HUOz7IEwYku_6-K)}HGwp9R8V$;+234r;TLrW3*-qtJL zLE_DvC5GeoRO<%&SjlVH*BkYO2>t=dtXmT8xSA4sF^`(4r*0kVU~b#fHg@7HXXCn# zi7bFcFutf zPb)@5XJ7nQo!?J9_+#rhxI+x%&_JKY8YWMSE(s$_pwv=^_CU2ZYr*+;yknnjUjL8` z7U!IPf%SA9wVhj@OeqT{OvJ&yMm;9>9m>~iVyIK1!E3OSv_2(6+`qt+#w~4=3>KAV zc3|(;RJPzuJo}o@!({RmZKX69`qgW;ecUuLv`CXNPTIeFqsG$BD|^|%OKJ@x=JDOx z&ycBe&k^GdSR}E)J>gCZSOh5l=v#l8DJe?8;=q8Nw)B;D<-0zqx&G7d{mn_e5xtzQ z*53U7Ps_RZ`Y-*VR1KjRD&m;-aWe!Kd7d}@%f}_p&Ch-(qrd`J|L*^m5z%-5>BF}D zna5RY9$#_t@Lq5G$hC^=zxmnsXl!I6l@uYKR4r5D>5cFGlx^Mcuzmllf110#PMHN* z^!kMt`sJCvL948&$>d8f^gaCie3k?B6f*TCU~!lRoT234^1^)2OlFj7c5oMSg(+|u z;UB$LiJ);M6<)Fc(vVkYC`eOv_Ky77%GS5LC z)X>-_`(duR4%V^jsK2hM)i=!gCa6U@jyK4yZ9Z2EhTTT4ru z)u}FO&>9<>#Uc_k^In4kJ?gCph^1bUAPF!lxoOI9YO%@XtjBg8>9c=XanKGO=U)D= zp7@Ku^cyq+%+G0~YV3U%v{^%K5-<$|Z8=lqtr}PZ3P@$3;x3%j!U-_KUUfUW$oIrD zb^#Xs-{GQ4pbBt|T1ehA%wUQMoiL<=$zd}KM#s%!FtQ~i--(Wl4~TWHPvDm z!_-FRBytA^gm`UP7|t-E30eR^WX$Q$6-HGD4<4{bA6;p8{QOqixg+1Se;tpKdp_r! zWp@6B7u$jbXLt>9T5H3TU6P6=Hbi3?rYNaDX3jG9TVH`q46q;LAD|@a$aLJx%%n=r zhuW_Uu;{f#1Q)dp)SiqHyTTzv<8dTgMMgpr%3v-Nc#O6XF1{$%k3{{rKND|Z0i%}~ z#w0`a8oHcW@_i^=Fwg+DCI|qB-tr*+i}~XQSb%^3s39d@ zG5_G*aEL^{#qSoAWToJ6c=p&q7C|fQ7xj3Q#lTFt5+Ol5IY+ih@)$`cB@tB1<+Y%4 zc~8#j&dx=PiIfOQB`-4IOYa-wK#(|Y@*MR#-M;w=S5RSEAs0`V$vP%?BMTQ&#iEd? zTYKG%)0V5BRLRI_n66R(UL4xYuBGW-zVUubcU8W(JF{~Z<5?cJ9g`OnK!e~ zIN#%+(`*v=y2~+3EID@*w7-!~e(~KV0iJIx!q|BoCq5DC& z zHOOrzPCr8+P9+PBZ6>Qfg;OD(MJi#MIPDC9SHLF#Sl3csZsVt(uII{JCARebm*sA> zgMnjZt#x&FXsx3_gJtx+0`jK9X3jrP%p{D``X}zvJ*oHM;Gm3TDC2-k!Jx|7eV=L6 z{f(PASG@pn$sIF(hE18dSn~t`=|IDi8^LnL-vg*-|JL>7$!5S_*4uZ`lg>K(Rc|;) z$&VeIpGt12`TX;871oWni;6vwZ*uN%<@D>Mjvhqnr`MB0kddduw%@BW0% zIpae6{@4CY%yF^bXJ8)cL*Mp$*DAIFEbdc3Qm}C~&U`FG~ z=az{LuUCwwr0HbNq_#XH?4;>C=GhQ>5_74{A$vHCm-P`dnw zgQsQGcpX~kletZ_;+WWwF{56HfP{ZzV+_DYI!YF^r?W%GHa6I+K)IobUPyyBYSb7j zFB{O`TUy)XdRkUCU`sTDvWp!@>80CKIz>!AbT>wN$QIVzQ zU{THB33B_qac`Kbl+-e%z}o`{4_c#EF>^qz#5ve|C}yl8jA8kkJAp83RRaRu-j@5Kz5YUawdLj8R|cZ7DQ6#P|iH zl6aJ1kEpO)MGZ#!R$dS5i2_Oq)VtQXoFpyvdMwo>irGxpCf3TqVjN>pC+DCsUB>f) z#KP4^hL>--1E&XLC7@Bk4$LCS8?5Jh74StbMh~W<&aq#0L6c`KRecuhi-I!&MF*A< z>=jQ)0qHW_C@F!ckxbJ~-LhGzpQ{#-GfnE00DuKxQgUX8tT83`Q*h?{iA$mh{%P*L zbIWS$IJn!N05awPi@}ryqny>UIM6@`sWgZOFmkPmVN;Dh45=qeJ%)$v zWuKci_biP!ZDg2ZI0mCK!7-Rbp>G5^ix}rpFpI%PhckAT>`G@9NeKbQ1QuEQmDTk& zX2NV4-E80dq*QnLd6kzksP}WK;daTlw{8Mtj-4>a>YLm2bIiP8+x0~fCAl2?zw_i? zRMrVt4VeKJn_I?+S;XUn*TUS}Q^!R=9y{kX?1%ck{zV!P7sBvu>>6RQ(-|?}pC=vXv&%NL4gEO$0 z*^b90J~yZ;UaBV#lf0s^i9h%97=DhIZe%iqscVv^9dN{^%ZBB1^Es~VIpnE1e>n1$ z<%e8e;qw=xnIp>eM;}w^P_*YEIl1+b!dt;~*mH6k!N)_>EdcSVc^2ysu(1w^7eUH?;vQ z22fP8MuEOF5zbQNj1+Qm^-JwMYO7a0Z2$hl?~7IZ&-mhAF1!5ocHzY@m2+x-=441- z-^!%C!?L(>AgeYpHFWns(_t;iQj(tOjS6)P$lWR`6x;?_B-rrGcW;u31z7A=Q0qxD zmkmjV6o4@$#lp-evd>Ys7>9SpCZ>8nXBZQ^m|SaRc9ejLzuxCZ!j2~e$3A8SAX5Mu zd>@9IF8~j{YSo+`Icf@^%4PNG`?)J|e4qq0(;Sj8G_hMH*f1ohr;uICj)-*BMdm)* zHiWFp*NB5il|9J$)SoY})$>htXZ)OlA2-F_JJtz+DM^{0dn6j74k%l9avHA94CT}& zN<)}>DN2%?5})BrnMr};W=qeB2qZnsbQYGjFJ3e0GBlVe>Vp8bM+B0}-0&q>MgPV0 z4E&k9xsV6DtY;Wvu1(KT^-joJE3AF&G}XlI+qvG39^Rdq@Z=yXkAYO;k>VTQ8%QS9 zXpX>CAbsRaRGTaXp~!!!2ksK^%NM(^001BWNkl07v_FZWPc(9?0)-9pfj>6Pu5-CGV{no`T(A3!GIr z`K%6Bf_tLovFF4wJ8|Mj>bL9i=1e}A5`$SiWBQq+C+5G81xW=Yql$-yFvY918S~Du z@ssD-&aF?#b(80`bMxcY-FaNPebIY;1| zx-C9~9mSh=&0cVk3~m6x^x537`W{alR8*EOq+eSz4b$%Q=il8zx)TKU@@6Xv7fx^sz0(b&wrzwRaf2rgOX+H$trKfcjbFN zY18MNYd3xEPxPL}%MLZf@>jgmUi!KZ+lt%1Zg<~uZ7KPewqg<}uY3Dn+WaN2uv@PC zTU&MC50c+ZI`q>CiXjrxS6K6#zxt=PaSc5g%j_gK)Ldecj*L^th!%}s{O>1!jeK8QbOY8VTclsjvZOa(|hX&jzqqH4@iK{cBa3z;59uCG6yHeTprn%K5^-6aw*%xP+H zo~yS0UK+vQs8Wt!uE{zJB*^TfeX8MON`Y12z1*KXb_J{Mn6m#bO%kMn~c#F-hyl zr6eBIWr1pvqk3JOvx*KHy`4sP7uNn=s#)Yufkm}%z-%Q+QRT*2Y~4`U8&ds^H%f=e zaOtVQVwJapk<_#n`DvKi02rf9g`3~VJyl7N2yjDwTB@uNi&=>jb+kSG)D!lvU%S@U zJhl4QJ^Ii2{@nYkUVW*(_Vrgz?*bJhtO7Jdy-D#( zQU+S46V$B9+@w=%2$DN8xs8o&3ZOaAk%)EC#F)T8u{3$xhcGhoU@PmznB73ifU4%t zpGgMjLt>a1$B-RHEubGAIe-XkSURX9gGCP#ydImtRIY}JIaE>sa~nWWrAv0GdvO=Q zWV)8T-r{-#Ze+oG;Ub>*94aavBNtGRgvYvbmM1qr5&Kh=ASZX>V4G_jT5ZDA1!7UC z;c{T+43dP31*0JkfLzw6T2$45C3BVpNHjjGQFKF^kU9GENP%P|cjG=#={e$rwXQS@@;GRtadl8tEkONR+W&~&h)X_3x{N%Z*)ySYtm^xnx z4uC%GH4g6CthNS7^r#WV&;-D`f7eDaU#K8prAct{eLxpX*q)v1^i23Hu7BL5xdQ#Y zeO+SfT&jrMb4PN3FVnaXkI|!Bt;#SG?8Di+N7qB_#Am6`=qbd?C0nbKOBIr{(xe@^ zBy)#7hwnADjhD%e+JIEmiqR93I%b-H{kDydsBOlKdCSxfk(M*atJkl-NB7QLX&W=m zCeB!>u{nHjw-OuL&(wd=K{qBo#IFEEN}mqx+oE|6nE?Yl>-6OgsLdn|2h1i;E@Kum z2iQ+aN^h{Tk> zjlcZKwbp&&sP*(5PrX5jeISVjl^l87N55>lx2zU}=Pt-ey--l?Ty*(|?EF`~%kKKg zm+bzZf1`v53$RF{;Iga#+|D@rHTLh{{-5^L%G*x@i>z);buN9&pV{h%Zn0ah|72+o z$Sg@&ZWmwvL0f*wHMZi`uiD+WeCed)ku#J8!mHo>r?&8%%k9n|e%>DX#kV~S}>HTu+gW5&+v!pQNRu+Q(Z}IZR=twYIifne|&ub(Q+fVSGc~ zEA@#mjnr|dWris0A-Rk3rOa$~jqVBg5ueMVd~i#*-T27<7bMHq6Yva#Pq>i=qrham z&<*#w#`eXZz3>sJt17qmEYDkMcpZ~(_FBWk0#pIUWTN4wDgD-?8Y*{4#euUc)hp`H z#4Pq;h$9(l^!rP-i&0-(NUTHv>iz6eZ^R@&Wgf#O*3^1kVtqYziqtFS4yYtlJSmd9 zpGMPkm_?tL>G&&1Qw|(DV&C}cwf6X9kG$}K{5AXr>-=?BTxpkG{yM9xt53>>+#JT& zn%5sVs4qAf7T7(Pm6bZs=F*|OZHC{1*F})wMiRp?QDg0n(l8vg3J`r?CD1yo088(m z>fnlv<+BWP3KC+N0-(fk<6tD!pB4We?v?_SUZ=*FelIx{#wK&}UXpg7!X^|!kLDO= zCACfJwdk9c*X70g3&85laRB$am*@lO?6f!Jc1c^>^U@85g!K8QMaaXldx?6Ww2{Vh z${Ys6c!YJDTxTO|pRko6E#L)PecDkRIpog0@g8y;%uEh+w^=|501ej4#~}fEITGhd z7e90J5Hgb#$3>)(^k6LS`4=ANGOS1d7{@AdVrmIVInif63WK!MT#mOyF0ieyEc$pAdoHSCKFKvKP+&!JSe zSad`!e4qDFZ4~VAfV*?zqkxnamTvyym+4+$qo5D~d>se23sie@W=Qo@Gv+T-YXXKmE*=E0EftV5>p!bpex6IKy}ooGFS#Fb|bp!4UwNxw&5P+~KH8$h3)i%3k7 zt&X2^n(f`S(VCh^YrLn#ZCJudGtRJmyVh%cG|QZ5hY~B) zVZxfuUU0sW69;x}baN~#jh(ajuAqj9IAQpo8KcOYl1Yu1pg5Cl*4#GHs%x5LZiTE? zATib1d%LaF8Y+yul9axuoAK|n_Hi>cr>K3zY>mW&n0=H9+PX*R3!gS+S2_3&z`SAJ zAxFk!iFR5p`K3)%xgFZS&E?iz$213Nufb=*LPB)C@jZX1gwOR~`U6Rexj(1Te0B0X z&${T%_Ufzt#2&l%X8ZZg|KPqVY5nEr;-Fo4*$3@{OW$jE{_qR-z|X&#*Fa|T3F+&F z_J()=t?k_Ognj?(e=3$aJHPV-(UvT~QlGizvD@vI@BDSi-X18FqzU~PFMQ4W?eY75 zXt&+)ci!^kWU%O)a(2*0@KkIYQJD1MgeE<3W;q>wW}fe8EJ|48AkV4o_?R%bc;0u* zXmL{}SoH>F&QwCV;~Is$fP(BybDc@-3I(qb6sLy^(w41o3Lt1=jD%vKmrc(jl^C;= z;85DYL)%;mmfTU6>@IAf?l)z6JwoxVKMWYec*v^T%{kntgGS_T*a5pzC)Uv2ACcn$ z6!|&9WnDe8RF_;))LdOx@9hY5@RNb{;%*NRJ<}f7ao||LePzV~J8*m$$bO!O;$v23 zEe%yReO#+eXm7NJT8i1-_Px8O-}ZNO+UC7S?7$IRVN=*KBC34e8Svr@{(~dH=r0&w zXK!0J%ILx9jDxSE%=Ik#fTcgZZYuiwd20q4-e7doi&JWM>a~b0mAXZjrn=FM|5r4+ ziA-dEE2&;AxtFT;Fu9s)j;ET%x-{njjba&VVdrz8C_@~*2kYl#`DwH`;B$|3bl7*l z^KH9##V`MZBl@fTb&^BxeAj#J!i!$2HCxh)EslreR_zC{2inn(u~c4G>ZI!XZL|$2 zj=rgO26Y8{9T`*t4T2*A8-g~HOMpepLevO*2#GRQ?0Lgxfyb!5DA>-{wMq| zOM<-oAk;Se)}GzFZNr9jVsS^5-4wpbb&MZB!RE}JSHe_8X4+XCciYTrfg&hPW+aZ! zA~5j~1#_bIu`}$zzO8oT&~9Caz+wV(vF|cit|q~m)Y~CM0Hq@-0e8tT0SbjS5Ji=5 zG4S$(Ex{CBRsk%gho1r5)R>&0mzD=Kt9E9KhW5kOQn;a}1heXo3q4ak$uuM-5Ud<^ zZm@jJPY0a-oZ^fd4)C*@rqs2NQV8Ph)-99=!tr z4>StLI0RWA^I`0`nRa0R78}(*S=V-W|8{F1KV1oO-iLoVCQhs@%7BV0J8@*c99NMiMvrPh9fmvn$^M08lk0)W?(IHqhY#+u(c`A+ z+3nr2K1tEN97z2|m6SxHUgHFWNCcNV6CVQV0GT9LWCqv|xS^J~H%X3BQzZ2aF<(`+ zKnVR1VOtLYaMN?dk$b}A(*z8-X8@eP3dd@z3?Y;KeYYAWgB9NV5^v(N{*Lw(q z6)Tp^AyCH12hc(070Q==25ipf2awaN&k!bSep>#m3>`I&_m6$ZbhC^KI~|RmXzhd# z5DhEI>CfraEz(x07@PLq#gvRANQGaxb~R|V0D#(R3-oSn`Q(B{KhWGzUq?Hf(`zt; z1;{$CFIqw2CV)(}A4VK24E@yJifikburccaGK>I$5FkoGf5@a%f^!5H@XRpA2p&YH1|)KyYEq4*SWWf4)@~fAayeh73)4;!avKkF{pI z3CGAjM_nefr~gZ)qm_jz6;p>ygO~jVZ7D~ddADpRT`T{db_vIfsoV1aD(-Rk*j?q2 zlm9{m=$9Uwq#{Wn?-5LmQCsgN2c2{ySq(4!eX^Eb1c62N3p9(JAL2E(RE??^nKH^b zh^}e7h-OZ9H8jS-jKohelf$nU3U0k&)3K2p%H0P=yP&Y*dBTx_QAkKh=b~O)Sr&9S z>md1ygPjh#;DVY2kqavi4T>5DiPq*QJ;$xvw2{b=lX(4+Y;?gsPYh%jJ}qnqomD}i zrE0j&k(F_$I$tc>20+{ca?(n*vso2O!Ly&SAvt;%LEOVQ&ETiw*jD9F1E^lC-8(<1 z0{@v`Dbs&YdGSa#3!Vq&r^`0O3uJJgOxa<0AK83Ro@A#bOG09-v^2L$bzPGzTU#z) z{;*D#uH7IDR+h-ZRb{3|HPW+1az+2!C(KS7CaXyLDaAO9C<#?joU9`LO@+c%dF##B=5aT^cnt~`{n27 z%h~5%C?iIW^0K|Y-L>XO-&IhiAXFs9d!I@}3}?5EPbn$sSQu4c2euHlUcq9#q@-jr z>I!?y3POCu1m8hzRd`-9$qXm zyiKv-#sXDZVA}$Ny%x2fAOIAoYRddj8lEoN>PWMBIvms(6)C}-c;;VE%8ZXbh)5U- z_ceUP2)Xd0Ns^wP=?x>7=4IctpAGgK+VSR~DV$>agL>oZs>Z1ZKO1H#2 z!+p~EZE2*i2!p^L_%*^ltWnc;CT6AL*)+-PKVMw~9A=50Qf-PAf-#`h*2CfN03G># zN3vZ3#3`_gY5>>(s(mb0{Z`)P^c-@Ht*xon5c;H}{Z z&;l&74MYn2&Oz~aLq(Cf{}{GppflJ|D|x*K)7gf@h>{UFWq2fZoTO#svrirBF)?2N z2q1C;8Y_Szj-B0W0G)cMtHOB(%@Nc#&>>ZAR+te2eU%v#LvhnN5F8~54qltQsR8U9 zA+g$uLVX$a{WR#|+XS!v*ecRG&cAEtFn(-yB&T42!M=Gnu3 z00?7lfw2I(C6qVwdTmAk3lBC1nkA=~IRs9<$xPa>$==mhWc2E$=*ci?OwaQ3Jwv zdn>8Q$DVsX+v~mX$i-4wUZ`Ccf;s=p!XJJ1eY}?E9y*`b;s%=ZtO2(4IQq={7{qw) z;qz6%$pedl7!DK`CsT6Q8hu~h+M0P>1U|-ug#pFD0>uIk#xodJ4n63tg!xA|V6nTe z+l9xhK)O2xTj0ECB!|t1+gdmgDWBVhi4?WvOQTngD!S2_2hpyum}?dgpbt(k9AFjrFg@lH)p=Ht52fNEyOLyj%y~6i zjGC(=s%=TYMGXeu2sP-l49KdoMtS_xGO1~dEMp9Vkem=F6Sf#2`)og04&G&$WTq?d z=xPHc@#Ak+%j=&ll^Nfzl9HO`)VnEZr0Y;k9oo&UZ5}dHn4ag(w&^FnMFj-2^LLFGbmte5DofP z6PzMQx9dV~!6F?KGhTefTbDv>0};N0sL!Zy*%gL4vVJ2BR zD$Kr>A6JJ^YZtv$(e!t;_ocR4vls-P6b}M;u9wRuT_6<|6;X|in{K&X1`i$*w5)le zC5HKe54~DL0~maVP1{l6-*{hmKafO6RtzA-QUw$%YQTr|xA;V6LEtcZPK25CHme9V zZ%{pTsa2q+ONAeJQIKghFr1WN5LomZm|NhB+du{q7Dw=~h$f&YUZ&JZ1e zQ;Mu#c5Yv0b^tUmFA7(F&ts)$<#Ep7I8b|Rg6Ib5ZUz))~=a@z^qb9)VxjGW%AS3_SxWMCi|g#GYbQE$daXP9T8r`lezxK3tq zLI0#$y`k*4qGk@YoNW@Hl*~Szs58WS!*|gmk{M4v(*%N0)KDV$q00FHILJDpR<%tU z8fsXxh@cyeV+9o9g8@L}d&sT>sG;tg!Z+!;1kZRT$Tq^pKpYAEQvqBsZ_ttiSwz(T zA((*PjA-wHF@!8Tf)5bMv4aGF0qu194I0BbeP96CaFjbi;APN=9eB)&lGP?63lZrZh~sAEuCChEq?opcHUcRdLC;P%gYLl(mK@m{R|@f1Z4BA)&WKJ8XKji zdV?SklbJh!pcC2DqMw!+)!R62C&fUY$##aJcv$S>*)q!(arzLFWMxFpXlqTsQ_|EE zk~!{CmVxn`oR-a2FZi8U2_lt&Sk7&LMr6^Uh6kXN6$lJ=Rc`;3jkxWRdjJLi6iHof@h#mv;hPPp+ zTgfsrcf)a^^n1)%_YpHa|Hy?>zJ8St7O}8^+g)2(YUHuaV&igX%}Qxg@pw1@VTis^ zfX4J|)Q4!PYrYd;9ZidyUHU|4nZ-y}Sexziqi6uQCJafnQCrtyvZMB%Jld*Wqeb)f zoZghM_oE}jQ{l7GP#e*9zi*4=-AHSv_hJX70qI%?qfuc$tEj>r>;q;pB(@zuP}=~L zT||wdZB9-q9t1%WOuZKi-?PO4&tVmvA&^}eQ4f2n-zLV!?ERvPQmHz{bQ9r>=^MwPq$dcVhq_VFZ z#<8WpSp#G#hL+}ts3RyNSO8SK1`E4YKSj2&h5v48MK7;*DK9IQ+8PKeG%*81z-WY6 z6fEitv~3Dhp*Kz`sD@r@>DIPY2B@dDw<79sNzulChPq9Mo;6M3Y8Bh1uC7iVefROH+X^brDckXLr-Vz++(@sB2cH4a~qbTWSeU0rkCvd5%K@ndE9J*2A;Dtlq zHrONV>k9Tmb0Zxto9Tc;Aw{xG?>;!5aGY&6(H`3ci#UgyRkZtfpwChaJsW6SQz)3! ztd?b91ZPuxTi)^Soj!AuX|pyL#tz_#8KL$zF0OD~kyTWOQ3ZO8w@x65%m*D>MzJ*l zUteD*mtA^+Y}kNi?U8Rc-h7)39XiYxGNNJburhW0+!2_u896u?=m(hJ7a|&k+Kd@3 z5|}YGnL~(2QT@7IX__Ix0#BM?jH;*RT{uh>KJyS&^>BAt`YzLIl+TJ^+NE{tE{Yz!1O$ju*2tP1;%tv@kp~)H=Z_hm#L5n39r3;D~ty zAcUGkj4|y88N)uN_&haLg>j%r35Sr`sip=}DFJ4@K)3t8_)v>ySg}Sya0hKUkd^iIFEo>ltQ$dM zRhglkn;yJ|LBOCF6@*(jzp)mfo=w#@A^zf}rxZZ2+yUyMiF|jcU&TB`Eg7CO<{G|& z`=S6CkK4j`it7d-#GHkmj{pE507*naRNw3BHZTi`?*YIfV8HtDmPP_Ph`JyPw0h}W z&dao{0y_2pi^xEh6|d$q!Ccawl&NGE;M&Qb3j`QE!m*I?2E`e*qjl94tkr`r2mu__ zE@D4dG2Dy2IkkR#c~*nM0cLi1>Kb6^%!XcWdn>1B_aV?OE&fSrt5N2lt$;MU2#{z5 z@l4CDW|X-!Hw!4Jb+t8;k=>8?ABatmvh_bvBnP5Rc+ejG)dVc{GOgUZjyc*yGA7mU z_N=W*6j>_0)~4eCj-Z+al;#1z7s7i&;0ry{VIL4wf;blD2W$p1kf;-duLD*A03?D= zppfESBS?S@A?WPL@}W-h*@w;}fb>`$eD-a8S4W?D56Ae6(=L@Y%fC^5a9DF?cVgW(yQlkAA8(S}rY5si)dDAklmWfRMCP(>B01BS*#*bQCse#so9c z^z+u#$un~{NJ|9GX7P;DlH%pmeYcd0j@&`gQlPThvkeC1xeph}T`$a*qKex80mhy^ z#*O+`R&uPIyGJj{OEWZ?JJ1JRwk|%3-`DCF|Js>J*b9YNOOs3l=%{5!rS6Dq0Gv z`kKK(Buw1dvp<(d9=e}d&Yo_VU-|jHq)*>|l9raHQRdhfjgU4qN?CcC6c(;fs ztYEa~>px(iTruSu$;;e9L1EwYd^Qhk-2wWs6ew0E;bHpsQJ< zg@`(UBpfc*ZL~CLb8^^3>IvA4w5@gW?XCrjp+ME6p(-j+aA+5BuTIT(&it&Rf8F{` ze+%O~hYfzIBVcKb>M&}vVih=HW(R#|+qH%cYM>Bf)AayiPx#C@Apwzw`UaVN>G?ed zi@^?yyKDu!{<^&Sjog)Drhyw~LK2hdK%!m|&bI}LI6ea?@nGM89bhwxW(BlT@1{?e zTgz?*RXk+k(5JdcX!-tt{-$o5X{? z%m&(>R4DgHZ6SJA14uI~=_pldmRYIaV7Vci$IM`C9QOryM79*;8g>fTVKbBvcL5;t z=6N87*);TQgv0K)S-^XQf;O`48Z-iJR9oZ35(MC$k^Kg>)CG(ByP1)J7}f+rtOg(z zfEJ*W^@{8*iD$2(Hnt8JK?95ztyu#@1Hn{)!+IW-em8|(pz<3h1^tJ!%>?=ZvUaw) zQ8E!+$jFuTh0C-BovAOkEnnEG#;7{CPz7ID_X+RpxdkOaH`F&UiK|BUv5As zXpZ}aDrnSsezTe2cI^17&MIz$XPS}IkJ-l3;#FR~qNj$6U^1wu%q$|CsJaOFy|%WR z*~P5ffs({}#daw!T+Tj}_&!dJIpfk_L+vW92^k?qyv*!i{hJ`q-ROFlNQW7^PO8WN zI4i1Y&@+P&EN6&Iki?WUmT!Pc%}iuk7HcAr71j9zCQb_jdk8>nv&#_-O8n=!TfEjs zXlnw0!fr>Lb_cV-uReLTES*0?#}Gx>lpc;bgL!p0T5*irN#1_;W?4A*zYbV5K^?=8 zIpj~b$ndcf*xKXU&tCPxq6e(JJ|G$;(z-tI+Co-pKd4cFoeT}KZ===;pK+`dlR`FEPcNPs4 z41lF>YQz?{0zxoOnXtSAF-Ka#Coj@x6j+<58)$w*C# zQ8-4Qs9Y7M}W98Q4wvxC;unnwArVljmi0t33aEfjG zZu=tv0HQXrr49QANFS-Gsgm02YN@HNA|;jeji!|b>ku4eM2g87qpk{X%}s! z`xroAGTYWsu{1;Vd2MaC5#-`JUcq!8gwc+Z&o18JmWxsne<7Q04zpFL$#Sj|JCR{X}?ANtE~sLAjcD?p<|@M z8#^A*;)IT1#X7zpuHL3~0-lN9s|woa@zvR-!()QE9@q-43$^dbTjP8xF^}XOFZ{H! zN0CYU~0svH?>Y)Y;bv^v9X^BE%2zEcw zy;4%!!997;ADh! z1Q?KL15wWBDu`s9OGAgl7z5o7_SO1Xm=hF#GV{lq-^Lg3I7p_xeP`n zBr^kz>>9*U5Qu_}QH5V^PlM;KZB0N?tl@E>3|m)IDHSDa80bVyUTAaT^7T z$PD{{(Yr=xEpoGo{`@rR);>yc4R2V3<|V_3JN$MWUINL^9JawxMQLOP!Po>7f^^!P z0%jBeB7rj?(1q`#)){OCWFAomjKD0$0Yp3ZIbyPGzRlk9{!4eu*Pp%YuM(G^KpzvvMB7bTQ`xi8I+mv;)vuMFong45=bFbf%eEQN>hbS5zEFvx;n5Yy>`FjF25*1PYCF zku7a+myeg$$XoNO!msclf5kxCa&W#pHRV9*o3C`WO|jKCHp`SpK9c7@Ui6#KE<$NG zGdZE#+pcM7mPVkb-|&X_zyJ1w<^BsN%G|l%NMX@Be?Em|v8>{z%`PG@Pl-Wk3E9?J2qcph1J>n(J@ooOc(vaKDG1AQ(7Wm}nhmMI#CENsQjp;Yv#7A=t>; z1B-D=t4qydL>pjH#WJj_s*|A#aTq-N9Olm5NIh+#vAg>2eA|NG;amYIVbf3i%$|kC zaK6+z#{K95ZVyAsvx(AMkqS_D;5g!5NP)BJ&{pJt4qTkp8MQzuTkn^Sg1Hj>j+(_u zmz=kenMI!#rC`xyldJ>IagE-%sa$K=x`e?>&!1=ZB|C2*DQH$(fGVz3)K!X|W<(wE zayXuB@D;z>G7bN&+ge08 zS;#B`EW+urv1#!$}|2T?faA0VsIpvtDK(T2zo+D7=a zDFzPEOA<9{3>vExzDL_N(9s8u%>VMX0bDp|3@sDm3E4{2*}=J|Jb!Ja)6z?IBlPa^ zB^6w<**iN0w12XhgH+LV{*C#7T4MqA7&K1<5Pjoe#BTg?0ZrmSy2KW$QohiK* zfHi40}A{df~J; zG*p{1gE+4|$@;vwH_-j^dk-aTc>S8Ctg+<#j*XZ6-h=6upXB5rn3VS?$qXp=DQ!f}Ij1g$5kDoZJ( zqk?zZLotYoN|30a5rOEM>Pm@;PnOh-0*Q@JVWzQg^oVF`i#PQhr#cjjW zxm~jBlg$u%x9vyiy8CkQ+V8Oqb)GsQTQkno&r!;I674w>TmbE$ALIET2!e4!cB5Ix zzzRUZ3PMB!hHfKY&-%A~^~pMT`Aqf+rImFpNi_qzmiHbZK!Hyl{BPt8$-vy?bX)8%=PWlYYXkpiC` z(KXO{6O%J^kzs9tKQuaX9`*70lJKmnB7fhu$^Z>dTVeR3HhvZnjgpHj)vXrw_cgApmIZjou9lu3DQWOO_T+T3&Yo^sgkn@9f=yZOeFRi$$5 z&96&gIU;GB283?viv(cWZ~MWr)8>7Z!T_u;H!& zi#8H(!D4W|qK@|z4=B3zirQB(As&55yU!}(JWoFHcbWd-d)>aj&>bM8vDSD;^yz}OLC$GQqlKk+4O2tRBVNPE@)oPR@`2Let%B0T6h4%v5G;LMsLZmcB zT><>81xgzG`Gy;)3e;_ODD)m&u;_i}W*@wk86ATrp-!bf zTlAjGWKP$7fBFir#56Z?rUk zodSro3@VeMHk44dNnnN;4YzeIL}1tkgqdBB(aZqu2ggL_kpW`jX!ujM4V4X?1P46$ z7FiYo0X|Sxq1@RhY3X^Ak=;uJGZ1;Ht7iKTGboJ1Y5BXxSuyl_SM$JT-;qsKu;>SJ z=qnKj8#-G^yuQOb^3+nj(Z{imImlWpC?m&fk8E3qXP>dH`Sa!_+O&XvnBAAb4D5&c zXZTU5*Mm=j05+a2>bD@Cg_S(mWMZJ2igU6p$$HekR~hr<1})KF84!2&8QD6ycn!VlwfGTB`la6n)T0StT}$q&+*DO3p1 zt)&3?w^EX|**$7$F-{RMV|ER7*9@ST);O)Ll9ZaoI?1x)A&qr4Qd3n z8IAxn-im0dsW0ge-SF>FmsoGH4SDe%E!2-r>;8ytYFZiJ)h5EtiuMszZ)zZ?8|OuB zBn%(2kBr)~$TrLtnuYBut7vMq2oy~nBIu@8+{UM#`V>937_ha9Hmhh_5LmGS)^Ndr zijC!h#9Ev{oV@XEg?#)&&aBR>-o>+?tgz7#E0+6ael7v zBqzkmzppz?wvPZTE?-k22VDK4l-D$FqWtToy(^62llR#|{&EI-`Dw)atGVCGkIPni zhQ*~2Dm_LWBZ5Ul18pk}7Q<>jSOKg@AEkC&7Fe5zz-m{tdF zG%aX74I=Ibo#*@c^W=$tOq1eb&EQ6}?e&L=a`LHXcnZpD;PeRL7P?Lszo2-Qf8nrs zY`C4AMmwlr5sqs;Z5(RDVB=Mwp^lE7-CT#qWgA4i0DHLAf+OQAJB}HHUZxjbP`uV- zyVzu-U0ZzQp=+34ErXf{2;y4d^b!yPESj1{{M0~(p?Nw~JR8{Xs7LK0^>qM?7e);h zp@uqS=r9!?i;eSY5AnO}Yy%8|ItGUs0G^C`(TYpO@qjFvOl%n9{RcKn#t+d4{KU86t3?O0%>T!dNb^y~sDFJ7rx zCPwo8gX{a&ERP!yfCq?m3{GxybG>Gg3|$!G6PgToURHd>0({)RtpQ`E7(yn7qKAFx zY@6CbfFU?+*bi$cXpI0$2$)a+!~ny}iXu-L-VaQhamZk`dEUlWAiIV3Gyt&xEfBlN z%I?EV0DLF-80eeFX7lFRdVZD%D*Sox`gCr6p3Oeub+FAtOn|-%=+@2~;eot>p!e?F z45Pm{<_!QC0!DCX5xi)G@~lJYW}PAFotnkQJ&}nOXqTj<3ljpD2mRscbU=01JR-ff58=0H6S* zAQ}Q-l;3*@*;Sy1(ie8d9ehmC17QmZL|dA*geNIY`zYFH2yv{~I6CjBSFEcpm*T>u zUY#id3TzM4dkCq;aOMFxL5D@44P(b<>#gt0cWwIT>h!WyZ1qR+9$90V0LrxXfdp_= z@Tk3F>66AH&=FAom0(PJ{^5FH?*NjKg@h_8L{6a8$v~UOoUnGnF~F_~=p_2*{n-VK z76`}0QH%<;!2mjq5Q<{UB>+b4!|3;MHeiv0H!T#lf$jl-VscupG`F@%>AIh!r1&Q? zm|PtM1cWr8qpT&bk0>+xu9iwPt8Wzhb^#WxpW_9Bob_9iTjb1pIw_cAC?|_gNaebW z8py1ie(Z+~Tfv%NW+4-`|6^mVM^{Cy?6$ieA*DsjhCq4`XZ7@8RO39?8m3cu2qTJ(}P*ZjG-?rnIdr$RUrRvBP9b$;g)2m;^TI zrO-_%tyVoY-+AhSpy_25$&c4s4AAbhRfc91wFXh^vLN!I^;wCcZ3Fao{+9qHE(MF4 zRn+6?La7ugh!m+xqXqApm0ecSB!8b-D7B5<*9qd*a?=y#sVfeU9Y*($V&+7*Yf)*n zoO1hH^38H6a{acli!eOkS6*%15WmQy(t;&4ESS%aGog^7NGl z%kTjzoPw=l!v>i->kFx^RRJsuv@!r8JBK}#jk-ipX3n#`j4iQ;t7Q*8|b z76JChLg2?NjEtNbTB-I|#MlRbF*S=u*an$KmwK%#sQ6E_Q=L&zXMX&V{Qa?q!-A`> z-e#|Y0=ab36zSi8fWKQ;!?V-Hv|ZkR_rLP&Gfzb=u9KUaE7#q4tK{b7g}>C!fTIOd zmb@84xl+@mSqOj)MEzmYv8X`y9qb82u|XSDrBDcf04!E}HK9sFGn;XYEfuM|d18TE z*!kYUSMjNuK@OG!23;W8;bl3X$PzJC&<5ieB@HSRpxGjQiEdDo;DxO!EKO9;fc~OA z5xB8nQR{3q<7Ax%mDq3L-vM5rpb3zUD6#@Yy*jsy3IGH(QcxKr4G%SN+7tlT;w&5*)zhAlu1e*%R@05YgfX_U^jhD)7sj`ezNw2o&EMMJbB04-EA zSz14aIe=by$Od9Jrm#ww9d-% zb<$8*DH%C^c>ic&z`(VafA9nL{xs{%12O=^j1Sc*5P}8HQ#Z&JZgPh7+SS9L)=rz% z!~WYA7?j#)wlq%r4?@6&4sN{QzRAv~@1bHn%2J4zti1kIARo!3{23s*{U5x^usA!_JTjId&}4&xZjKtfO|C$EpxRjp%RJDWs6 zh7{L~x?E%t;Txx<umGvUBK8MopgN80D$pvhNd3~ zND^vF4SNFM7oS^|bFIro+m}YuuQY~PPuM>IO;TA&Raf92WY_IKI$7U3S{TzY0rwdP z#n@h?&EkC{aG|GBUHsilQrF+MS!0qJ#Xm&t~*^`^WNF_qF%{G*21H|Ug}P1SM<+!y8;#v;V%FlR6q znMp^0D>aLO9In-g$!whh8?*51_gVXhxut7*J?Z11kt0}uo{X4h&pvowIIw6`O+CZh ziRTj%A+UR?Ayccvc(09w+J1zz`JL4!hIjzx>2w5(!3#D1g$a*AZlf&7V0y;W6hPai zvz$n_p|ZIaTa<1W9pB-w3$HF@R5D6Rqk33#BPJCLaI6AFJQLI7$&I4>^T;|G=9nP^ zj*E)hSCMLHTBim2sil^>V9{n5wO&zcwNSG~kZ5WZ5rH6Bgs}!CmC+?_*oj&lMoEn! zZ)y$56Q2~y{53TZ0U6x#8T)M^H=edTm0Ew!?bVML%S8`NgP zM!}-(C+bpA-F6u+0KsB%?>%?Oyzjn=`ZXMV%<*#YA%_QluLoce2LPpJ>eO50$EDHN zFP?GMxw8B2dwCX9e+hBo^@Vwxn+dajWCWA%(AJEiok%@ZZV~unEnizJGgwe#gB?vs zPL~9>&cK2dBk?dTurCDsAvAU;Qs3#r4(D)mh+XO*@b0RrEJ*URS^oX|nL}J_W@aXx zu%MKIc~lns;dtl~iZN&FalL8<=b{x7SvtQu;wrwOf)V%_0yj6`e63VhMaI&who3Zg zia;z$*C|_{;%8^r*DXNNCwkgU1fBAmSF3kPN%GR1+zT5zcX-* zIX4uJtxq>MA!8D+?%rJ=v5_6Ww@ zNJ>p7Ef4fTMDXEIA^VB%K~y6vw;#b#O=Sr)?x;P(ylHI@NO|cxwlKl_0!Tte7`1o+ zI_PU=+a~ngY!ugUQk`2{Wqsj~9@TsO+NHr@(Ne9$OeXf9L$6rtbNMr$U>Rcv>?k~A zfRXg{^q@d&IKRs)Xfm$@&l~;_20Jol5SW2&KnU|j8ZBK-}`Y@&B`f+{Uj z??Dw!lae#CyP=QcZU0JCry7sYFru#HG=!C>x-Oe8W=034ukLIE@;E{XG_q-cd{ zOA^Z#B*^vw09g===bx36$BZK~mdG{&7$H#MXY!O~fZ#yM`t|b0tItS9S*e#*r(T7z znbrqH00ItsT3Whnz10}$-MfIq@3be1;C0+ zN+mTIwWD}Xcm^uo)j}Ylb&$xk15|Z29#9# z7EX4t)dbkQ+Gz7c!&J5RP$*k`n{PIlPycm`1Z`@(Hb&7w(j+7oqm-~8Ok zz(TCfZARZuoUZbql|LxuR13_4#_r z4|li02n_F=El*#0kPPXU-QDgR{drA&lbmz+JM!MwD}OWDML3fOY(H2Yp0uANC3YVD z3%z;p=&zbKU7mV>!EfeX@IJR2Rv=Gbb&%v`shEko)z>%3%uha-($aD-3eDOyyP*!i z)B{jJ0#Q6upbn=V5kWXGR6sSd$_ z)~zd&^71mNud6qGCW8Zdn7>$il9H1pHz!vLdiRm6tZW@q+|1gDUU3 zOKDVUmS!%oh64a03xx~?#C#Mi`a$~@%a_UQ*Zb2~5VFI67**WruiTg=G zL0>x5=!eLj((LhvzKcoPZ!{*B&Cda101DVsud$ZdtlGL}nKf&M6s=v!j1vW5>Z%B` z5L|$-g3K27N47YxpugQRjILy~21;Zm0`~=h7AWr4Y$(w> zWBYD`2ABU2IP`T5E&LCCcOgoG`YZ%ES}01?$exDTIR%oEoFIdSZZ0wH4U(RbE17xy z*s7+fp`P`vpok)y^6s0@$;y>b7>y-Z$2H=eBDe)AGBPT*&Jk4CzWoNu;m4d#6;LRG zVm_g#ofTq1fD9lsEq}+*`t|bN z*RxrAfJ|9e8=hrWR+jYdKTyyzDLW^J^JwU>;ryMfhtMp(A+=d18Ecb`DzpW{7zYrO z0&N${!5EVO#dua29}rW)+Fe#wCWUK%lCo0NJOhZ;d9{$FZMOpG3;or!^mMk4>fNW0 zBqyhOAkxzpu_OaCk`YwFJHmWLph0VkO-YOW>CjQ3ii&_T{0Rh~;}TLOAtg)N+T)~h zLx~ivSw=<&eGM{}T=6`ptt+)v85%}G*sZPh4TCXF&fwh`uo&hAd%-Myc^&r%lUVDj zEU#lC&eZQaj2PH0uohrX@a&O&L>rIvY}7wy6FefJgsaKxJ(xk5Ws5$Oz<{CKv|~cE zpOmH0^qA&nQ_CH~z`+lp3+`@b6Gk6nXUmy7L8|HrIx5oUO*F(T+~;R1T0lCFi7Hrr zZijP*Twl=32^mzj&>AQl4wMHLjZxJ;U0QqP8Tk-nYy*GV!$Hf%fg+q@ zRX)O?HLfOJZ~`K>7fpD9V9Wijx*Y2x_!#-u6$iRhaGXO9CyN>v>~^f$#f~9L5v%J zCpzq%n|ZaIW_?1|WXk223LN7|Hvp8|rrymgiofZ_uvO0k_sQ%pK8y5lznlHwy#4jT zCnc{}UuGV(=H4^|hbRkcn3}a#*vsnsFTz~|;TRUKT_Y=3t)R*)K;r6ED+w5DYidky zv*4F#Su?3=X;M(oTQ=Klu;k_Ev(9(mW`pPet5Pu>^L$3Y0RWKUuy!8DU=KqkS}HfJlZM)AdH28nk!cU#6V*A7Jo*GV?u3&iw_r2YCdmWVnkNKYoIobpwt7j2smbEaVd;P{uq^)`JE67O?=~KpwxvkPZuqEXElC1o~7WJGXGb zcT!wjEVZ>YQdCqZE0-^mlJ)DPzP^^!&`@y0`ptwy$;!%+{sRV(8G-qoo0l&mM~#-u zEY##`Cj`sn!?hte1o}8?e#s<&8o#B9nsOAiRmcjeN~(fI70F9T$tGZIYmbrgk|J5Z zZnY_OQPz?LivXD|rZty}=o!JA5Oq|2Mt)gC(0%?AU@;o}6#lO&yc=1AuVl9ouQaCyp$U&&s?$a4Mc8?Lk4Td{qP)(y% z4Rtbp%#@jHM}a4zA6CK4x=U*J6u2o^G?dsb_`*D|S2GdZXU>-&_LcYam|8ST>H$D2 z2Bu?h?e!p9$tJsKnrf)AcrmCYwDeJcMO8qBgRGPU6|^xeGfbV9*D@nfX?XyfaG*)| zfTTAvpQQ9b@z1E#n&zL#kiECCO5T}Q9+BC?gc>)hk34T za@P@Z&v_HOycZbi&%gLm))s+=(@tuK%~ad#_vom`>GZ^IY|R0)iz<6f`l+c|#82CA zQG32=ki`?YF*S=ev#4!jv_==1Mi(qvVH*Tsl#1$uC-+%{l6KRL*T}je+b=7!w*Uub z(q&i5*s)ufF9h-SIv%7uuxP%HG4

9+MAypvrpip-0H^C!FjrbdH_1cF&{RJ4$<& zGUVGid-(y@Q2yubHzRu}X0P$P?k?w@f3Z>6^cf}AvGp95&W;-LtU8+;B_-?SipwsJ zDr<*e!_+(PW#rr6^x-40aq~^r_J{@?)dTt!c1FPP&b$96z5Di88X(vh$t@1F>2s=w#Fw05)I|QStmfL#S>EI+YiEF!Srqseh60qNJN2b(e%t-1l|z9fjEuQB=ebZM0QFQf*a(4`~D)Yzw&HUZynk1^Dewh z3i=L}l65NxgaFLeJ7AFq?8KKsR`IcE4@Y&*F=MunE3UjY1T1=vomW@Nw*gA7>8*P&gsBq@q(gnNc&ga>a64zU)Ub0TwLyUP?<<5U?j3dhHG!HcGbMc1PK4 z&@dT2W((;*U|Mm;H zV)FS>0dO3D#~pW;@w-kSLjxc_8UP>3vq9!?@Q|Uh&9>Wf4sEf;Rt&so*)8gHAsl7= zR$D%1eA<}U1O_CKq1{kcD2+|+vTXSZS@iu^^6fWYF$mOM*0ZZ?1b{^5cKaR1N#Fhh zWbD|j32b3ov=%%dNvRpETSZ+blNnx8M_XK2{Q`hR2A}cWW(1v~^4cOvDcKT;OO}?_ zb}3!AS}Mv*2o|B3T33%6`a1d>0GI69Xad+|$1s6nT6tKNU`Oz#!yMbhU@_>~^`urZ zg89=CcldvSf-h&FSFsXczz|Fc(DGq-l)9Sh*DTu1omWo~0-kJy-@Um`!J_5jT7w?y z2uE;(p#w1JhD~oCZHTPui*ZS()_Y zcq441AQ28SvWqFn$?7okZ^*EqZVS{?1&M0(P%y1^j9757$mv3g9yBddSkWlcW|l~0 zefOd^xbF1ic)9=lePrKpLnEU6 zwKgcAPP=43nYiPS9$&)OOA6)qTi%e0I@IR;IvYl7uZ(1Q=IVoG%V7oGUPMVrseJzB zx6BGE1ui&%f`5Dcj7((EYomc00z(V2K#^dPN~sDQt%8}msH(`5ic;7fq6!oZU`)WA zM}H!16@&RgF{dsls2Dr5XMZja-hXe@3;59CBjk!H*KqFX)&sC;OR*er6&&gN@8`+g zcit8i2*UUJ^zA1%+;qESq-S`MTeU?Y#1(6vY?RqmLhM9+!x;U)3>K%}d5`4g=6fPf40KZb zNhz)PssEwXmD1XOj2OAOTsiq1si-K6_!PL` z>u$JJ#%{T-9XdhLiu#obkMbQDRd(Hd zqKw&M8`)u}3DT!eKQad}9&DYQ$NqC#Yj}XMRhe-L_FAa0j&iAlq;zQy#50RnQoNdV zy7;}VJs@>;by8im!SgHF{~6gu)4S2FU8E%;^H38#-sa+!-xF9g{(ZP4m0gehB%0bt zWdrDD@d5sgKwV(KkgXk(K}g#QL+xZOMr$j-pgea|^G9V(WK;r-Kw4EL&)9T^l)C_n z9sLCJ7t_N^7q>VSWQj{)u`RM2EV4D=6e(3q5>?{UB5~~_e=kWRu%^ffR zrr_p7NWjWW<36eEWf}&1S<4_>>y+mk>0=5YP+&&bgNN4%@Wx{AIP&q)ytS>hNs^M1 zC5_5nt&)%sM^FfWn3|d*Dak2*LvkpfBEv}4)C6Wym`#y3iG!n^kVK$J7!37O;#|Ep z2*$khWr=*Tye1<1fC+WP_~CNz1^Yy#{uz4ES6+EVPCDr%x%~3W<(g}*30ptZ-Gw~z z+FZH$U!O^94+0O}9XpcG5smu8)&u47D-M+8q{wR(Lyrxkb?F1|%kwjrD0T2x+Ri(0 z8@c+=yP7f6^+jNw&6~ea7A^kK0VTn08bY&+$f8;WGlE6ZNYHapvx%yPsv4=w}wSr>Ig;<4wJy-&?UWVH;fIL!ceb{ygfZe#&X*%EWypG6>Xx z4&BXb^euu>jy3`ymNEy$*jsMAPL?f;PUr@~rgP7~SjO$Nvk%N%^~sL4ShH~$8(2(XO}b%+2{ zn3K~U{+qn_?%UBk0s&Y&``indO+>H-bz}&BL2*@Uk8SKb{ABt$z@oDAAX*t?stfcpD>XbNBHiQ<%OhiYfoA2 zgXpti)DN(tceb4dX{D`%G6aptCRS}g-E&EV_43rLbyDBleZ&ussURy^p1Aw~*=|(#4d_G1 zBC-L89d?*}`st_SwZHc2tFqm89hEn`Ggze?>exzS_76qB3do9!3CQD<_m_QkiaxU% zdT()3gh zUFCucFZFDqU01va=WhWl_A)e7=UV=6gT+L-{SHIF4asB&4HG{$D@%V^EMLx!1JJoN{Um!2mJQ`aQeRUM)K3|o z-+BA3QPWV7Sv>6Uqa-FSf&LMF4&!&=m~5t=kw+RI#c#|yt33?^6s-E-{r^VwbO095 zI_G?TA9aubi>LvH%Bb~U^ngDPSX40Tp2h8gHmN$aM>u!>fqsNkdN1;Nta6$WlT+)m2UVr*&m0W%0Wxr{# zi0eM>jB{kKy(Vh=3se6`cAHaYh&Ky*=G?EpmN{R}k-2j|{l#Aq=&1W0c%4?QQQqRV=fdwQsHc6LL0z?Vk5(Dg z1&f?jon;p{6<7=fph4~Wl(E>^7R2c6Dp}%3l%jjLPQ9kb$i&||WESa|A!De~MHnjp zGZ+R8J_yJ_YPY(gnAtsWjcvaiW*mPOu&ClS0Ita7d9@U_`LM&ow*8T8gJor5VsM#0 zLVmft_d@K$XKfVw&S>$gCqWwnCskW>XmnE*$Z+f!s1ITQqnSPa7K02(ylL`_rmcvI z>Wjzo!NbRM#beS|9}2d$`7#z474o2hM7Rm398 z42)4g1-*#J$8*5@F^)5PAjQN;eT&FrGuFz|;>e4(FFbTxnR3D|9fdu*8Irj72OoS; zF1qL7rDqnvyUtN}v#?YD-^c5muj6w55 zy#Wn;bF(UzS^BAIo8k6Qa$9F0>uURk5-b{_8~!v3zyOFG|Az74^;YEg*EwjxB7VO8 z)*JHNvrl*Tx;uOh!GbB*+(znqU3FPdvt-XOxZm>pIS7fFfR|BcCL_ah~aY13??>3#g9}pg`37(SpU@_mH#CzJPS# z#Do+E<{Rs(r5-&@IiKB0-El(oJhOO>*8n{Dy{kPy<`gw%c&5k%X(k4&s94F)>nDMj z1bOF;XXO2N-;u?O7yg<# zzMV?Lsw%4;32Z&GeJEw+r84W|kL8{Jys7O~ex(g-`rZ@wm+|Ar%iuwSJ;s}6v~*nC zdP}#Jh851EKhX@Te6vwmZ!j&n8U^a@E^u_!*b%U1I}Q_+M%j#8PSc^TbW>#k?Q;%g zT}A;Gy;t>fvFgH=4FW9oAH0<*(1U`WW}_?(1%RT74QU&^_!XP`_8KJRB|k}hT_uen zBWOnM*2_*tnnn$SuA=IErDOh6tO3UVeY~1O9duUKQ+?ly)Of7ZS)0y z$Gx*reY0sm%9dg12LzDX%sxOk0vttue>B={^tEzg0&LY`>8e(8p4TDmM$t{Atwrm- za4V{WYC$pH0eUOi8m)L{6H%uK$2cWL1#Hq%Q&sTBv=7j>0@^!Asi?LIxvC>#kt0Yn za^*1cpD(YL7v_|BY51;e2CjAVz+Cy~RR>A`UP{G@W?Qs)u^f8HA@aiyKD`cr_k|Z; zkp1`HKbk{v-`e^{x#WQl#= zBHrh&WBSRXllGUqtdyv4p37}}kJOV5Pi|k9Pq8(ic+kmQa`)xPN z^5vj)MZUofU2xH4(&PfMaZ+1ZVj`kAMwkqq8Z-SLSr}R;#=pRpS&E$9$571h%zCQK zdF=5g%7F(SsyEd|`BB%Ztvv^eyY9B9TyWuJ?c--0=AdiYWMFY4Y8L;$%Pb~^5%%dg z?lB)f`)n4~fuj|DihLGDw}u6aHlA!rD*P%_!nAqh-gt@4P7= zeDJ>KqyCDIpQqkt+wElk{ST5+qsLf6Ai<)auu@-{f;14ip*pJ8FWNR5^d(r*f*#Hd zQeUrXsrBgTjDF5W6T$i#*3Uo?+qV3&O1wcd_f9a1_sn|Ye1@gA+BP^{XBNHl_7p7k zNsV-IU<@V}QVteFcuhSRd zDE1gYY7gqBMqT=-{oI0GIHnYqF}-EHQD}A~#m)3!#7{&9aXe6MJy1%A%Lk^QqJZXx zK8x7!ypZi|ZE9quRkMe!G^lN?rBrn%rJ<^qWWgyp<;Z&Q?|8NWQhyWZ_-gHy&7x5G zG$mO@ZA@=P)Gew4D#UG)B@y*p{4B-mrwINxWp9nshU43XuB@g>9+^=j>nbDb0Tv$< zkiVR^yPUM|mXW_-vnPPSrI%hR4?OTdhwtvS*IopSh>AtKeZ8cJAZvYPT~Ht(+T%pJ zKi=UEBYMko*B&bAsQ^HmW@~I}ku&dnTi%(w@)x7krX|PA!x#NgChicuKo3NUPCfNh zS+llKPCw&ZjzcfIXeJtL1C+He{m@?w&2y1aY@+g6g)}tQYtvlxUo^Ff%q+HO^IT5| zA%Ol(U^|$MIVjht&1HSA*64zE8I7>b_w&D#yYIR^YNfY6efr3CH~vKmdJklT9Zj9l zGtDw8I2yXkN2)-U@#&OBZY;9GUYO#6}73(zp0Ls znwrMGzg9F*gBqHlv)*)R$$EMHwO3@uM<4v==(Hn8Z7xS0eVmLMwK<cXhKK zbu>)yyECqB7= zJ!`a8Mxv?B0$5BoSw!|&g!(B#WU8RJ8;dAJ>>vVy<04Z@iU{f#(S+A~r|h&S|D9hh z@63y=pBt`ykFovb;Ys^TPNr3WjNHtjM)8nC4qJ=x7v8G^M*hb4Vf!ViKt-Eo4N+szWcwd!4S~%tdIp@WGkjGt zI85&xvFWgl?GEs58sXA3(7g(4bv0Da^~B)GQu*{Ga6DLk@G+d*kzj zn_VOjSRoOeL$EbHs#!eye12bpN~-3rZj(EKSb*B0baCd)k9w$v3L2^#wb3v$?00fX z8WRK1r+_a6p9#Tu^tGNfbEf?J-_J>P6#{3!uT2GRZj#}{N78S~&g;)4Kw0rB`odt9 zp$rK$)XOeC?>7gs?9*nD?);0rdUek~HToDEHk8XNFFns1(oldUdI8iTV_)TFtek%P#>8Mml1z6-y%`$qm z1hzKV^iqwB)p}kF4lP*JtfJQHlCDmXDebKoPS^&`pl`VTDk!ih=#tBoWx-kyt>=zd;HIm`;@r$etD*i6EP79K{``6J#N&?&M4x`kTUJ(<{OQl9 z%MLs47+hOtdb6db=TK;6{o18mb9K|PjJ5fW+i!_p;O5v92p0Wg8FIB*Y;0E17(SmW zYCc!6_-<5>l>#>gEc*7e>nMv`nKNtV44L-mgHfGRTW46XXqiwNbYp2tQYry>Qv+C4 zU}b?R(nJxYe?I+$z^?utH>-v^V#G*ENz0L}+`bems;w^PJ;IlS@D0?due|)?-z3n& z`ghqC*T@!IZXML}zzlq8sBe%rUVlm6c9puj^pDua%`5GY63BWQm zviJ~eZmc(gH$GUjfKmH4`bk-S^>lL|fuWnDKX^257#l8t9qnMhSE@09ilbD^GFNulRzg5t)2K|NN zVnFdrW=$iVWi%i+&N3WX)NJ^)SIsmwwY13#UzN$6SAlv7S&&zsIRJi{qhULiN$cvFawL3c-2VDiL&zLV>p`b3%yAnyKK(eHt* z;?&c3mlOXOJqguYb z0X^M}<+GD2xbDFj0YQPauEFAp70czeTW{=g?t~j#xw(0A{f)OuPEKy5L(l9Nd_B)T z^UtW&PT4Mc6Zn+R*N+kM!fx#q#%Q4>Rlbd)+Kp95ZGs zirT$~odF@JE3dwuexWwC2X{=f&ai7(^ZxnN-X; z>33`ItYNk;L8oBRw36_N4k5iA?Zb>1Eb13fONfjpvwjxTnqGzgdKhSl$pBull;DQZ zgENzqoIyv=Q%eo0xm4jEfX^7u>A^E`H#RbkiznDa^h0SOZOj@rH8t>A0>II6GPR4y zZsNKC!a*`Yl(?Jab8)6z3FQy4%m#staE&Xbh1REdjeqcUoGTDm|1H8z08s__C) z39tx}kC=c8fiSCp796HUh}KiK$-=@0dGgcs?626}h7r*>J5~O5)j=|5h>@G`?n}<+ z#l^*P_~D1kXPe?xZMamQ}=b$5UvsjO*`Q>VTqpDrx?S+a6C#}=FA z$-i$rT(UEwr{P9=L-h?!a?-7D%FG38ewNxr+{f6>^5kDv9V~tF)1s#CE?Kff4mjWd zS+;Ch&@B}d6v*Vuua>@j`+1@*Zk7>Qa|Mg-WGbMjyt%bST9I8OU{p~X)FW81hQ)K@4DkQHolK$!*!f``kAD_*$wj= z&ME9eO;xFJqPh{4;i6*#YtDk>Q@?_*3X9pjcTbgh^S+Jda=GsrXPzs&@3B{u-`fOW zakstXs_SlNuQk-R+nVvtU~$+Bj9}-UgGJjyLRE6TphkPUy!_IO^6ootGkCZuHq3!& zYfg0yMnEx=P+s>}iM4C=m@#s}g_Am{PQ!6}_L--m&U|%$)}MEe9mnk~r=51Tpq7!F zY4reVczR~OtY7nkXV zy`P!I-}6SWc*8BS-HyAFjaFH)j!6d8XkuVBL&&GCO;)d7`LlyXj2-pi0=f>GfNWRK z7uSErSr^Ejd;NhvAL?q=uY@K>4Esa=^}aiQGlEr-j1`n$oqf)Qvcrz!l$k;nw$EC! zcGdb5wiSl$)y%eBhKfqCSYI!7tY1_bs#mvYz@lm-;CZW`!l{cSlVv}eG4Eab?;R{g z@)AP!3G^SbwQYat(Mn+;0DfAVRosR`Fo^0WB+*#lZ`%7TUNd&_38Z0plG33U;&9;O z;*uEcZ*Bx_s|$~yyM;33Wd#}U5Y9cQDO#A_Liy>I)+SHwlo>?I{D%N1Ct4W#8J>?_ z$T4W~Z15i_tX3)>)K36W$afQe#spNw)uh!4788=Bopq3H{C-wWfiySPf)gw$Y3Y)g zg_@{ZI>Q+mS?sMC)7~QK85x3JZ^$^}KV&0QQqe{uSrQTx`EGFe0GjG7!*NEdj%KNA zYLzEHEs>?`9ok$M0|&>r^oSkg(qqO&)Ue$>6eiuh_uea4TyaH2Mi1XT;e-?9(MKQk zoq&i3b-TPfdzqZ~xA&!{L6vGZ<%R|FmQyCkX$NkzDGwX=SZ~Z)BIn)zo;0)J?55q~ z<6>m$>3hiW6URnM>lQ>O5phTHb}<9>3&i6^T9p+iMwmXUJ|6jZJCB``$hskw!; z5}Rezzbkza(LL*!c-eA*MYhL4U9V;p86@c{t7vLAFlW&#>!us7jjCxg?gbgT>u$J3 z^78V%TgRMEP0Jzs0*#zOjo}u~#}8L#6z27Y0|@9<_V_;@4Wjl&^76)x-9j#zbcI0N zB=T+J!QyUvOqACdOio_lHVMuWO-Yz&{4ktgd5m+E?}A4*nEU&-$~ zOfEj>IQjgO4-e>Ww^E`$1uE&92w}|HeKkeg>r^`e4 zZ#-CpP#@Z*!A3VW)M`&fDmKTk4)dQ+KTc4yu^arM+}vEr&+jFfnVD3y#)fsFysS*t ztt*u3>Z+)1U?kUtXLi%AcgarU_oi?U7-Sf`09#<7!Ec25`nmcnVr@Z|JUb_wB}54R z!!Om63{Wncq`0_9R;^qqwYA#U*xmZ|A1G7rc~r78Gx=Un2G!JDFKsQYQdd_ikN^E4 z0WEn`Y?+x^(yw2C$;r*-d}m+EHVyJtR#i&j+O<+vRvNLt*VQ!*89H1pxM-5(<>fl{ zy1wc<0i)M*Q8SBfcCn$Mi6GHt6csF@4`Y)D82KFo$~~1;(?-LJN%@hXUm&xH2hyF; z&87gVJs1pu{zJC%mt=Dh$cQDSq*ET51-_=h8HNK2W3~w^sHzZ>K@@|nCJZ7cLUC`% z^lroiM1&9fHP+Vz(K;f!_6X9zY@cCdto3J`B&TIdLVTjs)m3W0NK=n!RucUY<^_0k z*$^P9DyF_e>;gwUlwJe4?pimY##J-8sxr%4p%6zbCmf(bC`O?;0 zC-L#I1W#Gnc@k)ErW$HiP9D`DrM;OVAIL<)r~_E?&`?%|zzvmbmG(+H!VgvQ>fF+< zV7m7za39+ZE0D*pI8b`$D7_(?ZQi_j6t!8oa%IF{Lo1EPAAekqI_jv1zhifVqUhz1 zOqb_pEZSsIdHX&`56G1lu0K?Ien}*wu z?%5NmQnSt%3lQDkRngg@pqjQZ_&(>Sv2riJ^n$$h>Pu0-z`g!3ku`upb=l1Nr%6gi z4ueprapBe-SnTHPp@0#K?@c#c!$mln4K>e~Pq{`Q2_N~k@nCVn?thT0ufLOy78C_- z%OE=zI(?Nt`*-}!poPG-CeR5is z^zJ{B?45H@JygD&{Yg~!8!cGm8*zdnPxY{7@yxT%Gpy`^9O{*s%U z&wwEOH1y;xT)ReAtym`L4OmoENSZjZLz`-2E$cmx%9dO2AeH5X(vGr+K#VjsHs}~K z{_Lg(i@gd8WbD{21+;4X%rEFg){MJ|z@J4HZ1t)YvUu?#g2p9_7RowPTZ}n&{E4T? zk;nd-*~AGmzS5xie<~BuxPEUTUR6t7cAK5z|a8)9wJ8{bDSxcfj?`?Ta0q4Qc+R2h%%Or zR8*T)v{Y2oZlZ?KW*4;trdjOgcNjOk+}NrcyT9FHi_hurHh>0!4?vZ?lgmNCmCc?KOxRN%Sm?dW(SL z+o3WBz>T0xdocMi9L$>HMOYoNX{vv;!2>bWlnDiGc+o`{F-sWjHg4QFf!Ze86hyl% zT2Ug$-29ppZ>Wpt9wRwEva2`!d4imN;MP$CW*8h&BBR(aX5RdCsb&{jx~B?9dg!#I zczJ5dfiixJ0g-;i+pnUcLQXpABzgPox4ZoAHrs3`XPz2O4|;ha}obuArY z*9@pKa=fHx_2Qhbt}J0T!;O`N6LpDX?pa%cpQ_&a7**_|-OzXIxZ_WXVlIS&#i!*z zZ@(GUX?LBlhg^NbU36NiD@!Sy=53*V??wP?1TC((>>@fUk#10!o_c2wz+zV?=ptKM zUso@eP1*>s=$_ZF-EjUI4oLWdEA@_ic^*{dpNRP8MSZmN94Wb%5Y`+s3FOh7> zc6|NyT$%UXH!}CDIjk+}>2}0X$H<|F9!cg7=3qv4Z%F}IEL=w41&pGCe#4n@Z|&@`iHhXqP-5a>sMdiwPDHc|~$Gn8m~ z1jZCIY%S`u;VNEw@p*aU^;e>Lj_%I!2??_GR@=(vqesj3+wUk@*;&rVS_hhtn8NiI z0e)?5&@QW2uadc6eJKkTd@oCXSlr|D2TiL$jNJRclN8r$YD9|$VGl|4$=2mVpYWyv zi@3M3TWlrc#_cRSjT=uP!_GFY6)b^LDrRk6E$7UF`STcT88URJ9DVGGl97RItY-S) z@5aR^FoSl}b(7`$`A~}Q*@i$61ZTG0ZhILya+IgE+NC*c7eO8L?Af2Qd}8SjOL}&4 z5sKzrbA9 zsDw3eaq-EF5Rr!2-Y!kxenTiHlA8^=DX(Cc7uR(rl9St8+S?ih+A^S@ zBEyJ`B7h`5hwut`?&;~-Mp7J3EbbQ#iS->KbMyK)r7~klWTG~p0PeTlAbIfOeI>02 z{RBVw-~&1KxZ|Q$oW!%jwNIToRW7;YlIVd}Tf5x$uTSOv*XNp1&|^EL3uAk`jO?Ey z|GwccDaej4yNZY#z||lB_(xJUBHeJ#>bfR5@z&R6_Tr)_9Q`iN&@OV^o}=WBbN;|_ z7VY-bQ%}iRXPwn;L>CU^i6@>cd+t5a6T4B`zfVQQbAiLbIsr!XG{cBF34;&HDixT` zMKbuo0EnMm^saP9590L^DOQg8KvR!23GmD|CVVGGF4Y&;jzU@L9RFA>puwfCf zP&>K6aO&jF?bXy&%hcO$mgUQXYmXzf3)$H@vdj1hf{Z(8r#;y!%FE@$58su~KKrD{ zDy+!PTy^!0?9q$y2C$fxkt^#9f8-_Q^&ZSxMbyr&TeC!NzF~^Y`!2fr-_F2dNM71| z1m53`4fwgiA`B%}JL3}h3_wE!4fU}oMZ7e#crE=T1i_M$)6pSKnxPVpe$|FywZ6Dm zZoT<>W|Dfcfy%$r&b!DSd;CFq7Zeyl7Qa57K0sW8DSN7CIh3VisXdI5g^L!*%o!ib zoY`M&RMrgV!n$$SU;iNk2li(s5hYdH$leXqY6-*DS6&wN`r$q!tXt!D9#1j2Aw!0C z{rF4?k+RY>OK!If6&134`H#%oSxD7NqKhS{A>?2@&BEBtGat;Cv?p&h`;~q_xVaNa+Cl7AOJ~3K~#3x>FH2i zT~+7abI*aAm{;hdIy=S|6WC9YTvTBlUG5lbkGI5kmzZ7te+T7RqQ(W+5&4ct7P8 zhtE{u9#a$I=-E-1QkMv_P^dAu@ur*Tt+(EC^P~gr)8?2qw0g~IYS*rv@iBJo%b}ZQ zzCjze9jrdks;s1mH=adzU2&T6b!^(SiRrYDKKdwi>C(mc`!9X)GYx%c9hFsQa8L~E z=Jk?k`MAre-BEVUo!bk78F7yuJ?Ojd+(qP@HET|jr_N;GPwPFCVb2cIV05WK9j(~e zXpbYUNambaBvUSdC=C(?I0|_5p`S{Tt}Se%ZW39|2On6-fYEdlfeX84$tT!V3FYD> zLR~Z>;CZ!ed+4%*O`*mge1>S~oLN(8lVOw=ZFA3{q13ta=?1rLk8+WM z#qpEp^P&|rRAeSXI)wON+2IC@I;-K!Kj12pNYxUg>*g<(Pm!OY;%qm2s zu;%*Y;}4A$pPgV4>ZkGXNmK-&SW;*SeV~n3y|$8Gerbj2qvHJ=Hf%%}UvfDMZ;6l# zv@cMf=nT9g`0bH$r6Syq%?Q&hF@}UZ_bdP$O_R4FVPe zEwc0i&Dp?O)yTQOP0`UaeV{(i+PT(Bpz155)Lh;8nK?6#s;*Hlf&my~;~?A->o6LR zWk3j_8zh5JtBA~Ea#AuyM^*A?wNmR)OiYy6Yk-Cdu*m+HvBFy~D`g7D{=5o$=Bo_a zogJRCh4#Dog7!4CU-y9K$Kg8a6Hh!rcinZD5j`x>F$djyFU_4d&v-$C>wjt8MjHO; zN7b^@z;RkNOr@1muArt3OfoZ4A3Aa3M4B;U2763C^w2{_*+sNRW=P()BF1{81k+^K*nI0&tp29>4rL`E3UknGb8T%Q|Pl` zjDY|LJVmp!&1ySwWY`9Pss?el)H;p0Jf^s)fU}BdhXZ@IP*%oYJP*#BJ;QhbZAwG+ zzuQQyGy3%p1{Uq81fG6UavJ*sg7t;_#<2JC#~((NSsXoj0>vOmorw7^iVE|ylogrW z6&Bx9CXVAQo9PB|l&i1lL+5loSIP*W5+4JN1!SRwW~sp-{vlZ&EZ|YLBTti6&BtrI{+3rSj4>|6Z*pQ&(Y_fed3N; z=+{Db+&O^GJ@*2~dO{1`04$2)H2%|6RHmWo?4lC6k?f*?Mb0cL&?vQzP-RE$BC?8- zS(LR%ko%4_fFFt#86fM&%}|qI(b=x5UdEp}Y0Vve*AtM23ZRFqAX3_>J8^PYb%7~U zy%a#w6jV?^(0}uCGo&UF$X^-TJL|Sg!J^EU^3bp_(-9SE$ErmyPO!+|wK9nQ#1UuB zqK?X{pFY4&gGKu~>^3(5i_Qn-4;EFX1ht)U@gDYagIJAFO=~eQ1Xx5}NMZtPHlhjM zS;;9WToetzMfO9A_evH9gDpp$&}L%O@#&^4TKU}pez}5exb2n=Qs}vHJ*Z7{Q;#;H zojZ5ZWtUw>|M|~2i-S}jz6KjmD%8aNFw+IdQm}sjtE3mN~W=-q=>WM z7@(z2C7Ox~a(SVk?K32(BJaBvg+iT@rl}G}yg)M9P~)6F zZ5BuM&9+L4B(n&xI3ax@i=*Xn&0>)Q@VHrY1W3_Y7j9?I4(#7gBM&)P^o#meoo@Uh z@Ambf&qD>Y=4hx6VCaJ&b?sW9i>vy?K_475YM609LLWT;{0r%Zn{G7@;DzgVSop7e z^<`T9`m4r^eq=Wx2-LhqOG>NLn38JM<#8m=n@E{^x6y(9+eK)ul4#zX2*BdCP(!^k z_$>roI7&aRd9Wy#g4K)1lR$MFv|xqzto^&h0*r`0`6M#1IA+{ru2aNV4J$AR8rng- zN)|(!mOjZkPq^o*KL<^+M~~jryZ4of^%TR;i0ukEpbeUpze> zo^-1G%^Hf`jN8uBIf`l3pFv+<^57!+x$(c^YJx>hWNATAyCa5gmq^bW{>WALa0eF4 zDJD8j3BrhUrxV~=Svu88L01KBH956DF9vh6_Hsr`FM6CAJb`NgCN-xjgioJC=Rj1c zlIdPh=R))h>RfuOg8p@b21DwO`b3AgC32AasJN(zX3j{bKMYkLaUNvkkeSnylXXwRhp`l$W8)IJRtms3FYAB^GB~q~)>xte zqFkfz00cq%zJH+sBl^{n2k$3P2u(LE@GrjjvJhVjycmcSERLVDfJM9DKj}+DRp)WU z?YL9MozPtNo`1EXoDE9CncN?prrcayA;uX?`LM+rA zbDY~C>^I+hMT-{BHSI!lRLfR0WXMQSl05_)vWiO{xS#8sOt+hFxr3>wFjcQzzd6On zCsI!4UfQ?&cLqJWKfz=5KmRck`~VF-Fj&-<754M-5wuc$8sb#%N8qz4nZ@9N6O5&) zX${GnREshX?4**ye9LMhQm{B-(sZ#ID=+17TEM6Mg1+|ZEA;BhmrNfITel3nYY?TR zq{#TpjMA^?IbQcLHv1*t(~71Qzxu9r-!*OWmhs9q9TQm>bz_RvjRIrEDl zQ?LQRqVsi@q(B&@OXq$1BX!kjun1;K9RoZM(@;T4jf<7cVtgF3i%D##oZy8*Sv(~q zc;$EO7cYPkZ3Tdd=u2Fjm*V2RJk_vCtDi~bv4ypvlupy$RR3zg`m zDSh_YuwesTeDTGcU971M!Z1%h@dRCe!wtrVgzWa%M?a#c-``+taF4dQr{^g&{^oN` z%47K&w{6=-=bwMRk8wRr>)(C%UFy)GgYkVl_WJiU@tMzDP9yf=G2mT#S}S^R$VHTt zU|w7F-h1!SHP>9@dZ7#9f{|m!Qt|2Rt{gW4TN>z@Jzx#cwH1tuA4=&g>l)pL6HTU@s_>4VgG(EMVv23`ptUC1@tJSuB2% zQtDE4tcUWl_A}V!vBIj2mNVPeCD*I7rOx{ZmSMzqK^+8zFlfXx$PL2BYwY+*E*2}k z2Z#hLo^^IN8aH_kFE-&>CT)ZV>KOAK*h<<@XvwVJ>_gRYj=0={mi%MnU~wVUuisGJ zs6X2zR1XQZuP>mKIwJ`Lfa)~#zPl(Z%WM%lebxfD&OqRV7wnqp;s`njZ_hW7>!yD% zdlKN~Z8y7G`=Ec`(RToKKlgm2@0sk3_X$d+i|+@8IefW<^Vp}J+KGk^A4BzR7*^A0p@m>k5+%Y^R~aN74!HJ2-+L2>MCz zkaZO*Q2G?jqBdnHO<>D537!E|qVXA2vaep%aU9S0#pjnZRo`@DusCrlwLA8>faw4c zd#tP$SiA{!wHIGvdTBxT7qA%3$r;^#I;jGio-w0_vR#eIR(e+3q;%p#Y>VEqvWELwq0`>l5sv=@Z(8Hti}F}c%iH055w?v{pnZucU*iD{}&Y#MTv=N z96>|WiI)({qQWim*KHOGEb4tkN!0%Z@y#z*3oNS4A{I#^(4pm`z2r@Rp>Z_9KpmMv z2-_qkB{DcfMo|Mrs51g2;wLDp0Gt3<@RQO&vAkUTFR=*2V*&;B)gN-{>#bF5w-VxF zXyHIuWtfY~AZjys@L(2msp;+1Q%<4PYt}?$rLk#y2KAY?igq2yb)A{RV{cL?iB?YO zO-DDaV{|*1R8ZqLcI?1E z?Hu4rfdnl4LIEsUU)UoL&hzBsOX;JJ%#65k90)PoaN{ij>lAtXQFYlmK!~g;#5FJ` z=H@`?M(S|%{pxEIp)Cz`Wzx6*9h#B~Q|3t%#u)pXfd(~v5RG4dxqgqYTk*E;aBUOjWF+Z4oE6|U>OXOG<`u+=% z$ZHk@fW-iTaGwdxKj`NhU9}chRxm?S-2{r$efRdGtW4#>>9QrK&ss>w9Mi@JEb8Ed zUdRQaD~CHg7DMTi$I%~uh+3%I4T`6e(`Q5*j?dta?eJ4CgUy_%JsgLRLJQZE0tnFmiXICnRW z>SLYLwL90hIkS2)p2{Ba-b6~P2SJt+%Gkf%$|~tdN+e+M#11D@`iuoaKSi+LZ~c>- zn@yue0EE~ydpFM)VkyH$jAjOuohg?W4t0xMS_DzPXiYgSvT76&7{upXrl1sAv49WM z_hAS>Wy*Le$d^E!+f9STw#NqWqjkLJuWD9T>|&*A+^I-+ViP{ zDk>s33M`hDab~duK#{>B#BGYHkmsW!$}cG3pZr;|&MHba5>!;FSv4uyXJ)AjHcBjyXRZ=9a5BO4TvyPHSZo1KqA4RTK**9sR?LfJqnp^whdd zRUPC3PB#N6ir`K~RnD)=X4Q}{II+|>OCe)_kjP4qjHq=f!7_^$Sd@tef*k;ri#ynL|T| z4mGyY!0{Kp_%+Ra`D>08x!KSb_x3oM#@}+bPqxawQE;G&7%L-s8J*O^wUr2 z7%g1k=71_Y_2}zA(4=QSwZb;xzKUDD{lfM%t#5bkTP7Rczh|C#miqO(({+Tu^)YQ| z=&;e0nwshuK7^NVFLLe42ia~(%*miE`^kHz7moa%s`pC=u<%bi3+D^0@OA%11gLEj z#*Ly(!^Jx6YsQVAOvuOu%ql7+I=tRYS*fU`=-60FN~zD2O?KuUDlIPNdvew-TC`K; zgUVD|y!!zFqpuZ_-K@{U&LV;cdbe}WqrQCy1PPirvlf~jOSJsir|Hc#ubXrqI_vDN zG-C7=Dq|{Jz6JKIjI1QYEFjHog2lIzs%J3G?GddOh<;f~HEKl;7M0H;_cxua6uEiH z;K}W3^=uK}(1V9$wskRuGkhquL#hu#_$U?%h0!#y-wl*$XfuGtW$V^$eA?YNI~&Bd zDa@0~$;qKnBL-7WPPWlAz38G#>84w5H~Nm-oqedAMBLw=U-7Kluk(IbkU#tKI%?Uf zEoB|tO$YXFaR4a$8PAD84OM8USIN4kvVt>W{A`)BhOBQOg>joc3b6Q|VJ4Ts;sEWl zsJo=tnc@6kS$RBO6+G8>GKv7JXCdNu&Vf_byqztd#1z+yWGSk%Lz zN~Pd<+qZ9z2rM>k+=Qmhm}4w(7wjJNI0_0Xi~XpKt6qn{_wGCF?P;>1PYoG5l8$QG z(&TF{_O-zxYE+X_YEy1b7EKs4n4pqsvVlD?WZ0+xU{M5Vv~M%&4|Qgdsi?>>YH^#w zLMnjZO+g`pMPwhDwuq?tvN8$Uw!4eGPV*C(qru6+|Lh8Tt3 zi!Je*Q1?+K9qX4_6i!vewIA=Al*A?P|yJe zs-lx7O)}0d?m3u8y~e*nTlQv$&5+`~Xx%uCo*8{vME9_L+cxUis~7$FqdPw`EYwh6 zbNU%)JMJ3`el72f;14JrwpEQYOJaE%X|{lR!kT%fAGq$zS}aT6A72`tbBw_6kmY~$ zktN1a*5gk&k%o^L!}Y^9$PvI`Wk40Z5@1pLwkD<2Baf<=%FoMo&`{;O0*s=4gn2-( z)fPIU_9~f1O}F)pM@7+=KmVW^Gp0~cp~LLn#ajVyys0y0Q|;PyeS%*crB>s+x=3rR zc<$LJS#-o?16UkBS|Zz6cIic+)H!n( zaowH02$1Y1R-sn*lQW)b&f^TRZ6hVh-nI=BFJRdZ3ql;ir~#NjeLW~p{cgY3II}oq z>P)7gYVjkP;(W8Kkz^Kk?%ctOj>s^&-Ef}aBgfK7C!ONiDwQz&EKcFH{H5H?fmRrISlv!~OK-+$}+`mm!_vuGvWg<&Q1YR6(S$T}oa zu-M-Mi_+hvk!npNhL)`0W4z80u^x)MifSh8f|&OjA7c?8C@fT#Yt1CZCk(0B0q0^6-2vt@1fBn23w^OZcl>D>ZsA(mf=>Q zSoZ_ii=a(lKjqwT|8KwjrrXQo{lGkdFd4KmYIbvG7UMa)45jlgKmXX+rxTgk*>mp? z2o}Yb3&Ka@naE%f^iv4juzdz-r$tmy0FfK*xhOS@0E@-QDnjH20ypq~)?SPM1B+I7 z2&{%$A(JQ9(Rt!1Hpas*2!sk)RV>UVLtF3^w(dR_MMOoBQEP|dYPR5j0#+G7De-`a zg#%CMfi@Rl(LbB0uQ9M>O$}!j1M!m;l?5DqP)4JpVyLXNkfM0-B(}cr#Kn>q3a0>t z@es60P(P796gnyv>i9j*gIY&WI>7snm&GVD7P^+p0TwYhW*3&xlb>hM&a6@%jQU;N zfu`Kv)i`sVE_8 zxsSSc|CcRZ#+gwB>Ee{Co(980{RCKibG2z^u^WvXo6ea*n4xQBLjhFIm7YT}Pk|u- zG-g8ZByC$3`F06ewF_7r>^l36V_=K~SghBezKy-CY@(eFlJg0$*A`M*Xo+dEtT?Sj zilW7)2p(sZP;B%PeChyBvNHG6y#sG`UH7Z+6ScAe7M)x5!Q!vK{7h5RC%AsMu_Kr+ zbLQPos7bEr%{OW<_m`ia&ox&FLYiz7r!AuH=UqsJdD)b4V29u0Jc<&N(`d%j3H0qZ zUzi-0uDSLG>e(A=s92I>OjF@z07Z#caiGB$%-g4k94y}BprHyw0ZOH5^_wzHH2c6V zevbnM4I%-H?N98;pvFmkb&fl4!MbO;nZo8#tyJ;}jPyCh#1B(iv%RbSRnVnDf-E+G|k#*aN zx^y{%?!9lQ+ug1Gd;&y%K~V|r#VUrMZ{X*FMGF|%|6ki6a`VvAC;7I7t>e%HV76l= zi`t-XL9C{zNV12zK9NOk6j&@M1QoSd`7D+)RTb-3Cs-^mmwLs2YG%>NCaj6R;0qQl zN)8HVJXUZV}P_$zib`#n0A#2D{zo>}6Ke+X$m(~Og)p15FB#=4vdXxEuFJ+19 za*puB3IkHpP&$RU4c8^cgMx}IqNbmMjw)c0vybtJ+Q1?smVqOVFJMt+D0oD5()x(L z+g3y`eV<9K8m7@RV=tvvP0Z@^a64PJY@wdRb9Y(*03ZNKL_t(Ndxiu^HPKOV3@Bl( zT)C3YI}el=vn{`{ga*uii{AZyTS&p0dMRFdX<{!r{%CW>zXuy7v(ztVPHeEUSHQE{?yNGVuscj>AX3XVOCsl$jCL6Memt1lQ?cTlH)z=`kJ!14k zYTddu2a^DVFt{QJ!i#D}Gr}*RkUPPmJ?N`YPMDyN&np=sqo@}EpiQB61NF2fTUuIe znmQdBxH=)TiaML9O@RTlE2CnlR_(@|O*^=62dkq3O!|ODWDgk_in1%-S%0u-y}Jr% zTf>tQgMlyIqmMjjoH6Zq(kV22#8_5IwxZ_T?n3F6Ihc9D++>jm+?;uKH_j|Vsa8|k zSeODL7V05#Hd6%`&{kseqHp#}zvsu%mPL`-@%(GTB$NAu>+F#1xRy7g%8{KXuotjW!{2Gc$=-Xmld zw`}>-=yU__9zwmYypcf%d=>5Lm?(<#CbI|QxDf+sy)jt4o_hAaimye2H$13Ga6st+ z1QWGDzj`_n8fv%h)Sqh>RaTKInca`)yZJ!D`} ziwYoGfy@*)QaRGHFsg(NhMGfWm1X3*MQ{wQ9V5y@fmS(l=1lXR9N{-Ez4TIAzI?fFZJf(veeu%{x?}EI%E(trYkuFu zq;%T_?P=zKbB!~s2M-=(1yncwk}X=apwB-0jF4qC+3+r){&Mz9Uk3%6330LX;5`@6 zrDwG@IW+GJP<8j+chjG#hDi0I&p15y=)xxj~GQD%bT$idL+^n-d_*^Y`sM z`}gmQD6=?wE(C7;gF#ho5d0fkof37{O=wMZWj$ zTP~ll>;`J%z`O3{J{#llQY_Xts85XXuqFjSx6a%n*a#I{U85+LJE%o-r~&)DepSaS zc+ida87wa=r;^e#W}HAU3slsSl5)z+&!vL= z0*j7{Y$7s`fx)5(=KPbvqRkMfnWxK{MV6&UCeg7NDTN6tii#b=C{}$zfY6Q&2>mDZ zDpM|ZZqRhRi4eoky#ER+$j#!6BC-?uMX4!NUp2Gn82AHGW@`#8>eFb@sE!NSYbcZ= zIw%j-R#}5k4Hk~b6axGqq6?uLQA5=tH!8!(RvKcj0YC}vIR<3$SBz%h2+EtYwoBg{ z2Be)C<#g+{7g57{4q+0Pee2tAzopABznnn7JX{+xs1HBz!(+n zA#ZYRs;rEr%mcfah8YMf3P6;sqWn|k9cwTFi)L!5XP(uS1`fQ3uRAtAflapc0uYo}Q0_4{*$Riw zg{fn5@lPjM*Cikg0tq7{@>vW47Om+^13_nJtpaOQMmCx}@d@k^2O2HFN(pK;E6O+k zGh*1F>eEnFTgccQyu>5ipcoNYY}$-w&bhzFz@lBJ7&tJ5@nPnSDfIKk4dHIb=kq)I z-bL5lau?<2Ww3n>*LJ~+uy$kiXwJ^~i>6H;W2}bi4;C5RD5j1)iqK;D5z|mDu!!|i z5~bB`%Jg=qymB{1xsXqHu=_=%U=cNoCkj0~_S>pazS z+43lc5)xA>#v@t{7$Y?3LBJeqPb4ZZrvWqq6k*(B76NaBmQ~S-W>Dnc>n zdwsecOAGG#m$7;%YNsx{>@xc1n{Qk<1r$-?W7yJEeXO#Qra$vJEq?twpXY_^Z;+Zu zPmZ{RIvsCrm2u#}0lMnA4 zpzMnCZ`JW595ZebQ@-tNq6#%Bn-Bb*vx#9~FWH!VvKC@9Zn7JSDL&)3ua@JQ@Ux>3MUe8`bRLdjR+8 zQ)g0gvKVAn83G-{B(k%n)HBqu-ZyxdNaAz-b(|&f&I>@Eh*7ts7C3yq0H7==Sd{(u z?%m6oMH3+uv~S4FqVrPRbWP<02V-;uIYG6Cb(GjD5L2H<46h-u7#5a-6hzA2HtqwAyF_gJ~Co_>m5nkRI-vEOA z?URo`iYT+lV_#w#j|tF>;DkXX@w@!&Gmp`lH_T|LOnVEY}n-gjIJo2DxuE9FsY4W-tP8JP!Z)bPPZr3V3P7KIDTqmtK~LXBG- zM>}?GryH*9W~>Gq30P!{x|mq2zEfw3*qc&W3$bvR(xlL~B6#+*XHBD@{%c;RZ}P7F z9s6P({P?ox_|(q1S?dL09>)BL@q-mkK|NK9r(CZHB~%R-3k#LcBC?M1p9YJ}6yiBb z`#6Tyx%fNUBGfs9F*~b!ol&ihJH0Z_5s76TV-JCpkXPV5FOs*zgL-a5x13n7~^7!6PV z9nS%(ee2hM?e=k4``vQO9dyBk7g_(dCME3wsl;qJtH>Ee07Wc(5-2*>%QX`@*%_3Z zlR+iLMf`8e*q3QVu(*+IBC`NgjWJZ{02q-$glz}Fp=KK}Bgvv4stA1)QAu$L&7L)t zHf{RN=srQAyZ7E9)Va$U^1Tqxi6>E)N~IuSP~I`;VXG@s;J{!}ohU$NHB3j88pWhqoIXc3vA8&2 zN&gG}trl2xSnRkmdUo+}HgDcUQznfyYBTiH=`-imh)(hTZ2a0}K=Ib#{2mWmRp z?X{=?qf$e)X{e%zDr%^zUQvNXYwrG=@7?V5fvM?c$Edn@RI6jVFb$Pc{VLL{{SleQ z5hU}b(W{mX_dT>uf6Cwhe-+enAfpICT3C?7(IIqhO*vIPpt|={<@I+^2uaSJd z90Dvlk$XrlN#_Bzf1LDmKU%2v6+_lR030$4P&SQ2rVv6me%VC^i>O;vwi@!eWG1li z6nY!LqVjOma{TJPbTpC&pUO&V)20=ja?**eYV{D&zvk+z>61_4`}g;3&6+i1v764F zI~!lXfvf_$bKY9|{O4U9%|xx@&F7y$Gy9**bz~+RY85ZK=pq6o*K|X6@xu>3pk{`( zix?c|J^v-mU%6hCBP%QEgrn-wQ==}W<_%Mg!RK$k{YJfd^`c*Ybyw$*kdVmKqEk-m ztT3Qb4D(A4S&Mkh=nGiFtD@s!sCB^rqHc5N=eu_8WGW6QNhVuzN(xP#I@`xq!3h?* z;GJt|MEMk8F&Yb*xFinz6c!dxPWA!H&&^>~HULE|VDP-OY9R-Ln0_i?5mMq@n+yuM z$}aNz3w8l3Ci{9Y%Ka!+Q6e_`e)_2=Om36+?bN9Y-7{#Y1Y1I|qdxrLeR|^YM~seN z9|q|UKh5J1ERQh0piT*GfNTJ$s4{Lk4(n!q^V{e1&p)Mymn<^6HUW!%0yp|X!hl6R zX6kx+1PHtdDZIGGeU<xOeX!24aY$n`{H`8boKG)6L{70p?=$0D}gI zOaT?ClG^P4lf=D?!=4f?E! z9Kqp8!D9ab_fSGoDjS(Y%ONlOfU?gBPb-TQEON~vk1wj88Wu1~wHUB`^5MI*V4hi4 z8Uby9#fA+VEAl`kQ%~bO@q|(*t(2@+WWv5uY%m1~7z`;Td=UckaM=_*1|bqCRy)8@ z(X{H7<+Su6GkcGKU{TR#K`n36vOUkK-+r}@2H$;~QNP4x1qO?{_XK_!pdEsQ3IHq9 zZkbXo_m1BIkTsaq?IX0wa(em2=Ltc+|7#oS?59qfBQu~{PjmaQ&#{0-fIZB)OhGM1 z&7wb8gy0SAGjwKAsHkP7Wvn?M!3R6D=oF{>zt*0n_akbk4$&GP`e=yih)}6cSzuv- z5YLkANy)WYy*SZh@c0R8F*1BuWCCkAfnlnO7U=LCy>bRyjbvM^NH2TvRWJ*Jd;RE9BL{1(|?QPnP5zoT{$V39M7ScJ-g zQ-maxM88!qjd2yg)T5-~%lW%q&pw0d)eEhNif6lE!2%jHdNjXWf9Hn!xX#S==0U9SJ8{l3th!zL#FMXdxu!<=ge5?2&Sf| zASn&XRBU`QRZ=wNE!6FSvX`5SjD!0vIXRgoOqwRyqADQCet!S`&yP&qGud!Y^A|lz zO&T|%;$oB-5NCPNo+T`uuh=Wd*3(n!eq3o*Px8=`0MQ^QLV{{5oWar=iFtt0O6XoY-irR2&9OY*27ILsbDbh;Uo-aa;B}Mlc<1D4`!-kPV9{1X<<}uP zn%8dtc7OiyJB=N6pD|dvqi=uee(nW)fdDqBzr=Wo+Fsv!Fj@OJ2P9dVR*foY=DN;+ zLb)IH;?vW|(zoAyZq#=yu-NWcv3}B4M^VvKztPcDw^2(DKz#Sr2P`Va*(QU{94u;o zY*jX7`DKg$u2zqhma^BL+Vk^^&pxJymMk{7!hgoD2v#A0f=!pKfu#q)h?Wq4MadFk z?ga=0VB`#-B9P*q^~e_+w>8&OSLb>J18PVMWDtU*w#j_Q|K z4T2$gv8)UiPe~~PJka=9B!EI;zleI_qXvQqfg*PtwK%oRk*!E^_z0ZwYhszj$~R@W zuG)T8j_Ux6RVEmvaEQneQw?C_rBqS100sb{lZpz_8~7}8hA}CT61)kPg$5R(x+V$> zQ?6Y^mQiut*~^isaPi8^vXTe!7R{Sd=T0XHWhBV9apOkLLjC^x@5W76(_a8B0UnRN zd-pazG^{j6J+h8o{&W*vaaLPeeBXt}Sw;AOp)EeGMuzqHT71SM6yvzkV(GmOgO zLXSRJY(2DO5qi@}M|s!JnH0EM{kC(UeK!Y2RKmaV-lhHZT{lk|{8nYf9r2Q&^~{s4$;Oit~bc zuZh5oIao}G&*CxWUaa9dJ)-7wXHTb}482EFQ&VZ;q-oTsag%VT2>N*-uqc@%WYA+7 zY-eR=GEEj4P?N2Bi=){5y>at)l8LD(r|hhKRE#x;3SQ%Qk$}akuepwT_JYr%Y|iyY zxL_9cU-smq%m6Uix^_R0Mvj@rzSCI;cX5!tN;W>k0YCoeLwfAdhfGdssi7h$r95;v z$d3#<&YzbHrO`o@lVcW`I^l#9Y1oJ{ynabZt3}8_eqUxGdW{1Uc zV2bO#5j0SlR^7K5C^BfOq;1=_GCkj0>S>+i9aJ@{ zT7(AUGVZseq}Tx#kzLe2i=d#Y|B8@VEK*rVU$DqoMPzQvg!)?rEV?aEtFb#jat@?? z79F#&x;B46Dd5zwzwEXJP(v&toda{QW;@(q z(dRnYa~z&&u}tL+K2tivsR0H?sSS_;5nvI=WC0ANn23dBJS!riZc)`Ps=CFbN1m`0wv~Y0%>LXm-DI>GTuLz#1B8#flZI%4$mKayBj^^>gOTi731H z+qMHtr=4OUma1U12v>n}s_TojPpSrv0vM&PQ7mv2m7Lp1 zqRr0x|Ni@LY4QE@T-TfGwg(si?F>{g-_0JYkck>KVu-OtM~kCc(!?pVC@C?K1vzAs zXDs)CUnIze`W#V9gN6&x{)<4W~Pi^t+Hd? z%V2S61YmL6ENb1l=D{NR_R5tn(rYVi33^vAKN0olc?AJDnPwNO2*NlP6FM`Z>2+_f zT}{tC{e)|lgT8ju_}x8dI5lW;3_lwP+T>*HQNT_!8Y*f2yxH`__huynS6q25U3GOI zD>x>>4owC3134;)E1ezy54=F93;yhm537r=Lyr8@J|X zleK>*-;+>CL*I)YJLIRmugzs4E)95o#k2IbVMbbyr4uGjrMB(bSt_>xW3}rwqsGmT zBFKC=K~q^4bjdaCvZ1gl`f0!E$wT+hn@ zbgYI7uvjXTQqC-@nneu^S=M^T=MJ3aWAq$-rphMF<)o;{=JK=>;=>f{v>F*N`QI ztUhNV;>9MzNkzqCkHv2IGh`semytaenT{$(!Ysqjlbl+xsd-K!=CVMqTemig-2i<0 zZy$a15nXrPb%)g|Bi!@DJ8Sju~{>eI1eXsp%7G*UlYAeIPC_o`wz|MeW;n2>Ly=DNNi! zM>W~7u<3LCEp*xCy*RU|Gf3zc&THqfE(Y%&CVR1J3b}TSBFZ>;kQU6FMO(LSF}Wn( z*A-ZFu0kCp15$f0)YIa^Jf7dg1J3U(pO)a z(G)?U9B|iQo;NwufJH4YA~7zA(mVdoW>7lmp;5GO!5o4*v&q(>vtjn_30qQUmstFO?jD{cD%xA)Yc?b^gN;O$$t9A>byHor>%03ZNKL_t(2?SuISVqxq#>98~L>kvM37esEp_}pAm z;`Gzcq+4$5ONoi7!;f^c2hfD%R7y-rW0mOqoD2sLbWpijj8Uw<_+1S^^L4Hdta?QS z5~VamJQg)j)HRDDZd1g;T&Y!*-^G8il$k&b7FDgH7Ot~wGs1yIe)lD#Yu~l&P913j z|1IA$0*m&*ZY!4}+KT8C zN1{k*t`0Elvp{7q2YU+$QzY_4R9aFXDt{Jj*RR94IKO@&WC0~v1kNntJfNu|8xb${ zO;}ta$`bGOP(pkHB_=^^A(3FKk&u|gq8V6pVsQ#ZR2I(RpF(xz`X|0thxE2mr9J7S z_HOZ=ctoURKsI~9SFKt_efsp_ zfu_0}-j5{@JwyZg_cuNiuAhB04L5jWUU5Zl`tr-KTzwOL?$+D;QP-~B?FGHXAh#Fz zHZ4Y?eKMB%{`5bgZhNf=Y%L;!0LEa?3UyfNlgCp=#z9y2q<2D~W%SsIoXODvE&aL* z#R-#HJi*+%GAf!1^K)74w5U)Fe#QJ3%4;P&`4l0mSgbOOprNu_oAfjGK2z%hL0Y@U%>Lo1 zqgqk=wAmET8F(pnL7*7fa1kE?Zj@}J&8U#h1JSGTV@J}yed3MicB@mj9?hJ6KP4rI zrCHU@zoXj!M(q_;UpH>}uiMk{erKI^4h^__kX6DAYA|Yz3-fanV2z^Rf8RvYr%qN( zG53cDtLc_I?xh~RuAsc^z4l_y#XIkR7OrE&Sg7g?4<6W0k1c(OHW=QoJ}!gBN$J$K z?Xl`lQIuA%88vEtEC+;k{`n&dChge1jWc$pY=%fPi@J6b$rs!&2h+6OP?)Cw`l~PL z!3P!^kC6x-*k&Nxil0SAs81}X3W}!6C=caiAEcbj0}K}N zU9rSMhEsw-VKa-kpZ|eH-vP=Riug?xWQS-#LQ)z>Tgys{xkI3#!A0i?vf@?SJtTBA zOf4y`-F+2IZ6C!z?@3L8MVme%^(nXy+!IUV$HZ_A4hvg&yoB06o`gz^eHKA{eGzb* zeHP71=myzEWEFLm!OAWIEV7-3hY}MKxo$BzxfZ3=N+qv1fubr)87LyFsOfA>X|og- zrB+0@u|)o5DojpJqHgD$L1}5JR#QLw?6WjrzyN;fj z*IdK3hBdXFdfI99=9)Fe*~LiCkI4?gI^)NWcU{+TTBkGUp8JMTTx_(MHFHnVVgPa# z{y@=ZV0UC1o!2aVUegmr{ZnVyO|y%jCZawl5RD~NJGDQtBMlikQuQ4NT~^gnAs_^> zfQh6aFNgB;ve`e8eVi0nlxQWQn4+$R-%-1WNT<+cWCGM|0R(c`5(l<7aq;9$(C>3R zvjAW~K*=pCWLlY-Yqx$uO*YNGywS%Ti8W+*K z51+N0ZtY7)9d$G-VO!pcjv#`Jm*LrHn9N}|4q%M>sYo^>u&6+R#}iLp7>LKjFi1pJ z5%qPvM)(JUMZ6zRKlM1h_wL)qO^EmN-19D=p1rQ3x^?S@{JtBIh%p4>OaT9Hy|u>m zc;q}WEBoFzl*?X3F%lH+I8n@Gzd8>GD-e8Lz3N4J=z+OL_l*Vg@DZcw`1T#t*d#TU zwxF-_l2+^~dDrD{>(_t9*-R5#C0rcZ`DWPo{OiIXGK0av;vc{N&R&{%d1keHJ$r#> ze7zdWD>x7i=2SsmmegEF0sIy+i(&h=twwE#ozv3l&^3K-q%+Svlh-q9)^K$kXE;VY z8WWhYaNxi`di}Lm2xGq~h|?#=I68h}I<;ki8{%U(IjTJ+)v8Me_WViv{@Tpz-5oos z3l?47s$(Y!@S`tdyx~$VpTJZgN`w3@D=UkI&rAcS_%7xG(5_EEFWvrJH7N&Bm|F04caXxVMyIuC8YZk>e0~BPuUjU0Jl>*C$X{bCWmr!A` z2+oz3RZw|lG)2WgZy=c{I*$I@{wwX=`m?Qu3V|DC#lh?WY@t|zj?er;hNchuh~M9J zW>LV8ETnia_QYGY8)fAsRG62|bOpS~T+_gyGDyb51?^PU5BB#1g276TtTaSaOJ^FR=$O{6sMBdD@qW8^ z@1~wTd(!&#>yOwD4GQNgue?HMpMCZrzs5J$uBEH5y2{A-H{3;G@_g*E$5>hQP;VPH zY@i-JdeD|F?r3~TNy#*9|dD5FKjNo+|N1pg3o~$8O1E5%tpUs&> zt$3;dqD6O6CcwU#MFkf5-IF?GQ7n$5gaoNW1|vZGs7igZqN8%4$Wgbb0iz!k74?&# zyO|1?;QnvBy&s)-{=b5DJKXD{`{xo2-Ay+f|ID+yQ;(j#saeyezDl|Nvum(eB6~^} z)2E+)%%H+FOXIv|Gq8w-qnB-;065V10TfxyRffvI>)j)qhKh^cwCPv2r$Dg7bVE&T zx9;cDh5x=dsQ02+`ET2Jc)3njnxhVt#xEFiqk$hJ)!H_SMo zbjqon=+6FkQA&#TBG!tP!T{1^m=*J=1YP<7J-B#2{rvL=({tA8E0btloA3Y0swd+OsL0O{C)KstLUW{SC}52_Xpbmlz%8& zqL$HJy`o;PgGB>&RRRa{ckS3hZ>?QTAFO+q$Kyyh3oN#6$9*WRUQ=q^;&>`8DWqLn ze`1y#)}nt0SVWKmnMGt3ove&-_loEA)UwBE-TRRRv>P{R$|VG6o_Q9}Q|>o=5QlyV z05_5;C`+@f_|*G?po%C+TV5&l?*SMmHvLqAMMXaqzzCoyATcV+L*5=CSO=C`G#MM|7NYT*QQgw7%!(&nlWum}+bp__Q)lc-)3sf9SWXDgMJ6pF-d zS&6Dw@VnP=l*TY%5pCo2SJQP)LSK_?1gL9?2}zWcQj4Gz#h*n3$ddp`&RB@rBG){! z0k{Bp4Hg;HJA_4?U=e`yoU^)6{d#q2_Uzeg9&Z{QJ*3Y#z`?J+`f7UO$tNi#Ir)&C z8kyA_Z@iISd(E8k7w)1U)`R2LsT111B;0XAeGZ^Ac<^Ah9C4e0JMa7p>DJrsWNIV^ zcOFO`wPnG8qJT!JCt#|UUp<-zg#1$lFMPcPUDPhBwbGU?f6~lplZ~@q_3GEBi4&($ zow{|c_Q16ux{Sy=>P1RQil`tzhl+~|M4Fq`PD_-RQ!&$9ID)Aa)`}omW#RVb;Ve2na3Ea>F1;7gI{8$NRG)fkCkDmV!rnig=r@$&+c z&XZ3$O)dPLl{+C0TS=Tj{OP|x(zoA!!!?AF()ru9JC5salaf$lB3 z8Z>A~=XC8(r=M{qHE!J0<@MYBGAX4lvkn2a^YgN-nqDbQ6K_miss_yufV<6`eq&1L zi5)sJV@|M|<{U~8ga1>2PU;mQa3mB|iuO=^VjZHWSboRL$||X>B8us!u(iT}*;yG> zQdZ7ZD|>eRE;LlOxe{?3ZJS}OkNyW1Wk_J3#Q>W{F;fw2@yAJKZz*ix|AWhpr~%jc zs7#_ITvO9vF%$p|2hOC&1?=pBBcPI5z*pc2RJUFWii(M)!h$Ty&D_r**_nZ?a%_XF zqJVLJ6!uy}XIL!Ss1~~c2=r27atb9SrSPQ1RJCYOek;ifY8z^wP`Aj7&Ui{rsYOv# zA(T|8D{@v*sVh3_7xl@tJU0fYrcD}CQeqru(Y9^d=5nz3`*y>E0budkYpywD7xDi4 z@6(l6UTG{J?&gBKR=&l z&ziAmVnFVY z11QEKqbPl#0`zMKb^o6X7V*xYZ5J+>Z44}&?b)PBGwRg2GqpaZEwyWVEJ2yO$}@F* z0l~IEHgBfQn}6eH8i`1eJ{;_z1`N2HPCw&p_5KDSf+TuKfJ7k68iLRF&EP-NG1v1v@fv#~jl})fW45wsHQw z`}WZ1pM65>-g}pFazU#OPxJMIfXhU1Pq zp4y+-ff_b!6r^ri5f!%S%h2y0@)JThToI<;wgETz_M%vr^X zvQpaq#}ATKK&PHDFdwUd}-lxUuc{?4%OjkDWVr(B@6Q(w^PBY141NFj(x??L4~plFRs5ylznQ zyu4yM2o1p>06eK(jPWFpH>ozoc~d!yn46u+z%V--)>fI6m3e^j^KvLRCyU~f>QZz} z9PQh^g$nYJfkeHcQbOe*w=K~3zs#cao{(TMior@WdEyiKC!(yF#Pf0vNU^O_H?0B| zJ&#d%_wnwp?86ab4-&lpDyo3x^e z@?t74Eo5NH^6$u0@Id4zc4L+AOBMuKjm^LPOcN)J3)iei%;#sEaR#k=eHAqbQG*rf z#bTjz%gr~_D=Sw(;d!z53d#ha|g*X!i{_+(2vAxHG)QBzeV^S94?=f=Ds3 z@w{;0V2O_QA#hBXBU;=jcx>(&1>2zXVR5oZ?NoQFe)lM_ohvq zNW1^~D{T8Zcff)L{$K6epD6TtC=MqiGiw3`?lAL)Jwj;-yaLO35@U(&vN8rPTACYm zilVY6N^78`3Qe_y>nKoDp(h*wKFJm$dl<){5a1BO9Z@(|!c|JmSZ5bS=*Ai3aj-bl zO`-i^J7DVRhOb|CSx@#|3{^Ss*=HZqlaD`Itw=sHqb*w<&GkWPscDp&mPRSHYB6v` zy8@KLYcDr9o9XXAZ~V#F&^}Zru)t!V@qs53jC)dIf&NfhT*!iLqC%)yQhxJMpwc0A z5l5oHjcy-!lEI7bi_bqZdT;!9#xrf+{3vRNXIiHY)v8sCYSl`mgv11XzY7ZrDJM6Z za6S*I&EXTMqy#(hMzX)Oz;5(z54(CIiMnfTcj~3M%-V*)wR*ZnH7h|Ng*= zYJcL1grEa_lfm?;QyU^hUY<+x^9z{Ho55p39{u*~MgbJnpq*A-x}j!q3LSTR2Ub8$ zNoz=%`?u4c9lxp?YpJO})L>D^Qe_Mlnmyk+v-V~xJ50#cz(*8Z$Y2WT0 zl$)DH`FVL%py%g;0!pddj7uB#@7+$tg|PO6b%v@}RO=S2l+Hi1=zLH$ofL~?P&!QC ziE4iINdau;g>ouI{oqW;@uZ0-S5jQaTyBoGr~#V0hkuQtnppLHSc-RQKo15M-GVu1 z`VScZt#nf<=17uNS}_uVH{rwXt_!x4oJhlNWD z#d{MOv@ZhBp2O6KeNKag%dAFi>#ESl9UTjSF5}&~d zEEA3~4mB3BadAv@D$38}jFQk&gyN!sqR4U!C4_~&Mpc?J+SBEFTZT0d2?nMXEYi%Y|PR1wAyJw z`%*z+5k30I68d(%I|bcPof2(<`^SQV!6N(^9bgd@qC-J@4-FP2qZpqETE7O0xDH>M zo6WjWclZwli@5qf|NNa*6G1JkiOmxiN3~M?z+zz`XS<+y3V`F5{vPUj($Z?vfV=J` z7{1#D^Ct0H1M8kZ8=fIDrz@5}QzQ3_c^d%+ z8!X22yn^5n=&lD2?x%wM{2J*y{`Vs^)G2hzX=hWjqdPD*MlD-j_I^h;tU5J|p=qeT z?}JjQS5!?d<4|7M?jEqp#HuwV#?UouUZ+=Id8tOmQ`oXKZQ7Jt9My_y*RIXMPOLM* zas$9e5R}<&o_LD(AlQ&knFse!K|#KnD~l*2GlR2<`}Xc(-G@Nq0s8s;`yXZzNz2C; z*+sS1&;e<^-Vi2JG?jspT3$(|`+`o&1 z!8)_3gWbXyaCkolYka+S|3`tw$fS4_Sd^Bq$qj<^Ksg1~10Fj%n;?AQ3MF0>qAt-7 zEXwhv&Lb4K3kT)`J+m4Ci%O1}vkRc0A)-@O!hZt!q8wb81W0?-=X}z z=iE;h%%`N*Wv?S#OL-|W9K{5>cWiXDGWE8l_q9L<#4?goQYba8KBd;KM}@fuh$>52 zB~`MELThC&$5_-r*|a~cOvwsz(b4=8t$zI#dikXnB32u7H^|l8UaeZSBB-~Xb=Fxm zcF-L=cCd8_ye1Fz*0EzpTCrjU!GE!)Hi+6FtN7plx|37KqOX7dyQ#|=XUcoaeb-hB zl_;MAi%L3P7n_HUVo{M~6pMW`i}s4 ze~0@R=bY1>`t~2l0c72V-lSCasdTCr`(GCVI$#=n{q>iJ`;u$)d>EG}PMJouqBgS%+=j$fEPrvniP@@;49jN!)XAczJ*Jji!bb$C@khScxFcNFs_TeF0yRn%F? zK*!eC4(82cOCP2me>4{;3)Rq4e-FB{KUfs250qcPUaBBJk3k^#G(K*a{b7OsgD)ag>y z!<|{w=MCKXh3bjL0v8mM)MZ)OM85Mt)rCs+C(uDvzE+YbAv&C&#fZlPiT+YGP!Yk@ z6rw_v&Q28-UrB#!LFL=z<>C2@8U5&G2Bx|EWd%F!OGETQt^0`_N2P62Ho znqs2F)`Y37DobJ2h^gzvIrZNT?B7cZ=g*?we>Yoz*64_Cc(98vzL*v+TuANOLE)@= z+n&99Y5KHjEDBRo)S^&VgaPXM>#wJ2)230&mMyDy@kF$9=S~_qawNU*!V9hjYMc;t z3IhfX;*6I+P{ilD2GNq4M%_TA07N~AYp|s$sd|!-44eGNAd&w=f0W;uer;L2D7y$h zP^1?%h^kLbpTJoQlMVF8$?3DH#ZgDIm<_H4^@(gi4J#bwwZxMWl+#qbqAhHrvWd#% z7lyx(>PGz{%XWi`3WYUHjx2B^o6~2J!Jr>lv{(TN0E@QJjbs;X3yn}hH*df7CM|#N zDU;^leLHnNofkEzZ4R_?Ry00|;JdiuxhJToF!F4M@x|597XpDr?uW5)EXDxEOhlSd zqlf@qsQNoMmvp3qMcf14ofltRP9J@^&h_}<=H3t0KIe41fcoD(oa)xC$Jz;aUJ#oT zB|}j5?E2_n3)9`Z|6+Ry&^Z5p-as!LJahzsMWWjZ?*M{l1$mi%0dD_V$x7Pt=b!ZC zlaJEY8mb@sJDvsJ{~2=@)A<+oVL`K9TmQ>hMSGLEs(N72DR5&4U#s4)tVL1thrTRX zwO}P(jw|$8V^#%Yn|}M1mMwdnDWCs@4PbHJ{0Eo{jed!F6MbXn|E^8Dry9D5+LG+O_>xDk{il`YG0RB9H0MZ7Q?lZWHdEZR_(3Yn?a%{o)-&P zq=GhvtO8!tpk9goVmtm|(4pRB)l`Nm2I56CG6!Btu2q-vb2C`3TI?*e%>`(HvbaX7 zA1_a0axF?qPN9m@V*Uxy8~lVxu_rEuqAE%#Cc2V5F;df*oRZ4QiXIQ-`#nUJ zp(RU7rHMHt+cS8(KC24K5hS<_6l@1PA9q5LUAH&zBsy$6A67Lgrz@rC8a zO?~z`=hEQe@XtD**@=%St|ead*s&dM@s z7qAf~PMStdnluUcJzPKP)=Nsu>6v9q>Fu}PFjnX@x}Za_vw+2g%8oz;k`SN+1v!R+ zVxbbVDf2zM`?Laj001BWNklT9ot^!?HG^D)2K6oQZom2irMQK0bdA}NOsKOpUO8_ z$-a&+JilC&-2Xq^&@WJr-usHHc>N(uq)Ha`186GDm+^xcPnOPvFA%~0->(0LmOuA& zwP?M6XY=F!7CrnNoqcW(%E{bIySH!TV7>f9%w&=U(0!ZMR|z$C?ZG; z3#q~)WEG28rM#%Hh-(!K3kobBEh$O=}8Vg1}NCpiphmq5@GpKx|z}dwpP|`dM&R9f<1uSAIKQDtb z9O|34t$^}JAP=_T(3p{u8DT)-Mcq~#!D`_ z#FBS+(}gi`@ZkEw3-r`ePZ=8=yE#X=eE=eG?S1<6q4Ul=&tYU7?wcY_zi!<+dj5sy z>G>7U8-e_bFTRYfz5Yh-6Tz~I+71JQtCdkyUPtIVEbPL*MHqyIu4)CFl)VlzSe#9S zcnhob#_~A@B!(7qK??x1O`kf6#WGAbykn!rrqfyHoW~1Fc;}U%CRt@9gfy+hw*a2a(uW_UFTOArF1e=94b-DYuYk>oF&y=LpzZG7y^Ee% z_6U9P*~kBgY?QtsAF#;dFYGZ;Zh^Y|0;V9tJlZ*5Sp#v1+QeY}?@)t9HJg+N^6>1B`8*I#{c*zVy-IuQhd`VY8=y${irx)2G1eqdK1V6FL7 zp>i1*8$bGJ9lf^lCCbh=S7QCU+XU~zqff7>YkipHxAJkHyqi}^wvNj z-SGTpRq|_loyCY6Xl$&PCmJjcic!d|JmGX?#^-v2WDjK_VPBVCTw4vSfFeidRNW#} zX0c!e{f*P?OyMi%j3x$YDXz5_m^!k;v`{4qqA7dgqv%oD2*~ZnG98u0GT1@`i_dso zbV6|ui&ODkjHRf`3QO#UGnSrs_R#|cf;$tgxdOr*e3SIsuRqh`MGFWV_%uhf4bh`A?OQ~D8 zZgld=Co|PJ*apSc@4x?^KKbMmRz3ad>#wS)kcN78C@dc}dIB|U)W`t>99cz<;0skl zo7Y;k15D?DRYaLjR*m;#dmUMih&_g64$%)es}A6(z+x2>`XHIb-+udrW$@i*O!a*? zYu=LPEO?j_6TDPZlrQ!_3eaf?;f^9(3wN-_0b40r%*A*MWuSpdKF>RII&>=_@fW$t+i`t z|Gt_LORA}R4R;*e^OMWpp<~*#p

k;(lSR*R<##K@D{qjg6>gQG-QIKjpX0x-4E6 zs%()c;Kxd!11hM&>ig8#Qw1zCSwivIs*F!jJa@hS-rMx{+iy~4Mn<@%`P)9PU%vq} zK)|q)_EDA@9CSuMjg_?q*6t|zC@ZJJ!U8HO5k+k$Sk%^57>lE#<0z$eW6C(Nn{u-c zQb}nE)kkOe(t;l{Zgn1NXP@( z`?@<{=t@L=44M0}u)+crK5B`~N#+GFFKmm|t1FKI(Mfy<*#=9LCLCB)09k`YfBLDW zlY-ibMGDS=>nz$6ev3q@m+MbgpL9`RS;s?wjzOj z+~n^N%!pI|ZF+GoKlLJ(sd6y>R*lD5Wu@YXj1lN2@4UU%-Qzie_QE2ubLY+kYmJ5t z8?pp>{rdHJQH+6Q|Ni~#>xQ2{{`eyc+2rNr9Wi$R5COrSPMtdOb>klJ6TlJKi~R@o z)84&%`M>q+*V7kYe8CG_S=4{^+ApMH|wfBzkmTjYJOzV;^S zbHgo6J;gNw$nrbKKv?e2rqTi^+Ef=-LG>55DHO_!D5REfkv(T4Rc4iGEnqcp6d3ew z0mrykQ9ad)sCZvR=q52S!LrrxS4Cx^8;A7`2a)`;i|D)4(kIcbT|1202b1&QAtN|@ zY8I4U1)?mYp~cDDwY6>$S9UV_#n>`abxz0 z?|M%D?a%NE1{NLh%bEs@Zh@jR=;|g&tKTggA3?!)-g%3@`}P~-U_*qDCFs{U*w^tS zy6|5Yv2?$f-s`xNq7lb=DXmUZ4!mY(?xBL*OkRA8k~@N_m>c6MHr^{4NvJxb;DUo& zCG_prpVQOJmeSTOk$Z^N^nD-7<27j5h_1ik7CO7@`Ib+%79PR61gs;}Z;PHm3^#UZ zDTMxD)m3Fwu>2(xQ|dDt=f&kq8Cd;OHjJN-J-e0~HK=tYlgeZl^FG1>SxK z3{=pnJB`X7@{8)os4`tfMX~X_R+hEuDma2G5t&0| z8_uN={mj1Olltd)^~N4TWVVuw;dMXgb+M?`J3+9!Jo zDj>ymv`Qs45LnE}I7sP}$I-!q2aTE*??d|ZxzxN_Gl|?PRaf+PnTRBaq-!v>Wd_$o zlt>iQj#}EaicYWyVH*a_r2wL~*Q6{u1OPJ?m9vXZ`wSZ_N}vbtalEB^Y}sh2;Eo22 z7z;G}z&T*O^74xj8E1FvejeS?w|`aZ8Dti{pt2`g{$ChJ_w3$9>)wBlKK^JOTL>J< z8^GfH`yZkfE!%L=PBMx)3>@47G3)-q5?v}e<6IM&#cGME{Sy_W-Z-yv_p;%DorBMemparg1nk>=cVw)NIu_ zTCF2FYiC!s*U>)7QKUK0LjeO^T>Ss{f91UAeb0NeK|05S#zX~a?;Ma)V=GNb z&<~k4!kd^EleW`UxWx0GHTewAMIQe2C*;3<^doZo#iK9Vt=@X;?L4=ieB$x#&%Kv; zl>-Ai

    eUU}O)-pzf8eH2Z~2yg`D09Ztn!MM>1#tZuj0VIGFO9ToQ7u0a=Ag<{j zJSa;`3-V`w{Ga9HANyN5^4zm8+kL&n;oz@fAN`LX{_oP=(Zs|N&MKGsg(M%q;upy* z=D}iQ6jiySFm3*68&lM=xr-U}0t^0Hdg_h~OR7Q0tA z$QnX^%8k+tW<0xw*I|L8rf-uR=_*DwVXP`vpHwJHq14EGDwG;1gHdg?W{tEhLF(QX z8+ZqKYvP!yjmy#48w_DdDr+lJptKZji8X4L(b%X?ip7F7G&D(bOEW=HeXVE>6lWN{vbs~uSJ)RvweoLi{4U0<)}qL{RR^~sB^ZKBbwxK zcUg5eX0TJ)V59DT_o1I=L*ngxbar*gPyW=;(rq&HL9ke6oj0BXz&7ml!OkFyd-(8S zIsDmA%h4mRoZusW-vEpM@wa|ob`I@Pptv}r($ml$2EUP4xNM<#d6~fCRzNX5iL0>| zo1b}gdD>RM5xo%~{`5og*kgy~#PMU>UTfQ#bNScq+O=C=fB%E>#y7rMy1LNk6^}&| zyPn7d3)9lpEzNB`GCwm;a}u8K4kqn<)jdPcS&O8}E}|TS=Vk#W8ujwnqo0<)`Kv#Z zCm(<8%X+WadtQIv1M;@Fzmw}8b!4b7#@_Me{J80+TjZ6jo$W6VT z9OH_X87oV3vbMS!+#=2f@cdOMxihlX~C@ZVWQXBIPRrgdrvWNvmw78cR&NSQ=8w?SL0l~p8# z3rwoFb`8qR#Hfsqp40M@l_m1XOdK;=oU%h#PO0Iny;56~SMr>HDc81bu(;g}W_nT8 z>KYJMxAlmyp8oj<{-u2N+uk02kN0X) zAP0-inzHr9Iu4Xo7SV%Q#6biD8`LZUG^UbNd|zGJ)CtwuNj>cJPr9@gAlbp6_ESvy zEkYTfwwQFx@89~!A4z9t zI~hedXS%bTv&%Zq`2WG+$xucTt!*AsRg`4E|HaBsuLKm+qv?ugmS0kktLeSP`}Dip zjDC?gdG^_->5}@yXIi7;Pz-Rth=KHveh8|~rR5nML6_DE|-pDZuW z%hcF;SzB2S=ed`I=sjvo5FU=#h$Uc>XK`%}LGhE_V3s90>We$uPT z4#J_i6kBE}(-r*{N{!9Z+|o&31*oDBU}H=n=Wc25m9-VranH;0(wr>JP07fmbMo+~ zJ}F0!J}1vS{nVGe_P?#IO(0)<^wGnzyo^NuwS8bN{p7#-ce3w>eMVO3I&h%o;Ok2X z7O{3i9ly;{jI}y%8(5?&MFFE5yy$#Z`85+B_zcCFDbJ`f;dx-+vwh5eCyjG`bQb34 z2^NnWc}|{w>PenyFV_cR*ZnshkQ)yilACY7MWAkC>51*VDQFKK2`CdmY+(uNwY3eJ z*UT>fEH1L|@d7}jozXaxQPWsk*B~9edu8O}NtvD)Va%fal(nBF&22It*TG^s9M=pM zw*-k-VH8m>zpjwMmqTChPH-I_FIRF#^TJ6Te zUvai1-ITWan=UiJ!C42ODCj+7^@gY=Dxn5a=!%NKa&2`%+Bk|GRlWKCTbX_BLW(HpJSQ=U_ybuq?tWo2H2e!F^XF2D2P-`JMR=F7DKUH?1V z8-e!r4*Bly{h%B;a4?fm51^4rea&=IRtbOz#?Tt!LK4FMgS4)OE19>Az`7TU|UE36a6p+tt!zQ;m)b7cd7cF^fVM3RS}t&K*MvVxgxV!#Hr0H)&evy(p-X;I)2Yx6dtn}xoS!`lJiG4!BB1~bH2^P`N9?5`NFj5cwog6>@qCEHP(}JFM z+x`1nJ=bz`Gfg@6-Eaf5&%gF7zqqYEs8}k=Z-3;!OM6=jfnuzu^;%p_PG)O`vf1YB zKCXeAj*fTZjpx}H0~R5@%zya#=|C}ztJUQ=_S?BQ0takZkOGA_E6o>+SZnd6SB_(hBj@|(Y=$Bz3K6bva~q6 z38;JRnd$K|7gy~b^&GFr?943dzK@?cAx}R3=$C{UL+QX>cikgUHr#XXeO%|MkrHaA zo_PH8lmvd^sVBZ9<|Bn-QEs{AHo58MTjYTU-XI;FonZ`+DEGEuE@6iwJND%z>>V~m zu&z~kRgj*6{j#_)B~#-Um654zFtOj$zmM|tsqqU`j$kjs>&He;aWA@f@uEEW;CCC$Uk}S*V%2T3WT-sR`Q@Os31EkWN%qVZ>DhSHf~bXWI^LS6eKEG zRFDYcGwYq5{G9J^3c6IDt%sm5vx=Z+F%pZXPMsvcpZPL5+v4nk9Qua+H%f0`pBy-F zh+pIEPp`+%XlE9~*^KxjfJJpUU0vOfx%oM^$l$q*gzo%;EVFb3%9nX*Z0?r!t|7T} z;W#C$ke_0HBEil0W>anGRmA$Q!kWdat)(md{7VBClfx%D0{A6t*4bo!-K0KO0gI_* zBrt8&*u5M`#fArOFU{q-s*q!X&O3<5x2FT$q-r$#Hq^nWx#z8d>=>r%%h&)a15-BlfO= z9XsWQefy<wXpGIZ#3X7fS&AYn&lk z&*=TPbUj4o${IK4NI4HPz=D71XMa+T9eeSbhaU;QpZ(C!OK)#~=66&!9fLa_V@WnV z58kSYXZ?JQ5;c>mIRoK;F{yWo30`6L9$@k8nbS1K0C+_G@OFVC0^81xPT7C(78%^R zQ~G+l<(6CTke1e#IOmdcpI;g-uP-zbC<3TVPYko}jsaz+a77J65+onSQj<203*y)D z4Jy)D?vSbJc}i1{AA4TD@c3bwoSfL!+{JkhAOo;Av}?EAbN9W{)!h?IX4303*ZHZ* zNqG_h`^l5?;tNM*czD?QL|*gs5hVX^Ja9nJYUH-t?vOou_l1^WUfJXBn+iIxpA^}8 zguQ0T7^>_SW6C|eP?EvDx6AnD(=s`FE*N&TcJxbk{~kI?YRd`qX>5`H!9%h*HzgCJ z=eSp4PXO3@_L-+;_~LoCX&JtFfyN>)wcuKy@c`7b{WbnE~qQH`3itB zMNeQPmGO03&u$vDjhsIri;HtoDmBZ(!i+4VO&$9wt9mYeT&=SET4%vOjMshfV3C`O z7UblI77rL3x*oK-UX3|z@a9Eo1H1|C$E;|YF`>g~v4NQh0Grr|H|oOu=DJRqHv>Anfq5wu z1z-`f)`i(If;+N;=)XvIqCwi)yQQtYOUlhHvbH=c>#GZN|7>n@k^MVB-&F#`!WSbYLyFo(u2HkM3=io{M? zT3b7$wY`ID8|yWI#d-j=W-^M9*dsB8gBgnyiV6%44*y3!^JzJA`qUKy-E3_*#`3n? zZkJncyM5E)>0l9i5cXJAO)RVBKEa|YNeCiM7Kkx{ImDUMCmC=9uo- zA$Z;}A!=`LCj;El(ju*`ZGv_u2rf{6tu|kpoqy<|kITjL=R#IE^&i7Lc1KM1En8it zvDH_7)!WqZ*&MPX>+RY3g0bM(AuCc@*H%UzykK6jbbu|6{Cr8+$8eS?xI@j~GYs`U z001BWNklw_m?yPl_&YB=e^f4BI8Qn3$jBwix^dPbFvd9H zSwdFbRBn>C)>i2s*g?S5+1Vur4jz=9JBRddrpw#DcChH|E7TuIcBc$2=DhnuKrt{d zc!*;>J${~w0ynk6unwPlp6g2)u6o(I`&PCk8#(tvCKkh3&Cbrs$&)AK+}YDIKR3%{ z0|4aI^d#9J$OCnLt85?j^yTKVbar;r0lcN9RodFyxR--{SC-bLqe4?AIQpUlBC~*O zV$~H&Qf}$u{8*fylFs%v`I>jXhkqxvdvzs<&qpwRICsXzE+-y@`GppzFRp3N-W%lp z2OhLmN9bj#;M-k2nM6e54d;c`x?_I<08#}HKAZ7cvPU?`X9+{55I6a(AJv)Nj7VeR2u#&u{(h$?*u7I{WP z1+*$liwj&c-8&Ab8Q`TeWN>S13qdJ`p~ac$>p_S5I#^5tfG;gr#6jeYpV92eY)b!b z#tt};gw@Prt^gJZPhss`Q$y(k4sXw@r{*x(Kdf6cf(SYpaiJAxa)1x7F+{+Fd!dtQ zv60Q{y~PF=DmK^F_Ff*~Z0x--%gjCxbeh)y9DA*VUO@&JZYAHX!g%5k#o^f0+`)B) z01X>TsiBeYyEH#zwO+NX(`+iYXze1c!YfiM0I_Q-K}Ee{xh$=19a4)!R@QlNt8oT^ zqBacIK9D7Do+xU^J)ssMJ$SIe{r>NLga!K7KVE$!fM@;wZ~7K_$2q$^sPxUb6yrkjR+m9%t2}Bl zxfc5Jv4%~h(EQAQ18Cv3-VO%$Wb7WDIkmBQ1;Gpx70wE5aE_3n^a+?En`Bbrx!`^= z=Tnf#zvIBvKq1$q%`dY52ChM8kK~0$kuX)-MGo}u778*maY>2|WlCNz zUp&q^1Xc;aZG3Euz)is-*0#EmBN5BiM*aQ#+LJfoIb^U!EjxoxUR#}$mgX|0eF)06-B3UR`q1oIWdd^>S4^vhrdF;~B)JnL6ajcm zjg*@^q`hk=VG`u?oH+gv6hIGG2Y~{etK_OyIcim+eubo>gGKz?4RAbJ5!ZVT4%zz145!T- zToaRg(*_p7+9hBSdtYl?H_xb=nl))|Dht?Om@UGGK-b;o37#)+^D`>4iYCJiKrx=r zR5O{WoU49NZ;AF*4j$dT90ti<1N-Ij@F|&@^cESKaP+f~PPn?6m`wjVSWM@_mj*1_ zp#lxC2L++PE$oN6iNXgGH!)}M;)3-PBU%UN7cU;A8nCDl%gXY+9v(h1x6%~X)JnOf zLzWk3$p%8cih^wfc3>wcJ;G*{fJM~h;5F`^ioe&~+D&Iu1Wc4}BtTgYCM`0~OI*{< zSof!7Y*Mhuwiu0+b)YT@QV~dQX6=w{Xi`Tr92hv%DwS1fYHT6ffNajj>VmAVuTauf zZbFs^k~Z{jD@aFYuT<8T`JeZBQ?nbD0BS9nT4s~60o+`VnIsQ7(Z}sS{Nm5crAx!P zE&KXEU+E)&`i}4X?(dVamQNB z(dft<&$}>hEtvOOn!qL+>w5MygPUK{yG@T53wrEK%9vmTGYorO0x~$FIna^% z4w&ACwLj&yZfR-hBr`QTGZt9ombM=0-HCdn2D)U9Up}KHDK#}rE_C+plF702GCw<^ zf6GCQ$ujkMYh6}TOBW4oz-mDX>1VDRg@nhN;-ml$O>XM|nEmPO0orR&O48QeM>!^d zC}fnao&5w-moFUS^Gg}5{9N*%Rm*vAifb~5LoPP*e`e6HJ!28>cLPI*q_NyC6PM4* z*vQFXf)d^~afFTYDblY#t{mK&T4`u(C9|@+W@mh;+vQyy?kJ-jUS7=E7IMeO(I1by^ zjNVq~F6IZ$iJg0HrGxI+rBej6>ZeidBbopCvqT?$@=N)5$hN%DL=*fiESbgl5<`z( z+Z85N0Su9(1TaHO2>hER4fwaQi;CX$3;|eVBGptXp5#yK{qY)=qzYo{kujwOH#|lb8>l#L;snd1_V2pP+{DAx)BA-20I5M65ycJXQT@qFR|n zw#V@DkfdA$tRhNcz%bUW4N11Z@KQYz(sS3rVwL6aMT14h-dOZ_ zs5El1LDvP6epFeK8oAkCsz1*f;iy|^$cE^yp|7(#MI6+mr>#d$`1w{_Ky4j2I|Ykt zJnVv0mNK1~_H`2)*YEq?c<`Xv;wl?gHRdp#jNy$;7L<`2sbm)g=N(-;q?RCYit<{F zFM=P801STc8JTEof(R7JI?#d{PLl{0>nTH}l&!5pT3Xxbf(pso#@eD3>NVI*4MtMX zsKwJ3teY*r17Ktl@%3N-<)6zR{6GJB+jT2jZR*#*|K%S6fRJzd_V1QE@47qFHo!N` zYVu4tCb8DT!_cZr5wrK%aEGdh~8a=Dk3m}rN zs4%)gEse4|I22P>1bYht6R_TpMj|+eF$3JqC`(H}5~hORWPQ%z;HejMcr=4tZnqF&2=9`)9VzD8aQ@rKoM~odk)+ zlA7YMrn9z&t#Pn^HFkmh_gZkmLvl%7pfxbVL!isFtz)m7$t1M$fvOLffh?#jzzhJS zW8A>jWxyg$#|$hkEo?1;v*!~6l*|#JnQ?to*0P1nWCARcn!5aI;k;;WCr~C(gzM?5 z0%Nk920-HPCAEMCT+?-6hm)O64my&7vi&h8G;r<8_+kJk4J#DQeH(i+6JSzTvg%s_haktv7Rq!`U;x#&ixU^I;|#N!f*-u~vq$ z3D4*^6vTBB!~twT8VcZm`v&{fyW>UzjLGo}G60=GV!t+goQ<$m1*#@B0E-i&0E^=p zu;`4C9-}o>)wH(vbN=G>YT#58Yl00x$7iY-M4~DmieAK>F(br-TiwBurHlGqWup& zDQ)+h%1r%DBS1`LenkD=&_u#zhD*ncO80(-v{I4U{TvN=%HAr=jHN}xroEx14*RX z;KI!oOeS6R+ayTjxrpZh#g3Z7sX3e}#7w>7^^4k{+f3#{(v?>i)`;(QnP-qDEqvb& zv9(6OO-*fFqi`mkn?Y@_O2ey#;G5=EnjlJmqADjenZfwpN<0u-xT=Zg?}~#(b0_x% z?((XvS1MEhw6yQwJil=61zA~K&|a1Xz}e3-?XMWJfY+JD%w9LN@6KyV(NqIOLDOBS zgn-Qt3YUCTrS;P*@CK;yD9+3;+6k{}A4MK&=F;hhxqh#ni%I35ab{P~7TLjp9x0aD z4S;a-vbO`w-nAM4^u?2`u1!p$9oqbq91#wUJ>O1gm1V8*S_BoSOGFT?Mf?EG+D?S$ zpJlqWR#CIwu)l^3fh`HF77SYQ=H^z}F?1s}fRnh2W)3p1fhE6cJtuRzg3qJk%NMg>EMO_?$+3oLPvd8-TnMgXExLzJQtEEUl= z6m_}vF?(v+Q6_0v>(|IyJpcohfulDV+FhyW%+!RO*EK`ESy%Dl5tLsXDbk%^?GRM`TR#k972CL(ae`9Y# z5(_~HnZ=TW#raSJV&O7%(DAYDhgv=>SXLC(1oD$5irjD{w88c4c2nMna5^K~& znnSQglc7cq*USGH(7;?rlNlPoqiv1$E_Kr>m#IatnDh&?fX!J#vf2g=wZ_RLo#vs z9A6WZMh@8d8Lw-nloj_6Bb9}@No|+nfu(`z_=wVEZ?5;8yDHllXc7y+wOu;8caXi9 z8b41^T3=U`&c5AJS6eTm!^eYcd%GcI8k2-6lZyr7wa2I>AHNWoH+RUu?whF&7(RDY zW+sN63{N7Tm{dtYqwakwt%x!|m7rqofE8A-Xe%niF2+aKRBn^OeRuGAj$C|^^Bwa> z7b4=YiW+bgOWHFVo$#mO1z_rXY9h zoD82mYIVm}BIF~OfFn<`_};TAwyU;Z+Jo~k4q{K1X-PN}Rb^45Djbw^K)wzj#PuzD zrqG3ZnP(~Y07GEtk&SjqYD%c39aQ6(?*wBw0(*Ups&gXCm`S__^2I6ntUGc#jL!b& zzlU`Wb`dqiFpc3H%gxB}J1!)#11Kcsa_c!&PPmT%K5O4&^#^dUxU>Z6shiuV+6T#N z2%AtB+c$VK6$zIwouTT1aS2r!s>}$4mF>kjf$qx~nZ0uV)HayK>`l=A-VR6{UYIC2 zgwW`o@{lT-UpBGKM<~7_1x1eq05*Za8mL)=ZgN=gI52}_S8hWH(xEL_#qe^IS}}<8 zJ~a-+yja?5di-zmcdJQTHy8I*m6mP>+_={|G9fO}KK*wP|`tvSkNLiIGZbWTQW; zvX%p5W$8WxTt;98d6(W!xKSSp{W(FK2XE+ai?&7Dx`;ufNo&p;2V3n7rs_us}(sDa%2=OsJagik% z_`^sjfcfg`-Ocqma_)JVn;j28z=sqyiyd7%Wo+aOS*`S()wR08@`{e0T|6JbD9+7J zD0^jPB7Tpa{L$s^HAjB!F2w~{S1?QmP*Xk?8ycmncMpN{wKh>mh=9ezb&L(4 z(0OiN2Dkqf{S-DC71y?r)sV_0Sq1sc*%) z1z21{efjEA0E?krL)bqRKmern4;_-`mM*z?_F1y9UKi)`NL_EPoG8*y0@uE>vJewD zN$oVQpS=ZPY?Iu}OFKn#yO{xBTw7a5zwF$52cPHplTXUb)M(s&wkQR1(BMpWK<0jN zCY`Q!twCaL58W?CpM##MS_6reOOQ;0F@xL^?w)8SuQJrtgqa;_ArKhgEz_8$XS`17}1(` z1Bo7==%}WvbGs>_mo{5pO}}-`U@?DF%;Xwa#6m|V5gEq0nK5RMGW>Hjtwu6=vYVZ{ zeBtnjVCT>i(%Nm*LT0rFiK$9L!$&o+ zc#Tgy92y3+kbyRtq^F0AdI{>>$kR%eB#Yjg*>N2o6_Q7NoHe zwOsX5F1JyBO4qQ;nyf5MQ+^7dSS~kf3j??9H%Cf$MI{KO2}bPI!^6S*OWNjvqVNCv zcYc%2U9W$;@JSG;k~t%5q&TfSm>xnCNKk}(!k5+ivB&5YHbqiX*xd~A=U?u z%x1Ac9ir!_RSsz{qRfmJ;jD^dlgP3tz_R*EOJce!V;<=88M?EmgT-JF;mNg_pN>ah zdX^*V0Odz7#RQzcFKWWXYlf2Krn z<0uD<`nN66xBcFONv#nzRgQp-YLSla!PvfHZc>BTx_asA+e5GjkUM(ugtc1GeIO>J zBp9Zkc5HERCW1w>tYD{#lnp}mJT*Qn)03CfP{x8tXYMs9kIy!p?4nX_Y75fYGf1!q z_ICKpbFwfG38nUi)C5BecKs_|M_DG3OtsB(Bz@}YOYAr2Y6wrBsL4zk`qc1wpyqFK z^eov{_F5$H)?~7mt+>3GOn16VXSdjdryW1VGG)-gDw1`mMjI#1V$pVwLko(+8i z{h#~(aaePF&*SKwHpROl7K}#(6$Z~hPRX6 z$E4wetCBU24=0ynGcy@%Hed+=){2EjJZFM7W>0hVfxcOXzjKX&53jAZj&7zZqe5m} z9Zq=|uPjJC>Y!G@R;(v3c-gFFcw(W)Q$B~74bH;CvD1c@;;r3MDwVmY;2sDm2z1|S zQh|Wa9A@pHPP3-zq38!8YLpO2BA{lLy;z{sZ+&e^YHK#6r+=3$&*MN`mtvuw#u-J} z@fYgpl!{=Tfx1f@tZt0s1K@p1omJG8i=dCS0;_AXM0ZihVKmd}h2^lPR#s7EANb6lTmK_u0zKexfJ7N;J(3d% zAc73qSVpg93}Df+r7&#*6G7%`V~y^^D{vpCBs&*|rT_FSZbp8nQXtG@9z--n0btaF z2q2eIT9dheS@b@Op275trXO4gVhO6<7Cosk3xS4Rm)4C$qZ=9%Sl>j*OW9Jy-BHOR zYV9If#YSZnT?L@+H;U$rT#*_|)irq5_|4d_B!e6ee0|p0jOymap~*abPXvDeg=#!w zGE~-&shN%@_~6h8>8qN4A?U^nwD)7ecG6*Fi@`BJ5Aaefl^Kwtz8eWl zH-yo{$N+1QbLPOJ2P*CWY>`edmoX`ItaY!&08HMo7lcBX8P8@uRn2S7j>ZkX*l0U&cDd< z2xT`xE}8?2#?EHJpR!rr6uzOUje9#Jdg1%I8dwL%NCfS<@gDBMXOBHDON($swLa4v zTdW03IB+hZwGW)sk%UvHNeYy#MlO>o*(!GP8qBH`e;mDPKv^f9f-^khq5XI9de5Ew z0-bI>c~uQ`W4=QF{g=5vz=%_bmqF zsHQFi`H)Q7n7Bb2&kmEJdJ8lMi~LODMcudkzfiMmvUEI?pj30$;2c=YgGY^{VHVlN z(u9S%DgFnyXn$P3-|N3MKF%mRk_4R_>bbn$OG9X+XA)gMZ#B+<$qke~W^!Yn2`G_N zs)5R8MKH%pjcs!A-1BVZMbCwB4kSx&h1S-eKaiV0iRsH}lf$%=qU?5+rp)>|;LLs=wc6)(yWjDK^(lu zhG6nQ#>NSZjSoT1#yYQq?x!d$~ zkH8BVaAY*WlCZw!N>Z09EN#dNS+RJzxs7hGxQ6xBCDuZ1tS$5Nz^HiS9smF!07*na zRN#%WvN$apYYS2WSZqVztCG~$Lau5J(#?E?`ggkgsr4}qS2ea+XCRt?7Fg_m^xytK z{^HO7^tHaOUXk~Y=lLxk_!sh)x4bpy(rZBw5&@R=#Po$T9t(HSBKjEQx5I#zyN+2AM2 z_=23so?`@y=qI_+4I_R}EO76mHAEy-7YMoTbP)M-bS64;!8H2U`A``9pq313bAOwyKAQ?Qup;(y* zU!ReI^8nJ^6nS=)1V9mqNVsz2yvLb^-vRg=*mVxKd zF3!)W>mdzJYS~K>z;k|XiqcTD;ZdhsP3)urrOVdhxEUyMpM%7G*uf3fSZhZwrLrjZ zm>fH+?N<0&y=0uvkX#~xJ8}6;c=rA*w_*yzxfs=<`Up1BEcs)?UZ6CU{t)q1u~GU5 z4@yVx5DkQe&m0Nhi*M^PYEvC$YB>!=MIQmtSda|CmW>JN|sYCmf=v3XOK>S?3+-D;4|hgAnUVz&5N z%nj6>?$~oHCB+y&fJORX*!Wh{nukXfV#w%hyy>YW`$LEVa|Tu1TWnmJghjFk;Ba-B zESLiyx{3$T=&h-=j*(!>+98GHD{G*m43%dGl{;V-Q-)DvIR}kAdvZzwPhxsfNYAR| zBbBV$w~-WT>FDDg0tqUfbw>4(Q}pN_X3xv!t+)U2{Wm6r020^9sv_~MF^JVGa_p>i z2G43|8lkj+<8*<)Ge18ooqc;`ZDmzPE}r1ts7u0G-sJwSgT?&R&iwnD!D0#wdCUt&#- zEH2FOpam1VzPfBRCP~d^a$xA&CV`LNh<(oiBb@-7S{Mw#Ccm<=%6b8?6R2BkXe!Iv z@~p_(62W0hd#98jf2)OCnFglbcagzs5mwlieP&Z|I4?#Cu*#9`5Re-7p!(%s`Z>99 z{`?gu-t`~8{3CGdZFk6be%JT0XI032d;JcWM7Bp+r|gP-2G>?tKS8$5H)pzoMzH8b zJOLJ=n4}38GD@(I#z3;=9Ivj@Y z#j({u$|PzI61-gojRaJVqOw^WN}AE-L4@qC0Y=m*ru7kSXhVQ`1y(VY-FdXg`d`bk zYtwiH?rKV<20$1KUxxtB=obhut;`}>M~;_{AL~-gLLKp#_gQ16*jOb^0>m1$uzggU zhTKyu5VP%C??dYXmBni!&_W>XwQAYGPJxErr`A2=JymX|d#>-H@lje~rF|pJ9S6J? z!I3cplL@mOswZG(vm}dilMH(8%60DL0(J&$mbCPs!CRbouo6B)rsSZLV;6(@kcs!& z(+pTta21kxn*B>yUO4#{f&;1trg~k*;$oNeU@9?8QWGWvOk~CFb*zKL*`MC6oj>_BrG7e6%8g~#R01A-KBX)Q zYqKpGf;Kocbp@H3ylg;R>s{R;Iyk^rDl{_Mchduu{GT}b2-#wFsE$mnj&FhEh`qbS z+F|YYstjqYfAxf!-H2^B5lmj~boBkmc9N)h469%Fe9p7hF4=qVeyY{Z9)FyzS|UU2 z;cE6_>6-Lny;Npu&vw%z_utp268D}c0oJ-&>I5vhLLyIOV2!|h z3iAeREx;H*(s(#wz8x(3x$L0LKZkYgY9C`&9V`ZB5d;#!BE~E-v0egGQw!s}by-}T zr_up3_KC~q!`$Z{l#^LkOB!5l9=?`-{*u9>7BJUy6G7&Sy_HxX4U2OtnyrG=a}RyB^H8O6R$H<4HE~vC*1V# zYsE%vd}T78njMdU&eg%9+o#u1a*C`gm{%N*bbw1g5->;>)vnpU)^Ug*{Ju?iH|aqT zz?u}cGO2JQ!GdmU@0N0NE3<)+x~;FyOMNXG?P|>;0#dc>*C5s9sA=CtH5k#_NDcIo zYw_*ArbhnuZ~js~`Uk(Kj&;{RUJ)YzbCmD+uJ4uGZo5;jhmR14haT>jYwTkLgDN-G z0C-|c8qIckJtA2)GqnjWp>zg?3{^pv8*oG!Di|+iF*NfT+h>Gk^u{m(2$fsfq^+Yz z5QM^L4{L7~fk!2_h6qWD++55rsWbq`dZ9T6R04@fh}T$Bf@-ZlcxWSIX|A6Lf6O-MWgU45*4N6B&|X&{^4M*xfERt1Y_;!UtPlk8PCxr{-; zo}m)OInSKy57D|fkh^@%=(_SM+l@hsg6`4tggUn@n>lD z-#V7L%&0%myo#?1hImB;cQ4aLToEj4-bxSZ)SLwi5CE};?A3~_p-y6bjoDO66j7kh zpRMNlmv~3)2=C(29y8Hk7wMeJznxFdWf``uip)3FOJ3k(m z%t3bIOhsf#a7`G$>FFu?&ENQSdFJUayiC*h`k%Sl2)y%MUnBp=`@dO}2&hlsp;559 zJ(YJ*j%jS5Ieeov4SKAiuGf|$g+j>Uvu1INvC8dUv8FE=bUEcBcSrSKkrNHH9&!3WXVPY zC6)ki2&~Ws0uA6fE-sI|FQByu43Ut8LAxawu2~JE0W92Sd)I*U4D4e9b$sNMtS-+7hwi=|H?oxi z=GukRPs`Zw$;7QZ1x$&VkkpW+Z0{PB3um6C3>7AMUH$u*h!{Tif=o}sxiErbCb23| z0hnsR>NeA$Gfi{^b~hOMV6SN+quANAQ${bo$eK$q`r5Qy>+SUUf#GbIp&RZbs|Z=G z%kwlD9_Q~?v1T^uf@vRRor)c8Y^uop@MG-NJNMis{X++2W^z={9Q&NLCUNF6JGQBj z4R<&O#IeOn3KqdAHkCVNVhrxDsJFKI&ka>sIN(AY1Tb*R-S1+Xju)T(l+?h~#>#}0 zP1GbHt{0y>x&}Bu;9~F1;JvOltO=K+=8Tg;2o5+^BdG9>}#3Dy(X>;1R9 zkuLEkj~=Eek2|@iahE4B(mz`bELMp|b5|N!<@DTfW1Cu-C^E^0@+TPEz}AQRwGZYG_cqe)f1%i5vUBp$WKW zof$~zCZzSb=9#DE*MH^T%ltev?AJfOk|WUF-6KEnuYXi_?i}JFPmpMA zI&GxaHCVu=uD#uKW7b*$wW;>ri7q$wK7*NlgE-v60jJr)3|O>80}eJgwkeAio6!Rh zflch}8IY!Oi>y;RH$w@XwukVZpK9~(z$>z5*->^WSIXFU174S(GWaym7n=Ph8A~#% z$n;t*iOYhr^3$xlnrBYKer8`p#e-VV!%Y%(TMKg&+(+RejWr5o18O+oV$95ZO+{MU zI;C%5uQWE5WoF`ntgXy*eG)9PKdOR8J?u5fmys5knaoyW6|OaGrfH*k#JO7QS64va zM>s1tGjLy8n3j2S!o*&Q{WHpJlOA`tqQsq5>z5*AtqK-1Or!n-KoN`x7&9FHFeO24 z9*_|OM3b1tncxZyy&n%+w0KVET zv-x=gU9wRJ3}%f91sGDSuQD+qH5*dTWUnT65Ky+Z_ek%~{RBHOdO>o)T~p!ExqJWJ z(ok-d%jaK|;d4iV!Cia?N#GcOH(D7Cu>SGf$!B=~U;vt0dt~DBS-CuXf_sTOF(Y}! z{*vn(vdXW$-=w=5daEBkVNHnTdP*W@>D#ei28IsE+{~z4zVJNVgT3Em8aT6VvaL&Y z?SCDOdf=dm51+R|mbWD_VNygJ1nxy?@40-?lB#r!g@#0T@4?q|uQ+r3aT&jKDrqf| zxB&;*qkfOlTz5bhkDfJiFEt8E6(L$;QYU*4-6sP>H_6e* z|5hf(&QikciUnt+>E>K0N=th;=Nje+CEKfNO+e(TU@?LZkB?k)?yO^N zU6EiL>@Zv~pMUD(R6*z_;WR{~EA-o&6MF=bUh7=tx?&t^znkncG*R=W?=`3`ED|^RBIuYoTI$nlVPfyu)Wy!Ujk(A zXC8+jCeb9WCUx~|bw>r@jtMjcnJVe+8$85oy>$LXCa_5OkQh?;-79`v2aB2EAy~}U z`o$ne7ZO`cSYu>7U>d$y&p%`&nW;(Srwz^R(%vy3qnA!nB7~28FyKoRts^kuv2gq~ z3Y4y%!@1IfzE-e^>xQIBrKp;@#0JK89kq~f!bud8oi%Ce+#yTzGh_z+{i_3N-f_4e zZ1#L_b6QiiX?13DyI?U4lLc0E9;CBuouGdd4tU%Tj6!heBkPACb87sotgp<6mKikB zD3xf8b^wp;>3oMg>cCXOB<|Qz+7%@4x)+hvnmc|F>UBob;Oi+n8rx z{|)b#_k8X9SPO@GCe#-zi>MB39ymJ_$PF5R(OO`*{M4OKBde%=jY4yJG#0kj6JA^7 z2f4E=o(Xkn44ph#pV&w?k#)5V=&d?K)&uNE>eA>n78-QKRlXH7zXZcKLW5QQn|R7SCj=3oF9 zXr-{cgeLGFq{RRw1}%w-CAi?ZDM)1QnAq@IKsLVDM2Eg}1e`vW{#h;Qv$b1Z^TR|P zlWM3%Ez&U@U=e#Lt_o`q%$AzMX??E)Sp4DGl-e2aI8RgOUYDcl_gt=K*UzC=03YOn z*rTzx7tx9a?O2*A_eOs~07twQ5>+%>ZLlH{M0oYxvAF1ht{90283*>{+jUCn3AtbK~8V$>KTr zbaeJ5AJ-#%5)6RO9Q(W`6fEJMWi2Bx)j6bK z(f2&91G7Dfim6&@Z0?lh#RZv}9?P)NdGjEE`J3;4mrRXbkQbi%d(KG?ttE^#L89h& zh%XRxEW#bvdPh5ZmCCa{iRI%LnRg$MY>7)g9#zoopu|!+p;xM|8_Ho@yXDXwZ)IIG z#_!yTFS!2K>>o_&7Gkj!fXDhu2aDDA^l&9%3$pKo);qC1LrpE}iR&mq)p|wkt*E9{ zUM~;nsg`oMUjTayde35G>2!LVeB6zyymm1Gjm|haX!Hb7a7J~PRIgj43^fAAR231= z58b01$}Q5-vzuxI7(lUGK{^g;n<7hSxD#nOk4??t5@_zhWVii%)ic>0VbgMvpspaW zjC~mO_d!zC(bx$6H0d5}*W;wtrh@kTdb|!6vtV&>-yH#!r2q&AGe99sUGO!Vzfy^$ z{a$p#@HPr2Q#BCO+SxBn(AZym(cIW#Peyff63SS)_-sRmWP$HzC&|_ztXllPNmP{= ziEjEO%XKnPM)1K55GFe{`zi@?S*LGKU{v9_=Ps%K9@UIz;#g{6;sy`7qQiJyrkhWh zx)|_en*nbXh_clNSF{F(+B~};jSVf*+KKwF7S?Ml&riwp_&I^U5Bn=x>jDLfDn(@g zZ_bq7ESy29)kE^I0E>utk4CaJWF071rB!}K&Yn3dANrXemGLnx$iM#a@{hp&8xP9A z`hg#juC8tdyTHoOj~N_y$ps8eFm47Wf4v37njr#brJQ8+FBy5 zuW(1RbgpL2GBg_s@X^}RDQ#W7(%C)0fNg1hQWnwPMPN9kCLGQxdcP<=#I$PYN)pBZ z7L!^9txvXIPF9!cSxg%HB(A9L?5ZX|v9*Q=U|J7k>_*PmAbr{di0GZio`|gk4NXmL zWD!?a7sx7NpKS%xI6q0o4&&9_+$L?Ey)wAxRt98q)59`x=>$QeGK!H+tRpDVu~NCN zO6r0XHJ`Lgg8J~B0)BKhD9zx*;HD_B@rTL+L%O&y#m3wu;5^A^i7RCduy?6>kFp1@ zf=Hg58(*XYX0P>HbtLVYn$@CR8O3q37xcQZYfiJpA!teDPi|zRM@(cDodFL4wK3v+ zjnR?md8Ev#gRclOQYjJ&0vsVAvgrXmpHMy9M&05 zWfzR~$7h?TTEl1wo>gt$?KPJn{I*gHO}uCiHuw+W-!LKp(}=*n2~OImapdbO($%+% z-y1o1RHnu+5=`Rv!H5GW_U*WV$$}F{9$}p#8JH9-Za$jzxD=teOkBKQ!+a>V)b@}IKkPIjaOV2dSf%`mohZNp|kN zP4*tRmt%7Lxrb>el-BsAASJRkR<~(vRyxPi{TO`}%Prk9K6;)>T~7{%WC{01b%DR_ z-gi^V`OIT~u63K1{7|I_63D9XXl?J7rj~Zrf1>uuAb@b@uG%|4Qa(mF?vE&*&N~>`a3*i~kspky$je zwq!oLawWWBqAU(cLvujI9t@@v&taLZs8-BGPC=p9AXCADL?zZU&l>|xRQzQ70*2BK z1BaEtU~b6u%1SyrNf7VPD9wf?$#62mw7Ov*#Zsl-8QqqDr*(x^)^4h|RCIR=WH4 z5>QTzKsKQ(NDG^_4iS@zH7`8mv{eKopkA-HReO!?jNa9l#kgglWk*@+>WZ?us#fC~ zNLT2dRe{|cWL=aH6uD`z;U{}8g#pno(xUg|VykUTRS%im4Q5nWNuZaV=-F3cV}^4p zfFh)*_`u;;ZfWNRip^wl^o*=5&RTD~f&xRhEkcIch+c~d6!GsMbu&wU91bjGPc{|Y zHUp4CN$r{&&;mu>{{HB{{ulYfkN$4;#krjadi}NA9sx)czw^64DEB}3CazzVoT6c_ zyF?}?8U~v+JZ0r#z^XF7$Rs%{?KO*FC%Sug zOG{gaY^*QK;@pHRFHV!y2v*-Flc8&yWwN!7*xWtC+S@!tF<{esW`OB3LpQjwz%-hM z#M%ee^H`z1*N?bkn;JNoF@$CGJ#f%FuF>9XXl7quV9P#Nr9LsO9J;@>k97bzcKm>p*;oITh~r$KvEL^JnL&RGc`hR1qF+~pa17w0c=p6oGCgrA**~ma)1_zz z3WHSAB)8tI-0Mrj-?t;GzGHikos~J^x(b}J+Uk37tJ#qc~rUu=7B2KF`XbY!2@ z!$U=9Dx3@pk%oZ2@#_|-ajutP&@r}NYU_(^MFllPV8|>HLQt3{DuWDD!D2oEL;@n1 zZ27sUCQd%56*wwbbmOy7l}2hM$s235A#nM-eawmRGBi7?;e0%%O?nPYOv0p~h{X_SRB zu;g*&0)?z({A$=?+kx0WkY9*k(O5peFEm$GIRhyDL@t!Sag!}^+k-^47LDe+WOZ$s z5+%ysC|w1M(8%o(v^6H9X5<}&#!Rys$y^({-->~}+V4A9WCpmdNNE)u^<2{ob`g>% zn8MJiAAN%wTiMoQX>LZFnfZq;jI@p+GfYXX=BDp&F_HW_R03s;p>3edNIEd3WJnKa z94;_3sH?%oqy^_5h*3ILYG4Cz)IO}O%q8~x1?}bLCO2RgiwYLK?;Sq7*^LJAnzbqx zOEgD-VFzkL02sM3q6W0GAtS>V^lX)(CNBXfl1W^W#b9cKb`lB}Q|Gpr@sGg~*Q1+9)YUR@Ztv)m zj-DNqz`FA;5#u^G1H2~K`%1v(knqvzM z%l3wvi6{l)Yhh(h1C*q}uji|MKOpmto^id*z#@SIpaA(B{$qj#Jy%OGpu&E;&N^=d zmAyOm(Rp%ZVTK7iY&SEL7YP!vt^vU63o0|M5%fKc{qvB>(!)LmXId7nPK4=42yt`Y z*MlD$jwTe8`9hz*TGre(wRADagE(X8d(0&oF7Z=Gh^539=}Y=&@yz2V%}NdvKG~eOUml0h+Ul zxgLZe(2Bqj&lJ+U?tavowuEvG)LBlBo|7dQfLNB>jUk+o@*rQ?O=Yg}Jx|2s1E>^C zI&+?8_ybr>Ym$<78No%jwniEo%d+?2z0%XaS7xV2cm|@T5mL~#<$1D=H{SXtvdkx+ ze?-n5f0A|2*z>cTO>C<~r|~)%sg>!Vi|dC(Y{wqdla0&yQ|R4ymJ&T@P`u7g8HZ?? z6(ws{pJ@zm0E?m3N`=NIJ9pnqqngVXUX)Acp3@SO8fzcoCO*0H3a~FQpu#wuIPw{p zn;NxRRF`w7F;PApoM#o2_C1NhA^aATJ9RuqVHN_Qh&CiJ3j$DMEm#JS=0KALZ2?P4_~4t@ZT|DH5>A7*Yu}*XikePg!)AZu)cfy)@JqdNS4O7=zT5V9`M#o{KV&G#ztSTW8m;l}4z& z=CSP_0ZNGAeqct0`d`L)7miuy08h&0lhN42veJKdqgMI9CU6}Pr>Y(78(xR4%(u(X zH}_oiUX-d1T$lc#n>b%l|4cPtj^s+8WlB(84LiJgBET>0l`2@QGKd&3m788!=9Pjb zEvC0jwy}xGnu9$=e?EXkWZ2QT(+m2Q<*x9pn~>=V@r;PMm9@Fpg>#lVo5AaT4p3*N&{8{5SC5GyzcJXE$y9X=39`3*)ht(VA|r$jQ4|bX-#0VomouS zsjJFR8BC^bY}pz^HxEdiQQcU>nH^y& zu`?3RHdb9P>0XqK6<(|NrF$Fx2MHo%mH2vTaZaWuE|4u^g3+8#HIPw2=q(3=eAAfE z3|LI|H9Zf|x}b&f!BUeliU@Au9*QxH&Zi!PY!1*}^WtF9+bj5SM|tPECJmS{3Bcdn zP&d`wcpZ~|_JCR0me{yngF{W4f}MjQ4_k;-Dy;dN7&#-0sK<5Lt{b1QPSJa`>B$xY zC{5_3362yX@@F1&*}B%iUjsL1a-Ah`*H51>l%*p1S18JkJvYnF-M8?$!UP7YAGEYU z4Q=i`EM?u-qxz5{`Kdu47A%itIk{db#;^ zZ zRebjIe=Vn;e^k#8Z~tOo5y=7=907PE0pgCjZ2WGFVszTnI#8|ewS-@2CzGvhPGczD z+kI_k?>{C2mA!TiOS#-3cfR3$+;;)=k38{rYP4ucE8h>oyYb$Xyx{(2aa`QPkd#u^ z^@<-h=k@*VnsD|}b*0`Hbi!wA2W?a0EitqV!Wz(fPtl~mDuH6YFQ8qFwR>TFTVs!2Pllz>%FY0~Bky3_C#+*6Vca}M&kMhIl{3fr>8_{o`zd1@ zl0Zo!*TJGoq}71WB&!BAU40P}!5BBG$j}Y1V~NB#>J{^bHk+j55lLJdP4(J~I%@{^ z-HBPKcb>`WxVpP4{0Spfz41Ndr~ngXZDh{?2#0BbfC4~Kt-_4m zQ8~jpD3zKPq`A3O8XKFWP*;hqG}z7nZ4I=&0k!YeC(i>~Q<&LsA%Ly5#_1|OTUc0> z-}v=kmcyU@)N5~reTDA$Jzx7?`MR(B1_Jz4b{ZsxRtcZkkh@*R#3w)EPy;KM!2A zURZ0mQMZkN6JJkWKF^vSFl4xXfGgA^fk|9mn&mS(6|wVxKr?VFR0Io0bNjx&77u?HT)!K(siK$WHeiFnulUeFUON zOihlRWB*x##kBs=*g<7AW2Roe*6kuFB$DJC_77yP!GHiTFE1}pvWdSHO_}1{$^?y} zZpgJGIxkX|&A(Rm&ZJN@dUBSy8dy}|rO8tT3+lG%trmQKDzk!lj=qC1wc$NNvO6~= zVT+ud5V?nvv&Ai=CB ziwib!&%t|`yg7gJ2^zWq$D@He5gYHXz=B^Z{$eRonO_~J94V%-zZT9fbj^((WI0O1@1;Yk}xlJ!*NGs1nL zSvVL_IKUoz`jebP+HN5B!vwHV8FAcW=mc9^Cj+~0mfbhpDMz0C80GQGoEq@<_8IoP zj3&3amdNmu{XfPPaZYOZ4d0VG>FgeoJ0JWfOzs|i;_u|t^M^U#O+=LJa&hfC6P-%O zBeR@!{KZsjM9Z0Cql{fT!@5}}957eNFlvbqWU3Fm{aa*lVMY#r{G$ZeT8nCHn4knQ z-F~jq87M;5R)gGJdojmG@6p9Nt`SeR;QoU|U9(47#?QvD8ccKbgN}iPu(dU^`^J0a z_WRz$c<8ZD{GnVPKA8pF9(U@-U~HnrRF34(H6E&yFbw&nKlWS@S zS&2RHeL_zP4?0xiG#R2Xe5x#oWuCHCUPTiw0+Od zX!|+cp-p0~YhM)@7$Um;78+&8-dm}n^Svc3&T8jhmGd-F+Dbl| zd101$^a6dDoZzsBd;^(8%@$+bsXWp0Md6*c28U4=P;ET74Hnbvza7-*7m0;K0Gr4= z@%I1{aS*acRRe76FPTOA=I!h1VDZW`A_Er9CLW9-Ym|c9tObSjMP}Yn^988|GPhtR zw76UQkU@e|Utdx)j6#XoAb>setOL7PSzDGm^tq!mUP0Pmx=}961|+HtW_Ck)D&(kO z84EPkKutm!z_O{uWG6Trz(gkvw;_uys`LVZ!_gzp%D?^TACdVvWSFmid^ty;zkfh} z@P~g)dV6}kj4S{~51f4ik97gw)w(~xHpYX z>K-?ZX%(>8(A3N%0TLo$f^mD09i#ss99+F7UX!$`)I?*?*f=_ZR!?X!kTQnN9b0{V z5;&0^O6sL@8;u9)TyM_ukO{4qp8kDolK=aPY__UH{iFX)O+Z8$s+x+JkrQ3f3)0>*B=a-lGCMs^fXA9# zPm<^eQNDTb_OF)59{NK$d+Z5SGr>HMZDQ2;sJW$ET045^61%cEr%b!eCv{==_F8)W z2axUwD@!Igt)s7$n#{3HE7?jJG9eQ*6H0i%5EnNQ2ppZiPBN8JOG1QNg2 zzu*$r6azAOXUVP#SjP-l4BTV*?R1&>^YG+8&H+6eS80&QJ>Tj{U0$w|YXeG{+k7U` zshrPo3uZH;8o(}W40%*Pq|*2VI406yf2;YKZ_4GbI7Br3>e5l|-(Nm;Q`xz95}8w$K$6vBYFUTHE`jqi3gFI{$*KEL!`v zjKVK>{#}hV4y)~2X{;}2g!h$s@2$b&mFg62V(8{oodG1cLbJ}vOCcK^+N#tQQHxiwI!vu2Oh2{+ikTN( zBU_qGTs>^oLm=iETNH3ZZh@>joStw%; z)`rY#18Nxy_0rVTOoN-6%DTCt!de}Tz+0tQkDA3Af=aND8Xz=igK%o!(Ov}xDr;7Y zRU$xTmf7k7e&@G-P5$~X|Kuw((_bTh6@cpf-}ue)&Ub!|H6Qlga{&UFGZ});SO>-a zW#-U^8pO~JBN*ElSOjRKG*uhcyL+2UYXBABG1KoCA#*ug-~dO+fUQ>oSvO`q^HFf5R4A*=6<7;3q&U!siwf*t%0f?ouS zNCE*&vo(=5!-i@A20*JT3#QQ6pfo(NuMQNkuO$-1svyzVMU{OVhp(0+tdkMN2TBM~ z%iYnvlY1lBQPkf>uxLyH0jtT&47{@5DUq87g9Zcqcvc8R(24=fC4eH{8*ZCqm#{Bd z0IWe?WN@??$!{itMGs>1$jY`D;L5NdEJ#$z#>LvNG_cq6&UoxlJF9YAuj@fAE{q>g z?*^Ga#vjR2^ru6wKB#Q;&w72-X0Vuo;n4oTdM2jrG_)r2?LwCNFwZ%_;_D|&O@yGdEmOwO?S$E8y zdaPZCOuA0yXU5pyPTgR8X%aFsJ<7QP!ymYPqKsm8@-l;Gj1znV@ZbF0w9S10Mr|_! z$uR59tnZ!2|8CxeXAQ;+pl07q_sfpmx6sM-{K+p+nL|fTz#%hQ!RumgOzlVP^pS7^ba18ryu<@UX!;-@pTl^RGGD7Mp_O`G9bm~B_Fv3#biNBviH#aa@QN)%Q1N3 zGk+`>Pd}r{njoDtR@drxT+xOlN-h}Rkr10 zd0X15z(~-fCs%M08x`4o<2`cU+rEkN_`@IjeHpoUOih<4F^wO(_h$b{7M$AHQ%bL3 zk%}^2td;`#>%$&n-v}%x&oPwkz&vq@GHcG&T#r{T0|_bz_EpuZRkqBZYZi>ftvlNf zF(kBj4rJNF)UlcM?v}jU3M>XTIY~gGolD=&gG>$$pLsSZFY+^0&&l*`RHcCJR~c!l zgFs~lBMa$Cpd?|IBtJMd-fqawIR(@Tx_frsD24hW+wf>xzpb%~ZOF;&sP<(*BG;&S zyvp0X3V&>1ar2dL$~@;^5?6%&Bmp>(nnF@BJ3GOE2Id;-rfRx(w~0=MeJdEX2`pC0 z0C;97*$V8-xSaLZqE)rc9t&1Y6NT&HUaufAWT@R3Br$4m>N_mh%=U4GnXm=8_TTUT zlD(`7B|9WlZx0y{Kp8Srkj-M#M8+L~2Lf^hirxG@0L+<*5z3)jJNkG~*Vfl*ws&KV zjLy=+6eXn%r6wsB;R079P0eL#ZfTPO9n6GHz&pBn=(t!b>tq+3Tid0%rGsoEvd|lq zRR-|baL~UC0fWjN0JwG2!*!oJ@uGa_XMRLRMlQVym&&W-k`EoaS-$IgzF*qf+Ctq> zx@24~!fd^_$}s1(&?^l(RQ2mlv?Qv|GYv*UDF zbT?;bnZhA#2bb4Y#2SjoUQ}Zfb<2z4M?z$o>$83b!2((jK&}Nd8-y4zgU}2!7~BPE zY3r4qfgAY!h1p4MrvQoA+6s3_wp##`xIE9b#dZuxX5oGK8V!UzqYsb{S)tp#YptN4 zmsNIJjezVGmVHn9d8w=idy2AJU~M2J#&sa8JTZEf2`LZ1^v^kH*7x&rg*;efkZJN; zBo|=@)7;uAOY?Iwe)$xG^biy%?Y1ch2{)IKb2^J)V9X?TepLDMav5I=7X3Apec3<4 zvrZgkH8BvGTd-@r1N-4Z#PK5KpQ?7FtfWCxHD!L7FM@H!u7f;_k~ zCe&Fa1ebPm!8FH$T%2o6wOGw4TOZZcNq6rqx#8vqc|M*vdYFkEW#H-=aP7bK4RY5T z-^VlOnMeOZUU=%`Of)iVH>5xpY&yT9ZC1M}2G)7zfL#SJnI69=t7|L#`JRLKF(GjI z;&D2|0>r4%6UrPK8C)X?iv5E1jx}|xchqTG%kNE%4-;G=(SjrcJ}}-;Fu<)9HI-;P zfi=e3UGK|kDh6f4lm+vk8Lz?Fj`@Dz_P5Zf`3r~tgsp98$YM*y<0JjIF;uxEZ`dO& z_6TxGpOOrY*QKj>x7`2sZ<6l5ee&Gr|B5wsP&4UUCu=wPTj^<(CayvPC1q~xx;lII zaL*aPd{$lGjjiEz@>$l(J#YDEGy{70uRkIe&m7U9pRA%96&4$tq`h+|C7zJb)1V3S z%2>EiD&TTwDvL~xnI^H4QUbrvtz*tC9guQ621^(VL232+x4xf@_47}CQl9wq|KvC- z0Liy4vHdV^jOmbuv8RJS?$KR~lf6v$2K_(9p2;4{&H!-GZ{Yo-r=_>7a<>5 zy79fjdN(43a$(xuDVe(@w@7!}MW6H5h zr)2EX363v*Gt6(jfvAx1vyywaGP#-LT(Y-iz@necuJADVa5%$lOrQ+JI-=E^0mz|! zcTlZ>`ta~^rPzBr%;L2uE;r4lSN}H%7OURIRY1+A-$@3$P->#oY<_NB%FSKe^dXtT zLExF$&3T>bgP8_lTMc&}^XGpDHqokuMju7Z!gCX_gEifxG^?vJSzIqI;eFHQVPULd z8klU#QC(qTTq9V---ba3n7~y4yqX$mZt3J9>REhzAB!9tIO?O+{<|QnYfIF|T!RZdpsOq*F4(5tE9`aDGXFcVg|JfhQ@BQv?UC~+W)xWI1GIs#* z{;l8sopR4T_nCrRS6R&P#k#C$YNPIJu~mk$g|StJGKq_9m7)CZ>^z(fu#s#Hv~q4)?+Y$3SNx+}Nx#-W4t44Gu9 zsVv1}SraL>wX!ffC37>Qbe*(QO3!yULrCQ@LEfh8-;+xzn;3$>98k;zZoGbN_Kf#H zRvF1N1fSYENEsd7gCMJ|u-6=v0FYZwjh!cxMpxnbg4U9iny7AoK@J!X1R)q7l`Ux! zPU}z59J@ivZJknITi{qbvyYj;e0a6}C;gs-6{}H70WqIPZ5>-@AiIof#5IA1KQiON-NdPn;XU!B?XUdv*>4lO$yz783yP0i1y? zf9_ht7Xy6%4G&bDq>T3-0jf%EIglCSAUxmBzFjgfc!+g*H8mT2W@ys@c4KvE!RoQD zyf>tEh8l;a1`%GjWQI+~P~c_CA||zRCO-^wmiMfzsP@3CB_jm2$&I(YNt&BG<>d39 zmCF~7b50?T0{}R5!(DRkTmCm`@7y8Bk9 zE={dn($?O~pb^qjNEV^a0sFK2z&&*4ggFMl7~Tit2F7B~fqSK)+$NXKy&yAFmnoNo zDN9@D4uUoqvy2X(kdx0JmO`P4*N@rFq$vPysgdX1(J%bH%%DyYHDjSpR@t#MFy>xk z`w&$y>uYrOzUi)aNPFjiJaza_36A*KLvkv4ju~k~{J!CcpdirsXUrJ)hz$bcJMRBq z<(7Ni#eQ&)ed528)%Cd-K&cbZTV&N^g20*abiHV@wySS1#}n!Xm)-kPfYh>o=RtY! zT_2FM$DfqXfBKJPeI+_*tCO-wXWt&yCL@u9adQ6zmt1O+!5FJeb;_y3r~#Tp8KU=E z?FJ)Q4C~L$n=CfNbqwykL+*e3H}mg*^3Q);E}VHrl@VSaY>y^Qi^Z>9p`rsF$6edK zxyQz)MVx{Rn+JRc>r;t(bM{SKUI;}(?(F~oAOJ~3K~$jCL82=ic*Yn&WbK_6j|R5a zXH1Qo3*#6N7w1nsE%Vc(fpPT& zvEP4y=jk5CHRPoMac_%8I9fvv34ww_dyN5d2c&_iWHPlF*kdGFiw!L@wD&d{9XTy? za2Ma|+{+x?)nQP&nl0`5+GZB39$(u9i*ZIdkz6N(N!C|GfifCC- zSBsvLMQKFsR1qc(Ez;i6Bjs|LGS%9e4QWI##&R=RM{J{%u{Ja^h$XW~Ih?g!SzqHq zhRlvZZKWbJbF=c(KmI{Ee(Z&pHh$NCYs(RM;0t<%f(76e1c zzKUQJ1G5O}skO?Wv5h*Tf_3!QudZlcQmrF!XGxKkjy~z?*-gNRKyiHJGy}-BwPh0+ zSWR>|?5!6cfR9VyldPxj&_T{*#ra_D0JPwki31(-qqP+@JzkRK#d+;5X*~cn`gnYY8Q)8`3lhWj=VB)dA|QnYlR{ZIn=Pxk7rw^9hBW~rFa+lK6^xHs`>X7>uC_qc zfZr49%-A+z_5Ww@y`$v1t~1}$xvO&k8W|u02@(WAkRSnOF^VE3%aSG8vMkAAY-`3| zo;UXM3+uiA-}BhdVa8!BkL4s=vZ7@r<|u**j35aRIp@$o1L#KQw|?I~=iYN~RdrV* zP*f-_3P5+&tsBnSdw+X>``hO{b#;y^k&G$Ara=dU21#$&(F0pEYbDT=ifH>Kz+wV2 zq9gEp3HAX6P-X#00NdlDwGBj-Maxj9V9{Irq~hp*?}cIz@Xt0K)phmE6J3+wdXx&WSA|3xpZ>48i&nbhhqk+S-gr`g4}Xpp0sEewToRJ_ChiB+ zG^oj)U9+`50cuc*QP3S4I;S4{d5cyF+*#m1?w*SqPn7P?vUmbtfH zeZ-wSx=+21S6zFLjz>a;K=S1AeG-1_=$`9(W?$|$Z+KD(BdDXaX1uoU8v^PfaLt0n z6sW|aEk@Dh9**dGR^0G_D7bGt|84abYh#t;QElgtQ0G1a2} z-gwV1>ps2k*gv{G+g?@GFZ0~|@yp=EqQq+er6K8|s#{Z=z&4d!o`d>9qbfEw=*GK$ z*-e{unS1Ixf8~xbBOBUpShtLUX`e0%`iWzE)u(8C$f`(W7t;2Cpm-WpxRUs4h;LasCd6y0u(>6_O4$Nop<-vmsJ@>$v&K+?Sue&{9f`KBH(bt6p?N6087tK ziuk^g7@uPqu*gOeyP&#Om2H?8BA&-dorD%23J|{P=BedrNIe;lN$*Og67B7J821w= z=Mq~KKbHtRhKhMwIkzM(Nt<~KSE{1Fd)q7Oqql@~PzColClL{{yBiW&!3HPxE9yZH zg&JG?;d9>BCtxv3i1{j_6+mqK44@p})YY@V9oqMfty6oj6Gx7dRu(S3}LZY^vJgnX)Xsb|1F=9}JP&nnkaVVw@jjq17MnOb-N0$brw=}o8hK4#< zXkvcjm_uU(kXTn!y>#B4kTHH^>zC=LNE zhfM08Sx_TEjVyqP>8dC~D`VWji6a2T6G~QOGRGlENGkVHwT9CUjrv+~mZww&qS1P! zsJyej*eydt16tby^e55}sL;R^?yO(YhYIZT;K)J%?)O(x)d|_%Jk@kkhZ4as4^+eu zXlQcu7_$$sMP%jyumo%-pFU(XPKi)h?;)T`a~PqZx+(+NUdV$zL{*HhJXy(d#9(KGSl|7J9>DhJA3L_0(wGFVP}zM+ArppNcPu+Cg72~p^jv*uqVQ6g2^#>d>r2vZfwAC<)o$k8tK7l88{OV*ugZ_`QYEiz zhP&bRPr9Yo+@YV7>^TyW594EQ+uQ3ztA(n`dgGc&%I@0yk^;$-Pbk~1^xJp2RX2Uqz4C*viVBIZyW!4H$({ffVJZMh zsgOZ?Wnb;ux?alP&|8lm-sxU?>Pt!%nb?${+Z@2Us;a({-tM`<5FW8#a3q#zN(GjA)v^5|aGN_f{ssa{se+OeKTwBBFe1MKHuL)*LQ-d}ZF-hA4<@xpiHuY+1J zD4Fpu(B%=dB3WS35I59BnnXiQs#huC%JjTNmAClkaUfqdmmY(~q>s}sl=Vsi;`RqV zr}%E&!(Y()wC~8c!(c@+yE%=v%rL~sO1&}KXYs%7AfbMiIf}&18Vb!~-5}=1pJBdZ zW-sfZrR<-O?1}AON#k6>5A(pWe8R*I7AleRSQ5rF0mU}5Hmh0lu9CRpfjt}5 ze&sK2;yX5}Z?E8n|Cqn!(tt$`h^`Z*sAtv^Q65nvGj+4d$6{1^?=y=u{!pNUsh_7# zU`DEbQaPdB~LQA{qi{oGwfas&%X^?8uS;w z(`a2$X4^LibKYz^dJ)MMGBBAyjeryi(Dd0$REY%4n%bH5K}oSnq8R5)3_~>BQO(ZM zJhqx@(Ma3dQ97LFT3b7$j9Ob$<(R)n)e$Nx6~#INq_z&%+|(l4X>&`vdRGv}vFd{j zvE>C_Ar6-K*_kta?$7`958O*HK40l0{^|QBxdV*K`1mJ2=^b6V{z3pOb+sU>FgC90 zRG^;@QxH3bZ@wh=4$na-!m@28{)=>L)#^%33g ziReG!ZFa}=8DNW4Lcbp8gF3N#k2Qv-!O_#nehjo+-p@D@?i<%g&kHYrJ=MF0#wGz1 z_B&!B>~n-Bl-c#YIU&ImdKHuF_5dT#q?mMb`M_0Au&P?L_O9vklV<=WFrn#L$e7LK z2K(kIQTA)bs8CV7Oza58g3tp)6*{gc+Fi}w*8r4^&tzv`R4w(H=nRV`T4T`%la-l( z#VB~wu}cIJ3XZF*H3ydw3#f&{py0Y_zu3QXgV;0%+M>1LXHQzGaN>$VdOn`Il{=SA z712LL0|;Z;Lwi4%Rzgj@g^J;^gF8h(Wgn?u571ZNC~D-jH~*X}qM#)kFZb0dQT zZqA~W?$Dl1s%9@=bAKY*M3s{MLwXZeta-rg+x?c?^4b#$EU&!o9tCmxcfRR%ZhlGk z>B?*GR{zubr@yLWojHy0+DVP(xb*|SVPJ9B+X9Q%-|3O*6^;b*#k zo&i+6)zgZK86R8Y)*~Lowd{FwFR_)Y)_z!{GL9eF<<>p?_wMMyZGK57i#i#*Vvo0! z{mjM)ndFZD6)^+7z$beTxq-gkkQ(!#)T)j*-TfKYSZH(4KJs_zx~;0x^;2C%DVKN& z8mlGHvpX&%i86ph7i&8(*@uxW2-U63wdui>dnGmflnPFa(NJ)=ec(6TqN{FlySBWf zsv^kC;yP>OdKLGpUW9=&t1ucuZ4Go{UeV*eVOzz3g)XfL(UQ8nN_9gwd-WiWh0}D^AW? zau+QP=(rl~MqDe<7*SEfh^^53=`CZ%?&jLQ?16-q5woSl=6nX4ELG(r2e$hd`{Gm< zFXS2gIDGb^gGHk)prTgmI;YK7P{Gjc{kz{zGBodY88?_8a|qA_P-{a5en^=pW`w2L zwsgK?vLI7FM+q{7ErURENNh_`&CA%OG|iQmA5U#zQ$Yn`#u8amoMyO}%7WHZyF#H| z6jFesDiopa>JSS;>0_!uUj_NrzFhjAS;F?<6 zTt{b*DvMMYH728aTmz=ZMg}B;)7;YHnwwi(Yg?yls6*6%u^WwUd~8s491IE6R0(fr z1|0pOzVbvi6979ptWg?&^2dMR&Yb?~D2)p>By;D^bN}V{{&&a7jI(fDxbwr4%3-MrANV(Pk<7*@}Qgem|J@DMDE#SmpEVDb`?1`wXo^DrLRL4!FMF zgHqFzK!PF$Q;`e%s?>ESy&^$1v&xiB0VrXOvz~DVr+N=-ER3nt#a1PWNbDR_dHlksyZSLRGXTo4;qzs*Zj!3q&E>~N>Il2+h~o`-cHqOFA-n@ zOs3DgOg)2CY!2*sTYDWq3E)gb#6r*#f&}kqQxKPetcliMl5$AmV5`bN%Peo_2>0Y<4FO?b36Lm!;i* z>)B*YmU?AYT`oYfEP4(cgy1r|ZVTq4{ooTWTn~V2_WWgT?&51zA!1PdsgnmqIb=<; z*Op#$r@QW!kBQp-*81-&sX=m*3Lt`YRKx%gQ~;N)e!r^uJUc!|s|R3^d5mwr`iR^3 z%EKCuL4^`Kuw}zj?!>Wu`kobQe@4OQn=gG=#{*QtK%kHEw);QlUVi2)ZvXZ-w9Xcw zoLW^Srb0*8Ot)nD``qRYPq^)GuX8i!FVi4<>;P3x_R{`c8`LTS;{a+p%B&=n1_t`% zKQ-%FRS^qlJxcJ^SQ{0y`u0!gGjG259XC2Y>JzN#dd$Qz(Oyf|zs5;ZI=q*7)pS8V~TtSi?54$tH zw&J8uw11PBKYc&(%j`uf-Mt_AUBx#~fB*AJeh}MPKV@R!1Ln(Zy9vOee`f*;m2^oH zQ)v<|y&s&J?0Q3!66WYMkg!i7RP2{?K4xkzXCl*G_IG)kmiXJypI8dmd;38mX8w}v zw1%LdlHjp5XO-l{UxawrtF6*Q$V^6JQ4&JdW?{);qg+REagNqIVWKt&-i(EjII!hx zVApYh+{NxYA(H`d-ouap{#2dPjUQBgs$|opV%9=QB{! z0BRULs0+}}pn9kW$Wz%AXA>;8cAGHG;5p5Fs;g~qt(`MP=i&1>T4c=Cw>aX1d9SL5 z)8lvqmpJ~h;d8FP|CDQJD5zRPb&%%eItHQFRBQHPl|yoR*fk0e*1EQ~PS@1bq`pRk zZ|dn|#2$~K&dPnP(O3-xJrtnhU6SCDV&1KRf z`kBxEn!D@nd($47Bza-Mib?GId0QF;>}M(t8(5@DNFSmpph7*hKM}K0&te1=69rV% z^vDRJQrOxpkrpZdtSO|~5k67yQv_6k2QKXy<31KLvj8JTPY?jIFZz0qh(=DZ2hA<6 z+@;(b15gcnW-nGH2q6+GDpZLLsQKW~&|;MQC}VevmQhO0v?C>vsdp_#nJWdl z!q3C+@`07vW2;usBLzsI*HTpID#nWRyMwzonmX(-v|`J6XX#)D7DM&4?0TAn7F7;7 zCiJiT!>6CTu3jP_^A}&IL?Hq(0JH#_xQK;UtaUfv_p7eGW2W2u)>H2Fb^qp;uDnA& z;s+1@PX&C|BVX&5t-eR}KPZ0$<}22IP?bsm=1uqfvU_X&cir9{8{E=Wcd0#M>s!yL z>IZ;B5NG)f54ic4U+13r{@)n$r>aWHOezsj3SWBa%Wlv1R|V#%9zt)$FXFTB_~3sM z^?K7QkGjiOyiW?KP*J<4FK|m&zR$hz*catvNWcL6_>-gxLVKc8o;s#r5}>QNBzYP5 zQ8n{@zo74U>!t6>jv5;$*8>_D3^`!W{jq9)=ygkG*r?C*mizvLDq&kTJnde5;)`Mj zBy_|~z#L9&aZ)qDPa^x)1ct$ci3RQ5YR^ji{?TKDMR>;A@-C5`=Q zXx4M%+1Ln*a;PS4BS>#&CS8-;3)yS)XIx@Sq}QJ8C4aw3QlcbFPwTGD>)jLo{@-2y z*1>fngbX73!F^<3r-AK0RVYsrL8seAWR8tSAg z>JorOGp0y#(-2J-lI#=>)2Dk68x3T#)2ajrR`QK7z~hZDo#nNb;)@+s6(Q+%`` z9dx&LQ98A{PaChDb*)beL*suz9$=yOaKGLE!=-7uZY|5 z{hA5Jc#JB5KKXwD=Q#nwwvKMs+S(={$iE9sO%lDS8Xs}BwTN(3xrW9@si&GEDt%Vw zDEU*(-D*Z=BuP!8EOzkVe)p$;{DsF(zN4xm2+WRn2go^=T8CVqA~dR$nAKDbK){^;`a;IJH6R0Ug=?t+^!cd7nU+W-uX z!L#n@!5!}K{;k$RKy|OAqw^H6DFi3wuD1yACc#stj-yQoMHc!p0EMv=J2pM{+SybJR@5|uOma`JEqMR2&}=^IePsE|0(P&FscsCP5xTp{|XRqj1KU&-?tx8la1am%i~*FF8+zjV8|zox`Fwj4hV zJsdmC_!5$TQg5c!q^#-iAS<`FC$7+^f;ZX2#&xRrW~6qVYerS~uAluKJ>zG-|9Q9Z zl}9Z8O6IvnmH4Q>7a6Ol;+d+ohN`3`^HLUo(a%j>ka$dm1mZ}$v0`|rbzpp4tQzcs z<~#Yf5vBapzCL;>B7W&Ruk{XhEET zC=7pl_bdS-=p#6u5ENB(2?AGTOw;**#rR7zRHKw0f+NvbfglC%XSb0#Ot=1^Sa$Z6Yfl%JCX2fpV9c&8fPLiPC8SrVosL*`BN}1`I<)rWi1e z(9PgbzpL@m{G(*Gsai7Yu%=GI4I)EOgaTL;t*yP=wRg_+N{mzyZFnu!M0!;k3yrR& zwZk>Hw7RB3LA{HOjg9)Rp`PB&G5ri-928M&YN|BkSYWf7eg~8v)B7gHyy|LYD8mf6 z#~yvi{qq<9A!Cp$S{pxolPeSo?zeyE_uMttpe|^yYyg=Kv_*(UVk&V}(F@yHRnfqr z{tJH}q+ii0jy5U-1y57wt*I}#wvO3SLc|#!Kf2eQI(|@;F9Q{p^~>g!gI6rQuSwRR z8p>D(zyv{@R8*m^_ zQz@V_cM%)om0PK<%$R$HD1+?PeLLTDhxTnss`H9XJSes{s@(nds($6G0F~c?7%UPP zK_Ts#eT8c*Gz&CP89a09c(Kh3fvG=No@vjV%k}v)eaGC<{aa0N%Lm?JtWSENJn+kg z6Jf2FyT*J~k>gV3jKN^MU()OJ;4~MkaG$C80+eUYyHb>U-id-JvlLO9)J#D2AcX+) z;&aPNRYm>g&uRkrK77^>6{4jp@6^3!_8{XKB(Q|q_SmQrK2!r2Uv;wtVqSdmOK$J> z*R&?70$+2}M+AcLJB$dSj}hCx;PM*;LZGLzW>Mc}i2cenA2K!4s%rHyc682Cl4Ij* zkGa_kmbv*$R=e&Q3pBHjksJqhza^l3`PH|HDYJOlEn*`b-2JxOv;B1eR4VKEFU?gf zv`Ue+wR5^_Xlxbm;&&ufj_ltofJe)NC0dOp2c4DA@h9K{_0^{4Hk~EQ?2!X$A^AP!aT1&`*l%p38c+- z+nR~l72&!1UzFdpF+JIb-t3k_OQ(9gS({v&9p4hsZCx|m`yTj@dQLAs{zZ)>;j}qd zk^uCc^K3~1raivd;r4byJ{g`Rn@(zACI*qVtBU}X3V-H5*o(J5@Huz&b?;Y?@T1@S z6RkCyC2F>!ICYfYkAXv$RugUXhb7^xf*+JVjYzDXQ?wq`-#V^+p!1}a2#p4@sk}hY z_?Y=FuTr036vPPze;+3;q)d8OFa8_2mn04rE?p!0x#OJ|wI<3XF~lSpcM^#z6k63= zFGhf>?N+&GwkTEm{xhfitj_ZQi+;~&cURerMUqc^m#O*sUg2;{CIX*RNZwuiJN%<@ z#PVR#tV-#tC|cyv+x+I@CuGr}Ja$f-r_F;i08oVuJW(bkW%!r5k&{#oCcFJ1xXbX` zgBS&yePq}gX5F}EP(id{YPWlL-+EIb924c(7XjDdXy9^Y95JpYyaxEP_svH8;Ms(h&^x14T zf>O>GfChz)>?r{QnWE0_S)#;PxBs{UWJ1ZILfF{ItW2tj&FX1vsIQYMYCV07D5g?L ztgjV_q^ijKs4`0A2CC_}4Gaf->iqo-IDL-?-K?%tr~2Gq{>7iVeS7y94JVbG@I4p) zNvc{KDn_ZCa{TtpGf(|j>d)dgT>KbrvL#n!4HHn47%G#PHYQBAKf+vcs7janyas;np_*WjDY|EAOJ~3K~x?nCNmX1PzZ6x@f|$d=f=dSxG2MH(t76+-0e_iTMx$pw570Cdh}E7XHHgj#7$ts7KTcDpL)a~G|W zPeWOiSOI!63aj*l(u)NBSL}n@dOZt(-LWIP6_m1fp#DJx1~?kB%Z^V;dK0xS>r@>F zP|?Sa(2H0ARW(WkbWWe^-g%wA$Y;frf^U=bAo}3mo=d2Fr+<^LihzbClsnz^xBr5> z`uh7-F-6pd%4O*9P3&c*u}xw}^N!8@Be6!uw0W`!M-S~t=f7$Xx40EId_XfV*FExg zS`(of2Z-+Mp5tl%hm6h{*ij`aV@b=7zbEGlcuMW%j4cl$EItv2VA8!G|9#OupL_Hl z+*>a{XcgbdDpI*X!J>|0u&Ae+C~jIs+2Sy(m<5~79)tQ__%H9_&IB2V~}{icfp7UQSvX>V*4903Yj z&_9@mgi|F8ZH@ny?JItn$t(#LOKqz2%m}1lQIWY(J~huOG_t2cH}n(|6pRl0=J2Fq z;&F&ZLNF)IfRRxyF+WCgfK;t$?UzrQwXdS|h(FU?!mK?>nxHJArtRaaPcU z7!8@x`bIfYC}4oS=5`aT!GP&KjZG@apX+DF3|Y-;fk^^7s*7Zc$*vNRHaEA6iZePo zgyf=v_2!l~*U(rnkSKa-tyEBJs~O5#koXNssf~q#YicT}R}t0Jx;iMvTsM7k(B#G> z@o&SMy)lkdw*sH#olS4M<0nvSH9!bu3aN5>U6UnZ)Oi_SDZ)z4b12)RWr!*TnK2;L z{qxT_sMDo>J`3b71&|CeykFZkld?g<2kT1bjV&8B`WlG+`PH- zlY5{nsG&wb0N5*_`hSm(B6x(5&5+igfFS=#&?ZzCy|4}MQ}5!SW0vBOD(mA~YY0}< z)i=35#$p`b=lc74ZJwcMSEYqJ>{h208?wKmI-!U;YmvYdYyM2%2@|6jIIUx*dEYoJ z^ZPE%cNe+;ciXI&1B>RPtSV9Ev(c))*EWc<1OTC5kv?JeHG#VlM)d{V2dX>+1E-TL zX`n^1rxc)2DN}!rU(5-@Dq&kEvz29ntPEI`w7m6MlO*FA5jX@1b&D5$J=q6W2orVB zxJ)49%;{t9$iA%-#Ib~$2a6?~`Q%_RA6|xQj%pIQYsyy^ZM&4NB*sQTijp%HsxqWe z5gPVAD&xvI~Y+vPR29pPbY|sgUs}pbH9_61M*B4NWcX z%4_a+*WdOD^_su@%vasp>mPLI2G1(FX^+KhC%%R2hR(_y#6x>gI3HDyCcq!RMk0YZ zXIHMeODd%FDV{ubKz;@P1O*Mi*VNXf(H61_^iebJW{kPN_41jb?%_{q3pvL?^AXz@ zv|h|y=oT%#(bd$~yG^e?rYZu@hihUylxYrxCy?HkY`hWEfvY5pL1Kq>O@HO(D{dEX zeEqp^xub`+B}$8StIONCV43n@k$cDZkX!Hjb-e|#pj}(miz-L5*4&mq!-~LSy7u!4 zZ_6pt8q(t0r_E8|oQ!bsm97O>tZ_Hq`AbS3p!TX*WPDuo+wPeQl?*s?kU6ceglLB; z=M?RnqqCX3&8W;)m>evoG*M!NwReA7ioJWbz2YAK)_?O=#Z<|&(jAxFdw<_m8B6H> zp{i&~y4XG?{u#lBxEh53FX&iX%lbqxanO?VFvMVY)i$U=z|Ylg8bqtEv%WfqQb|*nSlvuqn{pIVSrb+mXB`DngZem_Fvg z7BfZ)LCqukw~CeYqw$*D%l%NUBPq6|=QlA}oZu`oU@jVDYGr#10@x_Z08XFhI(z0T zyRdJ^236Ez0~c?LaNJ_BXbsEpOM&F1hI^7*?H9TY#;#Woqd90AB5wh_0YIbHVKB(3 zLsKzYY6^mEt^2T1V+uwE?g)tKN5o(&$dDo#hQ#Km@h46yaP6UfSndt}12}J~z%ozAD12EbHgQgq?6Bffo^9fgqxBKT znicQRiI8PoyIjK}EG z&~(&nsRA*pkCueMHjuxVAi+>JM$j+98nGeHMYJ|Qa60iRq621qhz0*1To$Lc^(~_8 zb@Zrr6x%C*Fgm8-lo1mAX;j)EW^-PK#I7jXGfBoh3dR!ZZM?Sx5Z~3$I+O zu?bZEsOnLvwu|C^)wo4ht#LQr^;uO7-+tv`Q6o{~RVB^a-r&ze40)D7ysy z!~_YwKHTr5f*aQsb9qOffaV$8e*bSu1r<@A=O6zkqbx@v9Yx?FN43vZ@O*;6kK;ku z&ipD>F9Z3SL0Ma?5dtuyhG9nGpBtJbumcVC>F@jxi5!KVYO2tHWa$6I4}8Apdy`F> zkKDAdE*V&~%BRs7S%dd{^mko*=PbAGkuQk)tOP>^WzEuO9TAy)&z)a*5o5wCtj64` zmkri@ToQL0g=7>|=6MTz`?-Snd45MsNn93~6e&}xl$D!G;^5NyG*ponU3rt3YKTbn zoj8>J!jfRo=2ZePDNOVp*=uoNZN2E{Fx+6sNG<(BVtDJp5Ie7D4t?~k?(n`XN*cYV zUp^kJgk?GP>$o@oG>&6rTjniVbzXIpJXkdU69#VjOl>t8^%?<1C>{j=GD3rA)4``X z^Aa3V9xUqL$(*CeB21PopXg3U&VmhLeG5Y#pq*5P(wvm12a+wRtyf&W39HPsziXO%|5PHjMFltDF7u>+W8P|9Gpnk{8#$42^iU^g1krybU z^4`%=nuEurl3E8!92++JX;YJHYHC)+v8j=P=qNT02vFA6QWd0Hgj9078$Nf&dLTUD zR%KQH2$V`cq}y9~j4F-_XUDa0|7~4ioNWY$IW?-X>7e!W5l;dZ!z|6%*~hE@ykflb z0E>xn_4FPuubxS)={>&s9t?{=Z~AIQUG{-`8qB4FHkzrZehTZEp!kIE8X7w11^|mg z1{SSX(JG4r&`v#Q9P+aip{Ul@H@S8N5$$exXwaQFy5F7hN`j(93IzF}P8p9F>xI3e zs9Q8@dSM8@`5dZ@P*F&vgi!#^)Z+JAmu3T(nd?(noZ!iS5?UtExo@g{nwDA%0DLxWnf}JB5Bqc7OY(7u<=XyVaU8%oruJA{J0!x4reO1a36@IDpC$R-tU@lv80O(b?Iv zz+JuiJ_WOkv%n8oYR8nN1GUsUrrh!hmMgUY*j*C1Yw!Fex9X;kxMPQRxM#lic_mGP z-40JM0gIWKCR?*h{^jjEK9lMV07Q%?&zix9&RVcsNnUI|_Z4OrYSnWWtZ-}Y{6+WX z`tQ59)<2|p$DUuCYwwz^xsQna8RN=)P0_I;nwfjT;TlziZfsJ*#S$ejs~WUN*b`yRin2;& z5s|?m{A<6~QIasPq_SAf#=lF>j~?Z@3s;FLz*rKlA>*UV+yE0n?7nl01-mqYM{O$S z`jsTYHd#`b7|xQW-aLdLqT(y#{<8mJOOS|R9h>U!WYzzQzv7a<@lt@ri*?M42o|GI zEppDq6q+i@-#0cks}G^C_ps|bbyy%WgnQ}5r2$~<45c`wsvg;O-vmBcpjZi&BYF>D zgzuq3$EN265Y(_@As(7`0V_2!s+>z($4uA9Of+a>zN!W`BTU%W0VM z(9-43_MLRcj_&dOiHH{&-8$1Z6{1fyW{cwEE&8;3W(v} zCCN*FtnxrH^*c%bn9o=@HFdbz3s<_%X>&XkaZG)*hxc!By+`&KeNxXL4o))Jk}0j7 zP(jP=sc?j3Ah;zGVrUY82KT?Np;03(7A(2m9Y4CqZGH1;fgjxuzh0nWi7rY4 z7lD&K+h0r0H3g?m&k$b$9h%vSt!+K-#IZf1mzwf5LHv-LHUDZUq(Ut_w0AR{33u+y zDfyl7N|uwv+>CN>zSAm-Vvz6;uNbbeOJk!-X3kxFjazud8c|-izWI!VS&Umi(qu}v z+1s1+L)(Bq()h~Tw=-nvL2UDXExpYKKMELwih1% zqTBQuDzT=59O9WI-YEeLVi1<>1Fg?$*;5k8B!TH!=6JA~rp;XB7B9P5B2?T{>;?Oe zL_G@XozrHyr@#9*ZtsrQbq`^Cw06#LgZ*bzX-wLL;(4jLO6`SI5sRNz3D_3fNB@9X zXY|kB{|o=O!^XVyuZ_v!kDNws-l3_t?e_Yr_#3ZZ9*hdQz0Sq z;})}2yW!yhUswpS^F-%+{uSCOU+@GU2s1&|i+pH@+rR6rq&*~6oQ)0;?G066YwBJ5 zwAs@8fDTR1Ch@ach+;)yUu-h-6gj1dia}DJwbm=xS+E`W4ia7y+xm-nhc4_`7n)!x z_3alQEZSNuQ(4TLr%5*4gkaGNz%;jsjzsh6iDP?{04GtJ@*6vGdJ!0uN~mY_OD(Vx zvcnX?q5vsIpoYG?D$%9@6=cEzV1Y(O19LrngHXlBMtlWqFmZMv5ERWSn&*`|g>eIP z^#xxcGpC_`rTT*Cc>p}JH#F%FNnKJf(>pB&pm#_<{LIP2x-WomDmH)5&^zA zyn+7Hs^T!85rGMQ*4WspY%O!B>ZN8{E8!ff0s?0vL$0Z<-8B_jHAk_o7IBk;t8yc5 zXyBx)hMHQ3;$ywdVr*#8XpOqMy5v8UQ6G@%7>*4a(rz*4bOw>2(yUAh+ z5C+iY={kTTj-gQyNi%z#TF8S6Tf5vtKsx0$3G4)?d>+muvq2|tNI`(af_YnCRv`~` zM61Fi)UwdEqH_x5pKv`?q%DXFRINgDn~brluwL{;6-7@E1ndD4H7-LV8>~-JfH8o> zbH2I=NE{lL&<$X6bPPIihih){aW!=XRfY~9*r~aA2rnszpE`fe!GfE>F_W-La28$)mcQR(i6u_cVKu|WBbv0|D>>1MN1l{hd5`@IEfG+XUhC=20nAyFfMc{!{MYzIPJqwk% zY;J?5K2rm`dEWRhdgMhz^nYXzeo1SxnR5>O~c$9krk#C_5g|Q-3EfKUKC{`bC$SNu^>i6Cx)u6Ce zc|Ua7+wT8OH*d)*xA~2yG=7A>-5{1zl<29XisW+<__OJ=7AxV_-*-Yb8T*3h5LDp0 zx_T1|JAObb24Fe&vK5LKSjQV*ea!9Nx?XK6w2Abe?Q>^N9Z5!WMUW=BgPA1Q1yD}U z7c3H^thw`3?z&q(t~m0cul&DK_O-t4^H0*m=aa1e5;3GDGA!X6Kp@W{v=K=Go^_+P z8U(N`scnAQ#)qXUcDcKdi6wsc9*%2ezd>ckmhai|x;uGvZ<5@f5G+zNtf|q6oaXj! zX-pt!Lji_Zl^Mz7QaFz)$KLK3OD~F(%I;s!L>M1ef`@)`gtADATxeJ~C8PZwdvgXX zR$@lArf221s@^T*3{N58F+e~jvw0TOZUXSINKl@ z?PoA1G)4PTow^@6VHO5J1}Llcr7u z)uXo7C4*O zn&qHstXgPUR-+pkRh9c}L9{BqzVE}A79)DpKE!lwS*Z zJD#k>3N`|U5>XRCt?CE#ssvCwlit=wNh_68CcYV$R!K& zHs1FE^8Bez5Wqqwrw^6BR-Sh%KVRmqO#v)sj}Wbr2rS0nFbO;++q&Le@LaHa8bUn_ zF$V14xJI22j4)486<+lR=j7RQ74XTva>6xK%D0q~64AD^J}P?S7=Hoq+y3@C*L!?_ zTE!Y46KiGp4G*|gH-ALn_l@Vju`9gm z%4_ZttrB6U%U8V5J@?o@h(*KDb@mTHy|ukZ;Pt8R{FOU>^6(VvUEXJewW0(^wVOSE zxm&XQRw=gArw9;Es{Z~VC3~)H?%ZN01IFg}SFHV@D5$4S9#VfGs-u~`kl%lm1a}_L zOLS@GLhUnrJ760?clSON3=eBP34)#nAR z8eakcCy-CCKYPJhV(f*i@c6T(NvKIHh6z8ro;ge1Jso(cmGfkjU#OitYQ z9uPRrzU*olH4Kv|hW^1zhInL10MHUQWb}-d!q4D^Fv|_2j>hd)iX!1)j_2@d*-C;BU6U~2=jP?M0TLaYVf>elrZS1 z0TTG1={u_Hqaw+7koy zMmTZ$D~-BiPD_AAv#yXYHU&bmJQB32Z_;=ZXruEMuX0Vzo$kn?ZEoQ73H38VVPW24 z{~7v>hTSN=iB-sCJL~~9!K($Z8kZ5k z;>f5Q9swv?Wl?>JqMD`(s0JkIRjPAM?K50sp;Nyj;`72S7QNC(FPF?SbVz9{Hp@s+5 zQ|y@%Mm}-Ed@cm1G>6JRUxGFOqh@p^$+R&0E7y;4DJzS9J!Tw79xQq~G)XJ^;OKj% z+5z>HYf!^%QAl6GqbRB@`puA3U2`iWS6Pg|A@9TN&~{#Fa%N1)B<%0Zc}q3!0ej4g ziUEQr#{i0h12!VVO8mJCnX0A8emn-Y3F9EK13q9)DiD@z;Mrgkx@IhJOP1X%f4Obr zvr5WJOv5fx|1oQE%^jaqYsjY89#^G{ATGH0AifbQ+l&dh=H`#cAH4L$m&7bsxa=k= z8ov6>*WKE?Kci6>fM}F`S?A9__&4$^B!?OM!puGtWI20)-pS+pG?$Yq9zE;~rAH`- z`@ZImPe}zBAHVvxPq?>Uen=|e$o3!D^_IpX%$T!OJ$Da%nX7$ld0{v8DH@ui#yu$KN)~r|fsr@VTqp_C}$^p0mY+icm%WlJq-<9yjgo&Pt zz@k;H_>UwM_m=yBPwSa;g}du#|Fhe@`6ajhnXjnzqOG$>_L>=%ORm1nt$*fU-Of$V zi)q9B%4=`=nA`T&4+N4?=st7iggeVUhyZoGO5^)*F>Q3P63KT(`&^Z}ni_Y*Z9nf; z-~J1#mOk>0|1atN3`w-afkY=ZHL&O@cVW(Ac)l@MlL;u*m0|1? z2_oVzDf1J5iFR%Rh#5PI2vcK=8$@M08MBstNeq$#TWii`%T>T3IjKa)Pr$1@ShR~j zpY@|eRw!r{fyIo#4Ju^>us&NFdIcxD@e!B|ipX4=kV}=6K&@Y}bnxU8#S@-=0F*3j zz*6X$U~qO#J*uCr3fPzlg)BO~g=8I7eJiwBwFg?Br;qVv7!DRL7sTeE?9S&nZyX|< zrnO_H959(z%RnJQVk)I|4Je*=$^rBq-IoT~A;77!K2Vg)$mSBr0HirjKq%FVpty=i z4nX|O$s@`bs+UruJ}f8#sGwF$_K4?o_yF_5&bX>-dLW0~$Z)?KVq?28RRtN30qxYP ziUBM}f7aLeks2+kOj3!IVyYLtpwXLtMqYM~tTk(-r{d^6xN)TYOe0lRB4Va(gv!8T zsP&uZ1tgvC13+hDP7)>Zqji$?uJ_wr%vAd-1&ftb z5p#DcNw}4)E?U5339%k!cd2L)>>oR_%fvwdim`pJF!31tM>rkZ{{bwSpU8j$GZ@}U zmdJ`Gp40vksQu=0?EOkk*4DeOo&|39f~(d0#qU_}tmFMVHpqXa;zOmD)rEt_{83|2 znzC1dMX~Fqr*P@DcWZF{-tBL=o$tJ0N`s#IhAkl>2pFUPXy=yo?v-c0qDmUA39_cS z{$pAbmMptXRXzIHp8WP->RyoaU3T=dQi^BMOoMS<`1PQIhkOr~lQ>zv2cl zRuG9nlxF6h;N4>#ZYD{jg1+canL*@wQM1WHCA$FJ6jt4(=08ms}0a!x&SUDM}UymaoYD*LzG z^DFMauD9L#XTB_vDN|z~b2r`d%j!2@|MZvLnUhDgU!e}KSo1-F_ZJ`kCxLv{J(XQp zE6Ooc6n17o^ZA9UG5F46EKJw**^Au0ANgI^J#&$Jqt3Gm6-y7VsQYp9jo-*?xAVGBt7Tz2JJ6(*=U zAKAA}aa#VBXK^ISe_3ps8;p&C(%RKCUzKors9~2G1Ld&C1IEZA)?qF$fKpQla=<4} zD!|ZT%|ey$>pkdB9Y6T)-l&WCZBwlXUW%km%7DxHSDry$4OJAWsVWJ@n<5vG1VBgz z0rbzwkRc?%0O+u=a4^swF?I^zMROaGEPrD|lgbEv*I`0bbU7Vd4NNErm=!|3>|dbJIDEjmr6jK-!c$p<6N%!?Ms}n6S;4>(V9~ z867lPZmyaBLn&$*Ws;wfVWoc~p)x=(92<4bEnT7rK#3h09MnC8hAMFzH*P(D8ksPv z%(19o@#bZ0M{TX^p0Q9=7BZBB1AW?Ti1t8sU5yWHd4FwfwZI>h#RkA)y;T$W z54vh&1C`1;*VZvjvlpo~^Eooe0*Z}I`mE+wLLZTxCqw6{xxUnAR1gmsJ;+Glq2DD_ zi91;jR9RVPyjWX+(@X$g>7t2)_V5`G_V3Wl!$C=d8|{>Hv5KO7kIvPo00QD&(-%k1UN_1(fuiIIQ!fPY55vj7WOD z=x0P7^`$5NMIt?-{`-Ey1S~4MTqOW?_395uxQ1u?+#`Q4JJ8iL&)xB%-xkQ5xA+>j zWy90%^%uUSd5t85p<0s2edmqG)!VuD&QGfn`Sf@HN=f6pKKwgw7kjtc=xB> z4e$F!*L!@Qd+00wk2`u`M>+~828+4xomyovfJNF>eD8Q_B)t8xbG6ZDrVoLDi&#=x zJEa4ZVEcbmz#^391y|gl`@o2rAd;20)HwN5jBG z6;ld#@o2Q{gB43|bX0{C)-npi^hp1xzT!eb#cbtEaIr~(IKPjIMrTZFyh@y14lLT2 zC9cf=R#Pkaahw@F9{?uFZua1cHve}}d`J6eKJQTKYj2Lr{qe11TkE=1*<~>t68c~IntRaJ8M+VPnJV~Lo zLyhxfxD1Fxc?HCtRh1UnXK;pq%eMAuu6^1(S2aE+XM@pWpy|Pc*%UlEnmKtF9Pcre-E+B&+WhRS~enF!rzj7W>XCNG}9s0h9pJXBiZ#%X>> z_Q{4Vhq;RJ>dFOY69l8GF8aBa%&AmWv*O@2u2Xxn?*T6Nieo2(%15Ahda;PAY8kOMsUoMCgn1&Q$mz%(pYYWPK67SJ8t+#BGAG4fImhW$0Bz zpawA;=%{1k)vms&Q|sPU)w+`>pbzeGr%oPqqn^HMRZsiQ@I9$vtJW9{t-nI6o+&DY z1gchTw-iPCl)UGU%tPK*Tmt*|E+4XV&M#|(6N9R<{h{eMU|VoXqA8+;!z~0sF+#%M!yoR z-94ANg-h4y@2~#gYZ^NdguX&(E@3SBM5E&(aJ6F1{chI0tE8&B?xDX`a0a-0|HuC~ z?Qxhl%(#1N{e$kBn|{_^v-ZR4<%e1d4H6r$=FVTzp!+Ak^XIbVANa)o>0W#8o2o`~ z&WN!*^}WAxSFXHMqGvBZ^ED}Xu2}macl_{fxA~1HTuW=WTfXLl?vbzmp@L41`PeuA zSjh>ic4PrY)+@xd8(T>v;#jxzcTzRo{Kk`Nb%`NMHiEGmUoI7(3N!=S73VC~OvP!l z7Q5G<|2Os3QGHbcI0lPhPv!Sz=I3Qo1nCt^iIXH`wVN^b3O#FDTLAS+zPoYPGjoaC zyXy`2+{1sTYhcKF=k&Rv#?M-Cm3#B$?`!@eEd)Go6w?uonM&1bq7=&HyCA;K?6-1U zM5f;V@!xmTXD)WHtoyoq@rf_GQQ9_=N>~0F=g+)c2prBVuHbqft(J+D#gVY){PPks ziy79{RZ6Uf*vcxM#TB@)o{H~N>Gw{4&o13Nw3g;wskKbv0I+CrYxJFYd+TG9%r5b2 z$5gA?!!QAf@x_v=MsH)9+PRoI!0(cKS5h!6d!J;h#>T{qqu6n1?>m|vklm^8y?Z-> zC-Of2y?M^(J!f&EWm?j_Rn^FNQLVEf#$!_YG~iV&bx$%g^hDUAG?0=QS6fA8o6Ir+ z$z(xMpnnl`S5=87DuEbAToBq)_3};k005{iEOs^l;1Q<~h78*r9jJwNJ)z>FUM$U- zv^hJB4uSRo5GLD*Qz2`ILnlKYDwYTes0vwCCAurYH@#k>=^7_QFX)s61UP19E~0A6 zzmezWeb6(I69$X|w5SqsJSlh8H@W#sR_Pe0`;Mtcv3u4c(H-~gd_xMb1Pkhe^dl<( ziTqvarXDZ?8UcQ)E;bf4f3dpCXs3+=jx{E9Q(vcQB0#O7(4-0@f2Wd3FabDM(c51e zjvUG>6kYx#5QWA-l?otLBz=gUxhLx$CaNz#BO1i1lxh5i%P7|&k)ls=JR6&xIvt%(2*Q#p6*@r@~{8kaFf zMG=7;DvE$b>sJIM4y!+L*wsKgZSHdQg$`98=}S0vm?7IIrFaT`)vAgHM8nz^2oz1F z(M_AN$W5DhndI^5u|3^)RC^?3VYHUx_`fLBE>0|6Iv4ov9JyTB6Ch#f@UM6sT8^x^ zsW!`~@M8z^3AziaEM`OI*tQ1hHd%F?|FqeQ^d~^^=%F2|P$WV{KB*C}{V6>GZ^tud zlYm7(qcjt{cqm=6vN-WKQ&FUX*4j2L2@u)W2Y0>gjvv{R_U9&GaU$qY`Ber`Sd^Vl zsIpe&vU^Ypq}tEsExOiSdF|cqo!1^y{~y9-&CMNRjX))%PnV$}cQm{Q|3BR8>;BDc-teRpS?QyE{;_{>*WCDF zfy@JYHo28+J}6KM2;IH)WjAlpN_WjoA8`+V?GIgh*GyF_AOF^$iB@SOl!?HiJ&(A; z)H!XQyK>dtYT;0yA{5c7`hwW5N$J|@I&ZrB)1tN>-uI4s`g?!vjvd@?Gf~4_$5NH2 zvN1~q)`{??y&tKatv0``x5eIZG$JyG^qnFa#j8f8!7i6FF??B%lSDSJ=ftvg)#qp^A73ogIj zwRg;LM-FZiZM;ZGG6su&^i9!s_>jH5bB1DG3M!WDwvk@MtaXjest9I)m0wt7&{KggmIR)243@bn9>S_@Xsr3Ro^~oS zl2NU=Ck;(4a_IaVZ~+LUZw3B#NXh_0IZwoTpbYVP&>kz}2{@3LKvbg?c#YqiAe)gG2qw(1urH1d5EZRgCj58xq^8K0oL; znuin(77yWAh|5a1g7M62bf2k|axB&`_qsUXV+{}_)FgddW)K2>Fr25+m$*(|$($x% zg|vB-_8<(1nz&2?96g{6zsrxyV64W-uu)L~i&P2ei*0J1?y74G8moekP4DqTPJ%g} zx@tl>M)lxj^515RslG7F3%VZb6X6elLJ)W;2Nv_sWU5ZRa)CSushq=>&~1$A&^1Bb9iJ>ppHZnHVFW@(51J=ONZObW85ba?PZcFgDlbP5?bNerX`iMw4wVx?AN(qD1k_)~lcaw3-3_-B z`zW>eYW2e2L$BhD1@7f%=vDk@ON9HXX_=ckC77EBi>efBma~6mIrf~GM1>Z`Xb8b2 z!bM@^Lt>wc&+gp=;1w?5+}kX^Y;}vSyh-sL^lSu$(gl$NyFvS*bigF2N4wL&K%c6L z(p(s2{MM){{6WBy*ugqa?G^8qQYCpiwV3ABSlP6D53gT@t#vbnahU@^_{*WBDLM{xS&F^Ryak4%-GAV6nAGE^d= z;?&k7FjJ#!)L{Q<(LY0fqBaop!LebL=tajIcdDr2%n2F-7$u{HVw6eo8zq)1qVepl z2QC>yF+QfDy{d5OxHd-;hav%%iKnN(F-KV3%FI?hI#c`Chut5oR($clC>%NF$@M#^bC zM<~c-=GER8`d59Wk+mZ5$4C+D&e=SMJ2 z7J5WUA1{Av8#&F?R{&5hiZy$W93;DH{78}L-12L4qTnGLUPi}KTpQGvA0WUY#gE60>P+R%PP&(cPjEX$>n8678H)!B!Ftgg`6}4(xk8I11~? z?_CQH{oV3FuQFypKG@~Jrp1qt3cYfyY3w*_80zN1J@06i-{`2#&@KPE#9&ePFU>h; zPR2VK?#SFl*QiPdCG_y#&90`d&Mms~Mt8&eKIz)KW=p)~)gOFa*G$3|`%fza_FnyN zHFffHFkfJsASN>~a9V7XwvHKY<&7T}O&6d^Tf{3r_?kpf*536gw`=oDZtGjm3hZ&* zSJ!=0B3DUn*2jw{jX}3v4QTfht5B(shzcUm_}Z}Xsgwc6R=n!@kaa#6Nnfp zB#VoZ0cEME?=JYBd>zN{K%{A0B3SGZSZyR4unQ96i(gS?v8Wf9_l1!@HKvVm^29;i zFWL8K99)QrG%Ah6dIc|@7x69ZIBdh={hM9?8Afu2dz-IR`&NjbuvnymTUqg2E(uu7 ze|!AcBnl%#R#2n*p}m{k$Z+TtuusM`E9(pN)fVqKLr7ml_bLMxL%CWNp}Iz8O95ys zEXv=a%_+{cp~iqkD2mo&z~~3-O_WfHH?Rc%1ndmkh9(Ielu)0+wxc8G46r3aB@Lz+ z*fB!}kYFB03O#saT6wdS>jdUZfh`y;&It-?UoXbpjG5gelNYATnIH9>Q30mng?g#)u@f*2GZU#WQZe*Z zLj#HiB5QqBk>549b_iSoEcvWhz+)o{9FRFi^oHu9nv>-q0Mw=s%QN$KCv^@<@ECp* z=x6E5D;G2az%(4a*1j(|gd$LwQ%X&$BZ;s}aImS0YoOa@)+OUIkcZaz6YJj#4hgkD zp1TaFrx6BHrp;=C25f*7g9=b%&Ee3cN*YGC_`XH@6w{FzBL*Jze)~J%u+Tc)H8MYO zWX$#U9&*Qz?2~|#L~*2`YQ2t9VGZAZ_Ho=z8&FQV+1eDeHJ-62H?Gq?kgEoT5m<|@m@n1-$Spee`J4seQ zCZ)yJBRv_}vHC^{zVysmqU4WyyhnyrX#vPU&&)32a#hL-F0#y9;>u#_s-o^rV60h75XpWgW?H)GD_ZqJri+)K}VS!#v=`XFU5HNwVbiA=P0 z&5{~8V34l^Kw+Eu&-UuMcTSrt;S>BK)w1mypA)+Ph0Q(NUQrJupc2Q1qA323%AKhG zs3F$Ws-KcSHAueqkOELfVNrGDyXGyvR=?w!Q}M%JojP$qi7w6yZ2;y5&Rev~U4Q$} zyNAE}hw7)|dhjJs;Y))>+cT^gs#Nqy^8H)id`4`DL~T3G@K*RhZJj9&Xzp-p?)sEl zcI|!c$o|dl*@wR%`l;FlCQ}rx$WE3@T!zHrxTv`#0oacuoB3WUz*KtyuA5$cM4+9@ zBMClcEwi|lAn^$ri+9G7xtv*b;Rxyar7vHw*Gf(WN4UnP~O;ojU3muhG=jrHvqpWTs7!d-ht}?|@Xe42j2NgOCg2pA%L&h=C z9l6e70IC#N8`Wey*x#1~W$^V4*i<#MSwlL-40fPoXR3jLPG6%674r4iG3e^d*0a$?x$iBRy-h(6 zed79`vPQmY?d@`yn`Kq_Q3ViM=e{Q_h?z*GvC5KF*ubPMz%vo7C>hW5^moPwaL_4d z%)Z>sn733uhVvjfb?neC_2+P1nUNp$t#Pc5?3Lp$^6d8vH2{$fyFR?HL5BJ zpxeLaE?nuBUw^;m5<=~Vriq9N8TS_+`zH;vXOEkBjkQVu>;nS;|5Rx0)VK>;0GivT zyBV{WSVB+pjvLkYc&6{TDsmi`*Nu1ovgnKeNUOx+PlJ7CB$6>h%-=Ci3YJK1GXD{# zPF-z-l)VAFEp5}?rq>>IySBV!=PP=Dnjl5YV#W3MyY5*F-NRq`ukP$=8>3Z~jQlF~ zJZv;md&f+T0pT4eu_Cn}s@R6RL#4ZdedC`;cz#!1`+j%JeZQh}e)ggN>2_>-!2=o? zNaIQ}m+hjf$WE5#Q*mGM{ZwTUFG7Wy`^&Su^Mk*ozPleh_%~Y5051Fu@6of!^}qrK z;!`xV!PLPpcRHk+1!cM!ket(%Rw?_b1N{B#%wa89KamuB-nHPB6 zkd#6<165)QI{S9M>5d-QX4X$_VdR4<*dK`hS#%^NWD?#aDaI z-1HE}Ow17$UzlC)!~9r8s)#qSJt3YBw;^A%zQEh_6aVpd6)Y+s_B|muYXf0W z9#B0ky|tlDCUfe1KVa4Yd|BP7Qx?n+7zaRzqYFTm${hWS zhNs#(LIhNN;P7)lsKm8*%~6JiHRqgC~7==}% zOa{+-fI+Wg3V@p1yKUy8<}?DfI{mQuvjzys?ABSvzYeNu4XUH2m?{-jsi6XN#?`NA zLOHdrn$LR4YvZ4r08Z!^FlwXq2oj)Df!0V0i^2VxDbZ&V)8OJQ?kl&UZx-rY60{|; zWRj{#9Fazwc;&6cIYl$IOwBb=NPYaKK$z$0$EJ9&s8grfSPvz4JQ<4-3|mrNkWn4A zIf_ZIs(n@nrhs;BCW9WfCbjp$G? zX?>J{QC?6E0SRPM>1RSI7fN)Xg}=AJVllk`(YEj&NQFwe@p_7SW5Yh45?BmXl*F?J zh?`5Ac=|I82C7sr5l;6WRUa7?r5I3!>UgQ3Sd{=z#|z4hNpQ+Jcu}Yz++_3v8_&UU zVM$g;{J>&3POv}8b?2Ukd65__re~1gkMVI;7O%ek18(2;H{9&YmW#4U zpV13Xd@%uDneX)dV0P_d4okeQ~X)iw0Z9E!L4p|Xi)LS(rfN?D^`EN zt^dK-)N9%~eZCkxTsMhwEBqK0TdxTcO&6B#n%DvtfknTl*%yFYs*21GeRKWy-80|& zyy-khC@8j9fz^_yr52xgX>c0d1Fth-evr18xLRgOF6@g9mmkz~9#?|Z1Ix0s`%8Hj zFOHWBF;3Tv%iO$0*Xa6oyz@dbjzVBj?J;$J$&{jer%6o{{i}0x7A)7S<a~V8Z_KTqzAn`rc=y0!-hbfW z0WCiJJ5d(MG7;Xmg?(M3kz}&%h!YIKhn#d$MmJFd3ZAK$?UA2G2>vfpdk5 zL*|7AN|goh$;?DGghMZ_skNDq9waD`6aBTp)mGPv!UrJK$dEedur|1zO@-42Xd+%? z^XU-XLBQseDp9s!#zh(BxCk?7#D+vCF#H~bAw=WnG%~{mdZ{X?9$@9U_$bu!ehtx1 zL`;0onZG9lcAN`;QYqwqNt~t@iS;%&HZo}Q6bV9VtBrQ5Q5#luRKFv@u?9Mu0YIBO z$!7qRHNNu8y%{ofShCcrEaL3j)Ju_Y-F?-zbhb9<5<*}sT5yd35P)0CT-n-WreYa_ za5;vNArrcYoJT?-^P@k^g4zPLfXIYsl=*g5Zj^q~QJcRR=*CH)A2MfthG78nri5xa zIy*SY0;>>MHd8HyNfnWw(`QIUunOvPTaTz3jK!co5n4(A>6317a6pt((N;s>q^i4s zM;qfow!dfA<;qGQKfFu#OBHzr?Ix=+Ynn3qxF`q;m7e%B=WpKAs+*5@{9z}v1DDE} zUhLxr$H=1(qjV&8T{vgm3-8IopP3$WzdRWjF6n_N=*heGu<{E%xuY@X8sIp>jsftp{Y;)y1D?ypix|oji8HQ|qx&MwPYX5_ZoN!udBg z7!bE`=~^ka@*UgWUgu68-U3uwo7@TH?CNlIxnS zi1?gmO-$$jF6CXkIG#t(qN+-L#3VofcYC(KYOy2FL@~{%=*+a%5LX6Wi}VcA>tx+G zG_{Gr(RcEY6tgpxK`&6G@od#rY~VA*x|-n&3vql@%B!Vd3hvUPTV6>@7hTwqHrve#9 zH;_4DzL6Q7S{sYOIEH%0S`@SyPY|3_&7_*g46tc)m0hPAg!0z80UYJH)IE`VCvd{C zvWW?bpav1#v(fln5WC^dSwNNwkWlpuRaC23g-o{L6ZHsb1cw1m6S@I-Lr*U>f04fLNB-IDW9XsCR)rd}c{ ze)ZS_NJ@-3z>&`|dwL1)=Q$GqaU3XBX*N2o+8DT#=hBxzBWA1%^xkYdZk1VUcnxdJ z0%0mJ#=)=G=dGgcv&}jm>oH50ya&*}a?G`x6N*MmC)Ct5>q)3&qDn>?4PX(ebb4e_ zJmngxe4}_uMS$!qmBb*1!{;~=jzQ%XBMjvfMKpp=o156{TuxMAs_riz%;kZ_R83EO zyeQ{?fyB?Lp2bCYf0=y!9^hAYGF){VE99UFvucVmSrHNAmo?4v&i(!taB{9PJC&?1uW2J1h zdTxhQjSrwPRF4Qo81>RUbCH|Bc$KO#!HAsdJ?IYZep`FQdfu`rq=}#K#HcbPgVLms z0jI>rg}>*YVf3XFRYNd4?0?i;ue?w)xKylY_b5CW>We#!}KEQ?i6Y`eDCnXslqCUlwho#!e_z2bx4KuJ{kq$}={Yxj=0fcWD(A4FlC@asdlTQ6!sV&j`KegM^e%e~?kl!b zfbaRa-*dC)U*+C@l$0y-GQBNyJLs9Cv@Bp&o;MDb8YQCVkl`g zVu-^$11j+`<4(%PuoPh3k&sJb%V_M0?Li+5NqOIxc}-1iia}_hlCDT}8%d6IOrIk= zbZGAuH#|r@oMqj->$ma8{0raJ%3^HV({S8O>G>F>;@~q1MJ54@+8%NywW=nn%E{=C zQ4_Wi@4vZI?}0AMcOfqgWz#BkBXW!YDF#y$oTC&-|JT0luM5zbNR0(Mp*fhL#DL1W z+D7#kini)Atz^PE7aH-89p0tVdTm2N;6~I;s93&IMQ$A%OFwP)5l=1ucR{9xwt7>G3Qyw<)Nl3d%d7zDi6%<2K0X z2XPzUjmfPddN3%CgVD@lUK)Am(W^fYnx zIf|7)g&h^(K~=CUK(5vx^0^DIk@_h?-(de4w{PbLck;vm1=8uO(u#LwCCG9W#N_Aa z3l_0eHPvp(vfJEMtL~OcE%WqVUH1(QRnLH-7%X}X0lpswNPG8OH*?+<67@NLc&93e ziWs-?km)-D8Pa8oJA_ulcL-*)pBUn4=DXCM4qRiQhJJowg32^O=B+ptR$(lcxOKeYzp07`& zUVr;1+}gW7aF2cSPc*(E+vi)!zKf&E$)I9B0u6RGO{z=Srmm?v%0NuywJ|64ro}<{JulKMLbb<9I z%k4D}uoKu@ssOP-PQThPlc;Pbz9a1GOfccSxNjpO$;k8s*6@iVd(A%k_>_L@t{L;? zW6(V@+x=6pcq!M;B?pVypgqmC#kHFdh?d&U<*J3HvP+Xy7GopHLIkv_%A!#OMhz9^ zX?#oyr(Hesv;g7y6EO38c--{rkiDf6Nq`S6hxZw^@q{~kV5_QV90%ZlfhLQ}cj8Df zI8qo@HD^@x)NxNC1vD8bgyuPD1MKSy0;(3|17>S=-ZeUE0;(>Tn0)V_Y{!^ zfij;P4B4$@ZFD$QAMM=JUntv;x%OR5fI|oTqg!HNJd*Q9ss;u z2fsIUwMK~Xh?_ePyUIDuTwuu64+AKzgr54`bcU;GVI!iC)j(47O zySKig09=ffWF1fR2vX~jO&Hmp;knSGz2vH!C1S*AkNrDdPugCRHB-X?o97iL2#1NOT%l+$ld2;-BQcgrGbm zH|6^*-U%W&?cKBWSy*xwFClI$pv?n0#gY^c_>b1D6Oara@sG9>xGM z&`{G;E}i*F&9iO5@R|}>v=x?Q)Rg&b>(Qa8#)$^%n|DRCtgV-fIEI!Lh;e|rLhl+5 zk3btGPpXUrayIO}OTi5pKC*a#5x^9}I5_4Y_YOcstR*PY>C`yB=%NHf9J^UyRf06W zw~zh|0t3t7j=Hl9P(F87??vTxsQ--XKWoAxNx&Gb2cr;JRV&(#={w3e&2ZmhSEW!2 z8Yz_5aXVic?0b*zODeH|$pL1sK{xV!0IEn*xvR#})w=03776^G={@Skt1a_CI&6KB zW_RuBhoSbtvE=Ej&*4cA5ngi#|yh{S36UX){FiQJovxfAw!aO*vXbO!Y+-g^n`Zb? zmEt8eYvz#+_FH8`>ZapvEK#BH5+b&jVo+5XU@Wm#qAFpaZY4IWXkYu!C!fir?(FeTP+jYuzQEml-+xe5 zknH^%FMLOH4{hvG8m?;9M7D@z9DZrmyk+Y9!EeD6oHc3Up-{&cS#Sp*HMzUb>YIpkwKc{sL-Iw{6 zc6@8Iu!?{2+9+LF%q2f3s50Anuow4~8Hzk7m_!JPyzha}xjoxo*ZGj_R;BpJ9-m+= zW&g_G;o@^WUptqF^XYdcSi$=YeAlX*KH^s0{Ig0rt$XMTZrjFZwN|ZnF1!LIy_79Z zzb`%GGP|f0SoG%-0~+ETfFiM>#QsL8(i+>yZ_?<=Si&x!aG3n=P5zFF_QQqzjyr}e zoOk(ZwG|yXuvN2WLwpkA3@D|EKsjO-$=0+?zhs#o$2EU@4o`TP&>4qnLJpXjssJ^RDE!b<`c%Q?4Dxyjs` zNfu7L;U>!ym8~p>1**{rCdi`T9;)U!0}Ie4t7@R67F>NDgWGErgue& zkB!3TOB8{_TIzEuIoDU z-JNqcLL=v#69Iw&%p#R#Te6kxvQ_qY-kbSTUZ|S#dsVNd-qg&qU1Q6#EL$2`wnT{( zGr<6W$T{Z>bfeMe{Ob3uz0cX_+;eZ=20)4&t8I!P`i67%*?X<^t@W*MncAnlG95%- z0usYUDhG5UlAs+hJuaR8z_^`9N$c$p(FTBIs!Ey}NqLP1s5 z`m&f!h9YeiC}s_U0ccZMl^BhGMlub)FC#G%R5i8s1X6(#;x~oH%QQ>vjy=eAKn;Pm z(bsp|kHkn-PA&Q2$777rB;Mu4Dw*p0KBoT^s#nw5Q6MyGnuXCkYmd z0?=~bUvkX}r89*`@%@&qG){1RO0LK6y)bh#>=AQ{<52Vp0?rbaM*=AA{9~J__D`F& zSb-We#_N|)tJ*C}eFCV!dj4GMqQ*2l+d$?rM<%$ny-QUi&IbuL0xUoW_AoFs020jC zqiO(if@)J>CnU60zt92DrR(l(RZPkDB4v7QNVJGmiJz5# z#l*l=8437ZRKiq7_?p+K=vi&5tVZw#Ks{?0UQ}2=p{159>AX zo#Yb#$;%fB&@q?{2shv#`*;|bf^VAprom;r#F?ZtdcK6QD|C_sg>!K16A=zN< z0u`!w(Tz=vsbK2Y_>QU57pn3@FCtXaN1y*g0Y<8vBne6Wu_yZPniy4b>xn%Ze|2+S z>%M~VN18lV5i?g)(<`!&jkSX}+`I#=mA9{)sFcmE&nt4foA)qGz*9xodMSMy;H_?nL&Eao%Z z$zvWj=i@`7G_#roi>WKkuR&Q*svzG+MT9<Ds&nR;+6hTS4C=``x3ZmY*tlF^hz?& z9xSH)d%?4q1y6f~vcVAF1E}qqI!o7%N}@)Iv~}7n%7o8u!EFFf078H^8D{z&rTmJN zvY+vlsX&AZV?qtHYf5wGAwaMNC_Iwhkg*l%u_SPz50rJl(Tbi{5ZH&&D)!0NuVSBJ zSu^#3P;F!kOmn;bY;?~-^-LMR-a9e@aRN5>pY^H+;GNJsbOUBg1A#07|8ZqVH#w%+ zL{z|O@+PCtUS()C{bl#=-idk|eF8z3VqlT=L&>jm@+^HHpqc)yuph!bR|Jby7@tbH z>`&6jKNwg{`=>(hTfEyUg2kvhT(n#z08WpVz2g-_i{4a4z-xygUH$m}11L=#k*B&& znmWf#ov}bcJOMoOwFXfDmW|-t*dS$q2H->$fA(Rm&9Ft{9y>-K757kEN3WtOnbO0h zlN+k(VQ#2?Z-c-A70~Gk@bC5YC@{2s8OFfGL59yx8&x9N=Vr^jqH3^*p0=%ux>SF? zlJMB5>@P~!oO7zEA%$kp!DD#2n1*2{v$(j667IYe7;Zq=xa%};+*_Wty-odOVy z7`Sk1uiu`fr!O!TP&>tLkkq?=^|ZU!*Q=2mi&s9T_2=0`Uqn4K6R;$9C}lmwy@h7y z>l7#wOp*++`HG?6uTB-+4UhefUbE}%AE}o*lMKjzN5$oj!J;K3sanztiC;bV(JR`^ z;n~}`i1-6bJx1(H)8l7qkoYLped}}IRq*=CPyTOr_UMi@IpI~?4g7j5KF)ca7(}rB zPDK-XAFU_E74w#Ea!MPbiDjj#%V-bMk(`d`Wm#)vWEqS*QE?lyXVHYCg+suSL7I7pwI})qMKI zUQ;t~$)*Qe>2WgHm3jlxB}hDbWSc$RsvH1FY)m$Y;ASl2=2tkV001BWNkl;5Z!jAC4uKgPB;P0_hSO{7oGb%& z?ea-&?nXpge9t1lh%BFG3^p|AfN=N-^f@3HKn%alnyF95VQ}FHyZ}Zyz;do({#5RH z!#q+|bjXxT`5yu~fQ`{@5qO!N7~O>0q5etKO&hg#sI@{D1vC#2(!gv^D#%J(fZ!y? z)6q4}H8eM?aw_mt&)mfppGm@Ldeu+`!1iZeM^8y>TZaNqsU<3CW$^PgZ&GeJ^eL_s80wPwvg1(B!_UN?7CdRCl+B*_-_Wiv(Rf zJDgU4vb3b4>*Ep@j%^IiUr!eqbH*ZSf$U1ej}=b_wMxx ztoPo!qM%#-6o6Y4QWGkhJ!8IsUMr`2x5of|sAlCViLsNNn2Gsxyt-Pjm>TxT zKoe-y*1Fb?Nv^GZs@9l*+D8@TU3@+P5!<8~{73EpJ4CVthJwlar;LDPB`4xAGT-AJ zPOd({{zb5$d)6X{6#wlT=iQYH$F0I_9!m4+5G!Ct?8UPO-KDb!ZM=<_I49XAY9WcD zmUdrwvN>CtS}Csg^l^C6Fsq^DNy+v1V#=25iFSUGc`dxCY60m5aW<+Q8pc4B$aPO`g80eFjG3^Q1^5B&1EKI~Xmj{dTJi%Ay*fgo_ zij0B(W0Dq2e3$jAEnfA6+xq+;sY-WX$1hX?WHiM75B}9%IJ4hx&8%zJ(vFSF=K$;p z;CgReRv#gPKg-uYuYu>s54bCw8UT-E1DjRVyYPD?vtVlx%M9J?cXxWON{Ed_6A30pY>}i$tB%?B zl2VUU87$iDR@#bcRX|X@;QeT2N@cdZG5#vw-}*kNhs7?jrt_C?Q4;;yrIYT$>3vDO zM=SxDB#tD}GuVGuD#wP~Qt=yUQ`FSEp%GIvHU<19YeN_uut+{q+hsp6`xRwQ&Qu zwx+-X#1A>Msm!<+{iM#w`^O4kG2^gnXi_(2QoyAssRR9fLsG?SRF(vzONNqvClxl0 zMrhV(3IZQ0Gzd9pV0^7}x2|6lki<{}G;JPXql92I3Zu4O@1aDG5#sMOYq7RoN|*pN z0=QaND}ca3!w|};DtT_SLW>!rbxDFqKg`(A|HHtFGT~*OF$n6z^bNydP8oq50UriH zGtrp6NZ$zxh>FQD8i?^YRnoY3dLnoqL*_9e$y0#VMg*qk?y6G$m)KP)zBbEBkco>UnqL+8N8{Hd@7;F+C_gE?NDQ0tu*tRG!pd zD}`VigJaZcDj3XA<-fh)4dZ~?yJX+6sjY2Y`Zoy{L=d=d?5B;>sh15PAxGsO@Ty+s z;Q?i{p}Ip$(-@m%!P9X+I=>z)hTmIN(dcRcumxcp&I{)esx5XFyKW4Vv~N0nuH{fm zbR`u6m6(E6K7h#6<-9TR8D@aMyd{rl{v5rA$M(J9w!iw{Ww+OD{fb6rFa{)(WbnRJ z$-TNdH)Z-l_1HsE931R(%`IJS#ro%D(~j(Y-CetQ(kigNzd77>8d4`-yv&yOV>*Je zw(q&co^h^dQ`qqM?<%pj``sVQ{@5ssKzFtDR^qR#smys=KcYO#*F7uc-lKcpas&5z zJ;Nhhb9(LNpJp72ru~`t>&HL$CvN$=XWW?+AE}?t;)c5d5urK~S6aul2@!;<{8~@` zg$~%<=BCeD;;z$Y+IQP6T)x#k@#6Q~u6O=XB0KaO3nnv+-3u zNEjOLo;dYrNgnLRiVZJF(U+e~=MK8CxSh|cR|4x-Mwv+MDkGP<%|!H z4!XWu*Tk^txp7h8k#n6WB9~d@25AjGojOVjLQbmcx z`Z_l{G%OoTucG>GePJZ_HKB@J_&7ghV6hq-Fy3oyk5xW@pGmNo%^XF`5Cl1L*@bG7 zw^_p;vVB3O*B{o59J_x_xu6MpD6_U|Ym~hnWGslVibexHexl_nB$s>4nxTn6R-LrW|L( zZd+uC7)>I<7r;&s#3(pT7DoAANX>mT5bggq`;Jg0pmEw8F%9ijb`odr2Uq+35&~B~ zgg!^^m4pF-B^5;}(n76^o{1Iy(qKf!P2)5geMN;?m4k9PW*|f5A_|NWoERqojK0U( zkzAk`WpejyIV>qvUa=wRq1irAll2_*(YD^~YkHEnj|*oH=-DZl@YT<8tFz--v`_Kx z%YjAxeR$^nYzerj$BJ2%)1=NPdQD%C`uNCtYlMLAcLJ5Calj(`WcI>!3g|DK-k*-C zh_114iHm~iN)FSX1@GpaeW(AFE9RRKXQxVfoSV_xWmp*qg_SCXpEz@}_aV@opp9UFnI zAOIwZMX$FKSxJwg_4FpOoA0kyk}Rr3hJ8+gh!+#=z~;b?@pmKO1@-N-_6T97vxhvd;$A8D|-|=&I z?!+GJPxSkSKO1WRg~CQv2e7MBEp6*k{~(p)v&VP3Gsk!N7KLo0DO6D6tbX;-A-!9I zMyk(SpZi1gjP82pCnh=+&2Y_B4oa$Er8LSweFZ$M-0-|U>(H)O)F;J$C=S`nUwtO{ z#}?F}{9Wf(Zu*?A8$W|W=ZORFDv^v&AEM_1wG${nRQyG3_*4mHDK=Olp1k#yH7it*@h^zi)o(TdHuw z>^gmPr`x^#CrL|<&OnlUz$e>WZ0?^uOgu(R)z;pnN~^KN(4;V3ir(8-#R!3=kSLS; zSixczABsl_cMDZ$wQ01GSg0!xM|(9n*C}N+7j#74p**Ba?96Y zyVlI?hmYr2A8%8jKoc*Kc$QAbotxRDeiTC`_RhzirK=FBVyjKeMweluNGjgGeo1E- z|0`_?fMXpR9idk>0_sI9oZr-%R{Y*rG{cDqw3X2ZzSnyP8jj;^gIXha?tq11c&deCSmpqprRYIUMuRoVErB7=SyjV&f1G@CdgrXurw*RxnkJPI_5od~H93B}| zZz9ywdm31q1Dt+FnVj?Jm}_q9l=uMv`O5jD%GiZUYNF_tJ18Y<_^C9!6T7G)(3sHP z{3shhH8Y$hch6T+fKfSjZe6xHhXegKG~BBmJ`Av!oDq8Gnp*vc0;BSz&Nb~3E4kwd zfJLLod4Y@>3k4EXQM`UZ^gya7(2dC0^SX1V_PVpjb}HCn;5&+&7tb6pA(|o(6e#Bj zyz#rtXP&L%XlH}7M}H%KCg|gAA(Rt(W7w-ov;cN=291Ko^ASaUa6puG{xKVrOH(E^ zDWjzZz+|FeMr%?9ZDdsE(-d2w#MehkhkoX&|Ag$?7grQAJ$^a*Y3d5gRU-lzvMbjA zdKFxr%i}Nnv0Jiwn*y|VfAv@H)R7NlFQG?neEfGc*q)hmpeMoLBTl=)spbziz@9~|LUeroA360@GtJe zH-D&Vv?V)zH6<^gW0|N7d!%T+#siD-n%GFM`8LXCpifoQC99tl9Tt`hzUK0|gQgrB z2hWAo+3Yu`Y0mOAzv{x){3*!>$8n{ac-izjlXq{n8jz9;C>Z zd0Kg(l#8{4XdPq8L{TLH1skm0>{#n0wFW_*!OyENy6={NBX&c~slomvsh{@2*<<6{ zut{hgpz}a7DO8XXrdcvzKL2#91>?V2PfM(~VA&QiTF`L74kXDNUnLCtm>7`csm_<; zno$I@p~)C}fW`WzR@p@8tJW8MKfAIz z%k^=*sywU2hl9D4;du5T?^CLM{Y3BWV+M-_4>3W!X*JL;I_D57+)4HbMwI~t_f}a- z&2;&V#H$EKFfh;@=*KZCmG#yH-~l+m`I21+Tyj7Fi+~5dN)7aGOxZC4dggW!bX+-q zSQIWYx^WO$C7d6?Q7fj$kp_BD zQpMY+5;xGNLu_=?P)$o!OB0ZjJj3kY#MMPAU-Ua+c&WN^{}?Kh-%r6}sTofH#%L*1 zjjD@SjS)CAM#Qq})-OY~mTEEv4!Q&VoWt~ZdaxMwm#v}a+52i!XtLJ2hb`-?wm1|M z;_$mK@b(*;lnAh@uz_(4R)g$zLEz}sNZD7cJ7ZjUzN{6Wh0-jUbCL^2^R;~*J~Qd> ztf{pgr8&#BUoW3KqUxAQ;M@I`%X$80UD!lTS#_^3o8JXM)i-FZP#J7#?@~Vu%EkaC zRj?TMz}SV7Y<-o^s!U}ux$^w)$9sLrp@^=dD6^=3-8%IncTSz@rp;WUjQQ0|C$)c8 zZ~lUm9-)VFHlVWY`|#(gV30_{PEw6xsJi+Um25I)Q4r^+)%GGAQAd2=bxTD`davI>@N04L18mA)>hjTPWJ0SENVsfA&1z|C5)M&kw!?0DIoJMobRC@I*48G#+aMyeH}uEEV&xK@3R z%;`I}|ILJ2U77^Q+R_+QWLBhXWdsq@O}QMbOsK?G`NGq6#Yg&et!U^rk6POzjD|w58wbXBA`no+cE3`Q%aR8N`1Y&)C((7pP zUX?z0yv_Ov{C>QIRnbnV=Kjjs<%e`nA1hd_bc4Z(qfAM_0*xZ8#900g^Pih6k~V9W z5>Pha)dn4N9g}7n7haM6j@#%3@_s!miT3!bbE({vZ^7f4jQep)>nlUqVR6d5_3y~dWG(w9V9K5INoHlEz8yvXfu3bD4 znhP_1Qh`oshB-H4Bbr}X?uiw;=P-vz^xY}47u*Zd`ec%n&8u-*uP_HO{d{|N0jm*c z5kFdLS@BS8~S)`CgZCU@;BTN&_~dS97lE-J{aQSqF?G)jl{t#mYvx zFdHz{sf~AIm5yox6~K!2y($oCh9d;t-rWm`p)NRO`dnAv(Bf`hJuNYtj;?OEcI#J+ za@)|PezsFbcSr!rdZjG@P&JOx6TYX-L~clWzz8rg8iK6=9JRN+4KfNENiHuo;?hZb5=d_ zdH2}!e<)VUp6&m`?cV-B1g`nvx)F5Q_~h>iEJ7tsS`aiYs$PS(x!+4?4#`)MJX*f? z8Lv9|u0~vxB#!*`rckfUuB>7|CT`4)xu%v5fiD0$J&VJE3NL?U{}c92iBMg*gpkCm zt#`BLu5c?hJg>g(BfEbsu`dJpv8Y{$8ma?}JiP|STh-ONrK`6|X%wUR&dY!4j_-fl z*agYskCW3`yJ~yDPU6JCV$NpyXEA5tdf9LiSnD~j)8;90K>R`+bNvbx$Gbj=uS|da zq(bccoyRd5an#BUpL0vrJS8^6<@1M?2->s#pWV5WdxbYj;ynSjG-*)c%Oa*(02;>d zX%%Rs^4JM&wPT7Zkk|tyxkks-0(1N3WhK#x#jL_MCZ-sQ&LnwbdT+^7{mg+yr{3q8 z^HwR|HKqa;yKEAf7`3%yvY1hX5^?F=5rIyebaQiu0Hy>*2KxmN!-iMS!yq%q?wI=M&|q>+%B1;z4%EN^ zdsM~kvQ?xGFqVWU@)0KputRsPs~7)$jT_Vu{YVP=|9EogRAXD$*5Vz_Sz zvSP6n1q%Y=Vdn;OZ&U+i=m{D#?yxjlRL)3H739M;dSam8GI*X6n3|WYs|^`{0#DWz zP=)a_aSI=scmuXBv4!f<6z@kKSPvDK>t zTAwAAP@b>$E`lhkti-kL{Ep6MRugoo1_}RKUnvyrw0pMpD6i|ieN8kG^#~-xfNfn2 z#9NpprCH5HTIjlGF4F7iJ0k!O&$42JctYB$a2l(ic~^6mAN)1tLa@{=rQu;Iy^4Kf z;~r*e-w`0(ynaET10WOtLjdqa-&Rf5&p)Kn+nq>n!MI>E4O;E)Q?STy8tT~-^Hq`H z+@g4SF3Tg{lwQsn%Se1R$9DZ5k) zc)$9Ro9R6nu$hWpnmr_4_ap8Uu%{rf;X)a%0V>|aNE*0S#xpaLwvs@ z=Ng4i>~WHi^i(nuMFuh(yify!w%heO#B(%CWAL6Ts-chCmb{XqF5MBKXSn2HmjjDA z8e3vreQz~({qfKJv70t~iH6v3|K(q~o7c}LJzUtJS@Tx8P20XMu*etJc=eN?iEkgT}IZJijNa*v|-8Jo@anC06v&yFd19h`g$K z@kt9$BiOM?Q|GFe5Sx2&*DpnV?G56n*9U18FaW}4>b$vZIWV84kx)KSC#~g6l zCl>x3YiJZE3(^Ee>DhbOPbRKsrQb$Up0O*e0XF~KiQOs9HhGziM`8q<%@1c9fYaL0 z7Qnw#MQTfu5qFTtyLt7T?6}sd4BMsj?L0u>6&!!BPG-k+P#dz_pBs zP_ImO8D2KrhJ8gmQtT+h>dD+R<2qBhxN5t?+cRTQ?2Q`txE?401SB3tj4+q z^#B592&Tw%b5P0Vh(3wP%E+Jr4aw0P?Nk8R3%3y18gQ`S2GD5&CC)W8x47B!*GPbe zxmi+~GB4x#_y#DTF`H#TV-2DUWc)CXX#;vt)k?#I@EPh+X`iIvl;A$C5Fk?H@7J%LmSA*5;zL|7qAszQ zCvYJvOQx3R%hHK!+sQ##!~;yqE|bg|!HuV0}$K%U4sYN`oZGubg&QFP`w~t3JD@H)S)2@$*Tp zuUzm`MJ1tX`|*G;EEj^s+3VQglI;|=siw{~w@;F)APIxs+gIGR%cr#e*;hrlEEJOS zmt3`*8W-%1vltcLUm9M9jC_q7b=Z?8*F9r_z+!D}gJ^U&uAH)7Kd~{4H9$gzO277p zrE1NwF^MTJ`t`fiG?*b3FJ|UATfuq33gnfWMU5V*;u2|VfCAdc_8K0MkNWc_p0{$S+86( zv%Uzl0Whdch6<$r)(Q_M0vbWUt=y|Cg2hyYIncN8A+r~(bx(Z$Pu=W!tK6mYhu!vH z{YVppf+N)G~Jd3{twizm@fWFhmcDY+u&-xpQ zlKp-rF0mrxa1epijA=h|1KS-l`e59_T%h>DtX8Mijg;|~P_nFqRsteRS1SA9%q(S9 z@;|96d6kP@@ntb=AMgAn^_hq9#Si!yH^}=`001BWNklK6d-bF!nRi8Z` zwPxH8NkgzaQKa~-`QNK@lD3S7shcB^4_A6Pb%hfPx_eG={!BDf{*Js^=!@rSJh)$Y_TqVFj?Y zbplD;A2dV@qzu$_O`f5u=8a3I)W9A36a}EQ#76(J;if}T-<6GY;Ffvo~)QS zz-RcZj;Ruo>1@$`lUW+PXR~tR9-XB6mvS==Xlqsu{e4!!3Ik}ZIzrr-huMjqQ*5gEAu~j>Rd_L-|4yGZd^UBz9I~?AYRm$ z8w_oCZDzjCB#l%AT6oAs)yi25*1GGLj=TQ;J4$Gg zNV|OTm=ss%E#9DY$Bryn{e*zqzW4t%5mAVhJ>{XGf{j{x06`{+E(EUV2`70)0aSyb zYw15XihmF-OX!)t2Zz8=q8CaM3@EurbxPwr{P>>ofYIM)4H%tods+V-ZR^io3EY5#2O%hVC;FTnrd&R{-8y+org!FZ`kIY0rD*z+#qMs6FSY zrQ95La?y&d0v6{^?Qtg$z2_CJEuN@k!?FQbAv6=)36uqPC zLPERnY)=#{Ml=)eW1x>y{b66sU$(^^+4F0E2D)VDH5b!YiF%kw>JM%05O{?BMC*@YpOFzU#8AE`!H#c6?2w*E+GseR zfrg$D=ZO|LySt0_(!=(`1z>e-Ov%If%N|h-dg9P~x*wKEcC*pMYj|f6pyYWFHxaig z=|&vq$Fl?m8|#EU#+IU?5n|866Od~gE82raD^dDc4|}~H)@k^k=W}Z2F5WmMnqxAD z&W|>z_8uPyEZSVIz&)-E7UNn$dU0hl>KQ{)pqS)o5I9hR4Gx3o1qgqjzT{yQ_6f)HUrJlU2-CyYjz7Y^OsMLHb^y z1yb##`U7B8U>N4d6@W#)h6a8>0n+MJ6X{<;=}|vP>=B=s@hYFy8i7y#brS`PVO}TV zHM1A2R>qjBE41DqZW1cSb_}Zzt?tWBl>>_*ATEp_d=|E#vK!T?{ll;d3{^NX=hJ2_ zR^Kg|V=Ach1#0${r;!Row@;QJ1pAtOlQ`rAOl0@0HkIFt_H9u%S_jCg`b{mJs{TL^ z?L)lFGa^Xzpu$XG&UbM=06waM%=#l3v*fe?To2?^wuSwUU{3wq?Oh5yq3B7NqOmy@ zFso+_5(z*xLHRR*!r_n-Z&1##4J3OAa*Q^cs`+I&;xS)5*gXHd(l!WR0gGaOThAh} z7_F<9Jtuj`>^x@A(NF%~tAFc`?|;ks(R>*r5!)CY5vydw6Tj>Be)zBM!pS{))-f=q z1p&Gl!a-Lrov=U-`dE^D@;zW5(@_pdE|RbS{KsGX69bFef0|29h6F?z@-KU#rp8U5 zwbZTL_`GHsAKm+gB~N32RhS5i0a#o)$=)M?+g5g^IB|;L!rU{HdCeY=P$W~XmlPrf_B+4pE_IG>KPf8qtg1&@u;uxSz ze&IJ&StOoA*oJ=QE9Z{7vnN0D6lRqB5g(hbVh2Dn+4o){R@xH8Twz>{zfWF=&?EMT z^KA^3kYvmXQ>F1(xouV)^P9EIp7uDzxvx$8+c%B70yRt5JT<0D6pl1F<_QE!CErj% zUC|zBnvDiPQRyOB%k*w#f|F1c&zcLX7zv*E|Br+6tnsj#LK$;YTj$z4rih}%H%Tqf z_q334rpJxgPI!^$Qf-G;FZ@A=BU1IZXltfEYU?W3C=BI5O(9i6hF!wYAeAepCxa1+uoL!S(iB zvHk@BqcTJWM%6&;DX|0+0+b_`5lbj%ArT-WY^thMAu)~wc%j!aIrL$!lMlAjXOs;@ zG{jzdA?aL1zLV-4l}d>VX=F#5xhDh2AZdEZ=&^#%o5}D-8AE6iyfu7=1)J&f55bl- z5d#(%YAvX=40@3a(PIgk{d$DwBmn8?b!tv!+hs z9jKiWEOYHR9C|hwDou4JuNY>#-+y8a;zg6)yd@hIR@dOGW>F@5j8{yxb6+jsg=J6@zF1TO&)nb1wM zssZ#paz44qpqv_J=EkEtOnLFP0AiTu3Kfkqe)P3lzUUr#>JOA0L(FE+d;e_06Hy;j0AScIlua2wKwll|m|}1EhXplv?xJ-X z-hTenUU&NFho<@(MoWYXc^H+%Ou(LaH}AIaKhVFs1cad(qv&cjHmkgtIb;4abw6I+ znLb7Q>yf>$E1?!DIk|7l9aW10vYdrvZrrdJ?A>7%+zdD=#o?zIWO2Ul8L2Bu1^ji7W=#?0*GQd_P~M_ zTim)WUs9_DYy8Sj{zA#3$3OQc?#}HiZs%M7Acb;!<`3C7sh_h>G46CGj**bVpY-Vsv*&=qW& z_8*DgC zgRLHh9iHfQRq^_o#Vel}6X?lH;8yYG!k1J77QGM+GU-(160le)C`!J}HYZg+i7fa^ zQJm4uo5*~QDQk$ECGx_d=YUd?v!1?TRkMt`$H7K+-7?WAw_49(y{oBfkkKK~A^6}2 z<3ZNN0wbfELPcc`AmR?n2k*qmqgQIF69dWDN-Zp!QPP6@4`X@cAm67xKX#Yc7uu_+kls3G$4N zczI_V-NEbIP?+t#sop?SPNeTMr5v%}_&9)F=cMWS3}toi_IQDaTvKNp#rxKx=ViBkz5XHWb-~w=20wqf)Pr_qgtqT8b&p@l33Fs2~xw6Vo zS+P7+^sIU)ikx~It@jHXf^CB(z??q=Ys_-BIi&<3*gJr%sN>K|>zll|mY>1sXRHBw zsanV;p&-qB8k>~_l$x>cOU8~<*`y)`O*>RUxub!Be)WGP0y{|-J6Fkws&a8ssS@EZ zyNCSe`2-;Q6ML}gk(b<-r@y7=viJR;X%-;?w2xRb30FNUz~bWdZo}5ExqTo0i=VUT ztEg_wluy?^qkd|ri`XpNa-N|QC2%b$_Ux88XbHf1yg;TPK#P-l>Wl4|;+}Zvd+zd? zLvH`hUqoOrhGOQm1&E;>(}GY_EA|ER_^6a0+54JC0g+rxX{!0EL+ME^1dCzzZ*84h zyy7wU)R+Ff^a?(F{ReJ0<2}3>Q@ZCX7`=(w-AZ7w#)-Ys)Y|24UOBDm@Xae{wJub+ z09x3z@Z8d*VpXvAW3k-X%A)Nt+v4_2@tu!6{ReK&!gWeIzxV6EQT3Ml-1^*i)yuql z`%jGd@Nf~6-LI16b(*ESe(P7||4FhS@TU<;K4F7h;<;;%rc|6qrATfCj$RY}s;g7K zbQq7ORwJ=F=Bu3q|3l0IGYq9wfa9H8SKS@Jqdq%~V)6`%gmU{agT>KNB_Niqc}6-M z2S0knXuqC?#u|}mBo-s7s+cj@sjzFJvmTy#y+j_TtEE73ef%>a7Gku2$2(8ue*asr z_)yQc)KJy?mdr%CkI&C+g7U61CMt!BiU3%U^3NO1T+oEkF;N*f<*iAu0i}!#vCvbQ zQh&L-YDA^9p+SKQ!6YWH&H)SAiClC9={4rhHad zQykglvxoKjP{q*if)&giI13+A3u&O#nyhi+1U7m3{vd7w#fP<2HL`1}>$`njR3m{a z1xmH*&lBhT?ri~+4E`#=Q0Mvdb&swNXq zHZ@zbc4Ld4t@;|d*Vt3>M!<4on<#aBMlZ^?_xiGNnXy3ohvWlQ z>SRW!8ybQY0hN89c0KzWcs*9Q4p9pLx#W+vTO#5Whz&~Wx`CSkP zQ$`!`IBddT>N$jl?}IbceGwQ-l0VL7qyhwWRZ=`{5U|94i@L5JXH!7cj73%3OxQ*l z|2t5upr2a5X0Qt+*?MkW$|e(%Q;>Bq3B@W2hAV-U>`_WtHbx%=7%y15S=AM&=qC@p z>)wCu`|jFhn}g{&xhV-Yn)x<&@dmg4v9G#)AN;E-i@XSX&nT4T>z`GSesup^8oQ%? zFG7xoKC-cXY>@wR5*+4@w(M^iyAlO$C3Y{WoVRy$3oKIQJh1a+-+Gbl=VYbyH|&YA zG5G?RNC1q5D;{-M&L4Hh4!*4_x$UvEr?FfJkYT#yxJKIhH8l=()hA#4o?|^3PELjE z_RS0OyV#I0U$+>FRZ2@&VMYtqwWhw_&6u@Z3?Z%`#t^I%o+}`+x94h9`SK6T4(P{% zvpm|$kpOemqI?h*C7&n|EM5DQ6l}Q%m=3S}_&=%TV*2c5Zqv4Jxbr9X2)qei67Gt!q84~D{@M3ya8XKB*PW$^|{0wDT7Mjs*`UwaT zc1)V4gpWkS+9!Kqtr`JM?$;8{w?!eo({s%fc9Vo$s=F}$4OR1sI00z0#F?==Yr$&u zyBTq~kV7TQGpy1CfZ1QY8N%V;iTe!4-`V6gxwR&|S|$@+@D z#npV~!+uT48Mi9(c%b@WU&j4>Ud=pu7URB|Xe~5+IQS ziflqM%Vc%{KP+%dYnNp&YMdxK3b4n^eCF=2zOh9Hn81R~O(un$j%Ye=EK$$nAWPM> zzS%Obj&Tev>XlLO(bucj6MWI&%YmUX1Vs^pNVePnOjK3OWorYmu#_|#oIr6;0zs4% zR2v#4RKs`BtHj?^^%AwhI}rNW=ReMxs|>BGAI_=D$e-2s=_?RCzS4bU50%fr$Wt|l`*rek zF>A*g4JbAKJ(M_&P_bw#0lN(N1%MNb0<_7Tv37`Q1Ugtr=B@BN&|}5Db|@f( zN<@|X79&rtoN@j4dfeEs7g6wMD}O!%*d)MRxa?6Wx1o>-^;Er{p|>#vgCAqqa6d-p zVZ5g-c=JIc{Ur=4CyUKKr5A<3O34df)k-o;1(m!{94y9mG=Dug`c09o40{5gNDxNf z2mvr>{N}Z@Vl;#~pfDb~r!Q0%pNh?aoxc=lg02|WCNMSPq?VZwV_0~^n9zihYE<%Y zE$x*C7~vN>RF>%TVA0f)EvXc~pZk%0RZ?(N{Xl(pZfg*uSpH{+=)F_ zdFq&=o=2D&#}2&hu3b9mD+J;6_`uJv4bK4ZjZf3e$&nEgVl8C>!u!RbP?FAk6STM$>tAqvcdof(``%W7ovqAN$`!{H z)Vvq5f#aN=joZHNHa+omF>=nF_(=PKGiNi|g%ix8SMVA6=bOFbf~W73v|J+Pf;N8qwGV>i0DL%1YQ|IS#x9a=o2S>Dy#BN7tw?3EnhCXCO zsV<&5;H#egoEP||`}ds@SXAuX=~iz1oCJPO9r@5*Ie*w%27J#eNfFkga|*Mm8s3`m!P=@3?CRluQR6NH<-Q?~$uC0Bl z3;>`4gQKSB8<#xT@(E%VRRSud!U9G4NlWSku@Zlf0{6asvaLy7y(G~wXkid488CW) zIJh_#s0Hm^(={^#3pNxMdCj0;;wN1bg%48}W6FB!4 zEXEmZ9~C5W_@OzR?;=QnLywq{=1@vKw!@9kzc_$eZ1GQ=bPzy9!7!)}>Uw=(6#6s; z7OYCBXDiBHv+I~LQvx+q_9T3xd4*O1rt-*|@j6jS0`155uw;9d@=iJRZ2X1{InIK; zgL*Cd^hT+|?nV=Ep8)$3haAJi^dwHWvN&G#B@Ye@D)QBPNqVhoRe9ljlZ3!_ zu_q8S0bB`8M(luPYoB&czVv6ZX}jL}N39e4zEJH^0lNo@K5z=jqfC{*C{Y)((V_b2 z9i^E)Q)mt;Mtc-Bvg-sW%wi;Hx1OIH%EF79tsrj1O`0~>z>ptjqeK@oMw{D`WRWF} z4BT2WY}noDx#|Y)-jQ9_Xrti)1>lQTKB21f&FklsU;tpJ+oKdL#^*lve5utb{{)lu z^F2aTf**bMyBZzBHGS~f_uYv@+f5`x42iH8Bhce}#QE+y3)Z=fPyU`}4W2o^ODzeD zS3aho{Pd9zG~j#;0XL&ol=^NdN+XB_Ku0;6kxFfeaK|t{AqggnM$D&>piaSyC-&WvF;yDuYG#+x(@ExNTqf zGtnVWAKRh$M`M+GuKB9dfYicCz=}@Tb4^KV+9kqxt9*}p*-OgV^&~2Y&JaEkK`yE~ z_Xh506a>6n&~n7>{94CZ4jDaI=XOJlFh8IPV#`CaMv-$VfOX8|mRw5Y1EusKX=HgYr* zE_hWRCp_3IRaum+78ZdD)8yJar>NfzdQt{R3b-}NNCPI*8!P|?DOo1@hzwYaKe$|Z zddw++>6|=6i;9XU8E^t@0Hg#_I;Q$+(x46G%>-THONwbTaM5wX7#}h$l-Oc@MiWtu5h=y5n4|U8cYl3#!pENTQ930#Kwo$;0 zdtnKls8=bhDC@+U;Q&I39s zMXShIrPV~Eora%a#I1?kGGB5w0^9YfV9>vy8A=EeX~v?{UZ6jb9w-6=4e6y)y;LRsa7!N^3ktH~HYM(NqvQ_>k3FZpCZ@yxk zhmGZKzR;0J`!9$|*|RC*_VYnb6*eKcCsA%&H5!Ax#rLtVU^FC(g5Hsn?BjKdRz2os z&tI$L2jUK>D~fXOL0z^YXjGX{QPequf8i^3b{!mS?#;IX_@20Q%?iMlSQZJhR0$&P zgCr7i^w+MOQbG&ci`a!E>HTnLY#EgxXk^_p7b}SC7r5j4Js@3UCN63FJ;(u#lV2EzFqKgx(L+`|Nm_PJCJH$VMNFUB|7 zz4h{ca|d=nL$-jKnVE}LZgo4}{0FUnVk?8@0y+c4WTT@>-WUEPzA{Jci_Rxtd)?z- zQ~Uu?6wTX<8;-STzM z%3go)`VW)<2(LE=o2OS#z#o)Z80+9+E$ix)OkK3{F(nBZ7lJ}{0v2It)G?dZRH|V< z!Pp{^FY2w5e5vYgK4EW)`(95ZP6CyS^9wKdA%MkCO|+7|5Y~&ct6~%^wjg#C+viW= zwX0{*`pV2Fa`6~v=qJhef@ss*pl0g{ODbdj_kq4>me}O>3QbN?z~nblprZs3MKBLd zlz`ba592#{vA1c^w@##{tNNA5SkF;}cM`3KH<#Cjf(WRFKlruIxOZ2T;V%g;V>} z8ICo!F8tsuWlTJMECdu}UhA8n=GH1$7~iAoaAVp# z1Z-4Ls2-Wr`xQ~`04Z`_IC|Sm$({-@#e&fkvcT?$>8Ht`y)y|_pGw5M@YztoML8WE zb+=RzJ?X1^7R1Q!gaA##I0S4XZr+kd+~QS_d)3upRadD#k`d>ArDUjN*@(c`y*{f9 zu{Q|5Nl@_vTY&zYxr^4T=MOQUpn_Ne7Lz1VS`jM(i&Nf%Ta=cZGZ8>2JED``^?kqs6PA)H)tNuwBfT#1>QtI>Su3Fro*) zfe$2+hyTU5kSu1NoY)>UmQc&g!b`1h349JfpI%w!7ard8nt*H?c&5F>;q2jWNy;u- z`MBn8G7FF7WE`y8F--w%x&2mD5#yezrlKUf`KfPeOv%~fAIU$`%7IV+;Pt;#!h(ua zYkQZ#J#h#61o#e~8*9KiW7m0hypO64Z4LOiG+{8R#H|#;b0z5b{GbnjJ>%J8%NSrk zse880HzSeo8JTAqz-XkFoA|+!CsB<_s{|G!`;d$9@@pIt$HbKD9{s9YvgS#x8|Uj6 zKm6adUSUMl+AUvkGv+OKJ6`{RC2~l}iqTM~xQnX4?RQgDjvReqr95xBxwhJxdMUB4 zSofSedGvjEY|k6keniER%3ochS3w0VS~4q%Yi(e)w~ncO%&cZXg*;z13JJ^B&Z%zQ zqhA(qBk7Bf6$zOnz6hd|$=-edigT3CV!tk1`>dPXJ=>i-wO75litGFs41jxU=VUR* zV8kf_SKpBKyk~%Ni0RB%1}2BO*4DvTwzEu=^8(}!1cOzz_~@{2Gg z)MsyPQ=g5>q6drd#g_J;MCa0H6hdGgvW3Yw1Pv^=a=uZ9$m-`FR#_kyaui=_A7mEN~Q1Ik`uw zOaP0{$+KKTW22lVAPfg)15Hgxfu9+3S19X9Mur~2{=V#pkfOdIvqT1Bvxh2oBT>`1 zoV-td1GoU!^wd#RwC7{bM9!X`J7t*-cyNsXT?_@!tDnl52SrHg6HIZPfblTEnV^k5 zqClddDan4T3fo9eDKzC?FRFurtj%DwAE-{vszMA6LNB%I9-l+CSaiYB;j9ZPvtJTJ zu0Xg+&qoQ4ur}U!gz*tp2{FY%Xv4u!1%V(5V+eS(X%vNerKoBQ4%p}VZJhJ*9(=?A zk>`>2WSZc}0?kn5yXc3yaqX=3i%Ir-=UYUh@T(T6Rx{?VbTeizbC=H_78NNTcaqs5 z6969fVedZXw^Wk@4>n>{XLin_4Fci>R?tq_@(&pm!0dmeOVyU zda+41*!rliT7Qhdq945zf*74UuT;v=YTf|rBTL!zBY1owQmdFd$4c;EFJ*gMG$Q88 z#pCYM*@LnJn%(OAOV#5TXkT9Rgy)Nr@aj!3DzM?&Ny;ctVZLK?yKE8nh;8FDsYsE< zC)mbT!UW;o2~GhGNa-VX0Uh0vH}PIf0ZFp2ysa+XvAHT>vZkzrr@+_N3e-LR!XJzA zK{fIH*S~MQ;K|ObwEs-}#lYf9x9Q2Ri+ZeH{(HUd@JFwz0u>S;<5DC`sF9&Z-hx1w zC#*A79qx|LwUI$yoJNUSqkHzt|3UQA^QZPnwVcFr@O|&S`Zr3v zn2I>>GZ86RHTXbOs9AH8uk^K(j5GnXYpUEpdsce|b9hGvbl!r`NzVnzDP{#*d;;Bc z=A0Go){XP7ujhtD)eua%a^biHQ3@GJ{(O~!r2Da8m4QhdQvmeEto98i*4 z_|^|z`&+kr`%krBg1Y(Ur@!qJCO^^hCMLjc5%=MLsrDJD$pOXKwnShpzYcs3baVPr zu?;)k{Gqkbh>?ZHgC8=lmK|Dge9S3R8w)T+OoD1EekBP)+vl_9tycdg_LwBdz7PL3 z(Oa+$nku5Ek@5XJOFNflx5tzeTeb0XN@AQi_>Q}I^_&2E0v2oQ+~jHV6ldd08KD%a z|C!2Zk}MBmJp4PozH#kMAtNJ=6En~6KEPrU-`%edzu%><;(c-lzD44*Rap!-SCkdW z-*`l)NGcd)Y*6Av00vHWYnQfxGLU{wVM!pH``oziApYDW@b{9!(5L_g5-zB#QxHI) z!9mB#(zg)`if3WK!r zz};Rs60VQl461DyLjVGlDwXFGVxrHh=MF-=78Unh07FnIx#rP9Ny@Vp$iD;Fafb8+ zupt{;S|xe|zzE821StZKV`DNN%53>z)EZ99d`UlM1A2{m2gJ9ok%L62h5ikKFu-VV ze(C{0$+fo5Mqv0K45P$<7y~k3SywVy8dHI^z7GzoG89P`l`L?Jsl}?t$2V4snut(F ztBkNfuNS|uYPtmx1esK03Xgv%I6xB&-Zj1 z?v`L5IwgS}y=GU>A5Bz#(}U*Mr5qS5s9Ha8Wih`PWh&!7YK=W?Rm+G2$C(2XyQeQw z^^7@efGy4`f%aIx?LQ3AmsFGd+2yz} zBpYQ#Mg;{L9`<*5kV=@f5d@09gl&4R3rxeXz@{Ubf}JveJ?s{(*s30$UPe_E3^+G> zRqostKCz4!^H|*MJ#XjP&0W0FZF%NfZr1!&?%eU+?%h}a+Fd?(*b9546v^Uq>w`Z} z_p-qA8?tGzAdc*NLw!(2wfCcXqU#O`uOdj0RIPn5Cm$(4*&ut4KWJ|2kkTyuo;(-) zuqEo!d5L+T9iBe3^&WlhJ8s_xKXYe~@Aefo?-l)p@n85RdQy4Dhxhzi3aEkI5*-+S z%*%u75{nWNd9KEFO`YSOc>l+`OXx<{k7QpIlD8?dH0Tl2I>uU|c_N+yhnJGZY% zxl(K3lSL)=BaY>&39!pro63BEYzieg@)kF1X;?{2cvZ}{a zwgU@H$?Ez>t*!MwTcR;N>vn6EC+=2dy7eg}UZBt~S^+C!NGitAvUT>7ied~F!}nMF z9i^|c%4(gPvuM58B_z!NsZ?yOG9TihIyb3%j$$(QTdj&R2GBFf*T6{hNybnr&jZRz zSNyS77JWtbLF%#hzuINqScXf#x#fEGH~C_|DQeMB+HC~1aM zy9^sc->Cuus-OvBv{@a16M#{34yB$tEGMGB8y#`2om1S%;Gi6b=J;uTVXd4f*+DXl zT9XRdPd$pVYhMfo#4m4XcEcls%Fc6r^jDyW2-tzD2xx_RmZ+W%4JvR%yhTr2)mx;a zeFaUFc;ndQFJzc^;S(SM;Gfw{1ADiA|)u|B^Fki=2EX zl%&}U*SO2)4r#Vnpo)cSsV2ejSpbW=j}QozGpvfQYNa}i(_=qfJa1ZUrhxull33^nak8$lvpfD<9tj3M#yhAZ-R5gs`AL}$YbXOE}DnV3RvGJ(o zlE?vkUpTYh#^)5!_hQAs%G)WVj6#Lhs;!<{<(zJM{Wl#o~G+tdgs^DsVD=^ zfPxIrudlBcm?2T9B$!w$+1MfeFTQj7?4|CJr@ra-eelmxZVh(M1Rv}fQ?*;Z_Gve5 z&N6rM&~{b)B-CckB3kby?73n)gCW8>Kvo zjsnc1_kaC2Ztn*_Gau%wcO?9uc=3DEcwpwCX;Lu0!h{wB%b@5?hFC7M?Lq?AXcBq} zHfzIUUv*vGbKI`Cek28QOSqcI9d-kts8}IlF+_F5@<+bXvnY92jVi1gp7=dgjET`m zNWiF&LcFJQ#+AhhxUPyXB~Dwq?rE`6P9NRj&Yj$yuuoDp6dE4wQvRoyr28{l)R?|EJ{r>DZ5v=N_fl-jS3bhZ4c3K z43%+sP(lc(&RNh>N7XJD|g*?J;mT-xPO%)+01bCqCC)!}V0KwU09Jm%OvrJKVP-=SA0ABBE>T2asX~6HEvB63esIeK1lZJh9jT6;_IDomd-$2^fgZv!IHI*a)-R z0@Wi1wekIC9#!3HtDoj#ku$Tt0%tM>KV6}o& zB*y`Yp-(ohjFePsb9b4gQ>D&tV!l7Ovehs&3T!|%4}j|;5kVpdkuA|)w z@Y(nDRguYOgaY7_GX|JeU!npvOce^UUJN1!5V&fyn<_0 zhbabJsY!TRdQc;>Ef8=w5T+w=ZEy9+1x`aPA3m;tD$ek@(R&0Rcq*qu1=ju$TqiRV(^SQ*%4 z?}bazcPw1vp8C@N;-*epAiz!^>zNa~Lu$sP=1GEt?)zQKP_ zBwmM~B9Wnadma3PNX`tc5qp^Up|9_z5*7V-Zn`_YHxyF=mgwuF&z=9K3dC8%kC*I$ z$X}+9s?r9{!*@GVRc+~UsDlZZ^YH^LowbjCNrFoNB$6^O|LFhJy#F*oBdti*r=HGtzZ0CQDPq+Sj@vPd%jSnu@l6(R90ar zg-F4wnnukIqw1hTlQ<{FDi>{7oNIa!*<{-Id#bqnky+Vl++x|+OyIFR(D(dXcyl6f zlY~ifP({+%`6$ce)S)7>@ywVSbuR=Aapt;gRVLbkM#D(ez2KFbxXqA^Hsb<}0*Op~ zql}1}o`**i3;|Zi(lIDKP*5}5HSTMW9k7ZK*>c3>muYwMis z?)CMk;)2)(*G0fU#+rZ(3XyU`L7>5_iv?S!9;kW*ZLGo==%(B+_eZY;KinhPWUDk9 z1#(0^fKF>-6+#OfNhoN3QC+?DA=EQiyH-PvSq}m=sqOXMvNow4SdPK?eHC;IuH${4uPC9%|821wWGB| z!3Xn+r0RJ4ngS8lPSoFYvB$M9tUu#5maN|9`fgu!XO8d8s-`Bcv()5P+C$@h@o(@2 z30N$+2J1bAo;KahTf9LD0z`g#$q*M&Dl^&T;+rbUY?fWSYA7W4vv$?ePB>5XjiRIh z6tPK+y18de($GVj3^hJRs$COe#3{+ z8UcXUtl!RVB~zjMBV~uRtpVg_Aev)ZTLm}3?~E@W8jqhIa&n(c|)U{zhskJ^XQk|v>6K(E585w z-?^P{{k_c&)yMz^3R>^^%N|kE4>~#(>xKqKnf2?n(h~?ars(_fx1Usejgh3eickEm zMvF05_R6^%YPj94+WfNGeq_i5beZp6c4~eoDN6}&HbAPC09uJh5^{s#Tf30P! zRuQMC)TcDmiMy3ju*i4KoVQwnV2CiW*OeI4kI{R1Cd78c9*oO@E+3Ts;}aEMkJ))k z5-JIv{BoizGx59p?K?iX6(|9V>2uDRjsofjhmgz>P6^db4D!9ZeHOU;AYWPFmNtO{ zW&X(xl8d!3hRcqZKsTf(oNm$pEcnXe_YIZPu8>9zZeT zF9I1Bgg{5I`G0(#fkqke!FxK)0+L=OO&MzX?U29q>%-sS99a)ZjYI8(o=botuz1s7 zTkyqc20eZ3@zC4XlGXv|@Z%HN&RY7L=knO#B<*X_X>dTbT>=LzL2)e8f2#pRh zCP&V_a;*dy07j{+woOu1HHbbCEOvBGbxp0E3cfJ7LBz%?zBoOk?uYg4_=ifYIovG0 zl8Pj2E4gvmto*%O&>Db3=v#^br1|e0VDfZED^R5BmsT(Ax{b=kye{!E2 z8tk)-ciEqGew%^^6vR5Fh-OQV4Hag3GYCSgQW5oVRRSHp(rL~3Q{BA9o0OC}du)di zF=mis+3GYT${KKgkDr_^c_`mh0v7fBMs3btZN0|m(4WQLymH})0?A}>a#+`D!B>SW zc^Z&L`zk*?_o3WzO!F)Fzyt>|*R(}FR#T_Vmt6!{UA=T%0Dw7*>Qi*18lORLPS=## z?$(V9s`zleY%GG=It$VQ5QsMY4mWe|a#3JO?g$`{jmhrG291p= z6V7!KAQA-9R)DyOgl&cg)xLl&Mkoq(SpM$Fp4Z&XYv;YdPu3l}{gT`A z^tX(DdikVA>>SwnvPO*n7y#akd0>RY{+%yd0wEHWOMF#qYa;t&+um3y;Yw}f!kFR= z?vZtX21uVZ3>3~Q{f>YtwXi7e8IhF{>&HWO(1%W^;o%3$TtzY*T%u-9+Mn z2VM0hQyo~$9h5**#AGYj9~uy-Ah;!X zKr&iEx!+)9IXUp*fR-${&lGWx$VLIc$Vw6%H8etTK~mjj+YtzaCU<%Q#>R#vs3U3b zx&~FK5O4_na+&XnvOIsVyakb^7YE2h%%5RRz)??cE_O0 z_9ycg846BGU-v#@^bwq<4xJC8ih9keIc70fG~iU{g-~KtK-{G%l%<3&loO$4w2a6$N zNiu=}695vbs^yG>0c``58sRc&nktI)r6BY{cA8**5XILDj;81=a4%fPq7{$nI*`?t z=!YL-9#?US!`D2C`Lko<3c;dB`1I(_S-f6J7-)k8y`i%0524?M#*L_E6~+Sqr8L!4 zc;un2Y9Y9_zN)at0RU8upr7*hx2~OW*DsxR{r7s4dF_^Db8f-%EpE%R-&SG^AqT1> z*dX=8Ns7L72(VF*0v*+GWT+@6Az&nY)rN4>)Y%f%>FvE95w=Rh_>ceu6yPtYY|(>u z>FgnW$I>-VE4fAAJD@Ec$Zg+jgXC?NBtkt@Oq*KUJvcU?h!6wG6j}iqq*6)Js!dD@ zdmiOC|cXn|V2Te#v; z_vo|Vb<<}paVHONciUh68+ZNkX|L`WfV=;9mBDEEKC`X{PFQcAv4A;(Voj|AAXIQk zz_zwc*6#pCP#dAg_ujhZ`tRIug99XE@gY7LmZ#no?A7?Bg?%KEH$T(1uD(vTk}3sM zdZ@!|wtUHb_}bqIs6jd8V@W_PSiaRQSoVlJacH|cbL=A}In1_)kv9osC=Ahy&$Iae zt`k23NP8Ok>5N5E8)XllJp7&nMl@Dxbj*XrZ%I_=;I5ZFBgED=SO3k07_pzrs=K00 z%vDUEvkrYe{Qv+U07*naR9yX#_}=3O-gRztSiSqK7s)UVA8UkKFRu|Zr@le4542^g zI^K{^ptS>#6PN|o|7i-yd4F5PwtDDb(Z_w9vy~fPa7$KgQ-3Z!s66kT@BB!6OsyqR zvW`7TTLB3jsHns)uyptw?ic$NROZWq#jrO+oaeuRQB@lr|C;RQNALcV=4i5>78BG+ zA)Xc<)-eF2lC_KfBDc2V#cOfGfb+Lz%NJeO>f8W7%GctKjZi%kB8<# zOFt;t10Ume{2Tk|Qh}SIsz(V}jIvig_?Xl^S6NxAdH{;xbTMLpJ?JP3{fn~mKC8%V zEGUl}xxwK0`UW|Cf}?wPZwq*--_Fy7toM#;SgSJY0Lnfx-OM{o`d;!+G=$f-m4mUg zA*8LM#E_NcmH}B952HX>cA2pnP_S(NV6A8*Mvoj-_Um3>uc(xKItG%@K`;f$?Cdg{ zi+xyN5wH%GgDQjQSM5{u9LOM(ZKfxHV63H;d4j#lSWcd{z|S&c__NKMq_?oi_W;@4 z$U4zxcosZg3^~1*MztLhoeWVQYlOBD!QnXpzE~3gWl&X3o<>lGt*K2V$&+7tu&D7I z^cO*K0({y$!Ib7>`;dKrQ{m6huB_j{`VQ3)fG@0d+!pp)a33DC(B_niC`wvH>Zj`@z9tOu`GFR^S3FRf?-w{4$l$knjR1 zPM*$;&iUHUBqHd6PYBRF{<%MPv*xW)kL?Gq|E<pc~D0mHa6i^0OhYi%pxQDhb`DO_K4GqXY@DG&tJAF6Q zMgdquMN%R;p^YP_=v`V_^?@VeaSZgvKG!#D90VYTkr1o5e8GMA`rrE=Qu@yuR4rb* z<|zr)9oh41Kb9ldyu83zx`WFld~CVGZj|1N<_|*wDs3)DYyGIi7X}Q_+&H@qs3sT1Y6{9IA&)h`^vmSdc8iLodC0^8u$3y z*L*rw;J(0O2-x*+XcY}j>XCzXM|M_~j}T~}h~;OvD4SFUEV4NXCJgx5aA?s=2N08i z!h$j>1JXy-A7{#*%<3CZ1`6Xs77nR+<6&pj^MZlTIFAa&o2)qqBoKS17i=fPsNCOfVya&LSm_dw4g z^AS1lT!U0uweIlqq3+h$xC*La9aH6S!kCMYxfAf>GwT4LlLgf7-np&&27r>8LRbh& zEvi|=Lqj%i(hncUgy8&n9a7lPz)HZPZ62fQT&sv?jjB(qKLv#-^I9NWr4@K^cv` zU1J8YD;H1i7bvj#lt#g_n9%>*2i*zK9LI5$3pBI)B!t7+L{mO6spkGls?0@i@>yB} zAb<@O5SRi0tDB5XxqK=aijFLQu(vQF=*6NJ1{=m6qJNBP8%ZO?M@aP03pO}-&sW@o zm`nt+JuN?}zz61p54};s)g$o0GW4nk>Znz?+Kg&?YL7d8Y^PLD!*gqD zY;}uQZ*#NeuT-^|Di74VKnKH)bkAI@{z8C`2`MlawqI1P%k-@x{xLEl@sOGGR>_VB zdO3ETYXsO*Wuq6J*U|S$Wty=SR5WbAr9VNfv7~yRY=bh@>tNe8(q>e?5uiu~m7xCJ zU;d>#b@T(T(42yf2L+48`_Bh-p?}Wz=Tqe)5Vvs;449uLHUkMx-oe^Z(V_JKdM-0@ zxfk`P`q`avWhk|*Q4%8VUaDc#l?kf>_*ZZKg67;^yLeo_d-Alos(P@W5AS=!-M)4% z(+gWzvGq4R9#{-1ANu+?KJhzl^E2NT5Fz1075nJkH{AKt`;#gQ&mHB?Ezf>OwCKaT zUrmzFu^$h~lgPOHJ#GIA)Y|ZS?vsA8RU2Ot_`7?z$18952q3eDRNF}kF;;=fA^mkE zGDrkb8ER=q7^h2ZASkR-5u?YLgb1%kO|{op|FMlhjL6Pu(KD((^03$=6(q{~ zITHe0vEg~Qc=Z#md)h)**VwGNihJMtnXeSbCfnL75aOCXce&0oAenX`+G4~uqi?Ri z&y>ksjXuN1r8O!BAuhvj5`!d_GVc#qtBqcDlu<30&tq4H#KsU{6n1<}$3l_kwnk-#**2nxdS--N^G=TFud_}2OOEm*876!@&YC;S)&*%#u?i2Hd2~(w^st9sLG~Q&=KorNYn|* z#G815XiChftffjjECb7X$uet3nU|}Ex{Aa+2>>#f1c+ql=~V>8%Q*WCe+br<4fK-N z))O$K{zxjnnE*b@dS(E#w{Ob&)z&JogC?RXiuzNbnAPdK33%0o#XLwH1_2^Z5WYGT zSWkcDns~N=R<0+evZm%QTQSN8h(XW*X?M$N;_MM(AjqPR)@Y{}eE*M^_^+bklo(f4 zQBmkyC&gIAHt01aIJ2Z}NywUPk@1|>czfy7^n1&~hO;uJb2)FxCItfoO;i-axeb&s zO9EI{-_Cs~`lQvyiQHqz1g90~?5LHJ^{(PMX9KF-)nq6$b^t;TH5F?>8GD{Y1fw5p zJb~?p&~HqD7J8nnzq3vie)^XuPo3?$XDtzUgrRZe!m(t8hO+#DVc|2;s%VCLvbG{W z=EctdlL$hGz#Em2Ti4FTP%#lZ;ra;rnp)cQc~{OK6A(-iAbf{U;7pyq$gSA;yubkXQ;fI}^Ock1Q7`2g{K^p#;Iu&K}wJ2X4*gFSwD> zA-D6*AG-ZJe<_d0+?boc{fy-8)Kju>Uy2&`_7G zdQ!<0`saBoXW{hmof`cTgxmm7U6W=yT3v|0cpv8*yFta2_mfB=HbFmOpub1Sl=w+x zSFbuRl1XSJ&NF>B_{JHtSGaXszbsG$-IBBSi+}jv%m>W)H;)#4)H|*Wh5W1 zy~)!keInbgGzMP<*IzMNYl2`@MM;Qk+V%%JN4wwoiCekp1;! zWKg5Le?kWibl%XLM3BIcYABRQ(39fKbFuB&mE znFZ(P@a3IWInx+Gxrrdz=m6#?PMvA$ZtS&(wXNJzNkG&o?0U!jRPv8o*@W$2i&V?W)vH_a^wR)SIy>P97$jL+R zYStZnz|11lwaZqHDZzyux^QZr=Hg)sV0r-V0D%A=0_ZU7jvdc;)+UUp3duj; zPm5oizjU)(z4`O*{n!3h6kwh^6_(=%-&WNb-($Wzp650Ju$%vvQZT;@qOWo$DzUdC{`L)2Be&P4GZYkaa3GFm{jY`Ij zSqls2dE*ldrr)51`iHOoKnX#7BXJ9$oh0@8$9~84^;~sF_PwcAl4a|jR!hQxT`z0g z1Mih+(CDyclu}uQzD-<0Wtj0CjLPZgnvp1$GvE2lv0YN-P7-W>jne&7ofpYaP?O+0 z704nvvTD;yZsD@cV%@N=AH4o|?xT19DQO?d??=uCqoDwRoOu!ekw9+0yMSVZu81>O zN2#-WCW+Ci>ysW-Q+>ZGyAa||?vv#GrYFDd+B>Id{0Y5^A%U&rdSg@4>lu`M^FS-E zp8G6ilyI^ARet3t6gb&diX2qV7cATC4()zbU~SX3uPc7t{;R+C$#AOn1{Teb-e1pR z30S00cGgn2bnP>WosaE%LrK@d3SdMrEtj6j-~fLPGVy*jChe1Y&2PctLtE)Wu&Cx= zFUEpGBnLuDjF~PJzn`IJGW484*=GU?=m}a7GEf$$XpUD7krm zrA5yF|7Y*LgY3$#bHCjYXf)73H!{!w8ad}Ym>fC7FqBA<5=8}5@2On&d*yonxLoD3 z|8m(?&z3Fe`AK#uJW-SwWQJkp%9Mwb!@Sx4uQD1t$mN4Xp$tiNk=(nrZ+=O^o8SC7DGXYd)%L4oX0)((e;xZ`O68qy+kA*whjx>ZHEGs8Sd-96%^ZMD}=BwFDuvS3g({ziX=N+|8R; zErTnn=M7~xpr>-sF)z?YaCUKOO{Fq@*0NwRIowlfOPCX*oYC9NvZQGpnnmmqgBI6k zc%aET95#HU8!~jHmuReU z^c4wB)>8!9{P+g27@XE*|Mer9STeRzmfO~G8L*gtncgyuWu7NwOSud76xt&UR`yrzJZd0TJ<;lXxBULJtUOX)hWRmlnn`B zLKEkmc`Dimv3>|odkBSp+PwSJo`Ikn zeH1sm^mR`+^b4lXjC9{zlin$qeQeZ>9ZaoAoFTPpw&;=EQv7eDIOKKVz=EOVBj1}U}G(+72q8Pmp>I5_9VO`hwPuKm3GaMRDN^%VctMR`ru z4(M4k%mAwiHW$N6VeqF=5q`7YG6Mv+$^_3s~rOtBpZfLP#6jKw6!53jq6P#%r2J>a2`c<+wwr~7tA}AG) zQsrPVT50k6*BY`h;J(}s)lqsX!UTW`@#6RX4`p)IgF2$;T80*%tJ<|rTPi<-EM(Z1 zlpDYh3aa;fH;8kE9?j@WRM*tIEA6Kh7>~gs=f{FopH`-N$L60Wx*78Mm~XFtp?L~w zx0y9pNhB@ZC{`zjs#%w6WB`jqoS|x(SV$;(_Y1VZq2{2LB>S)y z(K|5+NLb_CV2E(Yi7;7h;UMe3c>S_u(aCb9HB43ummK;zhdn-EGm$p+L8?=v9*_)3 z>QqZCto%JJZ%SbyTA1|JkfFGLCmCLnr5J%=@==Ctw- zVGK0N?O7jrudQzoeTl=KHG)_O4lUGc)}b+;ym_q@Eb8-QU>e+v1?zN}9ofId7vTHG z=^2ocxUHF|{nZDHmASM@h^MDVPRG>QtK7l8o80N6dvwT}50(ak^83s(fKkmv#)<3O zD2J!S83Qy~%}-}4eQ%4Wmq>C2AfViVyt2&fGlCH)eFDe=UE6FHJxuFF z;Uj8H6dgxBtdP)J#uR&lD3aN0i8J|qEoZf{Nj91w5y2v&{AA})={t2~w`*uL(1krF zBZ*zHT4q=a7evF3GcVYFo}J7vw({`4_vCO}kT2RNIUB%tW-WY3`;2STaslVwS`&49 z+B@}Gm)-sy>lGxl^Quu<6>Jo=aNdo5irpGSNkez1J9glG1ut=6v4^}bHk&ggFcG*` z3>E_=G0+H;>|!~v=z%4FkPW);sjs<;yx1o)`i zn>J^S+xOvHZsOF1y7sOuFRDF+M60yL%fDHrU@??nPy_hz=l-2C;RFq#B<}z4EoBTt zrY^8XjK&CfSuFbEwhhmzod!>18V2c%XfNgFFaV%XuZW)@D)Rkb)Yygf`TY0(cLfIJ z+f>)O#^Iyg+Q~*j+rDMaN9dS zbn9RIFDc_DH(tSxk!|LOHGr=|5D117cE5(&ZS)8_Zi%VDdNECi8iy(~V`Ypof)rK* zN!yLZ_dTls$M%gs5e441Cw*w^0xZ-M@!D4g#TrOeil;gU!vNJ)lI2ElJ=`#WlFG^+JH??^JbHwU^jgAf&Kt9GnT zfHxHT6Dh@b0TdYs05tDN6x3AvETfrM87x^>ab(&&2GxlWB@9^u%aHV4Yn6)$nFA8t z5Ch5_&>n;9(KnI9#QH#{O|<#Dz)nw>3@je`jmzz-`QdQGSkss6+O>A%VKpYuM68(H zvK)c(SyCsOAAo)U#Q3WT1v)n_@jS-khWHWn57al|Kyt8Hrq0*?$w>-x-pfkyQCsSu zXxl*VFP;Tw2ucsiw`J>^`Z6j>Evb`Z0{s`c_={&xcu;Q?!uXhu^5vPU|Ehzjwu!Z1VA$!5Ikab^N&z@0uyKgh03NMf zL#=CSnc!)#)W2I020MV`uA1u34%N2*omF7ghw|ku?Gvg;%?F z^|DGy$fC&xU!yIRP;{2_UHkRI+D1eTcI7flq_cuJ}P95D<5^bym zEcUr_q=7(dm{o4h(#IsmMWB|o|NM9VqiTX-h*<_SyLlLY_HXO-#cHc^rJZt@7R?pF zk?b{dNUJik&)6OA75opbOJD22kTUbu<65UKb_-TLqf8}WQ2{MaG3Gm3W8Jhwv+stV zN?y z`GfU>vC*dba%|lGoo|^fP8P2J+;19CtZ;treXQ~kNWmgvB3?!~6s#gl08NL8F!UW9 z2o7xkBeLWe{-jQ&hCWIb5h7a!eF|!5LLV#x6hdUqHm=b;IE08GH8!?L;nI3ET2zT= z!B7Oy8a8@TZxZO9C~UuSEwS2b{e#J$RroH44O%MT3TDG+R&8@)6OZ z;rF(uq^3>O3EeV8sUjz0KxuP(ej=tkC-U$-^Vt&zT>JS`o-q>Wy7r_}xN|+CZW*oj zq#~Xi*uls`?C8cifNR`{<_WH4T$>w0eIi0Orw{26WNjyPD+8G)Pp?Il zapuAY6}=|&U_C2ig~V+1vacXPZ5@549Ukpo)= zWW!HP`;S*4-=i`2%!LmLpoaa5EyH;f<@M$@Jrli0p`+pek%`5r2DAcDcvjvETgEeE zuZ|qpqVESqZhjXSBLTd{3pu;w@`sB^SlnCIO1 zwuNrmtd%-X+2gz4e_3-Uff;Ypivdb$Ca2uz6w0ouQLBLapZXK^zZISP$5n>Kf?M0n1fIbsUn)CxiuL=?^g{zQ1pgUry<0bt30kC`~b&0qGU zyL9o4+x6ay0zY$?J?5s)S|zpFcVGQy1$#wq7>n0@&W)Qq&$SS!t*zJE-}LIYlynHn#Ad0Z>}++l8$Euyz#aDP(#6xV zf9zF26>G;tvPeW+@QDGxkK(8DLV~i8)wOQ<17FZ}x4rulDXgjwr58d|X_IFWaQ(bp zPxpQr80goQ3=~zZr5cq}ELic3Y}NGRgPdCQ(~JKp<+JG7fX5_h#d8OG=K z!J_#vi2RHiJ5_rRdu$oWSZ2t^p+e9>w6d6H-DfaY(T^MdfFyjiK1W;MK3yR%;<(*dk8x;nDayZ0ESLc z;9CNp2wh@C$X15zTfD*Yu4iv!on&l6BsKRZz!<6*h$drMSEy175Qm*t zE+gpc(lV44zcH=-19b<9iOAOS6j2((ixoJdJS(bx0*j3!MCl@OhqH3}}S)Xiv9^(^S`q@&sAJpo?OFQTGbu|`km?%sf|E@ zA!G;o0t5w%klvM+*sM~)JHY(VUNUIcGd&c0C%OEJS(08JC-2Z1T{Kz5TK@!HaO`o6 z>gxu(L;E(XW-iGX+agWx63<&s4b@MMeK!A{+gn~%X(ljo>Y&Ke#|(!On;lv{C}0-cjR@Ez zenIkYNSvE64x%MNDVQ2Fb36@HVuwvZkxZu51!4>Mo~U2fuc+oG2urYMpj2}k91?LhVhm3(3ilay6oCTWLl(XIQ-Yb8gv# zU(ox$zy62r!%aU^2FunV_v`k7!MwM2_uaE1xL8PZ&)c}%{Du9j43}?tMK*{z;0z+m z6oiF1bNC&>SS0*+Z+lI1$$C`4FS%C{3@ja^;&(7#n0n`RPkl}5tIPrQi90txFCiUT zEXA!-vS6`RAam;M)o$zC-&e*9e}Ib;crd1l4`6zWWWso`k%lCo1iLdNXeVGCpunE{_l&7dQ2CSg#SLEa$KTL1Zi&pMYQ=6R8 zY6nwWCy^I|Yn=B0H<>>Ia80A7xQR{4w}%;UX3_6w_9lq~0z9Z~62KZhVywGx{)GF* zxBgdm`ovy;2AeQe;w>dUV6~{o^dF>62{d6oLof;zb^5=OVTDQ=*kpxlo~R8PAaU{9 zvw`^KM%elCWa==V@|4J_h&5uDBc1h5!(Xl5mrqoC)2tKJiKTtkzx+SoR-yY%fO zJ34dGBX0VfHEzq>-*qPr?MUY8PJ=}f1+3%7rqS-?kq?u5^#vBoRbu{9ypH|`VSgzP z`I~=J4;K9aSyd&2hr^9?3~=M*NAV;ZJTu1zXeqOns zOk~oW6VaFGo#?6rOmILfI!6s*t$O)Mh{e+`Qdcu^_xd$keSt-s7v2enqM@-_^#hkL zo%QeUn}G)*6#-`=j#8$301IyZ#m^e&u`ph{E;~$z8C#PpJ zA2CprG0cJIVkvTS(v2o$(ReeY>HkmGoUg&M$UV=4Vxsi}OYR-hbjxKq`EGTU4q>Pp z&;f~3Ub;Zbfabi1L$$GA~rCc86a zKrWs2nGQd9bzp!NvBB7-nu)I>$lX~BY1XO#O?j49YF0QJbxlil!T0c?8W2mCg@B#)S?zG$owuYs%y)1e$rcSA zK1vidYo$~xIv+rVmx01eZ%TlxJ-*qmpl}`j?gt^xCzhOX*>&jaKto2Uw$9C4`h;8l z!0(8Of#M;V6~wQk8m(6k@1NSR^qO}cEEbuGvXsN3KuNkn(zOuSyW5_8fwA^cW-pNx4vZJbkTVb z14U5}t80`Q#vYONBwNin2#8b9zZ+LovyOjauWO|#2tyG>VXd;Cr_5Ncy$y8~=7{={ zBG!jW@SsMm$;s1~xcMudaqVZ1DmV+c=1%}AffxYbsiQlkj*U-+U&NZ%{hG&{c%7@# zc}*abpgI6`%*5I5qn&TN(GzAW=!uvRV7WMpX75mxY_e5b0LcSb?CFxY7GsU54dox$ zg7?=y=hnaQUtDJwy^(8eocvgYGuZ;|HE!~(!~mx zWCyX`%1>7DdI+OYZngC1X)FBfJ+N5eKz*_w6Ie{hT|GUDRufUaeie0313#gj2H>G4 zsC9!Z3z8_0hO>~!wDr>?a?2b87ELA9|3pB6O(A7Il1qcJ5mnS`hrHsJ&xrCF^`k=4+SkRIfi1}N7lB26I0ZGf zSxf8HlHoHBll?V+fcu#Q*pdOp0Y+(!$otsVIqF+^{J<7>6aycCL{ONEPqYxxR)A|N+PpbCKe>(hxtPNbL!kRQm#Y&)L09)#uN5H$UFqF5m8SKSVaSp z+as1OD*%4}S@;96ruyC+2(efr>u~>!D^;+ME1n9U1?5?=vjimoNPrymQ9KA_`iC~e6HMQLR0tXeG**om`s9h^%X=pd_a%PC7|5BG}akI{>}eU{FxUrF9kL_vG%oYiji zV_$VGqb9jSd){>$U;CE(_|!*9Cev#43r~eGFufE`RJ^+G$Op>;#y+ne*LcPAY@#Cs ze#xp3jO*yUB@kxHlru(s}}W8dqHC4nx z6HrNCJJvA)M_OI*efBaL@HLPBq0W}=n|`Lf0DTvr3%wgVgipkJ$0tJciZ&S^pV+S! z8Td|6H@P0_=7{9APF^Cpkx_? z!hjFy7)1bqY13dzqC1h{g+9s6jTqMWguIT1PD1*Z&}8HW?j7KYWt zA1u3=P(^)h2|e66w21hb0S~mkbV26nrQzAbye3iQ^cP;$%(8^$3m8a_DJWs>h1w%g zOAsOO*~N-Bg)h3tuu?nHJZ6#`LK~2q*WLLuhji#*V8cc$H}1V{z9cZ=omHItDKl0m z8jMiKwW}8_!xO2Y4P-O_s(z<;u-K!+bHR#Ft6t>*3WdG~u2j$_yrB;x!6D7lQw0r0lai9Jmw3;)zUlCm1&c*iC1;pDeH$7XAdxH~Hn;uUNfV3FS_|!l zLhA+t*Aj9WJvkAZ$?U5T4UQ@2oNO4kyhvAQ>&lk)?r z8VcArQ)CsPF+%49K+jxozbIEw#fj!a>kDm|lGT&YPqV>@-0HHw7C0*T;KjH}b0uig zI&G0d(C4k^|5i3O8Rv4@nPf#}!fe0vZCoBK8jQBXE{cZ6S?efo5o~roivS5rxEg_>$?kz?{?v^gKSO|vOg%j=PaLKtk(G|vJ4DoIf>u4& zzYnl7WB&baV%tJ@V8>hT#E~8D#mG@`xDXlS3U9-eGVEbXLQJfCP!^VZ?7n`80Ou# zpWq$oWjL&9j2qiJOV7Xg&3|$4y!dsM!dMWu)CS6S)DPAonzQ6l^@jXl<4*<35!dVL zxFG;+f!`j@n+Z|zp4WUY#?;=1ahkvUNd?BYuK$7N$jVdjUo4nt0M&wQ_+1K0_6ID6 z^_%}QziWGX+=!8_$|`bw#zghsJxIVi`>!9b8wd%l; z;=n-CKBaJYF_(A@Jh)~S*}_CXscVAD1|S(Vh8}DNX!${jjVNRgTaXb|6MM@@=wO$0 zy-Cc6s9pf9NhZ3RhTjbyEM72Q(}TLi{qas}d|;SgA7z^}^O>(0@P3J>u$Z%9h5T_w zGF)Fh856K*GgbKG#|)>P2p|p3TgJBOU7%f4pGd=Q=+EXJ1{w4!_ zD?0tj=6j6J8+=!z!595x*IsFMG3?qVFuGk8NMu!=_T5W_R+gciPL#B8}Ok zY~Z4XvDH)Ad?DslO{NGZ4$3-G_SK?>aX!TK?{lY*NQv;qjWjEt2+Y*hD+@u3iIL;l z#LfV0;uHp;$e%$DKd8YXa)IqaWC~je&F|c)L+)bxNhuc3T=0PGA2t(pR49XmKheI; zFPqFRFP!T@W33WZedWWy>!#1WPiNi6SHG$HGHkC@qRW%MlDX@zLs-F8ZQ&q2F~UkL-3Iy!#{7>|Ja>Enf)#2w}aO1Vmhw0wPdJ z$>3kPbY3kb&?3N20Rp%l_F?RVnQr`)dG6>(+uYvmuZxno>fx^_=wiM6g1?rId|#QO z63Cu_MJK8^B04B-vX?p6$gIBj{XcU@4!m!@E4@G94O-&GV)LUV)up$OR=-m}r|`QTO2p?OZ$3cWLFCqy65SdCTtCuh6+vzdeU z#JCS_9_uDeU99U-7kU2d(Zn7FU!=E;a`wJ9@g?U(GHCtC#`fohY(R34@(JFnzt8q- z^m$wV0|)uJK8qpZZi-UY=-3Lm%_#|49z;&8RYZmkAb@A17wTVBV>5QD8#8{IjIJHt z7SSV0%m#|(lvDOt8uhdKo^au82C>kYyUhvA1Lv6bnM9R+WL|(aoI7#U)gNGXc=iq! ziExq4Q%xpynxgVnD-%m}?#9(iky>i$ksE3@0$Akl2wz}ip+#ZTp20Em8OxFFKAe!*O-5abws8^#cnA!4R_cqt~-Tr#syz9X3?o_61`hxpa z(?gT>%wCTkG68fpdD+J=0`bu&Dh7-Gy0K9$u?6|VE6V8S(P{=P>KTo)DeCE%DRS_r zQKV+&=FO|t#2oTCEreiq^f-yV3>`5>P81UU*REdFn9+w4@EEd(AxLAkRSVN7eo=j* zeKyR5W$F{#o69`r2H5D}Rn@AM5|x@ZJg8^a)LN9D8gnUHhe&;o99x=!6G7K=bvqNv zsjX9;69E%|Z=jxH`)DIXCLibADCL$>U`%k%uU$T`U=H=yfNLB|wbZEUQAT0>q`CSY zt!?=CkR>iz?|lV%!WT-wBJ+dbPn~QBwOVtRKIwXTI^Dakd{YiDEl5HZqaSeTZg0t6 z?w8%I{dLWvRn=0AP= zOot%SNMepd8 zi#sNMP^J_pXCt@|z7yF)>;zeD=G97ioI|T%-IHHaaCGnXH%eCf?Sn-NNQ`Zr>qd{C zCZC(OTvB8%IaAAq(+f}Ed>}0;PpZ_OR=Bq_AG-$@2Qq4R{5yqUQJ}-ulZ3-RcA)q- zYs^fc`jrGwTEVv|PD$mnr`rt~HqwosG)Hs`)UMjkW3;>F40PV2XQQu8N+K#@Kc+{N z7G$Vt<6MQg{23ky%cW#Y_YVy`rx8VgVL_DpF)|uBok2}7fK$^r{e@A?IOyfdmfWG;!|&zN_=)+(Yl3M9pWp>)+Hy$<`GZB3(3*$8En`7c~A z1%ZXaVJnlN${)(?UNT-}zeZ1-At4H={3wM|;}onI0NOxal>$g)%7!$JRF5`M89=77$JHPYGattLv8aw8PH% zY>xtI9UTH)cdS$GDN>rYb|pIo{cM!<{{OPyv`lt3Io?GYBhD z(?}gHEld`!`m{T||2+W~>`CY+Iv}u^W&+fQdeNHC35+xjALT}mon~3ZAN-&0_($74 z!NK1pcZM=olpa7cWna%*_N2~U`r4}G12Cr~1v&`nI$-_)U-+GtY(NC(mYgQWW$FFD z?XI?;bz3+5z+Fel+ShI?!-+4YI)oktDJ`p5E)3FZZn3mpGOTC+p7>zYjxJpFi~<2W zH@~0`0%~JYRpX}3UE}60e^N@j^nWdNQ?jg({%rK{bdHu>WN`6-)y zE?`{@bBON72U4(@b9xkU4pANNw1)N(p>+oQeZV5dmW{y14PZxgimE9Y z?IyM@aAR6$yW<~ibH@&DSM=EW6MBIQFHN6BDeP1?XQoWVBEOyQ_)*+jwjw_4a^Nv! zwxEtcgOCbeZ(uR0n~+Q6eYjjS&aVXC8Kp4BgiJ&ba$y{;?FGt){0=7yWw4={v$wv! zQFS#a!&$#3T9Fv_4LT<3T}CDAmH-RJ)Kmz4kF>skQ5j&Ban!=xdS^A3@-9)6^&`T+ z19myY0Tfn)WSQrRoxdO~qUPr{Zg|T?MQ2g}B|1s}E$W-dxCZK*_bzP=D+wNi(JliP zIplC;$R?3V({u|UYfwrL4ZrX1h9USQ?~!KXZH)&t*eNrYxz@JDZpYRa6nQP$^QHSd z-6#Ef=B$I5nbUIXy01V%`~c-5s|s{=iDrfJ?Z|P{w9gQ`zEDX}q(0p%SS*P+1U6Xnx^MshAOJ~3K~z#| zBL@Z+vv;lJJWs%)bJ{Ba_l2uIBS3WO=x#N=KeT6)yLsbs=9~yry^wig9Vu&GOJB~x za^|PbUXv(P*A8mXKDu(z)WPXFeCqH{3C7h88su)>xbCT|54Z_a7KpiX{P1?E`d++v zMtTJFc|_<5e`xvrUzD2h=GVU?z{p-j@tr^-fetmK|M-|1*|WZ{U%jNgf%qW8YdHUu znUG<_ZUP(^uKu*UeBrcc-_%@k_Cv`qw;1*lf=A5RsbhQG;eE7^x}hAj#vvcg3aYt*#N*| z@X^rX7}VgFKlmjD4YsX+&Ye7pBCBaW5L^JjkDWNnz4P)vDxi`7xf7X1TCYr*u}ncL z04uhsl08*qQwqW2-2#e5zSk$2#r&j<>TkexlRk^7v+5(TIp>uPNevz9UeFSW@DM@4 zIe=2YpG3f7QWDoog7@qIy&0+;KpAx)7weC1(t!I>4ABb^u&}r>{ZEP%gset-z7ak571wAQ%*~ znc?5lj70KDJsTMrfEEraMdBzTS{xw{7Sn^!lZq0M$FuN%)PG6HX4FI-syNXcxHy;s zp&9QkIEofHDKw-Shu*alnIixK#pbLFn(zYXOQXBlJM=q?*5{`B<$NFm7JVy}rslCa zGyy~!nj6bF{E$T%r`V4$ zQ(BO{Da$P!iF@p zxR#NV+_ZUX)d2p$hi|HNL+E)p2->91^$unJ2*S{7l;9uxdg01XYmd^$kRg&KeeXu`QC^9DP});^he6Y)U^j9O>D#|qLfap;mv6*y`0he6U%lsj{cfpFX7aWCXGU%LH3sD)Y9E z7$*dMq~qW%CH4gBFY|75j*w4aOORDG4G5hlVkq3Sb~d@H+W6@2b*mL+*gcR|nZdZJ zZrKB0RLdS(2U%MzW5=QSL9Hr2+uP6oy?&SXdu|sj@~+q@RH3OCKeG2dF)b>$boTbW z`q~AIi{8Tyw_&`>_`o3 zkYfrAz^2-~`WmY08hUNDDvM22`NG*F?#%H60y^>BCo4Mi0VMm~JYE?S9A7y{idpb2 zYKDwv|A|>?SC2$kO zm_+SUoh6{r)CFxnT74sXg?VLvA*w~4CXLduHRc3%h*}D`lSAkMqJc#Z8r43hM@}>u z7lK~|#m=1ACr5nLxHdPjZIPUA`p-!yE$qo&z+zu}wq)M@c(9MxJobm`!3ULp{YzhW zNA_;c2AYx<8NXp*vA4~j^V<4vrnas3ip}_QS=Y2kfF*nLU>hlSA&~gcGyk=MaoBXI znbgjatqLV9*{oU?ELu=zh8x__B%v9yWji+gT*|i8$=B5zK;dkJ=G@TOqqk4+E3?Jfs`bq|D*tJ)8#8f+`fvgQ-+un@)Fz0};9Ie;#!sFrD(e0Z-?Cnc zv=u|0zP4U_4!=54?8Z%;C6O7(;dhEQUkQ0<8uhodTv!BkT+wH<>!) zc>?FWD|N}(MzjMEs6t2)z>i-ewpyr@CNtQB;7x;@yZk9PVe(wH=^=|2XHRucFBm8> zq@FJ8m90{p?0T)p*7tHg0N|O+1*@J>{WO`@&R_VGW`Hd+6|-^*u9 zpEnEV^5r{yKA)I?T@nGBHfN1%7~146oI5EN1_6%#GArV>k>A(ZXSquyVfQkMeJ+7d z@&lz{(Sx*5q;3tXZ80Q`jJuIC?vz9{3Sf3Xn;KrCn2EzsU9IdEDyRS!^~v(l@mTPr z@CEyzp?;EsQt7pML<*VN)EGGZcxBnJF^#@uKid3JpjE9ak{*y*Qo`q`V;E=P`PT-TM&uqVK+Km2+BVgUSUv)8z*SKFn48l2(au$HTw z_)P?h%q5P~gtqxwn`)Zu>4q_&OMy+82W_s>?4WI|bVrmqQ1Vn?eIo{oeNn9AJy$`n zgtdpWH)7Nz1t{2aM9--gCa@$GzoO`^#=?{aQTID@a=)BP%X-_IHX!PIi+U+|UnFGU zv9?}L6t+oC(1*1s5Hx7;FgavNU%TWzynPaU4Y1WlO!)yX5`jt~4v`!WU+Wd9qM`O$ zPJg#KbyjzX=uNlI2(p}JtE?uetK*hYOGS_Mwv*p^mBP?QLwmRmun0xm&K1s+_VcIQ z=&@4;hG{1tKpZ*4f!UCCl1hU!rI0R9)w6LY=!vsGUrL+T)KGiRw%3x{$!zF;U_jAU z`6m{muk>ikd@i3|@`qXP*Ye;o%2}5c4e4#9%4R0DeQT6yBBQrxHCa8&I`7*0vT6o{ zT?qAxMVUp`8fOfYL0C}iIr_XF*ztBEvJ_fl@xoA5xi1vZp-rQuQaYh+fxx8Bl`}_l zuFwMF%4O>P+qK`7d0hQzH)qi!?x63($r=&`*6%TbJ2a?2ePoY2ePW+2rx3JB>b=b} zvX6$hOmMRnKA_SRYG%)#{KzXLBUoImzO~clu66IPe@?a0MI}AGueDsZx2j5h#QYUc z3*173pEPZ;vWhQ!@6S|bq*4;OFE*>G6*21$h{e|cc=Oy-XRns;bmqif0deaYIaG5( zy{GCDJ32I$S1+EEz!w4I0R92j%kKXjDI|Ze@yGfOHp*(>k$k}Zkeq-KVJ+dHxrP=J zMdcrb3p)=IY#q6gIj z*rkj|Xum}b>GZj4^}dvSL3QmFC|1Ohv?$g){lShY-PCrVcEhesp42rp2Haxi+%*^Mr5!u)Q#;^?;+9H0x z>T%>S74$C(0uC9+*14Xl9@o&&qq>2J$SYw!i~FfYmTYgN8Iob&gsQ>OMoAqGeZ7kevYmQJ_Ov z4OAs-YV|JEixClq-a;J}^hed$N|3`Beis0SyooHyhL-~wq1m*na${R(iynxm4ToB# ze2_b4bU(Q*P|=mM+1YAQy8tr)g`@{wVe63C)wDHK2%rZH7Jb%Smo9+peI25`{2pKh ztAe%=I4WeJ&YeD-?6>%SiN)|v2TiCE!C`C=Ku{n`qBkbg5EM?iF2Sfkv10F-Ju;_= z{RcQyo1%tcqCNo}`5(e#C`R%lW$U0^sC^?Om^i8mE)n3V1ppdFR72+P5du~A9>%EP zPm_wb)&e2AANp8ghj5gVY^0w9IaOX+RoC@^6E*_b1#ATNi;@Rx9pa?+Xu-Pd9Ol7d zrL2^6KK%8n5aeidOYZw^w{Yb%8c*nMID01kmAb|0h8Xzn{j~s#{=Bz^P|zS!Tqk<)wq2--qcwwp}cOZsSN%S@55f6x$q&^+P2W` z-??4@lnlKkwM__a_L4`{)?(}1KTwdWzhE&x4+Nh=OA*?V&>t0$OcrSHyGuYQOa!*(pj1zMc`adHM2WzTr z<_b4?=5i^(qCT7WDc(MbZt7|KK~I8lC*VbShz09&E39mbe>Kj*duzJ7BtgR=#S5+(EF|lpFvfI?F zVxvlY&-ey?opaja-beClD=51baR&x&`EqZ44=h%`4DP}wt6HZnPJ+o8CM|;Q9@jX0 zq^M6S2KEa@07X_>@|Ot+O0obb9ICN00HDL#Hz)(yXb~Nxdp$KMPO+O2wBBG+QH|nJ zcVP_f;4SjUVU|`WPFSiNH%l-0~%h~C{h{z;ZOH=jm94mE(NVh%PZ6t%FL zYGoWyoMSB!p~J9eDH&zr)k&)WA9b#8Q2!_D#Rd;*6x9VueJIfaivF2;iS`1J)svng?V0;!nRo9gL=X$BO}pHO=Ygero7P3CdKU;O%owo0Jn=>9Fr zfUA{;uZNacgT!UbAq<&D6AlVJNDV9+urnbsz5~coM8B@V)i*S%ei_Og84?&Es%@^T z*S#zlMFun6r&eGw09EK>YL_DlswtqRV3BA(eR(ZvZcaBxhKW^#TE)OxNT}pq85-v} z1aWkq?hcJ9W67CfEr06toTrcNRW_*{Wh>s>y@ADi<~eq(aR5$1vA%F;E_~3fdgS*d z8iI1~<~P3M&YwOa3U2XF-esyJqiI))Pm$b8AAps({jZc{7Q?#FIm_8Q^|`ysK3K0{ z(fbN~nR0@4pZYg$%JgOKV*4r4PIqs4NfhN!K4G9Br>Yqdve}QYO~}M>PJFa`gX&?) z`f>iS?f?~`-?RlG349_z)#PR`dPvmOeLLS)-73Khf-xwgvQ_|)&{&tO`@HIp0gmr) zcuv71GF+^03I0Kk?6{>&+vsuA1OQ>v$Qf6*&Y$g7mNgvLI>*gf`j~1Xsf&ZkA1Jqc zmVLft&F6Lgp}0!j^X-5|0#)N$XS?|;Kc#(778IZgK!4?jf8mbo+hV{s_y)Pz#RiZ` zM4$#R$XG+$y>a!TJ9==N-VwIIb!B1em1HpWWLk!d5Q~k>KKE5iv5uSa4R|Jk&3m@J zB25hDt@Gw}l|U&u;q4c80~%;omz}?A^+O`V`+bo3zI6 z6j-!`Pi;~{ktBX{^z;6`Lpc+gvwppt>v!aS_b$@w2vkj;zN`mh%7NH4VzeA;Y7g1? z7_X4tRs=+9n?!1SVyHkYBJ{;E6+3fUQ0&71&>u^OAxfy;8IhCWTRrHWon)Ep0KQ`p zio3K3N*&Q~W54LjL~uflP5NmMN+PhRD7u)IHa5^&IIzh2YOK5io*F$UE1Hn%7&Vz@BE)D@sMh9e2U;ZVrWN8UjTnZ)oOiLikGhfwg&J(L~vH3$^q zOZ12uguz2y``IIMEHT*DdL#u`7Q+w!KZ2a?uc zL{}>Yi&^(Eaec}}yAn|84S(1N^rGUOj_%v+Zr%*_3IDplVrKj0`uXJp3b`GVd^H0& zZwD+!5z;>0*-F5oEhfvNP)Af(uev$IhE-f+%PfFvtJW>b;#gi35#$;7Akl$Ah5B|Cs4Ym_NiC!vR$ z0Z!4ze8cRJ#Z=8#{a`&4c7pGcHA2-HAdX{c&Yc&$iU!v9c9ssGANRN}GhJ|&$z@zo zZ(Z})AE+NIncjC_{U>+&*q(&SR+LvPJ-sRii+Aa`Ds!9C{9j>4Fhj#DvS$N7y~~2d zL^<60eJ)!4Ik)t_-x5G*KX=USeD6hfXz!*ZK%(^o<0n3UJk2-sHD)ih%~~OK&tnHa z(D$YA-ou$lfTYfZ-V{U+fj%-oRjzH;D)r1|kMG#>yt{eriqG`dxZ1ip^$?_<5#bs@ zEoT`30-%GB1%314xs&d~xug0!Vo(5%sdHATO%7|@DEd$gttA%A9O0^Y%bpMz-M9S> zck;+i{~4KXrmG=jz)86Fbx#Mo+n5nuBK%Ag(7z=zHlvSax23x|LQG#Rl@wL|RjtJ{J|2~nu z54GEY*)e0@eX1Wlv~RQ9{XU{?H@#m*X#h0(n{Mus$K2$Z%iOjN&$$yvcIhNb{HP=o z-=7ds7A)fTP)|+WDvH3WyEO-~m^~AIS7Z$$aFzttquSFXNn{??ohQ%V%PjtKkAmFY zt0vD_)`P)>M{bSUZ)j1=Fd64hhqFXUoKxyQO?rpr640Xolt4Gt66)@@D6pEuds>mF z{!y1BB|L#rqm`J`VFqvD$IV?H;}G>LQNv3JsP;fbU@@VsriM9D5liYHQ-IDD1MmOF zwTr6L3D-_)^oYV&Rm=Eh3ffisLsM;QdMk>AH}G;qy+g`10izhZA;U&kO+`(Oy9o^h zFy9O4OC)$|;f6>sK#EecL=3G|pYNpOZI!@m(qfi*}X}d9INF!jzfI74e3G=-t^nwm8!v z>CfSE$8O*M3x)P2aV1OQ$d@CjWp7gm@cMD6B*B!V=inU}JHMt0u&{#Z~N=+!a46O(mRnLPpBP)66%E>tTxErfvA4G#zJ5(d@r=A z5g_aAP@hBO=C8D$kpKO-fD|JTf0!~@SE$Hc%c?_zBDnszk z6zJjrJPFhAXNL)JU`Iri^)=C|FCt6nX|Avy$OQ1iyQ(&xvq$}7hiO0Kcq^EcFeDyya-AzP$gkA={d(t}^ubE$ z|85)5H~OT2nt>~=6D~Ou27Y>%JcGYq2#4jrk}YR^fe@i z(qnyi(w-+?o=$X~vf zSsai}zf)gQ%_0$IBDX}0adxzMFQ50Br#eM&SnSld5&cR85(-k!VROqM`DjL{ZRC4F z1V@GCLx!tn#f)8uj;C3l+u1aCYJe)bj(1jK{(H9ht=~Llz+&M&@)XsS>nrDJ(4Yn# zGO=Q5xTgxdtDFbn-U;y=4bV^DC-L^BS{M$Gl*Y3bObaz!(6p zvKTc+-JxxWr=bO7#R0}TBExKTu9lTBA&`kO;836GXO&Pj{k3DaE{HEBHEcec$G8k{ z9_JN!hwFKXf~wt%>Ju#pVdt5F!~h;*5Ms%YP;VL=$KGhD={R%9ahOe;vs#B8QDSpy z^I6g4Y3!MNlVBWh9YTJ+O^E#GV`GX7`@4Y1603T;Av zz+!aWJ2GlMqlXiR6VNhhq5?9iQ9O0fU89d_B4X9s2v#YpIBEJ~?Q44XAt4`}7$W0Z zK+vju?IL~LT#dAhHL|hO6EfTBlm=0pYVCV${kVyt|P`K$R2;`Hp9iXg3Du&u??QwzQ5maATW&j+u%Q%Cn0-84iAIU9vf46s<;aJAYWkVPW1 zxOe;O+N-kNs`KUUsVEffa#lX_6*p|yNVoBgZ@J4C&bXNi9@JTM_@k|AsnIfelCo^H z@3?;bveq6dpojKucGoYTch|39()q=TAhWk%#nbvb>Yo50f1>$6xwmr-Lz>-+hrgs6 zz|F6J+xIH;tG=IL5nAoywVzij4pd5^WJ3vs`uW;V{z~_-I!Rwzk_#r-zgH`($X=$_ z5<2R>4__Dfq&!LL(7FZ`djt8Y2u)-g;!K=>W5y66FMQY#^d^XK>eyaAGnrcGx&U$P z@}>5Vbq{RoZIPR^$Jr^9NIOtgS6SljGv*yklsNmn0D2!e$Zfn0HPJai6$b3bHgTJW0Z4j zIi{(Fqy2_O!F^uR*Y;o#Fnl5Fq@z7oV^GJTX@IJt{)uOgxJwt#c!2<$iG)rOdNg_fLp`YVjq{S)w*eOUD&Ut|#Y6kvbC=Ga z^7|u8rwzG|U~DD5J*Yu77sOF>J8R+5C=Z@)(y3*&Db3R+2V6pGaqWNLP z{Vw}_oPI_nnUl=k&E3F$Z?f#{7urHJqk39htrjo4@aDJx03ZNKL_t(%PaV?!alWO5 z1;z7iD!lxIZwOAKZiET0UT${>cfaGVTsddiG+)=E5fWGg%v6i*5duRz3xT(Az?=9B zd(5KqJeO#7taIO(nhYQN0Sa88{#z@IbS_N3e~@~qEnf3kIaG46q-t%nQL=@4Mm4{- zM%uC!uts#YSdAtB#t)7mzYBj4&WB|V%u(cfreJ7w)PQjUSWx$j)=LYW+#1Wzae-)3 z_(pGF5&9|iZpqruyM?Qs(KBpW|9!XZogb@)JJg-_4y?kijMsHBd@6sPPi$wG-7Xb@ z#pK)JG*3r$pa3y_pn|Yb#A$}wi5l(l2fm~r#Q8Ia+|I2p30RStA_EOQI?Jf>Wg0M~ zd`6ynN3vy5#>q;4v}?V)2}>tpz7z?c5s(};Zn}CU5==#b6A`%N4E8Sq6Q{1OL2VS~ zFMmocHTLg(OIbtObkO(k_~9L@XB;+sq|QHT_{f3*d;qPSkAPvAF;_00bJwr6t4$0_ z(zMs0AEWkRq!D0&`D$Hb<%3_AGV9j2zo%>2Gv@7bdXi>;2Za|vRV@J-dLa_TZ5};Q zfCSt2`j7ugJskCuD=*NUl;Ne0u1@|0fhTD1fMo=Jjvm;mxspA&Wp&8mjD}T^1a1Af zU9>h8OscKde&xNdU&VjukPQ6JFM`i4?KR@5CCf+S*Oiv#0^5um;%EcJXAL`BM?G~QA_!T<^}LYD0@X?5!Fg3Zr9hT6dA9*gW*J8}xnHirPSUeUQGJ=_h=Q5Yj`_ZvIY4Q5 zmuqSsqi7(7^w4F3184`8&&0`>H!%%UNK7+%d_=P2K6-~dHgyMbUc0(Plc7<)DIl6U zV>!C3KT(pQ3Dti{CqMKud~ z&=x;OpvZ7N9GbRS%N>ewM-FU>#GuN7MSB(X@fzAJiXVTXj>msPpT$9krpNnPPrB4V z-@b7!0%|t?8Jf(17O#D&_sn8tE^6WUSNcq!1Xz@i#1PR=$qwM`w4XhxS~}=(VSQM} zFDdo*M0U|%#gjZ)TN%=qcr3(!~3p8iOYe5)Pzdo^Uy0gSZ3F8^#ur_$$DjI>Zox7 zVWBW4){D+)n_OF&$s5-d2qBOdR80j_rJij{+kBTZ2^&WJF`3qrM|NpX6#XQ%$4QW* zHy9SL%QW|BqCvH8-m)j%iif_WeYkh~8}6N#|4|HuG~5|i=@dOp_+;LZiq3;%C6r&p zy#*{PUHbj`TxB~kT=C9>#lri`?=a@k#I}X*{-^(~dJ9ACC#y$xkIa#py(7$b`GU`+ z`RDY?)CzpSpz7>&<0j3PY9*Pbo$o#GgNj`eSW|W!T69$JXq3nvfgS47s4d*_-t$(w z8d|?7qiA$+)-{yC`=0!-q$K>-3xBV3W%iQCw7<8${e274sLY3;Q;mY0sDQVOo~Y6c zo)r*DAk>6*x8H@OM=Lv3=7|d|6Q`l#jizf197a6O0%bwDIqq6z>Pybq400{_#-AGX zw5P}2x^X43Ay#MV6_>p&OWliL1*5aimq}4;4M<|w;YTQ-ruuH|62e}CT;tFd(fpyS z0@(KNd|PwP*$)tgu@L;55ctpNG8BTBDmP~0OtCJ`ojL4wZGA~LI|L76K{MuL`Gdcs z8dri(szjY5R_IDJ2V?JLsdB*Y{ zA|BnHH$|DkDDh(yA#?HKqrqGe+pKIpgbzr)Cy|s~(^reI4HhsQJb0KcC+ElazcCSm zEN}bQ7A$6Hxp}9cOwD4YOQ{@SET94hkQJhg{HZ7wnMKjWEUTBDU7yia>l11l$y(GX z;wJ&5!9z5UIBLvah?WJgDEhI~OoOz43Lq1zCq6ASRYg%J2`qBhq58(5lZYb)+FmAt z7gPtW7R6k#DmQGzDAzK^gluqHRiAk7m=5G1C{jXG^JB?-Q4=y^WUCqrlK~{V8QKQK zf(AIQ>5NpeV$i}E~)6__tH3pbbMiJ_1u#)k8GfV-qc?|X7AwwmeGJM2XIWq(~ zu3l+(r;hG)7tfw>H*Q|F>|J0mpm3_btG*>gFf|^KvazY#vJ9VzTuC(*AmqWOeuuDw zf^}&|Qh?1rr)48?rbfDD>kzk?to@3k1^BaIpVd1i?KqDQS-5K>gA|eJ-mO5+xgxL2^CX)7Y7fq%wk0S zRscZflC3KM*xaR$i8fBl3F_uplUi@S4|KvZiRiC@ky#5Lc9Ul;bH@(8udJHRM_+df zKm_~|WC!>ySow^Al@l4 z&Fg7{L8%7d3Sk`TBoU({+m5{mpo{fF_Hx<%Uv!5LY;}9Ly^{1YEzK;JUmNVrsk2tO z*^3`m@D=vN^m*%)?R@n||JfbfyD?=ldU3)AMUbtjMPmZETA9(CNh zmIR0ycLGtN1zS=o5?E;wfJ_u26x^jv5bT2?@*`m8$kz2ZT@O|qV>e;)JY{zQQk19= zq@%|seKRQ+!1hAzy>jWi{zU8umQ<=N9|90YjfDwBrkge*sL~$Zx5e9POcsH>)Z$R5 zxoGug1myN?dpVo+OUAFiyWRE-z6lv$GUoUS+(SNJ6zs0t3Zy}nQgd0bcSA{!|8Rfb zpzL$q%PjVL%09_2RJBfB(nFRgM4N+1N}}|XxqG1Und2@g^SU}2%T9ax*acvh z^`&`wYo@K*qq;%*EXGolR?WAyyr5>v8gu(hnI!M6W+U`d)3yDx#-bt|K-3jd4+N!) zgRZ0Fx`_igD>zTTYY}D3dZYk{`vRi4PRr;iidu5mpES-h|Yp<443>M#k6Kw&A3#)c!oGCFNDm&?gLc3^8HI$~EXbe$qfuZGb9 zV(T?u9Dq2m)?W%iks3Mdw-Zna&!1B9(q{{qet;qkr^%dgXsTykA~KM^M+)3~-)JEw zT=*%!HrexOwp$}#+3u|bMD`Ob>fV{#2T*KOBy1)CuVw5MM_)wiqewRUlCMowN9f2d zswgj$EjM;jwWCc9jud@Bp-hn(Vc!8dQAE6S?xeeh7)EGj?=#B^mnaifV*!)|2wJNE z){z9M2*%ZT8fp$KCVdlg?QVE3sM%x%M~|Q8Ry_D+?KxA5>=qbQS%RyQU=7c~zEi_% zUz^Bx4Fp0f?GU)^xOpQ{KCJSBTM`lR43nB#&I%_wI^V-i@DB(^5U~$+j~Y5Z@5*p$ zHc0Bm^iAKa0Tw%R!6R%EYhI>|v6!qe<|*~cos zn`dDq;5B{RQm|ObhAsC#$-NT>Q##_Xljg5_#w}X;8J#@@sJFiTUDc%-1IFLk*BOSu zO4uJJ`qHQw96xEEo3UV>GC{O_;QPjG0W5YTVk)sxvqW{;7Pz_eV!VFI?b!SaiKt*F znPL1G)yz@j-*Hp@^vEi5y^XJZQv!lh5vAF?S;8~`kl`aIC`*XAO$fS#F`zdvzy;AM z{tflhwpptMQVEEX-Gj19=8t;-8fmL_@xp2C6IxU7osV{HaQi-dGm|B)WRBQNEo0l< z3h2IFw`AKywH!Xm?Rf76_wo<_Li1oXhUs1m|1GdsgCgu8F_MOl9H#&(=NYw*WEHKX z#TZCxWu?07h*{*XtIVxu8t7&@syuTnQNG$b%P!KY#|z;IIC^?%eZx@IlwZGgS$2&1 zW-U?&4Y*fZj-eyOuB&foaM!O~a@VdxRXyp>pFJj_GR|JEhs|XUM~|ECmOo^a=#8&^ z%P7gAI^WYzL;2P8`46~R3mIRveT~pv{e4yI^rbySc!R(U#tvE@purjrM=5`QT&9_# zz88gDEI;W01+qyd9gT!KO>+T@*h%CZ#7~K`TwR%0maDF*a*a)+T|>h#IgU_= zprUc`VT7qe3QgKe=*&J!hqDMRhgy@7qbKPwqTLJ5Iz~P2hZP&jm?CU0j@6s-EWCmG zdv+tr(o#$brRxQ$o)w zQM41q#}rZxbW!HPqE?Kj2=dz|q zn~WV<6Qbfcne2({S1u+F2>}WO3ka@+@&M~sX!KD9Xd+~50Xtv&mjpa46B%a~xsTDs zL#?g>VcW_k0Ks0HF@K$#yYvY;rIzip9*b5BX?2kNJ!BghHO>!F*?s2H6jZM%`+an1)M=f`!@VDb1Jn1vpclOr5>P9XYVojh{Tn&0h4V zGIB5d@Gqs-ti2n0Z$~y$Z{dZh8XAYWAw!zo$Z=ELnDH~+sbjm8eIo!GYNZiaWDLR~ zsZkHXpB|Lkud7YRj0N}0E>aU1Q-lfDVNXy2#g>{fE49^EMb*80`K*9E`y?Aa5#;Tb5loJO@9Q5?CC-aNr2F=l;VR5F?V1WTa zt1Ad`<+3I&%)2rhwW>4W9z;Gx=LD<`X%Za>ql}@IyXR>Qw#E$9NgRiaW>2>pHMT8L zKWjgCLI(m4oz*(TSx7%n`PL>Oc%fQ`24#F|>IX|$rf%>McT*s?O9wF-4l*c2kdusF zq}&^(B4j2wT=_wKKx;eqJiUU&qIr$7C+U&mGp^A%^~X$?%|`b)H)zOEHGEdvm98## z?b=0m<>DEOAgi8){fc6o&njo0p?}9j>Kqz4q4fld%Ia{!TJvw+n@#8^Sj^8s$@v_sgq0?Okv@{JLtJ*k3T*gkC?FJ1RYE)K{ z0%!m7&a|gN9$+UrM0d;x@v9X zYqqoxyX1tfc<@VZ!sPjKl7a%WIq^n=Wq&C1Of(<%0sr%0m3#0Utfy<2+f79^X^rID z^#lGaWyR9XhK<3#tbXJxs$=6twyyty>dJ23 zKmi&mueA~hU@=$eopq3+^;i=0O5CYj*17P!t~gv$*=b+lr^=6G>GKR^%roaoVn>Wo zVVlQ~jqI$GILXR~f6ukeT%n)|b%KZu;SlS5@WHg0mS~sZdKQof*O|TWVK;2VSOKWx zhdwlb*wd3_nL_ssR|iQv43i7^?UX=XVcWV_euHnz|QsV;GTCB zuv9Rnrbe}qHPv;p+qASG=*0g}VeRhebX(Uyr}3)fC+s7}02(WlNuG;7hV&WbJlwtY zW%ue&{Y^T#?{zwyiJB`yuBN5FP9`^6{XW7XhnJ02TV1aRc|HVDjxzYKaIO*JLfo zH~`qLUi#RpvsyMHxZ9x_G0r1xT@U~ObV6stSs+4q?b3zPa8}L;TDBz3VC(%j=shTb zP7T!zs*`HucoA6a=JR7+>-44W#GxH3mgmqjXFY}v1++AuS4`{x!n3CjJNlj4HcHo5?-`o- zwR+?X7z&u(fKn+RhN~r4WQa)*Z6G% zMf$uB8ltE_O~HLseIr5s-1-c z28&T3G0->!7844FZ$@8JtE@I6D>%T|hTZSKtl(l;+h)tL71?oA00e=(K@DnBPv&XT z^rdQ64(Pgm)hOfaEkv0ND8|>YtRi*9OV<6i_7uV_1SqKuqp>_$KYlnfaMGcOk^!B! z{7GdH$sqB4GFF@4__jN^d!v92wR_Yi5;#5g@ey}y|NBW@9eb#=t4qLxKoH59N8&bSX)2D9oe@@HJnd<@xRyj?%MjIDW~=z#CTryg{Xk8ef*C_ z1wDOqm)e`GdE~3o;duKOf9n?C_jxya(If7IcYf&h?_948A1z2WzwsTnZ^xSgfnz7m zvf#1n(YuctJJr4VV*|!Kn+XsNlfB^g0KcKb$0(Ca2@Lh>DAw|BtOwP1t9N9z^atqI zO5o|8m;Whg6_VZ0W>fk{=j>4ce#)#>uAyP57%s;TZ8x8z&q>cSZhEmU@wNH`FmK0T z^%E?bJ?%F-xt%BcHTdqG1JPBp7eA`2vA}VFFjQ(H-OEDj_jE*H(QJxk6cf6LAM%)1 zR4k_PYcMx=>Jcm1=mPnChG1Ay4`S~p}^vkonj>(++S@x;%D;)$%Hzb8#!*O8#7_1tFJd@-H%Tl)L{c< zw$L#40T!iJ7S(TgJEO>A5O-3vQ52agmQ9P=C1j@AAG8xD&2vMVT10P3+5$v#R2D!a zV`qwgCE3x6z~TTMPCpLNa9U?95deS^gbfJURQ1=?kM+8fu!;6>N>a~f=ZfAn`HX*` zg25WED}1lu!tHAY}qA zc))uj_=95Ju|cjV)iNkKgo2dw?P^{EU%(Y8?*EZ#OybXB65 zPoI0ATlL6SUCZcJcWCcMx8db)h~PalzD^3|*DUN8)qAq&7I&U?;D zi&+xoj)s1pr+4a%xdYcp-cRRMWD$CCRx{^*#88Os0UM~hyTgqfH_bir+5c9VpmS%A zxLsRbu$n*YzE>Yr(4oed4{5s#+k-)vY}B}^ZrYqR?&5`0q83x%N7(>v!I(exmHK(A zeh!K?85;|r&R_PFo4()y*Z%QQ_1Yw3N9Kw8*5e1a>)z~}vnM~2pv(iG`Zr=4oI1Ko z*(m~$oS&Os{if7O2}%G?5Ln@NWCWqql0j!bs$Ti(B>@xe1KpH5L9TB#ebn#;d!P2> zRh?jUom;TtDK~oJOeu4oIP_uEKh=YSBHtn@m8cdtT)6r(0%nZY+Q zG`6S7{jlaS?v0=PwN%`n{?h*-W)WbYj4G{$uzj0e|Bh5Z0b}pI@g4hpZJoRC$**ah zKm}$E;WyA161&noy45}QTmQiw+Vig4^v1uqC2O8l_7OWuS(eHI8iu)FeCL0Yu0rq+ zY|YiUmNApug5{rbLr09!yZ|PxezRNlj(21}FJC_AZeG2tY%w~i5RcP zknF>OfJNs};(3Xp;}pq{Z=I`5Cp}6{%`I!(iil@CgKBrBF4-Zq$PhUW4SS0~^Z-{? z^0f?@>8a9Ojh;B&T|R%>b@gNm&v8%akVLQn@?`0>RT0+c>NFZCnY)|Jmno6*Z$SkR zCke+JCr33#RfsuRYb4e>&L?|BwrH=QdP6^5! z*(IDvo>i)j1^sG+gVWa&-p+Y?yLMpU-?xZh3Wft~#jp8Z!D86kp`T2)$+v(vwZVfM z-17T>$IV^(xNARmQtcXcZ+$^y_Sv!k03ZNKL_t&;F0+Z%VyqBEY-$;&xoJOpT!9Ac zIkZ6pqX=@MsLL9KUJL*l-#SOOhKwV7j;wjx?3Ky}o;kiZ5mG|vi2Dy6K2~Kp8(#Vc zy)%6WZ*^RE2X}4|#c=-eCv`7uKhN{Q#-C_!pq|QEbEW-b_s%QdkPSg;clQUcx}*Ew z(=*Op_N3Se8(;sn&bQEm6x!>YC66ncx^v453Sd}Z)-xD9Ko92wdx-4V(sjSBKq?@~ z+RUU1$3=nFxE`HM`n=^&s1$*gB-7@uadVeEt}%M~M}O%K?s`XSJ#E=z0*0b}PF>^{ zul|exG>`uMdU)n5|C8>u>Gf}^|7`1wWm0ElP6*_zc<9RlwFL3_lbTSn z(44D}|JHv{s}t&wJ8#j_r`|pNd;g=mbncYfx%GK>|5JbBP8{B)U=e->ARQIjpMCp( z(f&{DxdK+zZfxruw|MR6)TV3a)))0104C=-wgTWx29mkN4swo?)jqs$lYoEbOwWPE z%J(FKg!Qg<+9I75*dkO=lZ<&L&lXbl`Ky=v_i#A>5`FS}nZ?SNLYYtAQLs35_G(#o z^+A*!vc6ks9YFdNw|%HZ8Is!`h2QiGRN?@a0o1)Y>lxEfl*Nk2HEQAuXjCnMWWuAL zq`t%=Zl*Ab-2NCjx@4%XU2V^aQ`oimywz2ibbm^%F$0CN7i}@fyzqIVjyST2PsG%; zUY9})7K0!NGVH@gDVsw*hU%~)XF34rgq9T47W2-3$dL8)xbaiwxnWJCRjU~KJe7N{ zcz&QHkmWDR9s1Z8fH^p8=pl%3A;nZ7J?u?@Ej3=}@ z1V*5>lBH85UoAZ7cREDQt+g_s<|cJ=OR|by6s<2H=DoZWEJphXXOdoY)T2R<$LYk; z#X%lBakie3%mfZ6@7e?#Vpxl(9`@+{P{gDsCMt*>oi{Ad6Rj(qr^!PUuY}t^SNpT^ z@7QNkHzWks0%Is0^W4p%vm(wy%Fad^MlyPg_te>|RjUZ?`PhMNZrg?*x^o{NwlV-z zcZKcul)jHyv$rYO+z`cM8^f@o_V{e4Fh^Gg>_y2Jb4 z)0$rO$XDFKJ)7MA58u!_rnV8_1?`)lCz=i$U;Afeja1L>#hM8AEm`}lfE~5~@f&*h zO`Ee;XBSy6dO1=%hpO=O`Rm*(&;5neb_onYha@wE!YIIs@g!)n{DCj3H{tsmp3|Pt zkEhMrf19pAunj!Nf>qC`-f;W7Kb3-TsQru2kNgsd1CI z^y@pbR_|pN`)$4NC|H~{ZHXroh8&U?2+28McjQ1T8!6}`y3y|;`VII(B@S>u!D4||R!VAE>1 z77FY+WXYmPJx#W`d{!xTa5><)uTclB&WmU{N_M2OTi z-z%%k<7sAS%J-?z)>t={$8WjV#BtPKdLRt5q`k%;}rC-+-jPqpnm?MDI>0b+$^ z8KEXOea>2U{P1?It%a*Ut9=1rY#iR=8XH^G#)6uzM?U-SG?$xS|BgEisOs)?6WSJO z{w|z3V%fr#Piu||7C^7WA>Z)Q*99I$K(4NmC>Qj3M4+Hw62#f~+P76=F>dl)38!4X zc-n1v=^F};AkxA+z3~72N9{9SXu-;-m8qo3{qchzC}>2+44VMu7BCdpUYWHFgU4s~ zS<_@e0X?UW?-Mu;f^VttRl%9$1EKte{k~-F=UwxtiK4I)z*@BCv(m75`3HaQ4(xg- zsi_N@-EcmlM*y$~;J^IbpNqNBHfxoeJad_9{s>l)^~67*y~nl7=k$A&VqgF1|D&41 zIg1~a(kvo2>^1Dx$-_I8rDTjh^`-xxz4wl?>$=W7&#QzgFKp*x;?gJx0CFV$1R7JWr-ri96%Bb$T{bnGYYv1RkMEI zKIh(Z?|ZKT0E&{DZ!Hi+)qD5dd%`~Z+xy$!{@-Lrc5GOxvz&kw<9=k{CU^eK5jX## zuZq%&J-l|U!S(5n?H(<#I&92zjmfct+hlK!9@yj__~frEa7I1ypkWgPutO7~AIG^!D8k-ue9@+Bq5DPOl#UM}Dx8s?AqYkvY@(R?Vu zDDR+`FjZ~bhX9MGV9|1c`b3Q8l?$g0*p;}pNunFbNgQpIc-08L#v1qn6ub2mEi1hDmcvF-*B9;I*BALpXdD(WOo-#xc5Q>%thM9W>R8W*p zO(!5Mp~*#5)$p;R4a|25V4A=K_eWN?bN4=Sz;S#+Ce;95jjs`_wHm{#^oDFb;F90h zY8YH7NJs?7ma!f-W`?4^(74E=ai|)-klv1$1wceURQnJM0HpCtb9>F1(ZhJkl)tac z(u$#CX;A$W1B)frH{(KGB0Us2=tVs}cS0FOlXy?kpFS>NdnmS%ZDo_fS|D4|rF(BT zYQjANUS!lv7@^TsSJ$atiL3_e!Frq;?GtAN0B0>Ja5|l*s6tnzMa5OGE@=*>L}vv4 zD|N3pNX(^W!U_&xjDy>~M}O5BkvR?2DjY#TA5JJ#O+a9;{=-GLWBm|42ka3FL1w zj8XWYw$E7jX*YA>GXl?K2cVyJ?>)ecpSoDtCLGc+lNO3v2w22{Rd!Q=w^B8%*1n*> zoNIzwWVPrQOLmxRK%FGxrItXxp49Fy3e0AxVjuCD)1j|7D;DYx2M?R*3RP7CJ1EC0 zh?QqzggM9sX8>JczvGM4)O2xk7k^O>JL?n$Q2-lYoa}fA7_eu^2EO;oU+a6Zo9rQT z+$%&SM#!XFkA7lHbn7udA~UFpE`I780{HK}{B0?ra!qWV=I2(E0veO&e8TP8_?E!r zl(|nxs09jS!-dlVZ-BZH93=HV8^km$%X_-_r7eDoz zuBNumz4@bWDGy_>6(R+y6V35gVKA8*VY}L}gmwn>j zoXPVZ`l2B&hpVHc* zHzolLRBgjL9X)Y@f)~3sznz?i%m?;7jX_%GmHC8b%iL~W{gMKBX5$c4iZ@-yylmDx z3^IA(0!=2H|V&3d#2#{h8xG7Kgq zo$Y%Vt{s+M{=3>-;zjgR=v`gS@#GNw89gwA!<^gkw>cHLkF^IZ>SQZ+w%f{Rg!`2! zfNz*>#;b%{YHLp;dg3j~WYe&|Yqvg0ls!l{2f>y=SBbM=F+~d}7I7J9cO1G#0lTg! zFOfUMGBN^4?H%Qah8jEcs;>&aYi<@T2B0d+iKo`Ys;uR{j8l^P}fEG}c>S^4XB|EC|)3p~YQn%ZC;0QGe=Q|mH4t%2O0758q zsPK_#C!nD~L1mSzEL6FQYW8o7_8|9ZqBUfHZwM>`!cYyio{YDA5TsxnF-IdRq!34|QpyH1of);L+qxZhlUs?j000p5s-Lt_*+9S}^f>C4aB$bW`%muN38MifnH|4waFUrHGV|195-c-t4|TX8 zut<$788<*QnP98=F3&v3%3Q>w5Qk^lI)zK`toCOv+A^?qePx7QiyJy(iZbNXrb$_} z-E-sHy7)RpY%(kjGKP#1R7#wDz)z?-50vC_(-*60{A)k_1JSA#^r)&)@M6HQ2?Al9 zNn{eq45O;LY31{7&(`+^7SEnMDC)5Zn%RqM5C9=dh2kYm?fE{kH`G3IFJ$`ITZ2bT z5g^6>qIgR1V9T19wJ!oq9|4s2Uj8f9NfPjR;8Xuf?|b7%-*ne6U(oj=cvC-Vk$de2 zf1vv$(+FLgfCcw%{+JJ}CdD55Ng(GwTB9UESgS}L}|YAcVpWiS1On|=Qm1pHq6=RZ&>2hT<}j%@9!xBgzV zPx@REe1Z z3wE)dC@0`^tRL`Mw0z0#?~d$G#$b3oW87Qgg8yN?LVfT*;&YX|?#E!UEj#zK z{rkHL7AMYnqy>XdRQWQh0MQ9bg3~gL}on7V9}Ig!;AW!dmjFp>pyh7yKwr5 zd-v79QXMLp9OiyIZ5a-4*Jp4}5%)0%bWaL^lv(jt3=vy0{?&l)T31)sP5YO?msAxy zb&&%H#qHwxWA5a!J?_%k;{x@}aX!YA&yc2L(E3I%xdk(4Wt(B$4xFsE!U+^YnMNRp zmIwQ`uh6q91DM|7{`M!0{+O1Ej{kF`$kf8y8NmensMnMLN5tT6!=_70!to~e%; zGkKwC;3x{?A3>+&8k<(Upx%9b28_}gK67fHYr1(;^^wO9Zda`zdm4}jki>q!|LXs% zd*ZB^I`5NG--UX~9zjH9(PO`?J+$oQZ!1fU;LW*H2bG0_#bI{a)^Xz8do~Z{2xQq< zzt{{K!#5yC<@G0$qsIf`B-r7z^qg_5`w7z@)-xa8w_YtbplEU)?B4pGTl(CeSfI?e zj!Mtqpgmw2G_r^@7koy*jXlqGVGL|q^`fo`7=@-w8;rwy)~PPPN3X$ZUomp*Y&UxH zz3$Ct|HvKQvtF!&dmjF(sI`3mgz1X~?g$)HcSs+}A){vq9MdX;`QUp=KH!6}R%pFJ zF!a#gb-E7#Jjs|+VWgV1Ixd#(_jmAif8O6-7%_HE3q5df7y%7e zBwc(tp;W~NzuZyP(IY4!Q}{!i=$K)EcB&u#ywA!VK3{wwr05{)N(d}a|Ku|h?fuH& z&I7Edt%K5q0VUF^%oDQXarP+M@Fi;^T|rJOK#{*$0+-I8QloPswwWwcV#|f z0W54GP6p1-rE|wcfd=%%JrwOQE}t1{?_T14%;m89nMu=U?tx4%v^lbTtV=0zB4ooK z`XQofT2-xi2TTG`$U-{bd(9;D2?A87cN*;%iQp6}T&LR3T2llg)c(R16d<4$2>KuE z@63t)`a@8H?;JLInjCo?U#T5S{jXN)gfyi_k(I{fWO|6I;}CMTP_KkyFj+(dKn4w; zq|6L7F0u=OmL6|2-=oGEVKwT|VxV{5Ms0ZGN@pIjkOXpO7#(maLUL-cd z&dqPD{wV+iWd!PHx(&;plR!tdtxZg`_A_o9T|kMk0(8`N?&`Yt7@*ou#(*FXW57OB z#_{4AWmL(=lJQ6=+;$-5mQp*SLai>oj-J%5TM^k2Xm>5mq5#5#AoFH{#Oh*(QjyK} zZAS`DnQ`WN=AviZq?wPnOBYWmo3(rMGVQ-oX9x9!fJML_RLLH_2Wm|n*s)TAREW-O zTKS?oxM!_ImBvh3AOWKt8{SZx1?u6bFQlI=;w$tDo)GrXxnra{Y$Zi-HQUB-lVpC}^C3)s;)Xs{kl{c(n*a-~aBJJTSG9hPE}cJTqI|Wd zky;SN`U#`ZO0U#yYhQ6w=6+Jwynf|^d;Qrz5;(>N#X>kCFh#JcvfA2Nv0PCJow?xC zuJ?f9?&Oi(3Pz!3N(&Eyoa}ojo&ZSdLlGxBdvd?7PrV~RkBl#4kKheKsbw$yrFtv_ zqS-r$YxN&e?=D?9EigwtB4R`+C{s&Htua|m>=J@J4d+j24RD?TfC*A@Z#-+mrPJDz z6K6akkvhs#_U~GwHYsGT*`H@m9gxjsoR}~Cg|+W~U-j0RF$reC3;#e@hboOo7;Q)P zZTr9n(nD6Ucz>4N2Mq)=! z){ozNw?{x=5hJe*g+qbrsy2Yy6sWBL(Oy%lES=H0y#q*nwyJ7eWkp4_fj$O{?VI2d znU&bDR^3?6nN2o+>XzS$!^M2<*a=rxx@uxL$qYF{>E;DJp=rR&*ypzAYmr0d$X zkH8lF-Jn#EX-G0*xy;<{sDH)|etra~Kf+n*2Gy^o&RxEAS~Xin$+iQv$fy6h$IY)1bMg#Og!()Qb^sR79@W8*gKrtlf+FXE227SQp>4&P+i0A!cETLo zbVX#>ZXUoV%ec%z6~-=c9^(K)xy_RUi^*I@88{-zDCyzU*HqUkU~uBdF5eT(Xkful zD|H;VZ{HTbiyA9x;|LJo7%~Td3|DqeoUkHMeB=Dl1(j&I(jj zvWlR7Xcr#*TN5Y3M46Z1!A5_)FHV3!kWvbCLQ=b9VH*v0bu)h`r@ zLRD5N!-oI|A{tx_N*I{|>f#X3*tcV)97`fGwS44)5QnEG2;Z&vP&j_lv+CQN@&nOvx-Fbk+59Xs^_)p0T}%wedV#y$WjIRo)MsdF4S zWUO2J-uKl{cIe1yuC_}zQR_L6E}S{0aVO)*XSjdrKnZ@%fB35kWdvJ6?bl2DlG!+DuFYUjuA2<`+4%{9yfZzd{OVInI#}c_LU6t@k2Y@y7#`Xu}(^} zqI1a9dY!B5)=Rb7i1n;^^ScUwg#BkFKSAiP$dZ)UI?>Fvv?z#(KoD#5-04H^=)R36 zXq3|uNd1; ztE7gy*DR}+v_|lsQN7YD001BWNkliRY|aDG@vB2>P3ohUU1lP+@a)CdlXhrIC!%$-VSf!%m=7h#Bl}u zlbsU{w$Bh#6vjcb$|J8C!oAQo1;B2N!)2ERq)fO;Jr66ZRfEpIQR7q7asmp?w?sh& z(4laMy=Scxq-nZwL*D`5BvLK=jB??*69P&&&%?*evh`WrNo&OdMzwP8k00JHbwIKL zM-OgMAO+?Dwu$dXtb)3zhD&GNo~_H=^(&WMRduzgAqT=@ew|7r#dfasNbJa18*pNb z$Y=rt_=8gkNZh>YMFm}kjGX399Ny;kZ2Q2d#u4SOe)7F)a{y>Lab&wOU&1|Q0Am@j zr~ps1G92S)JmiLsoazqmU9YC$IO$NoX*v%581M~f2DIbUQsc(oP_tAA5vM)YZ!u zT~p&V*R$_1QMn05uqM?KN9W!ZflSsSfsAWc8{GDdue*z9OsUv5ch)xYOfU_oW2V0& zfj)qusM4N(8lQKOQT2N%tuP`ZIs3lPt2PnkPx`7-Gs(Z-c=iw7zU?cGR_tp^gPBeP zuC{ymeW$wa0$T)?wr_Y{XV%oYpOmul)^)FIzf<3jkQ!i-a}C=Ngwp`*>@lebS5&&8 zqozvjlU69$DCUG$U_!7ipg|8GJ5vk|T9ceTaX@T_1xtQW^LO^te$j%rZ+Jrt3GC9W zMbGGZWPKS!?hkN^%_O7BdOmS`%Cc%>Xj4*W~!P8!9o#9`gO zzd~dy4;BMViGhnKhk=rn zJbDMQ)s-Kuf*w$ zFB;TX3lySv(}9hXLDbP|MZBXLPDuX~=D=ziCTg!hXA=0y1v^rcUEDKJZa_1tt9DTi zNklTpw$Sqnp%d#bS*b%$s%;)DqPmC*8cshoP-H=LfXb=#7c4{BjU7yaL`^81BBoMV zEvL!)teOI>z+gp%BBNwG$Rb093{w-gJxRL6N8bx5tn1p_HPJBM_x;0hhQ1YA3v?JP zc63q1+0W>+VK0!~={;bi=AN}kZ4LA|%zl-9fM@TV;lbo~09KJuIi5>>@QztKa#a#ulfQ zu^`g~E!B3rpY7&m(c;F>SnM{he%T${zsa&?C1~WO*MOa8jMd2cId0UX1*&}lNKg+< z=9g<}KhTP!M_)CLr#~%rfI9(zkToC^$^IAHLf>D!&23Re_9_Axv15NH>oxybt-j`F zl@CC-L$n0tOM=X;F_E&@A@f=zAU|QoL+Ty6d+Rc_P_Py%C9V||Jbl)W2ZsqF5t11X zxjub|yRGYAb7$4t(~n8Qy6_6%vXdyl+a8uuaG^>~lqfg1K86iMn>PoLbcnqi%9D!s8k0LvNoJn8xl8sm0t zen%PZ=0@9t#V<>-74e#Q-CLRoSfrZ*1V$Yv&YE99^SK2!dVEt5TIgy$zGCWh2l+M z1RKHGhW#aIMQt>}P;3hO72rtQBD6IC`6L?X1&m#SCVckPA=QCWuR3!4d;vt-R6sN5 zIS3wb_6!>{Q>+|VG%yFqI-fgrST+}xQ+ha(*(O*-mipL%%>wsR=YC3aOD!ojPwOIM z57M2+oT8=+;H74k472s6jK{EjUXBH2j4fuhjs-V(#AGod8gE{eAdpHW5{eSdx<(M461?9f*d(AD9jlSGT;-6X`mtF#3^%0y(B?^&fN{fx)x;|jk| zZ}>fJC2$&{t>dIo10~1FuhW?7T?7^*JJxQa5PfFk__@k5FwfK&t$g$E1o%f!TlgKtwOLa+9RoEAv5*zRDAWY{O z12Jg(FwQ+}K#x9y6gWG6aGUDM5-NOj=9m0#G4U#u38d#GVDIRGt#0$`7t}_@oa3~u zM!a!!rgiD%I(O?SAV5|aHB9;pA}+Ig>$|2Fee0I!kKxcuL7LrW8t}4!M0HJ#tLxg! zb*kyC{ej(Ly@wi1iNcZ5s;+T!ANZ0QqH_ii3}c;;4W)(>@hSCCt?Qz8G_=70l-RTo zM5vN&=YGg;)AoX~+p_v)1qMPuD)Y>o1D?5p%_3_@Hg&`D=e0Jpc6COSA|qxElqkF- zr~10Q({A(17u=lte?bbQWVh*+$eK5>o+J81zCZ{P!#tq&67d=oWXYZb@CbPFw-^ge zR^9-(g+&BVq-6y(Pv*OKf5g5fSZ#1~v+NKxq?82o>^0a88aYYy%k!rWD=@*CNbrk* z+Q6X`R3FTkb6xhw+IRm+wbv-iQje%nX=!m+>4$untaXd}D+1=V)+#FH`*MF*uUvEk zhmO~^38pHb*k`cYy7o19VApEzALjzI-q&Pr6AXv$N+x>!dq2=QZJ;{#1=_bGGhnfz zQmh05S=eC4hBhPseO=#MGH=Cl*~a#LU-nRr?zhN~NHPPriwf+kJ_d`o={@{pKUNrC zKf47d8K(}#CZb+A0nj$Ae^-T9L&UK88UxXyEUFUvDYdx_OGPP4WkG~wZZkrWIm*+G z89O6do9*^GezKF%=C@%)iI!JE-?Ap|rNAQ38=Cm)P`U*tzpD%_(SN`{LK#UUy0y(3 zZmKL;v=Pl7EMa6Ce?;k;qTq;X26QQzr7| zuN|nU1Wa(KJ9X+TL6_!cqxZ#NF^F(r+)TN3fNvFWIXVR5JXG=6WCqHMj1YlUkFORE z$m@!5;y?lh0gX7{^k%XiN-d&V5k2KIWMrjM+H_MOgSoCqqSnPL%6t{pktx6is$yu& z&NCbJvY?1F2Ol+=I51EcTOxp`ta6Dum}DM_u2)&@BMTQthkL`BwoGh#e?{4k_N>XQ zC)MWmiQfPn4eA>p0xIaG3n$$1!#gy_nV5WT4F(lETQ_%>S+sMK2INEBpb=9<)8yY0 z8>9WjHDeF(UD#+M>xg)msEj$l=Ir`8H4oF)tiL}%uUcx{GRKPj&u6&?**$?_s9*pX zfnn>fDRB=8>)aFwNdj!s=y`?(&=y$C+X%mBc_#MA!X;mK!|G?b%a_hcXoQUF_~{So8Fy}YQ+1ZK zh_POjJ^<$T2b8(Va~_vK$AMj|$_B^$Ch(L&Ye~aircWo}g>j+=jjRU&25YMjC+}Jx~fjHT6&IvMCf&Ib#Koy5>3D`w-w@cSPT4!Xm5|JlQ_m6`^ zJU8nJaEX1Utpjw*nCW0i^}zATkR_94K}(TIvmX;c+qLN}*Ld@Wd+6!k6tLqyXlDVV zCHQ=T3lVXo|-R2WB}!& zw|D7fVmdwptBm^18w#XQ!^pnCPX$O~dziC8*$2>*xg0orqB57PM?e%5W!n8PZU8@+ z53CL50AH6ZauE9h)S2JgqRb^p6nqu}J^+5iuFjo2kf=6?jGs3ing`Yk^D}DPJ#Ocw zrJAEeAni86Vqg^D8v)3vZRMJXB2inf>ubM+`u3FGA3WYX<}ZI>a#mX)iU3&mQ{y>KFvND+riy2pFx5>c6+wHuYFIZ!B~@af3ee5 zOc`&5hMJjoKQ{%0f(E#`4}Mv|kPP4Y4}PRf3H710c%ViRdKu1Z%yJ259AIVesA-}{ zLYqaPBhE?{txZn>4Pj1zKR}b7dqyoJ`cL}@3)CcWl87#vIiEahL&8NhbyCYk42ilf z`l=x^1mG1F{p?Y9>eya);Vi1M>5eSkKOe%$S15=sNbrG-3^mqz<;=G!HsjNJ!7fpR z5e-@FCeQtZY%R5{06ha+9xSpCeF;U#Kq!9#J-$?gKQvK!EQaNM{Lo0RnJIoOHd2NUZ}_4f@j=_@pBaHJa_t_7i>9X z>%PT{Q#CiK#*MX39cIvFz%Hs5vZ|95KZlN);f^2N;&yC&OF=>SQwHtbZ>XLdDSip;Mn7{bT zV&u>+L$u@|_;kBq(SIM;L@aE;ka~Ch+7)+T_bPX-0lfsX|5jUSWd(U|Q%5|izn<_=I&_|EskWi;-q!Cs{DmKXptTWD%_6lNLDYbTqZkRCWi}RdO*k&l1k4eod3uc| zlE|khdr9GL8S-Fzfk?UoZ+q5aU_i!z=vBk{Q;MjY0+pree^y^@fyEI0G0I=HtEug( zXf$(#A;H*$-h6@b6~?7qV^RhzS~d#fZB9X;n9;PG>`kxULtSNcl{w=)}S^}kc?tkn-;V7v9~s{@`4gnC9QvJ6b?4_?xah%zS?utLC`}ADtPQzux3R?rH(}r@Pg~zZ@4l|WJVZs z>THO%QgcTgn$c>q5&87_ZQ$gT&^m*L#a`@%Lz(L~H{MjnrFY*U>Mw=U4{!!(U<>#| z-H0NPnn&*@Cqf*73KcxZ@{?7RRSXA3oAVpJpq1aUA z?L;|xdt3G-6Rar8^t4C`l{y-N2Lg*V^y}*^=T$(EY=u`HX3R~Dp;n>`*lyNQ=Pm$E zv&%*c_Ek#(h$(AWsbGVYPp>uTy9gc$oYHzDaY+0gE;x6k;i9{6_OSM<0t?C(17x|U z8&dcq14BTFaXfZ#vobSAB`-+Xmp+o5Avo3hcdV8zGNo3(2SbJ@1aNd8Sgu|yP8s!Uf*tHHY&tY)Y$?G4fMRGV6EHZ~6`*m?LtoV$(K8be zacK7%1=ZLe+P~;MbncSJlX7viHcyPMGnqKo0#LPoFSbZazvN{`jDe zK#6m;U3&<)Am~C*Me6-*Jr=XE^7h`$YK0@KIAhT>re3@H710_W|NQSO6A1Wx>&O2! zZ37kdS1wa**D9#q6g6|Qqm28hqr2SjadTY##6|AXrBiO{v)@XDIpg&+fpE zRc^+@Pb-V=| z&OZJ~`4K1#9X+E3<7UpVHRq;Ii3s%dE0>hLz?p#)PsB)t;Ho|AtzvMTf7>LiF{Jpt zFh=~HKT)ul9{e;$re_*X42C)di{a)v3L1+Ia-M?uku0`&eEsG#0U?Y>w$Z#Os-mu8 zN{kMbM2=dUr&cmITq95yl}&^y>FGSEg<@zeb9ThUL$2XCc?w;r?2M<T&}D*}st?3C4r?$3l9D%2`M0Us!aRml90(w;_HjwbMAif|-2NV!)o0%)Yh z54!+ZK+%|t9nTzEj@V&Sz9u0!#2+eHjGmW+mcRv6PMkzQIT8O*QGN`=p+y&$Dp=*HMsfEd|7GL22Qnq-#=WJonwGU_l0da0JVTlf9~D^`DK zS?M4krj`a$8-%iaRe=z5ZViNl=(j1W@_o(fyL;*UaqSb{r#0#KE@#AuQ0hAN_6#2JT4lMe8o`UkyBbChf$veNIKO?;AGt7d)?)R zb5dMnj1#rt62n(=ueEm}M{^cF0_YhsYPyLW(G=W|Ut+&Pl2M{JX?71iVy_!EdWPGy@&)x5<^H93+-snlI{#A+`X<@Rw}1R+?%1I% zJ`m3y^DD*MeY2$%%C-S8Y3YEdjWXlD5xZp*b1N(d@&H;RC(L(ar{1p;iv8P{D+5oD zN$BQpzwoDOb&>3=1T1=rcC=RbCiXJ@NNGE?Z~F(XbJyOkYtMde@UV%lx>FbT+V}sn zSDdXJ z4nntd#0vzN2U#1J%4&CX|0W4^#Tj>h;3nl^*{$8qZ!YHtcE|@SV^qpAeo7guk28xM zGR+_In*|mveN8m-mg)d-3NM{KE}9**7dZCx!y=j|I;yBA<3wLW-469eoCu=S7<$#h z1o?j1_Xw253+_W%ly>L?UT|QBj-DotI!;XNxOVi=ET%>UnAlOk`60|`iSbRMLM6tS zgHKZWQc{evDIEce(Y%I;InE0-X0nFRIQk77txO!0SE>4)IwVjLfL|^`KK+RP^+=E3M zoA9##`$>XDfGh_%&&KmYb)r26HjcWvkjaksc`;b@)6&5$to4}5$orL{8qO-M1A2IM z?b%oRk=oNBFa+qs0Rec4F6yJl06-i?{#?J_pf&)vT5c(G0Zoo|3vChLrqAMBi?&5e z6pKXPB2!HnL4lvsmytk^tvdh*fspIhE=qigv0x3bPWUL(b@1@{M)jYjQck8#vCtawgJ zl!Hc27U-k31E4P`2b+yaBk&=mgWW<#f9U9`s^=oui1T^j^igG~$V98g-!)T^A(c!5 zbAyIWbd%>kF2@^6CFL9;^Hai=x4UmAKP>E_piGJLJayhD#WJAn#>VA8QX3z}zGU{( zk5xNe#*(W%Z(GS61IVc9#2y+}^tHS`u%NvjWnp++=)q)Pu%G*Ota4jdzhwQE{pUl= z8l#+AKiGuAE8)FP%3v>e2P&yN8?@L-vmSG6-~FEIc?0DdQ5&wszX4ir|M*Ycp}iYi75h{a z_)ve$R^g1MDf~e7RK!OkFn~&~f{F3^jStKm3kcgn;CAlfFS*J>rS=8^l_k&omd1mY zGH*TqCrPhHI~vm{Xg;XS8AkAp{-LKCi|rriI#6i=!UQwl{NXpHSjr3fH^EE*A9F_L z5IYPwq!iX^3e78p$w9Id;+_sqF#~Ilq`6fGPJv85W>(>)Kb8C5DagsW1NrcX*;UFh z5HH%lYqhbA@NI+N;A=L6HUo1x`~ELTh-&@vXQe?9;v|{Rbnpx@cc8+NjYr&$Gh*M4 z?)(qMFAv5icb6Y$7H?xEd^8^s4He_cf!}oNrf5Tm-9X*MVIZP& z1nWXUgb;l;B;n=Dvw{ev?xj6*Rt_izaFXZ2r({V3a^W%A z4>&IzG-LqzMZ<-YQs5ggey*>hsCHK_o>nx{uAk3yaelmt=C-Z%m|q|n zI}PtZYWiccZ=nBzb(_>y;rjJU`kT*-f>%=~`Y>52$_wZ-hqx436g7kg zCyByj>!8A!dZ{_*WQZFjYGnNf#k~^Mj^H4*ii{t%yxbFZpXTGL`RdUxQ9dMi#C=d3 z)NtXn-kUg`9w=JfV%WKD0Y$%pd{!~od-mzTp%dLbOa3RRJkoXo`Wm2c#Mrs+(#4Z* z$ND#{Wr&HEjI8iCtSNpcTueD+}FrGvIZ5n4|J0LuS@+NDNY$Q%K6h;&NF@{G7+Jpd> zz@q4={_Lr&RA!275-k%DD*~(m_z0pc{n0lCRuCuw$WktVV9~sXzU)@L^^aPEfIiwo zK;a!X?Ez&P-~7?H6zoF1mvw`>Z&27|-VufAH(-=N4q05l1X+2qf>2Ky2>sk~%96xQb=%icM zzoG0K_m4e7ftY@aZ~X9&1jyKP>?^JZqXFOsotIkTQ^$4*#6I@<-&4zujmw|c+IajI z{*60!V3VE|eb4@p{yQjbQA6*0Os+w+UuWwxW zV`Y!UoJ!hDng0^%`l!K05q8wXd)(%gFG}UrfP6MsczgSg`fpkg%~fd_j2@}7%GWOK zyWKUg*e)NwonCN9GK+0p@-CgvZGFwhzxU8-c>SyvWmG!ViEhCm1bq?59-cS~RAd!R z3C|o9=mkWtl~JS?##4@@Aa>+A-yR_67K$GSs*znfAA3-`!D4TTE_=ER}xiNc~~O8vfT18^BQL|xT8@V(zU(oPx`jPP@bVHY%$EcmY&U|6}Vh{5OV;C9?E)02bppwI=t2 zRpSG2qIViC6s|N}uzFd)&g5MC?+lsp^0q4vXj%`n6a|~2ENjSY0qDB-9waGuY%mTG zf>6|5<6MzJpf?{t5gVjzp%+b1tzrvo3KUOoc*WzZresPFxN8lTc~-qSHodFs+_|R! z2GM@zkZY=4lA|wTX9XVsizpdV^NgK9sDiyr_7Gq|c7=6;lXmUOdAEJTQaMtHyO^j} zqwXJCtN@j7(Gu56XId9@(3pxE$a1elQFfSH_~8ZLBwqU?yMbD7opW6E<{k3u|#5@@8K+DKN48lwdGwY zLR!DrglyaD)1{gBY}VcEo?l-+C@1>q#Dx+OIdWj5_82|kwyb_hfCF$L;Kikcf3xee z{aRV&=E`kAs_$M$a)bu(DeBG{`;_DyBHnI{0%t;QSb$G2zed$P55j`;EN zK~4jS)Y_W}i89`|nv^kz{>Zqq)=-7ydH^%l`8z-UQ+*B_1&9Q|(8^%Uqy=u-OW#(o zYuyZzf&h$=Z@=EJfTd@pr+*bXvr`?s%jBgV~f zeFxXOrO$p-HF4voKjfz0^P~VEcA8qelZSV>om-YENWo@XxltVVeCJO5n@w2yrDw^eEZ zXj=N*AB)DDp;(7iYnvo#%fUR*I*Q;3YOGQoC1~nv4*}sFCE_ zsJg@#|lw(>Am>+5B^ZCkf5}lJiJru4OZO4PyeQS|JA>7ySKe7X36}Azvf2N z&vGw+@BdOQ^QXW5pLD;>57|z@K5HmuMcG_=woprp?DyOUzMwf;{>FEGnElSWVb_);ly}_DyU1Ib9F!3AOvlzMFt9Z}slxwLb=n9Xv7b?Ck}>BA2M?)Kv$5 zXtr*LFb!jCeYEIS+PA2xN(PlkmAL(N-4wYqr`J^TjLj5if4R(IG|91JojywI&R3g{ z?ECbvkB5$)u81~@adGynwXIV&JLN%jk6we^)vFiXHK`}w;k~x`Ft_)HaJp07&Pacp6 zOxyyZ6j;oxk9=m&Qwq683Q#Q)nT~lnJE<$ieyw!_hfbm*%^gMk@8%6Y$)a|#j@2*GJ1kPnt*W+cBekMh=OH_sw$Nao;Ve^Y z*VK4T*M-7_Bg&qX17205U?EN;R5xf{OgZZTkbm>qWn~g^BneKiU)77307t=zNdOfY zV8veNe%W(DNtkm1DSYeGm_C01jY;&qRa2K&M74gBECbYJXD|Akn>_E6q7R~2hy$x^ zLv^jd+sUIl?S5(1k+0R()-Z7h0mVrRl_^Ek2GwQ;L!v4YnL%p5o9g%ps*tfZVWJuV zZ@?o|HYl&ultT3lP2H6-i`%W37ilZbXLkhNDF}87;>B@Sb%FcAP(R*bN>zRRB7u*QzGpQ|(y`Pr%9k*rG3vSEWS45|rGUpQlxEtR8q3XPseCD^@ z%D4W`?b}9{%l1bIpfVQhb%a|63>z;n1<16-dRQOn#>t1V!h4{8lffK5cD8CP$+j+f z^k29sb02rtuU>Y`Uj9qVj4G%X9Tnlo&7CLRdk&P)4mJzg=(Wq%zuB}BD&2jb_%+$y z*M9I{T;ugC3NACh1fRxDH45^IH^1uzdKv{5$t3RD^p4xK>c@`jf9fm$LAIs3w$5ET z2VM0!DgI*D?|uAV$ma0=k>h5&VPj^iL}dTY74F!Nqg~5AIqk_Cz)za2vj2dxElUCVYN| zzV|k6wc{V@STMQc*Z*ifQ5Zepo)(-3HhpR+3@VtIO@%Uv6eSa3#t_i+hF&i?3^+DK zdXSKoc#53D5UDj8 zImxVsF^IBU*)^LUG8~LFp~iXSegLqcRY~GUL}yYSjA^93Gu zJ@Xiff(c%#oBKy{9H0YDT@DTa;^IlEv-116Zc7x(T#v$XU@@-qN@_8Ef4-u%;DZ9( zEkKIMInAqiCaCf#>p|N^_0FtP3ZLWs($@C=oL)dDSvG4gP^tZipa=GxdvF4ZmQ^G& zk7IU&Y@xr7+8dyPt88JV>XD&~5q-xF;Ak<<*mleCP>bd3&XRpx6yhm8^hvfnNnIsQ z8$bakc-Fn26L{FSbA>3N*nPyRa3r&$yD2ICuJpRK=@vcbm`#^@7*Bv(I9S? z1&k@hmgeVVl&}+I_&2Y9S6#?KDJ^IV;(#6x7CxFa} zL))xP#-h)tUXBbs^Lg#cC5f%P_>cdGyKv^X8#-#L0OG25{?T1Heat=hwNSJ$H2fW;bchV^Y~A1G(z0|E^5*BhUPnTj9Z?u?0+EDP+2#Hv@Fp zgUm4uFbgOaLBs6+3BaaM5U2;B5yaiJ@_E$~Kk}L1(fTE;`1T8bCPqkF|L8B31Bv{U z%<9;w_qmZ{=ctDu!I1#;4J=l<2R`-dYESg?_x_Wzzd=nK+p_SHU(|WA^hbZJ1O<;l zNy8Ig{C5Jfn^wJ`pz{-7`rlpGZoO36fPTQrxBtQI+xos#pdbDGzZQiV&^vv>)2{!J zv0?%svI8}nfED+#^to@TwF_fTMj0OjRb;Zc%U=Gro}DqDecu;c{p3aNx&QVb6qtDU z)BmeL=I(9pxt$x9sy?|qSS-kPVuSeJb?<#&=VmfLMSyqR2r|yN92jj1i&IR z(6wWt+08LzzYIRpOLE-NM}n&zn-$;$!{8p0+!?ez`*? z1{q-vEJN%^OW6V_sOIeB6tWJWospfusFT5^E(nllAiw;q4A2WSyM;edoj9Mm6+KyWbjq8M3!J`PwMcqn14hY&nU*amup z*1@72>evQEATR;htsE#g36@bD?J1HMrAjE3LkVw%dGi0)K{`uE4udSfE^i|eCV&?i zQn0T1mVi3}83dzvrv8KK9V*Y*YaDht(M^`&w%Vo|>jjEpWM#GGpDFGEY_SlcmZm6cNi`82Jv>UH$49F$|)KHehKA{FHI&rUoI{Q>x z+R~z$e-w_-pFZjuE}e9Z*HN%c?W%1FV?ShTH`84J@aOCqH+`|_-iUKh6NRYD&@nUJ z%mtq=28(5ew4>*1sq+Hr@vza;-L`gi)Y*GG|*>zwCPVAEvAx^?>xz#QCTGj?bW>0EKke zm|5=Z$^D`do_LC-R9LV>D~}b0*q6q zNX8l}Hni1O|LOl$(2)Lph~=z$n_9>UH*?`L?)_K)+8sTxMZdfMiC+^K1n?kg0|STs zvh2mb5Oopd&E;?Yt=qS4g$byr-3?jMN&zE+A-(&JaNF0vE^!x~)0sYc<@XNThqHA0 z!cXgacW!!1Dw+rbO_}?If*8M7>E9IF%tJM-PHx%&yfsW7~Lb_Z{fyuIPtSQiX}H5P`#kVeVwWN-x*E3BEh$tzb#k&Lc9?WLhc zr=C?=d4tIqLD9l7=a7qEt%1*<@SL{sb>-uc;W#ko#UK9u*;DCvniw~`PMy0+ik|vJ zfFe=J)5rFzr9$IP=xMAUi;~7pL{gU+IYwlG0EU214iQmQeXWYbHe7|&Ns}6Z+!N-( zVwdjy6riBpMO~L}QY7P0vaDqa>bOj6z&Qgdh|Uh1r24Bvd)F)TVxLc69RZ8+BLu){ z;~&;r@iZoD%!5T}aMUpn#gr0Zh{ptmQd?lrXZLKMn_?k#PL(w^ZouHN`uFjJ+gor(2U;gBDadw_y-E}rWBRCntkyD%t%Aj}C$K5!^4(;*q0s`Uu3SE6)YDi2 zvqUheC~MlvF1mfNm^&0RbbN0jeSMZzCYdKsePTZX=#Zv|*+3=>K!m^$fe_V%YBBnD zIArFlswG+@r(2DuEz7P(<(}3W7#IW!OzE#VXv4MaU z0%weKu=AoE`}0FBIV!CwddS4LnGwluj?CE+SR>eVsD<}E{x4nsq2sjvS1kQI*Qut? z4IDnvojJDG?b!U5vJH9V)o>04TZH{WXo`9uXlFxCTN!FTm6)W?6##=! z%Qyi=gw(cgcvH?R&KzfCr@HR0Tesd)W#t?qbIbWk|2SAUC?Au>3K@%#MbcU7v$p|2 zCRD_kOOz!6$ciG_cwLMF*bZdBaIyhRQo3#hOmy^o&CeHW25^m-$I*jZMAglRY=k;F zWl>qTwQlI>83IZ*HC-fjw&tDhNr;4cQwb{pki3;qRvdaXwYVM_F$O68QajkCM?bf7 z{hRvyyobIbS}vJDf)&t!o11R9&fWUBQRD9sH4thjb&-I?K%=J4aKXc0cW=G$rxH;? zjd=b;Uv(?q`g@5$p{h%EnSPuPeDZ&mGATf6N0 zVgL}td-tVp%Lf`bbey~Q@qZ~1pB}viyFUGgE2~GFB*b)B8>oPO@ao^F$1ZC!sBNl| z{Fv#Ypi+y3II>#CN*xz=xGA5XO8c6>z6;L+S^Ay`@6c=!+Y1erO*9| zGNyr9W|ZgNoIHKl>60^hCY9$#0@*4R{a*~yEt^zbP4#NNJ{W{$Huo* zZwR&i(a-&^JG5`T2@Ux+S)65$eeU<&uC4F5Eh}GA57Eaz_j|6kOHV1FBHTn)_T-`M z%J$v&_^(K83koe+>h82ds;Y5sKKCs#EdZo2Z&oe+J2!Uf0}|ibvHnesFLliG9{Q?i z!$ieV5KE!rs7^R;fmnz!8*H+ViCCOiG>O z9ZQCA&wU4uaYIH;QDAWY&egIXX1_YRn{)T`F<86}_dMZd`_E?Qvm^e&ZG8Dh_L0Kq z2@6^{+@TT?S+WQoHEA@4u2qyS)brp>kjWsb2o(xS2nS$r3YB^5-bap$L;<|=%n0sWzHlmaI5N{)?t3yZPXAdVY6De| zMHEx+a@6$vX9X-~s1bUIDBBglia+FSSPftWT9cG;y%Pj=1ZM#GW+J6VJN3$-o^EVT zZ$uyU4zlP))JEYPQ47*|!ojXz z%Y(&iMv(g*F?N=+C>&lv5iYFTqD*9xzbdiDVgns1|K-7E-YO)q-9m+^aqKmMHW$x9 zc{`Ns0lhEgSeCe#?8v3}DB+#z8nr!vf+Y%Hpy1^9j-N}$l>m@sVM2hwXYbS;-rr0H z9Azm~`SBB^4|KY=GJk$Nu_=IOfE1YwY!J<`FP}fN*4lwT*&Yv(*82Zg!ZIHcJ4dnGJIvWTE@^|RdX(ppIUA(AfuS3UP zXqRENwTM*Qv*c@T)Yy4y9YQ@5bT}UnwMYhjc7fA5R*Uqu;#?N?IG(uDrp@oTxCyI1B?$p=eoD)>zyzAY6xEx$S3+t2G zII>+(Rh7x~Yd&fE-Q29q9QAmUW-ie)ZD0SUGL@?RzIk04KEPrkaPuL8#SmD6VL{6d zvZ(;p5Qs~*Mxt9#(4L&N=raOQ*DhajTi3p%tXmU7MdBCU6eM8LxAM|?;0m(e2IyzF zk>lnn_)D!O!4iNLuLC<*o9Z%(y;m-%g~*HrPYa|X0>s*-wwH|0-fhcWUDqC>L%v0S z!vmWIa(MsJ=l?{RU?`h?`;Sy6ZpNZdtBuCS70(MG(UN2GoX6c8Km0>?=Hx+T522w_ zgGhFoIohI@4b`GYqPogBK_e%?&VIFw-nU(^zC+xjpZz^$*$(Vp<*E?R(TZf^dH?_* z07*naRQc;1v|a8CiX+)7D909c@lde@MKn3HwGZhV+($K{)RWU{;qaafQjDEAbBX*i zGN34ss^ysi{@IK-*OPsysnb1ms_o`x-}gBMiq^gN1M54e;EB=a$4z;__3Ss)w_!4& zL;}btcT!`Au-?QO4-4oMXkhMnUTPMXeCD^6;UwsRZL6QW(Dn^#yW5w$#>Q(>Tjn}| z)qX?jMG4-v?p2jNutum^WL;5N=zhtCS%Qx)wE0#A(h z!CkAB(YIsocCHv1-k%1r*r9Xaqkps6sgz!ypMjrSusC7Hk`@jr4xKnp0w9#S>E#P@ zB={Z17HS94<(oIJE0ROBnP{}FTZ;$=ry#A(@bn`eB`0Eryf}3wG~y+bl+rnG2Pmd- zHf>>L7CVV9OLR|k#G;xj+i0a;`7DE}u~o^~;~WuX51Fr0VBw=*&gJi*2rMQKV8$=0 z-HIrN1{O^er)R%muHS$WuBxW9sD@`w?o&ft$zz9R@R^=ip*2PXO#LBe&VWhuL+c_E zX>}?E*HS1XYPUS^H80e;%byjZlpP7!LH4Knjk!eg3lEZ9=&NQuE>I-V&Yp(h~+_=&^YlsyV0 z+4PB0Fle=MwNjBYx~Zp;`gM~wBuU3QUu{#g6Se--+rfXR6}#a30^*GJ=|56IDh_TU z=>#yyGHY!|6#Fzt5;yQv18jd(SVaa`jXaB3%4@?{dQHN{l zL{nld(Dw`hF4`X%F^s;5^i#ANyC5i`Wqr7j3Jo>)=i+m1eT5NS8J@&H8nN4&Yiov`l%1N zK|?3FL;KeYd@v5B0*0YSAfi!I=R6^Y567AL=+TG%ZoLJx3Haay12hk>2nM~B8wAe7K>?}*#+5A_cAy~;yu7>sIFBema&%Iv6bnAJ7IU2 zLxqnpVdfH1{J3B0+qSKJMgB%+eMD=6`?mlF>#;)AU+UigIAnZxZ+=_f3lN)g-xu^9 z%s21jKJZxp{j^Y_wou|%6I8$a~{ z%@H)#YYpe!J1_l(Kn@}`0Do%h*be}j`bi7jiKDxe<)n^||F5m>;(GTVcFlw7C=!j zIFzPzmLLtbBcWD1Cm&4gvkGXjJuQHH^Sb;h9*TB5)CmHr=^+_f3PD?)GW#)=y1?jx z5{kb$ar#4U;E0K$jBi@;yzLi)mQeSrYm|*0Jz>84;Pt;%DTUQ;Td>6&##?^S^vX(JQ^d!zYSGW{HE*8pB&A;dWnX zRMP5DFi2#W8qS|coY&&)K`UU<8)CVvl~u}6F$QE60XA0amELVBN8xs#<-`13t6(uQ zfT9YAX5~}6@o_voK|Rz zH{1A+FS!T_FGm$FSkL@AH( zau>_&ixLND`{y#B(oKzo04wzDD728QHQ&A=v6so7DYj9ejZs3A_Sr77jfnY>O(5D0 zwTtXC!c3j$*$CYmK!`|=7$JzDSg%G4h?rmw*G14QFhpPu;AE2x159B90XK+-HQ(ZS z4by-)4+bSXt+4vG$*IOCyl_NsNuXfH#fTN>)x;y8Gf%9Mc<RE-jU!$A}AB))>Bxy4t2o1f6Rn? z4c=P2ij^=TaS;DPrUv(#ZpFqG8KG)z8liWj3{ib{G)xVbb zPB^Rj4jSdA&HI$r!{(JQ2&4u&bz;g|1B+e}e#oe4>S@UyzS($P;F-Wsr`qnS!K4@D z*;5CVAd+k@V}Z@VkL*9BUVDJCynOMLJ9p-&#B~TJ?A-K@+q>;OfoutN z)pm6~dJk~pr#+-KuyW~lmB~-&y&e#2rEyQPb+?olfk`uQ`onI_n@;BUhW)i z#fFyr)lUOh%-_RLdClU_Yv!=6rBfI-W=5KXh`=I6%AGs+a96HeaJ98vWjqyKZa6Ea z0;7Y`gg!$?2&1X&WB`3~K%wmfj)~C`5yIg8IJm0K2oaLo28(u(#aoPMJB||d3rIRA zhkrC0tvP>56v>YVhYk^7GpPB(<#5D>i?=&W-qzfFD8DaDL-l~4x=bS7&_bbK7*OtJ z8H?Tnb(meba^9UizF$s~4om+E^+X|qlhhZL0gH)}s5ih;S*@}L2C-{ ziG6h9@OIazo|);Z-2f+NtU2_FC4%fCmmT_J?+;19qD;|P0 zD=XI{WMKW@@qWs!c>Obg#SmOmy_ftFpFORp5G@Nkhy#S}BI}5l26f`S`V19iOSC;t zIZd+)T*w?@flI)dy`-}3K+@dM+(T{2O zJmu!z{{`2jdvAAi{}$Ck@oel*oN;QqGJ((dLVoRW-#DJo4%tULHZFB1kL?!72#YMX zT_M{H&{l7`>5EkZ%jYhfITG2Nu=efmP#ZdE#1u6lhvl+s(_8M+Spt{{g<0P~>>bWB z0UGLUyZ7iX=M!)aU?(6%%K+3*5gHOL);p}&J;36O1y6}4sXmK2DtOWQE5oSCzAw9` zwW|FY4bUR+aCrARsi0boTdHVnL5OD6)-uKjkT884KKP;Az4hHh5!=?j_1+EH=>#lR zR9UTUMTHwUWW0I|0tlf@5?}_nu)aBy1`HnW4(wSYx}!b22PX*a`2eCF0lse6IRXCr zKl!iJ{}4cMB&f)8hCr*Vs*>XBtouH%IbQqD_p}GtKMF?B3dREl{2uNFS}ZIEGIcgT zl~PKj?FM^j?YsY^tS8xNfDTzmYAT`DlHmj(h0N`gIge?rA!I~0HW8m`%PX+RkJpj7 zDKQu7?`XFHBW&ISU)Gqg7GVeQf>sWD0N?Jy+2gYLYWt#0V1=mG>Zv(;x*JwMOZA`B zB3g}d+D^iH)$$|Df0|$BDc_0RmjyE;>(`9+jqRkdfC@^m(m zWlY$!WQI9=4(wc`wkfEy*LLZl+C`eyqf?+ZBYO#+REpk9Ha_(ag5PGrQtp9ZBlKhF z{3j0YatC*>RuCzv|BY(zLy5$Q`q^&ETw1bhRm+cCP^*mdb-x8mT*iT^u2`m9gZUoBu0^FJw}iy z8q`C6Moot3N!PE6q9S@>pmW%MT%-WcU8(B zj=CtaQEg%3h?R95v-w93ESxQj1JADLS(J%sZ?>|d&vm!oALZNZ(zyUukk2QI3MeMJ z%D5p?gfrHqM}Ijf=T6e7{e(4IZ@ih%;o`NEq4I?cZ3Ia283&sRb4H-T5wioVhGq?k zqn;UevzJ7dsh>clHE~|=Ffx_TEOK3_MkB_~b$hqJpHN_H9_f*B_cZFe`WK^IM5w+|M{;PetTi%2QL9i>7b>@9$*T9mNIl5Bh%0h1D$ z%%ap(d@%cr9MS6Fj$8d*r5tRiRs^>Q4pGm9BV>KqtbWfZmtmG#zqfK@Uv4am_El_4 zgIZoDXwmxQXQ;A8Z_R_UU{{R>#;{sRfNxQu=y`?cf3QRVkhPt=E8EzA$aptu!hB^K zaYR!Jx&=W1gE)}{1J9n=uiDQGr;n;W(AuMTGm=nygM*mbl99#d$rjbEQ$?J$=(AJre5jpaja>xTz0_#)zm0 z^gn8=%&wbp)H(~`-P760lF_+tIKg>;-@rb}IO0B1k8g0|Q z%GeHKVyKT}rE0YhE$Y>GxOxGSEheKtZ59+XsH&GQo^+Sao$}6ai+TwoutD8s5V&bA zXw#Ov8V-oqme@U4$Z4g0$LZsH)Q2@;jL7#l8Zv8;ewX!A?spSsEzukuf?oK+vjQlp zZ}a|!XqP_ADElw4=b1?rl?wWz2Flu{ZVwSPs|_{ahn*Tce3HOEZF({@5bD9>H7bEK zr#ec6fdEik^DH&r(OM-aN_M{ApfSpzAE%dX(@n80E;pP`vb$O>&9}6#=)DP$C78nf zp&B}M?h^{M;^a$Y2PIvAW}!mjHUJ>@BQ<$yx6sn8mLz1)*>Br6yzZ`EI-8@$XZKnu zi=uJ8bxRpJlv~*=R%`i~*7~~lf1n{FsEQ8Fn0vp_(L``w7;UHXZrjnWe*5S zD7%`dlN(@EkRUd%K7bY9UwSsCZ#1el0j^qsw%}_T{nKm+^~0QdP_D;Kdq8L26|bBw z-y!s-EI5f;QESf{rNl{qQ?0(5k{aeXILN074iJzSJ${}V-jlJsdgZ)p3IW*Ir|@=x zy*c9^+IEa{YnFY_ojAJF*WacY#oTZtUTXPMAUi^o6O5>z<7(x0cdpY$ z#0UoUGa`P_6s}*nm>ejj94mG*QEon;aUj|`Pg$^L^%NYsM2Vpng*uD;<;pvMDT?AS zs;Z_otf%@m;XLJmQ2b2ocFx=RY1Pq{e5oseT zM}!q;$9k;Ud|QC9gkgyRfd_)&c`{VROtj8th?5{fh_T64$`b$l9A4;HaG*bF&ygMCKP z_kn>h{zJzr5J=Dg8wZt`U=g3gp~TsO-hBS-F=cAC?;|RACi@nHEC2mT`9TO_ z43bR7T;G*+$`#w7s8R9MKeRAl$0=Gm!>zKiDWW=~QYeW=&<=@r+tdp|d6=EJUM zzu^J{0EWQCu&k7c_1Nb;jgJzL+Rkq9u*q)hl>3z7LD+=(p}vv~RwJ!SP90Q6<@}kW z%7{qJW5sh)w@mw{mUj5s+Mj7iCc7KR{-B`AJ1GohkJ0`E5!R6uzZ7QmKOFDC71Y<$Cf zmH~@C`))CFpnHXYA{kOL&h%;o{6bZxR*`aw+PdzlF(kN7YZmMQ!4z6n0GRRhu&D%_ zXy37O<5JB9YeaR9VTpKlLxzIsZ9>U&KR&5^Ce%jXGf4az@iU^|;MDMPZ&oL8U(kC}Fz}@7p9{tIVqdV6pgYD|Ihn z_kRo)+v_6!kMh0@SX30cs>UMAjW-jpXw<}8NlzpbwMmsFLlbGDYk*1$&54#lxqup{ zjar5RNSy$xn$ShLZtU!~cM=i<iEXD?ydp0FY#4nitYSj@C6(u4{ed5)t7bW-391&RzihwpAWqSRz z7c6ER+iaasJ_;EOe>haaT%Z6Myp=pyOfsJOP-HIKYh?W)gOoP{8aS973ij~;Bz^*5 z(dSv2C!*;%z0{m=urp7{*W;9h!}_+@q902@=#UYUMNgucJ!fFaA&bCbyx&^gyQRQl z#u>7?3bjzN6CuD{QRR9MAdoRifhr079Nn$@>fn6GG@Xus#r%DzmZA8Giq={(0L6CT z!vl+c&y)abG3Zo=FF0@Bc^2in1}2C#o!9^Kr?N_cHugFUf&hv{EAyoV;d#o{sOITj z$>@cB6Vs?-5FNGDF|o8})dekB@-;VZ+Jib@c5QjrT{v@C!5gxByEZSAFiaXaN*(@C zk1OXEMa}xzZrqf6-TBi;B+^04ALYbUcb5h9L9C7MA2an{*MA_O<$ZTx_ZkyTi@>;< z7jF-sidR>=F%uU_WCO<&;S|+Q1ze?;90nA_4~@RrqWwH!`eOB@+q3mut!?I|XRm>- zd!NA)TBDSMj0}!3-wXR=vT=Z(KtEL=S_;Yb*a0kB%`9gSj(@Y!G)GQzqbDs;z+&gdw~}YIRxlW( zW}RJR#fFZVq2LDRlrN+!VS=*rYkMMO<)b~D&xm<@1wiQ1wU7K2z#||*B@oRpPpsE) z5LQBcl#D22M1MzY)P-}$Jasdr^co{01=?i$=|y?$;5N5o;~S!bC#_#P02Y-ktE_a> z7Ch~SkC~-)HF)F{`6%zb@>f!IRfZF>7p;4vL<0(;c$#?HFo6|n(pCG}?A*ztJKd?H zyTr1xG8ChB2D@N`o>EiIte5tS(*0sJubBg;M2jl|HKWGQb)zRPRQs5no8LCQgvgf2 zC-E7{_Z7=oQZJo?fvZAWW4H-4v_3k@F^|*(2uM>kW^J=djQ_=(X_Y&LUz^eEu_GR0P z3qF3|-5r4pSj14PsJwuBmGwpx1r<5!YYkQlBDw(^l1=981Eh~ZcB)P_FpWrES6JHL zqB_}fqxcaJ>wsz^@q|lfqsHRNshYk$rZGjE#GEz`=o&==Imj~+@MPh~$DkdX+00-H zCl%SO>*D$h7$sFjXpxFEslj^;5+Zl9oD+O^=j^Ur&7V)+&?@Jk16rK_9s>mSk;|r_ z9ES{wpEcpO9%>fNBN|>NTNgVJ9n7d$jX-%YmVk$7Bm(%)IPhMWhiJa_0ri=N)-Zj% z#{5BtGeC_LnYKfF)=Pdp(p)XNi#q`)rJgNG%y=1XDf~6w5Ty$hOrph5FRh3OmZ*c$>EG(x^~@np6|OZfWR zz27npP6~Q*aoQ5^5BDA%rjBI{Z)5y&fF-^{3}m#%5@2IdfF$dvasbPCh3vUG^nOQr zFxMJbOvNCgtedCF7Dcy9WfH^vz-+0kkyJn61CgFR+m~yd_a9U*x;(w`ph=Ulg8Ims z3AN60g@R2kIQ3DZPalpTJ=bV^Aa+8?Y~;Wq4k7eMGJLeIpvA(@O>dhTc5s5D&)B0_ z-8B?$D68zzotxh=aOLmC+M}dQhfpSgoq;ugx*`-=+CR|l;M(PjIu~Jn0O-l05yVs- zYM;TXal|&SdGDV!HtJnh(#Eyrs0LR*J=3)NINLjQR#u1cQaha{Qy9+DT}^3{_7Rh5 z`OvkeJAQDhdLZ7UEr_x_+RgrpOkLH?vMKc%3&gpey$88*(-!OZn^wLcV5T$J2R1_h zn)@NpF>u%x{IHY@Vwd8J;0FO{u{#9mU|n%OA`H{5SAPZ80ELLG zAWlPj7kcgiu&4!8O}VFTQi@~v$WCH@-m~{WH*?YF1Yl|TK&?0{CA`N#k-fiU_&st( zSkv4m;zHC!LV4{39eD3L_ttZN>@IjQvQT$v-jJ0DAuhy=3^&1nDf2!lQ5=GC0AgO) zhKpy8DR6+_#yTgsB*r-VFwj!H5L2-e7+HeELCo7!t7i@61hCa6&U#eAqxH*wWV@^bue7E_sT5T3|MqJFaSFU0$8*uHWS65 zFn=t@--(gH(AIVCrb80SiJduV|FATh8Ju&wLdRZ3u2YGRcl4U&?jZiIa82&rn(e~b zC!&ZL0nZIcxOo1!j1&%eIM9;5Wxi)yssfn%-c}4vps(d=Y{?b!y$4Hx@M6;!e}8a5 zDnuK@u~84Rib{bis7mb>3E~s(VI9W$*$ChI5-8gPE0H=;bJ<)=Y(T8csTRWUoH)bLP z%6Qk-sTn+UJe(L&zw&_gPJ%aW9h7;HQ^JKauoBs!wyt?cGuHkOXMtk`t}>L($dQi# zSRQnmUCi3CgnpXox0oG^vUjV!Zw?nUw+S0#LNdQni{sQ0&z{UUD6ftKh>u~A(NeS9O`-J8y$2!cX-)|O- zDhTKS_&ED$bwRC>1Z{#l>F+ZhOFeH@wHnEf96wh;7J&{Lf+sAVgs#^js{%ZRUVSH-9F0}GK&=z0yR*D|9|%014^&!y3)Lr6LQWu6>`o52m&NX zF^H5zQo)ie$w9W;?jBE1yWO*9)~ud2)9&u&9%r{L*_M?lQ6j}4Mg$@dIp>^nD&$-> z>)Yqv7yeN7R{@l131ve>_``em-Fwd2=j^i&>=r1G^!iEpRTarlm5Y-|*kUN@2!N2( z%%7CWzW?TdMT>1%QtSV1t*SgR4b?ZQZTK1b02%XvkkO7!??(bM0pihLUsU2V=o;x@ z)h*@^4jM62_sd>`-4*qM`^1N>c#H}&tH8ng@LkYiM|773*8l(@07*naR8M(I)%31C z2a6%_!5e?;wy%HJl5ZK|l_iCIzjH&qz|E0L48D_nO7cBm-DDy-_W8;C@_*~akCa3xEpy#^4ReD>&vs`|9B^CK z{5+-pU5NEd>{ffZzaXl2&`HmqJuHxZ?Q)%{=ea4U6eH_hzuKv8WVI)B^V;F7@X~ zLgRerJ5tFlAA&=GVudKMx5TlJR5pY2&sjlCY-sOL!*?RuLH3Hw8V=yrjq4^U-{6$l zrQbmn)LRIvc<~Gc0EJUga~jNy9gzee_qtg!0ZjOQIp1OiQ+HGl&S(tQ5ydx*6TJb- zzKb3d5A056IKAcdm*^c?<`|S58NXmyqhK>50ifQMJfJ7PlTSVaYh16t!~QZkbSTyA zkuayod~XiW?)Q#m!|PoYjphT#i-rpQCNm)UsKH{mUueO|u#>zYThBdp?KxBdEb5Rv zyL%Zy6ZRQNaED7z3%$e z3*IgzC_~XrWRC zt~^-G0kZAAakgKy(Be|pXV5q|<&j@=-Fgm@zz%(XP$9W4=ARM3BH|IAMF4A=eUDUu z5U&7aB2aZ`&w2xxA(5G^D2DqhDRI3AjB|rWJ>+g&y(Ajsxzh&~{2FKpU?~kyVIYi} z^rQq-cC3F-gU6-Dt0a!ie6=7w1my+&V6ll1nf|*Pb*!YWz>Q++T z958f>ltTdwh~8muspgV+ymaA&<`~|(Z8HM{I0=F^oO1y1z}jhgzKp9t+z0>5I$FPC z9QG48@F#pV$>uOvK6jG&-oT<()r;Vm-!#=>lC1Rm(XR-2f-VhM-m>ydv2sLq)wSCg zu7|>~AN^N%vF?QL(M`-CP9!|+KJU7+vT8Sa%9EN`xpC#I?#RAP0`0_oC{NSt%sfg& z@Tyw1RpJscpsN?pYoyBMx>KU%@_U=5jo6k||HJ-?5`2*jNc1fGvj|&^WKq9ilQatx zp(K(-1?S%KR2%tR;WwidUq-9I}F` zYibc#G`<`5uh+nFu0!XZ?#8vN?$F+~qG9L!DG0><;=y7_nKzlXegGB=4om(eUl@T! zjJ5Ty02tf4n>VgWfl3tAYse^j09jHh8Vr>T14?nA9RZ*a5I|RCj76Kyq73mKt2W{| zi$xoy_XH$ON~3u1yWL9Q&C1^6Lwu{m$mazb)svOs2B%^hX`q`+Eqy`D~6Q7Nfr z0&}RgG=W!Cw-!AEuwfwihN!v77+>%gi)&*JRe4#Jq~)0*X8k-l0C00GO;M4u$Mmc~^SgZhq%y<` zmJ)1%=6qzquT6j!f+dncR4nKN!e(&J&z#(+%3@NHPeEj4F8ujx={n?#M3SG^M6~j8 z1dEwfzJ)qKL#}@@p6K@GUdluT85D!87j_r{`FEr#hfst#rVmgv*5IH{B zP%t$+s<^~@_k1-la%I6uCBPSw%Qmq4l)HQ9ru83*=2@+5A%=h+kYq(9a=;mszSOah z(?;E{%9T~th_XQz)5KT8e4qTsG8b4>&q!4(*RksWsVoAZ$e@XKTT~>+rZF1D#r9qP zI6!?NpgwtcyE19MZOlKz+}F@DuvpO1%ei*~;0VDXh8QuR_MLl2669R>*;D%!ghMR} z6iko4y`S*S>#1*{r=`l3l~yPVoLYbcu#8p$nRpGju2d$N0Ec}A^;eF>gF^P0=8#oX z$vGrPRiv_hnU$#2d?zl)f3vC~0VL+HT83MTxcutJtrQK5>K(!|MnjEvU^Zg$m#F-*8mn}QPSz~9E;@> zJ&C@>@V+GYG@uyzjdOiWNEqdL9-50+FK{yB@vpi5L#Jp=2Ve~#1g#F*7pkHriEkoE zv0aI6E$1A2(s%H9H?Vf5z{{>pi;W)V`>r#uLIPUM2W;KR4IT4{>(XO@JFs)LJFsh| zlBZ$cTcB*fHVEV3BcQ7?6AhXi!ZZZOfxaKxT}yZco5#Ncr1-wh-3Ge7+Zj5)QLP;f z84BSxE(UsTnX0Zs$IMf;6954CGLaEu=-ew<DWk%Dw<17?s0Th-i96 z#j+E#pZvNginK4BIJ{j7s3dP~Tnp8=jvBoIcwzmhl#nQ9y_nz0{ZUb*9~JQ-1L#)8 zRKhTTMQ2l zV@zqo`2Av3Mq^XetEx3}^3$&F%we}>?b~8;L|OnDXEU?1nC@MS!6Iu3XdO5GQxZxd zY4P?;f8wrQId9-qXD5+ROC(E71-`QDqb>{O4d(hL5*O6$ICQeW7D!l$o$rFOU_dm`GTXKr@lt9y@p}TwUS^;Z}-oz0MwU+0DA(x`0RMPDEWmY0GfkJSbe5NH45_89rPTgNpxOza3 zz~PN6T6?I4tOuFHaE+|L1qwz%ikBjHWic0EORhv*wG4UKJZl-0*tG6eNkb)$nN>JV zW}R`b;rV4g={P&DE50wMI}+{ilr_X!vy5HtaIJ=UihD?y<^+QT_NYK|aaB!J{8mpp7sI!6|dw3@CV8991gf zd4LR#M?42xx?}yj5}XQWR+c_GGkzYOW~P?OKazwZ5N3`d;{ZswrOt4oGQxe~gXrC2 zl+5m}AE+lXh{?s*832CMJ3no|;-C_+*mvk8^{GL>C#kD7_a7O2Kj46|1Bki+{@s*F-&gHkQMlhmB|aF{buiRjKEkQDG!rx_IG~=15+u zJMC`YqB3r@@??dZkulRA`I5VSzE_)$G>*y(#MUO{FHz( zpL_Q7K`-tT>riCcGZ+BlXMRTee9Z?x)OkU7+ zD&AROzUI(+=2 z>XjjrgkhXC=X35#-5F7TMof6zivXFFI@wS_B_Jqm^vqC%pRCGeIJ~(6@fL%{h?8e# z3K4;lGO6cbD5)GFjUO_70`!5d>M1H&U=e^)R<7rL^V$`!65BW=is&Z(=4HfvRvyQ} zKEmm;4*`pOK7*;DJcZs?Tg*5cnya!{7+ADxRVB2nN`D~hs-6l3tVVqe0VLl;b%SI{ zzoAp4HfUfmp5OKh0gH*fO(mV616mxjwCIoN*sY(dJ9AVb1KeNeuULPCUs#G>vsROh|0N(kcm z51Xp_c=U|z+O)u3ID6cDN}`uu0LBON1jik_7=;x7w{!h_@eD?Z#2M{903Q5D01xc( zp8ZFusz?tmv`hSFB>kW9pzwtNtq~KSP%@J~$}`9J>b^oUEe4Bef0If~W_)fg8Y)!N z*6q8gZ<8t^;vayzBv=V79%doVe)4w&1fhptxp>ZOZ(VerGSe&`0L5JU zRKnTppD_jc4V^4u8uk+4YROxFr{sT{&K$2sGEoP>Lje__xejXP$pbNf&9aML=qbV4 zNi!8pd=Q~P)`~a^rCX9e#FU&XD#j?kUa32)_7|#-N=*3iNmTJB%z8nIlpX8d_pB$o z_JS*m3AP*WBLO{l)GRl6ok=t5#^*K zzCytw1(3c&Cc4VXR!aUJ+G{=5aq!rZ%3=NEK10bg@BHV8o&@?9D;7ZBh^AtHxoapJ}O^1 zl)?A?ixI^m0!9gAklegb7#Un##W34qi2gcUC$_B`kNjY*2_UKR6IfomYI76`BGr@S6B+<9LC(IO3mA3l7}zhkQ=&l2 z+en2bv6nL`r@1~nGl(ki0zOtR%S;}rhc#Cfq*-9mlt71#pXVmdd|tMgY8e4E!@;lA zop!soF45nGBu?^J1)v*jU3IGtqG_U#d3fIjRim+Qyr+G~o~q&`-$SAlFiIdheB7h@ z&XY%Xsb5aLb?1($as*g{W(VyXO024RckjAxeTGZy0{?LIz!poO`Z>fBW+C{e&o>ga z;cOPWPTl&sq2uPN`T{ULab%~yBT#u$mZPXxHX8s;)rZ-A2X?JCp&t2Bt6n9E@#!j5 zQ`;yFM5q8!CFAF)Xt6h=zVGBGao-O;`E}QOz-V{*!Wp-1-CG(rMWS!R@}C-WNJ_Bb z$Es`A=0H-qjfTCCm^fee2gRI^JQ4j!g^Pslz)(KP83=NsaI8GN%X7LZ)>EnAWnHyL?`L?xxKEYl^_v`OpmDkxXx;AY)Yp&wa{To#z3FkEONzt|~ zlC}fmGSIJB_5OFBr?r#go1F+bX zQGD?4$#}NcfN>2KRW%9-ZG=LZfFsT!3|nQ>;>n$b5de?|0(F;kvVHDkqsZ!0($Kl4)>{EP!c)*HEHC`!=d1`eC1j38@>K}Jd$ zndyAl+$_VIqM%0JC`~&^fWAU@a2%W$IppChTeWeWx(-m5o~kZXC$jATvOBjB4k&R| zRW4(TOtx00Vb^Mx3Xbq%-8&U8$uCU{PR}c~E|y6jg1#mtKt$na3A9X&t}?0~vR>>vD&t%))VWx(F&$_W^4$g& z8*CI!X}O$qWvjNDF=v%$59|u~u*Se*^6g3RM^(RdhwhrANM`lQ<#RUY6QCFg>tq7L z_&)PPySRSY_@$@!jD23d2q_T)H&JCwo}&Vm?qmCs>>fq!n0vTh6Nu?OV2qnS|EsP` z_kr%hx#RBO&XuC9VT*QeTBKQ;>TCBEL3-gO!& zaPHIrw|@C6S_^vJlHz0}dr4+7LIVH5$Oy(e9NE9o9oV%>0WpDj$L<3}S4F8CzY5a{ zDmv9Wz&(o4vfas{lFExF&TE3gt23Cf4B1dD-dAw~I`O8A77-G!{fA9)J^GB$^}|L& z@FWa}*A`Vviaj5Ej*^chWvXnkpP&-&-n=C0H*FNangNb3DD(PxFC!+Nc=108q(i-C zd&q;eFW>s;i`b&Ea7~@7yeb!w% zf84EK_EY&86WhuExllvLO@B@*z3Z3#*pli|Z(~#R(n7$ZX@&G2I8M}EfbzjzYux2a zX9}XPHg&?Y{`~=1Z1$4BV2jH(#a#Wjn5pmhRFo;!2MojSVHK}`^SwX{NJoQ(M9 zRj(U`*MqElRYu>bZC9V^L8ao##WPwrg1_q4?OdzYog@*C5R`$L41j76wyEvi=)WhyA}?f3m0cx)(mX#_d0*R?r4udQRPT!e(KF@s^W0Q z33L%p>D0Ba>=+fXq7t(o%ud5DJpA zAt3BOWRgJet}TnC@N2eIUuPOY8^DdgC*AI_g7|5a1&biSQPEZ&2@HxtMT~5B9a` zvJ;t&AA`)awf9hwA5K*K{8$TmO;Ov$KWtm~w)KyO9>s7C2^%62rTPZfse6C*c;32o zLwoVkh0|h81!hFJ@?176%iblb_$0cg&-;oLKJoKZE9r%#>K!G%EGS8fgL%-?XV7@H z)|@`J+ihC?hSr(0Wvkh=&CkES@u(R2Fa(RB>H5zl{@_^~ctjwlyLxlkAHYudEx4R?6Y8Xt3n(K$^;xP^g5=*$RvQFX05chnu;x6#LFO?`d~4E)E9{+Wz- zTW~uM-ty6|fWRW#kN_0H6EZjiX%>9PV9|%!Iz@mr1veh z=$nC}3e}WsCqV+4C1@GvPaSbn=Kh+3=xuA?af3$AbgkNSmh?A2^wq3c{6o>0LeD}L zSWIOoeOMJmSKcT$11u&1MWCH(83P4F5er67p%lJwx z$Oj?-bOa7mY4%EcDYKW$;P}~XfGw^i_@?%b@)rOAAOJ~3K~yAWN&-!)WjG4%0mWIP zwlUN3j+FOexp8~CQE$uT3#ufLI0%6j{|-1N00a=@=maR$1L0?4di6FOfKh30X@3b+ ziavB(dm9H9=+qkBp{hBRY*SRNtZpk%#d)FXf#RE7YJ!&6^4%YwiBulh3u6$BT2%p6 z+twO;!aP%|AdGX#tTYsI9m;%rAPrrrth_>r5i-Mi*oc9(Q(cdKqjb)&XJq*g z>|Eu_%PZZOX`d9JfYy2P$aX194juil_VngeZwSE6nEy4Mj}PDbN7*<&lVl%&5YaO1 z1a_MqT@s_c2aR*nAN`6LB?#r*Rw9^Wx+oFyEoKrVXiuiWVq`_zNTV0G=3BInMZ zKH?7SSm~}vg|c4BJ6as*m7-d{eZ%|i;yD0PJSWrux%E|Y#-Z$uob-eeLi8z~IK0Cs z;i-gBb|NAQc%x^NudZg*UA8rTpl9C^TC1b`H{19mPc;^s!;7?3wQA=ce(HBsrNu5R zed`-;-_8#mVpJ1men#})ZEN4M-s-!E-o-5lRM!A}H8t(U*61~0oRR{J8wp9MNNJVt zlX7;2l*qB|sH&3uE-|=4n5pzGg^&0B7u6sx7xAC*g2m6!$AOo}| zz+%^4gWcmV{3of>QZ+kw`iNV<{ADHk!rG?nP^d0Br-~keFKs$>bL*G9to~DD;}`(X zrC*RQa?AdE-`nW_A;d+YB`8Xido2SJ&Kx3S0VCif<4S)3 zS+d}~3`mw6EwQ*n8UFyf$nIFhCa7>VQc=ujq#N0wresyDj4^@z-CH-^)oXR?6S1C< zJU=-y6zapQzpKH=WR)1|Mdb_GYciTRBvi==1gI`Ti_k4zpz=3D4Dr64YY1ZXP z0K#YJB7KVxQ2IKXkEV>)O!bdyApw&CF{oS6jc;--UI{gP4`2cyOyWRJC!>N^UfEi} z-BbnHLZw!1^Z9pEGG&cw9FFMj?c3_3U=JYL6NW$2(@Mo%35tfh+Uq4nCVpeA)lyxj z`fe4}l&K=mtrKVx7>c@mANuGbs-_3_d^TX5>?{EpP9_F*=l#0GPo^=TWYsYn8^HPQ z-gl(CaE1Zer&Nswz@0yJP&DiaX9SHOa(AuJioM00J9xb&d5YCZA(e$w}>vguqPzi=LiIf`(a!%;qDZ16ZqX zxFaBj?Ia1q96>VwTUY;FZ381GJt;~wy@bpcZPTHs6%$l%P6Dl62?B1?oMgVrhaBMXq+-JW1uRTKHXe zhXhtj!wMc*y?HCd; zA;E??jz-PYi!Fk`0cdvaK1fv}hM_ao1a^)k=Hi5@fmD{d#Lg8Hpq+d{DD8CO&0ebJ4Z_99CFkdC*7sGGfDsljRZ4Aah8fWa>RuBYCqb) zeTCb#Dzm$G$&VD!PM!B9&7P!>5jp}?55OZ% zve%$-qBw}gclWN8Qn#&nTLFDiOd;B2A*1I9s7J;%5oonU&;|fQ5QaENn+`o(849D< znPs)l`V&1+RAK0hFMi{n%4eZATmWcu`NbWkqIKBfH$?i#jYN3>Z^5nPCh{a z9n}PsOt6XTWdB=FW5RKI;1BJUiYHFGvWlwv4OdcL;jUdetLrbMs?~JBZcZ;${}fmP zu#1Y+*Fj?7?1{aSBR5J@fnZVhZ@n}G(9m;G$c4rP1sM>>c_G=LA?R6^#Y}oqx`Gh_ z#rg(!*Y}5-3T}mhL;6$*8mn8ib<8Y9;gJB$swXl1Dc>62J6KHBZsSGMatE4Gej4eo z5?Hj^aPfK-4i?ju1@-I_%4xjL-#FwB=Zdm@R+q-Rv=$P~s z0<=i1KvADD|0}9|(9Qt0a>S(hu0xl8ZvT!I`h^dTs}m+}5-ND?e0t+YPJTl3MX5pp zlGOu9zj(@EG!?8SgMG8X!6pU}i4E!AcevInC}4(XEsI@Tsvx;@k0EaEv%l{;bnYiW zvgl`jA0k&lpwE*d~laAW^_)?%V#MzziUrBp`u)bf%IqLn5)N zioXYK0LOM6ducu=RWXugtSfY4fGE!bd&cL+70c}KKIMaRQuNFguy`P1>h`^XY{Jq0RbW2b#m6o2Lyo;e^PEY3bN@*Ip4>Y4dh9$EVfxdl!UJSQAtq^(99R-kCmh?x!0IjE@6 zoG%$}8nAH;e)ox@SXQn;Qc7lb@4D;PsOnfXB31dx0SKcYueo3mrN{CrFEkRWmqGb0 z5BN-5BK=8V(bM%f^hllGxOT-IJG{;H=sirq{N~kfxIP2NS+#K8yUL7Cn)RaV+;gyc zFOXMeZV{5~89gxhZv zEC$PzBa?&^D=AUN4Rtnz7ch=w+NcTh@CtpgxYV_7+ff0TWj2e|-^0W)^@67I zWI-O=*0G?U%nGCzO;MKFH7Fabo;#`H0sQXjTBwKu&JOYaT`AIV0ucLZbE2=a? zfg}f@L&7|n7nj572j#UOqpz%@lwj)>tPnu5cFYVFr8CTP%gV0W9t^=G znlE}SrmNgT?osO=&Z9E(P@avd%UV>o>gb>#oj-F()VJn>#Xt)bO{%h5*;dvQ2Mt)H z%5&=I9__Ip>Jz)a%&;~5OH5B>uM^Cnbg5Aom(RJ2XOFvb5*ytIib6{zgB~tXgYQ`1 zW%B2v0*m>;W<(u}5<3OC0JkXM#jbb%v2N<4Uy_nE zqZR-iN*q;IyLC%{ED9t75BMBW(r@2#U3v}C+(ZKIySHu#a8S8}B28}=LL>CfeelNL z3Q+MqA?Zc6hkiHqvMB`@yTK!8XnzAJsa~#L^nI}qNcz#k4xJP`&#-O)6kw0)0*a*A z_eTBn-0iOWg6GyfSn6l49)g~lhVunbu z?D)uupHL-l%j(zNxl@N-eLW&`iNHGANKFN+88k|-dK^B9#9W`j<5d+ys-G%oGDw9w zssvt58#m+8uSlFlEgTEK>$b0bM`XHgZ;_Fr~{Jy}GW!^H*uLRl}+<@WJ z)T_u`Q}(;fJG2?Yxxq+NmLSKq=b4KdodMr3k8k6gPMrB^cjn|lw|?2nDiTrSqwO$PyRz@w7j4fWcej9oc@@}RqL?x?$c`?hA9LVd0Ni>Xg6 zG^Q)$CLg@!mv#k;`VXDjKqe0A2AMZ{hv)^d3X&g0>_s)K0#oA3%Aqx0m(j7b&|%{}N~D3*D%gH5_FaXAlo!O#?-$e#mv>pwG~dA7)@BdW|qhIA8i>2uuMX zR1|S6WYso)_=@fw=Zt(e#(oi_qZPJ2%DYC#b<05u{(aa9WwRit4uNv#6+QBRZCpCJAmtVNEzZL%A*6{5j~V zQj0~jrld?F3jCgA0MF*qg%etTf;X-Qus}d(v;E9JgfS~nfb=<~TyK#CmZ*$o(PaJe zNLL@(!%#^}A|aRn7P$@#H6WDz!RJP>hxa%qM`6KlC~A5&)P#zff>ckX35kGvt}G_H z5RJwagGHQLMRhAF@^Kc~5BB|WQlZJGm+&3YI@bU4l?Q_ zE*Da%LdEpXO$EN}2LvCWJ))A!&~q~H0L`&8KBcPE-tEf;;?AAe?-suHmj*UOowvYF z6>);<${Nv7hmM+~e#4^&HY%Hc^Xet{{;U6=f>G2?YsWpN{$B!T`e)hi^tv+>k9npj zOu{5w@cT1Qb2)3Qylk{Vr zB9+WN+m;DbS;aHgPa)PN?DE7Z^8L8jLxOWEHdF|$H#yx>0`TS8jhOhjKncErKEoC7 zeM^ZXRUSF#{YFV4l@U~1=~*NRC(vPb9DCn;z*voU=wmPVX z&5OL*T98IHd(g34e>YN9(Gs^~!@G(H8q`AJeP_51S_OQ9lNOk^?YnA@C^5~36|cGr zr;nt8N|Gg`yUwshYg%hYxXqGg#7%1@fDy)_Kme5$|F+@7pSoiQwuU=Qx=Q;y_LnNI z?WCZLT|%@FW$su=C((~ufT`Dt1+1Roki*%b7(pC!aL+n-m6@^`Y5M}cCdW$>pORSj zWZ!7ZKKH@9ew9|BXz<8c4FrVr2eC7)s&Lc#47~HFYJIl$MD`@ z;(Q?7zDr*><&iJAs;V}+KUCB(rd_%Z5|xQxljnRv>XJ~Is18k?^K0(*om+10k{@bR z2w)TAgnAp)UDig5d;Z&!6vf?Jmbjgp78*5$zBUgc#Pv0byZ>#xkg3-V*zXDjro%giO?nSXQB|ZvctO zeS)#&-;s0|pbWsxi$O#U=lN2FnVI5@DoHS@0W9%-K?yEgM+i`?PuF~XX5U3F3RNND zT)s6-2M9LkJA8+MI@C*ByKa4k${`Y{N?akMm(xdG1wAS&Uet?f$E-z|1vuBFvZG#- zv(gj?3V{D!1IJ1%ialRaR%z7e8&~wac{{-(eP{?hT))mZ0BCmERjmAA(XJ%^v3-{Q zDU8e&0@Y+y@t2uqnh6$jF$ZE{t0uNi$~G9yJhH(a2()Y8!_9d7Yf7}SzfK+B>#kis zC);(U?u;8edbVhD484W|*QMtW*QQ-(RfcAN;_Cu4Yd`p*DDm`^PkQ+C8iEdZd+71s zP;zeZ8-J}TAZMcl3VlhbXo*yrdJPyYTZ1Atfgm)}>5qQZUA=V1Eqdc`T(5p3-S7#I ztG$4JCVIZG_4Jv|eC(_8dGs%eB6jDN8#Lk}H*@~i+^R+26$nBQYQd|2F4{Kzi4Q&T zbyd8W6^VGx_6_f;B|v?70UQMCDK-}Yxr%BxY}CW9$AB^J@b0y4|E`suq2l+n3{Pel znLjwstSK5B!dMzyLf4*yT-TmM-J!kfM463#qQKIqmtA@ec5|NkJ=eL%AoUb4di}38 ze^sZ?Cjt=ff#!$$CZjZBu!y)%i4>(7{{iJ3Ai&rXSPX&H5sld(p_&IQTA7mn_e!u{ zcqeIhu>iEna9xP;)wF4^UegYpdMgQw@5V-wq`Y$Zyq*{SP^zl1U3@Eq*gx1(FVt3E zRpV;MKB`%lhxe{`d$uh#VHJat(KUtE9NB6ws75ul_n`4^@785*@7ATh)hBVL@_@zM zHAjECymIW+N5AaG&-je|=Emhem9L*V?~AI8Q(4qlv#jbVy_cn~_rM8mvk)!w0 zv?5~K_`QO~to@fXBi<(~q2A!6PEXI?v`4?JWbLZO-*cDFpG<5?-@X$5Cc)GS?JH6| zMG&cVM~4s-J&u5AD*lKgLC;0>$L5CnOtdvE#ykTwB{LIww z;-+f)@ulVmi&TdD4W6hZI?wFj?zKiiz2~2dBvBrae$QX?-~)c?SD>hN+`I;|IoB`O zISip?VXh<^+pTX9>KKml>ZNn4Tv2tPpRA;~OpWQhCS-nOsB;Wpw}0obTUICzRLps0 zrguW7khjHS33#KQ#V1h_6C9cI%_7r*g0Myq7Dkw$G8=mD%j%_KWb&kENED4{Rnv1;9G9bmSt}I^yf5lN|ce?H{9@XkBM?hpo3_Psyuv80?1m0 zszd;9{qmpadK{uE^n{gHDr*;1M@6Ub%9a>M)Jq?J>i1+Y=pEpvSHDpjSpDI<-%@6J z_EW#(u3kB>SzCxfKp$z>xu@H`X|bxJWW?W^Yc6JSS6Zdt}9lRGwa7Yx?*Uel{M;{1*jL7 zm8*|545v1yZuv`L;-&U!VI07WGx( z`*fX7Nd_{hI7E^lI71R0nSiM|*AVW8ecY-009D_i?vSBYP?oq~%b5Ci1j?qU*=^jQ z5i_LzNOhb5lAx5pn;;z~LwR|P1gtp!R2r!$(X&Wn|D6QjOeD*ITi3qh9{R*@tCtFJNQGd`v}awH9)qP&4Y;J@h2;N|pZ}e}A~t!{l&4gcWav48 z|Kx{1r~L-lBgh8;K@Egi!T{`9PyDt5XavegqLJVrsnNf7nv_1VJ+VPJ{kcS{1pGd+^ zGX>R-QS5pR9HZ(PiPr!YjX~3(xB+n8v(E?tQ^1KTUbLG)H+Bt5Mp-q^s(1;M5LFgE zr`4}UA|Vm%b~H}J?6TqjRU}Ik-#}lc(n!S-yH-|NBmY6qJT~aUnWLgLvp>XKxqDl5 zXkOF3&u}+#(&K7T!2g~+x2Wa2qKE+{FLDm}DM7z7Ag5hKa}CTAcfe6HO}4E7@X z?UmFuR;Rj+8&Esl^&U7@U>$KOoxym6#R*vN&)7H6dhuV-#!KX=O$$VU0R*5{1xNy*Hn_X)#KG$C_|U2oiN{Z>eAO; zzkXSBuLcaCt}5YsKlxJ`N+@s0oFhoWp`?+VU>76A0BAYvyLUu`Lz0{ON40LqsM%6! zJ9%uE+kw()hweJW(EGSwveR6XDQ8}mgG8Z?bI9LuFhgdN0GSM8H$($Y9aKLBbL7aR z9@@Re9XYr~N~IHLzbG0Wl|v{lbD#MG4Qd9w@|p11=RW&y-MS?|QUEjKv9Gx`AADbd zH9=GVp_AOe+L?Mkl}y&BUoDN&Z6zs=qric$`QRlvO%wqE_$Z!jTJf5)sVTZ?p$4Rd zU{Ma-)5MhJ*60;a#s>wSt)^rXHo4g*PV%ITn02P6Hb49f*#!@7O~QEMg2qRS{nS^tOU!;ye(H4IDYkb?VwrAYk{F4v z-1r%vatC)=WznjaMq`9x2MDH;w`=oacOCjCRXj!~Rkm_f)vZInb1A;3mtCa`&d1D< z@r{5;ez0iN-${>rUP+jeq7t|M!&lsj_y1XI4G1K02<1{O6`{Z0gEYYNfMHYI(6Mth z-evFhWnKixs?Ihxqvb#)vN7I25*rx^MT@}tkx6ztch}vyeMkFeC9G?7#xcDC=8xv9$sQvanPdjvd@8!$7n6(fu3Tx+Omm?QP;i&r3@E!ntFr1md8P z=qA%jZwi3}{U#UA92cbp!wCKE-JkraL=WgG03breL?NwbpW$xXhWA`)NvVvZRf;T# z(Gd9hyUO-4pQv^FF7D3F8?Nrc2^(r((_Z&RrV-%Ps&z+YNvVz$6_=^6geq(3^D@OZ z%jgh@AiMzo{LsD)a;{V|0Wgc+_-kcpXFd7b3Wk{ZQ`4rid+3SZw0?;7?+JJUe7pA= z=9azv50Yb_`S@?T%`0A2mJ-@9*}>6Mo|aSCx9vkW>EX{RdmgA<&;SPwpXrwT{BI?6 z^T;RvK#E=~7kp3R3j$LG8=)Kkt2w7DAC1)qKm=Jv{mdT25}Zabv``$WPF}xqQIs+h zUb+|w${<$J=!li3t~=p8G;^_}%u}>YRzD;&^Hvt`8(0jW#?NB&6-9k~afxQtu@;<5 zf;lQSBwg+qEc&md&kzwBsAq_gM4&rCA>!E(v{M}+6Wf32WY@N1FNt{^*tODKy?9RN ziurQ%ig7lfX#*soAC*>AsxrzDW<)YjN~M1h6+8kSl1V}ADD~L9c!q^n_P-&gnhPA~ z47{?cq9i0j->H4uFDq~iL2dve5hw{W{PHCIvX4%ZV&#Jat((p7>pNt!oBrsRCE{@V z`Zagz#9jqoD1uU@1ITgq=`};F0-HwhFMEW&i?Uk?z+h zh@xU8p$Kw0Z%|9QcB{xQOK%>P36i6spWY)zqpVBi{1{Kmfrg(DofVNj?ox6Ov1j5BI@+ zp!K1$4BMq!&mqz_SopI)cSjFw_Vh{<9WlnpT~*#DJoLPLJ2QwaDOfDUW7ZOJn1j34 z+B3at0D;%Q5NXw_qq}|QhP%P2q9A4#Hd&XvBVAr5|f#l}0CFqfrx|aOch( zR^Jy^VwJ^rkrukDZf}_lHK@K6xgp` zI(hwVDf^E(wqtOsCr1b{%TD~{7?J?NY*)J|}wG$q5 z1BXr1{7?X9RJ^>Gs$xc*#adA?=wCZsF%0%>|ISrjrz2)VMG29nVwULNGr*dUMM4EU zQ`NfQk1hCxIlf;Oxn&9SM1yz1SMcD4_jd)PhAPFzBo8~2V&)B#1@R1(t(0-)ef*MP zkNTIqAxlhkG7!n^J?kF;%s}US`^W#)9Xq(mRaCTc6K1_A`VEyqn&_!AEPMBx3Nq=b z!~qesGW>Yjyf4cEeen9rBbq^J#|EBZdd(08UD#4wh@J65v8RII3A-n?Dmx7e0(ybW0N{Z3h*pUk#ee=SwiTRzcY z{hFqtso9W@41YXRvf!hW@x6Q=S#Nq?ND!d1mQ=e7`#b07CqAp$mA&L6v5gfuH^mlY z==-Z>GyTmFXqBz<(3BVLpM^q0ZzLLBQ{=(**QXxTs z*%DiUA%VaO{fku5Zr!-O>mX1+6hcR1=c!c^&lgD(ncc{XwP6?;igrux;2YlimIJ~rf77x z7%b9f3797!$8HX+ou;)TF#v0TDx}ul4>niz1Hm#cWR`XAa_+(8E;GB<2voF>jP`bR z>p++zO`j_OnS=u1AA1D7pM*K=`@@>c|ad2meF-T5Z;e0vdSoli8gNZl&7TF zxn<3p?&Q&3-i~Knt!IkFNz%qEi`+T=x5@ecIeFxi;;)XeKC$PnZjaq2kJ-U3-yO zbQ5O3Aa)k5M1WVTv|2ysJyB3I0At%uJzU>G6J?j6(H}pwEj8k$DIZiY88#$bf(AvQ zab8mw(8#}s^^8wu!B=|^-}>OKAH@n3^&T`Ht8JehWorDN6AnKF6M>!(L_jQnZ9H3$ z3oH&8I@SH;AO3^8dEo%`_Jf0S%D04!?q_bVHE-K3U! z`?j*h1UK}>P(ekA0dR@~B*P8ApKLGLa103Ta?{FtYYThR!4rP;b0QLIfxf4oc+%K?LS<_ZC?Wo$G zMx`>dDmnIK7Ud=^TV{1Tqk3kPCWI;M6EgewGWXHH zBv?#V2JhuMLWL{zgEdBw%YBZp9ce{pUPlFM=HtI1>M=hg9H88j?Ap5S9qm&a!Q=(D zlGTDB+FwNFr$&sB?!9VN6`;rQ&Mlv)RF$aI)Bi1qMoCq6%?p*-I#De&Au$0(jc6$L z%H8z!KwU*-tVDa3N(8-J2;ESvvA!>_)TuE^MzO@c0DABXBozS}6J~ryR969n!#g7O zMrJ>(SSXAV83_G$mi9G4GGjR+p^+pA%3J9zAPDo6P$<0ZJNJ~D>!k~)eZ|!%hatEN zz>4Sg@YBC1#tq3ye28Z7Y5Woax_<}jc>AVkz7rpMQ8Yi=ILaz&T(ACPTu zF0+0_Row{WgW9#((7cgEi@;(UOs4y+eaMs110Fy#&ytEYNk>L}Kt1h&-Ksm|c5nSa zY%1nAT1y4hRU0>DR7k5#kx*a+3ktf&4s2GX6|tnekTz9#$$Xv}6-eile0%h{KXjdX z40Ls8kGZ#A`Y-O>sr^zA9y)f88#;Q96ltm6$Ng`1Z5_JxbE79csXe{+gO_Am)!vbq zubm=>c@R}dT__(|B#}w-1)Fg0^g&m5?u3M;sOkfz=^>^4h}IEf4Ar^)yH-nAp*|#i z^Tr;zz_m|*AQITBy_gN$2HFi&$fY%rh=u)H@2af+lzV) z7}Jo)EERm2*_$=HUnpdU$yCCxr@!PU-~10YU+Kz#p!2Hkrd$(uH5^>r&UD=2b zdGl}G_Vw@S8p)2+cL-QSVq6wW!mbUXoI(?2w$QFEi)AFB(LV9QA8V~>&gOMgGs(7* zl?SAv)VF2L&(&)&?a?o~H^29Pi;hU}GoW^coBfI3c1z#>roiIUU--Y&M7{Lqe{WQv zAgNslP>gJ43r%H1g8~Rj#cKQ(Q;NJSEw8I@du`NMlRC@2E(b?!Mx3dB%O zQMDXcJ5{R5s}}!2vldCXB>Q8+nj?rpRg~! zECP#q#tB+;((zhJDyz4&sgW5i18KR=ObdHB{3dJ3b%gh10%1$)Szuz7tlTajY47s| zhMZ}V473wyR$y6~m=cWhxp4Zh+p_L03Ak`Z)$5%F7Hu{kKLn2bhfGmF`RS8;-H!DO z-1Vy$lvJQ1C@Q13w_F>qw|TO54`FW=sbUD@qu$lu@pBlN3Q})2u)M5FuP3l1&?a~V z;IN+qYa{}Tp28?iPOd>CkeGMcR^R~t0AM<>bCoJRu}2KTCt-1mq?$T>{A1dK0Ibs| z_L%~w2ZkAtC+nd!9W16Pn=md|BU&6nJ4PBh31Yjp9lN<%Pki0=9Wp_FX6c)Mr+d0f z+s0k&wy*Yh!4jTB@BX9R*y+!?-CLGw{vfKMBgQ}Oip$E}rsc1QA{+;+rlK15koG_l z3^&3oDL6QZUg-C9F8`IqEa0iys@k}hQqepSJ3)1vfS$dqS&gcE$ANc9*l`8hrTau(y+6<^`Zd~~@F+9Rv z;#x^=!)`*1Xz$kLZs*4L1)QRhPr)CXLreT`(>u-Hk!jOlqgA=F)1Gsky7$-mkxYc* zt9YuOdD@k3*tmJ}4fL~eo$MX<7>c`$#zAMn5_!4Cur*SNg|6GVkDD^*^X}S}^8$-% zo${l?GAWLwuYSoEKi!zLGe zB`Jm59DXO|7w^q4<%5m)RFQ4|p?~m>`?vxh30RD&Z1K)cf<-8$RQF!_r~h377Gxx$ zrjDQa8TZx?|6e!h;m^q+Q2C+)LH`n}ZB&sMF8kEy{}0W4WB4)@M8q^6fANn6=rEXb zp7}STuP%H0o9@;fo8v~%iUVdyec!~Ztu3G z>Jde%e8&8*x}|UaPYpeP{DnVqCy(uxf}iNYq4M?%0*h3Lp?g8m(tJuU6cgw#5$I|H zEJkjOkqjkedJgmuv7hKEGu8BqifG&?f^uzzu2(T8+i zp;2e*?p=3R1Hj8%d3mL(*sLeYj!>BI2UsLo1C5k%7gU8TVM1`+AX+KO2tX=TSA-Hy z9p5cc8nW@I0M@jo7vsD;adf+SqmXIu+H;6ov-l+qyYXjey030}cSQIbhLHRoc1cuJSdOV7cGU zIlq@k0?g#A?3wytFIDA8e^y?w7=fE2S5{f=hL3wx?E`?XOLZq@zpz{Mj>D)>HB&$@ zp6TYFn7e%oYMLpLGP{qth$tX$UH6s%r&dyxEvk}Kr44xS6TnCiRskTg!}vV2-?ksD zqG_};t^@y4R$1i+*UoS~2aFL_de62cn!}eIp<~aMYqw`6rS2kZO_?gFL&rWM8XW>J z+;hCOZRG;(AG_PCO=mZJ!lOE0d$ulh2lpVEA17lnS3cKMZ9Hw41J3Ixc#VOG&TY&h ztNInIk~?Plb8hUkXN}_c;VW+Kk{^juu5lPJQZm3IcZYxovxw=Jr{!VDs9B;PGb``F z&ef5SnE|YS9bgfE-?jHJH+lApva2u~0KFRdLE=FJ>_Z!=DMee)+kExN?c2W0?cKKA zC$4ip zKBL%a-IAA-U=DqZ$=BtuY6W$i+FqO5-Eo=J96@jiWg05Cz%zPDSw`1`89hI5<- zi#FpLd0th>R6J5JM9Xc6`7HIE_EP*tEQ%jvlu(!#U8qMWIBnk?Mp$!V z!TShE9(>ftcLlP*VpcCuW7i%y&>1EqE{-cSCA6uO3tdBkmA`I_dhk)a+v`6+kinJZhFZb$FMI1@nknwd<4{BzXle#56Sfu((87F%+?G zF&nPJ6k|Jg8|coTIwV>ueN`9|=o17m^j(p)C8G@3qlx?dpZ=K!Jo7r#U=gW7D1fXP zRZaq+{X0Gs4ddZwe&3xwx?3uM%mtzkjL{kUwk~r!HZ7DxX2}_q!S&HkLZ)%y&;C+9 z5|2OsAKlUYo89JBKXVn;ZKXmuXyi<{==HzSHP3zS4;7>Xws|hUXs{T9>xkYLvDd7J zH1sbd_o4xc@MFKr%y~jDQ>B4yu%G)0J(6k{6^!6ya=Ye4H9W(p2I@6|9bg0+R+yQo z>j+@P{*V#hWqw=1rakpJDM0F+SCT_+-kEwJfnG_es7VBR#}Dt&ezl(nHu*m_8It&S zc<5AI>MAO$M9IE=gDOdb&TPkS1JsLzV({4$d)>j^>jVZ!z|fmQHXfzHYgaC+4+9|) zp4zanbG3&zeE5n2uk^DuuoBVr{Q3&J6ctJMg!9yU&{%;-sN$C|o)N8@eju{51aY=I z{60xOpHwuIy$*$f#qit>m}CbhjZ;FC-&<%%aQ~f1CcV~dboRYuezU6Di4z!8+zfz0 z(H=NrhExsPw(I6@+_FSN&<2N%enkE608^;`uvbDb9k*i` z;F36+z(KKE6G+Ul|7Zzdj<0Fbgk2Q?nf;ko1I_`XI{;QF21CnE9of|4H$Onl*TWY+ zDYmhpRn100(K|Wo$=?wjm&z20NY-9w(}U|wu*kDuMlb?&0AH==;EC?+sRLpHVW%vS z<7dFCs+$}Mk~j-_Xs0c)o>Ap8sG(+7rW&F6vHXBRM7btB^cnT8F**g%ql7Z_d1(|_ zmDOVav605j__Tn=rWHTa$g!;0Do^~B`=r~u)e=!s>L$#3K}wyd%TrZc{@y=&yN4KI zndU_!7`AHh_uaV@2mG;s)l=<8PJBY+i|A+EwP~^bEvu51^CAk{f5uR-Jk;X{;umkbc)8@K-Wdp9lH*l9ATuegtk(ZAj zXOOq=;7N*;P%S1dlvm8LnGk3jGG?|LJaV=woDvE2RrLD?7874gY)6X``{>AlO`0jG zczz9^)G3ernw-kc4GYvj-=;$sjqTviyEZR!l{IbL zsL4;cu001^Ngkn@JGV3|i$EQxjKKpSk%0o(QQ4?Ff6Og^`WNTZu>!!e!jPd1* zr_}Rz^X3%|U1r!Sil>siOX39eQq;TBifTzw0|qgE1UgciY|}}Do&kjPO`_gK0E_qn z;1Fj|Rvk;kpAiB=0dUz{-;ne=v|0?;V!bst8nLS1TGGN#=i6`LHp;IuYjNXL9`!-2@XvD-Pq!`G&%e?|0fXN|uWi+)gH#H6_EOsOG_feSi#{*e{gI%d z`2HlkAY)$SE<#^!2yzqE%yi(J$Pgzfq(w#6TUTGNy%^Dr0%b4C&^HAZQ)s1NQJGKSmiEXJgoq+eWyOITd%=769nBPgrKm7KoRBRQInoB|SK6W^T=EE>Qs76o(qW54ctKwZ9Z)m^!8%3Zp6)*aZnLKPP1 zWHw9BD=zv9AAcs$MZFp321&x!Z8|GhW8?sRMgxb>RJD=)%}hDw7*bVcu3ua&w8WB< z8YRZs@K(Uoa{aJ&3mC(*0PGEQwPWWg5xHyABK1?YZrjxz+`C48#we!-3`ok*GJs7u zet4VIu7^*2!c|sOtLO0O!L14agJgZmwyMXnL@JpuTu7p9U-!1Vc%EJ*6ZFZqZ<-61 zngWXvY0w*Do&mlMcFus|Gj!hze)i{DU)n3ePm;8+co=_el%2% z>A}RG0lZ-VInB5;N^oI7#jH|u?_V}0q&8Xz7WrPlGm7KbGeCsI?HZht!uSLw>wJZr zB*2IXk10+;)%L)i)y_+{#g8@N_zJx%*+51*bnfGxc=3<42kB3L=jH$IP8{B5kAePi z#9SWzb+Iu%eE*-_wM%EUcKCWKY*ZE5b5x5tQ}mxE6a0E2O$KO&0IdnpjCS@I)SM^YfCoiFsM@%;~8`mcKhBCrT(BkfD=z(d{XBa+r8o7TF0SG@*9 zjfe)6Aj|hj<4kZLaK}D1AVqM6p za-Do8!NT>cm)!9~TczrS8Y{;4)Un;JXWtQ0^9tEIQ7+3W+^&ra)KduEi6PEyJ9Kpy z&K}b>i_&`Ww6aQkU)Nqkl=)*WBlC!GP-LDjoIav!;aQQfr>6_bEP*&662S-h70Ros zUC%xvmAPi!=;NbF|4Q8{T?@Y$fpF#WnTSGTi|`SG#pGv)^lS3$_@-;FjbMdqXT}ZxGN{u5OV8yckS+qK7F ziF>feQ0FB;2y{QP@d!4N89#Gux7)Ppbw3BwW|BpnY8e%-P%UPx24E8bECi;QNyWKr z-?68HGuR1$WcnFl8ek8wEy;j1H;pNN2vJotBUwOLiXmhOXu9-{TnoTg8phdqju&Lv_TJrGG1CP z8Yj#Ps&n*u;{zB|u=tI?mff23)bDAQB9wka#}KXH-=UVFLMjTUSEw`rBq-`7Qt}kR zvZzQEa?xL@f-)zt;jR)7B;dOC8s@62+qgB0e;_;CcgRHbI5F={bVEK5N_xj0u2;X& znybioC-yiX6A_qwJ6HOF?s?iimDK4gMQr(oO^Y;2CSrKxeTXd!P&0%7d^H$+C`zwa(yI3D-*`eY>c&)Ai2y=t{D zNMdYR{f2ySlE&;ES@VG}Eixq~Zv4#W-K5zsDz@3W=1sT!?SF8$@7xqRBA!BX0kDYO zgGNcxnlFR8KVs68u3PWHZri$djn&~RyJ@JEFAlI2Oy*C%{bWbnUQfb)-1JYnuDxod zE_&k7R$V`g01}QUy5d7NuYO%~lRYOy@g2#}*-!tjt2=WIuKvD03;~EHzjT&Oozy$>$iDXi)W0Tc~6u@Ft z8x5fcEWYu*|18P>m@a1Dt)4+Yt1wWNl!26Dq6Inp62(Xc2}L?The`|x>lwf)g?|rJ zB>HD?&}6IW$AC_%pvfD-V1}SUP?00+Lw^PVC{-2u)(CE{U%%qcpE~R+t7}}xuKiWv zprXMXCImr}J#EFMY{$A@Bx(i43~Hf{T4V-UWXu2tbCf8?XUem;2)l9$Z=QYD9`#~#0Wwa)F^woFcr?+0j*IDt|_ zr5$RhDlV7Lr_^ZKizIqb>_u*V)uQiOFr(~>2a6d%QR=9bHR|0RIAXf1tZc2Z3j(5y z2x(x9N|mZmoqG(@HIQ^6nLr;1VooUUk#H~?ov&!+u=&w*Nr(ZY)*%9r_H?strDgw9 zAxtCXkO1K9Ttj6u`_(v&HU9j9Y_)%R5*$X`H3U{>DE+M5(BGLWIE-s_QQ)YhurUjh zAO4(Z#t1iXHrb!pMd+sl&t~(|J|^@olF(x84@jn;jaOS_zXEuusL&J0oHu~wwW}9gyAD0nFNpuawlZFbJ}`g* zdu{o<|K!?t>M7xw)$~wZt<%4;r|6^SIT4gI6SsBy?(WjLl{JrdsumDAMrN+cfe zL3|(Mp%{ctWgc2?v~e1#NVlxAriYu}lhFqCVY&CAJqL_-bD#YK*P&Bick1{qxA^tH zai@;#jQv@-wyfkIlSfM2z}o3<$jDjpH=Iu@$@F|uQN)Im%rx+hfDbJYai45lZ;xt1 zStqn*_n+fPMj+m(=)Rt9mxSO}Grs|xg4&R{ofc;O> zWXtNe+^HiwOrz4i~nvbYM7;T7buo!w0Ik!{`smL;mn$a}L zn9t$>d`K%dZu)a#f^A&!n#NeLXJfFK9x>LEy%<)8=hVILaK(&nPRq;I+RH zMS?Pa=1+<$WGEpoMJjxk=4vJKb@8YA>{eN&tEy_P%<|1^mo#*BQ0;V+jLray7>R3F zFT0A0D*Zd}xp4ZB4ePC_QiYGegPsIcG^mc=ydjVWMbIcw25PxKs()m^0e-S^zTYME z-w@;w95G#T$ILj$8#rvLgg*f3I5#Tk0BmU405$e6DyKXTGP8(DWeP}<1fmj* z*a2ceAHMfb>SglHWEQ%3@L^Y8Bqd~e6#EUH?8+)D-QnHq-N8MpRiz5RiUf@MT}w(; z_374Qh^|Kx>{sigyh~3bl}4)doKgByNUT^gg5Ifk$M89tV_8wHeZd-su?w1^2BpUb zLP3$!s!lK^Dot?3_p`AVZr{4*1um!#lzl!Td(X2|>SS zHYmawFg~aP!d_txXuA&GwSO+0J?vVw>7wA93L}fcSf+kMCcAOdKjn@b*eKDLs_Is1 zG1$KLUG+}_7BxSz$6yJrA!x(wJ)6OpppqtnH2edfOOF;{YR|T%qIw!=${1ml11hyV zK+WN?gHo)ojL`xxeg0Qf6$2EnT=*TgWBq$JS2oO-%eOBz>aN5M8a_=UKv1OKy?L=a zb9|p>sRru4RcG1ysBeq`o&P2bpM0S!9!1c-CaC)%&q?52eQ$`Cn&Sh15DxuP-axm?DXKh zg2k*@&f6LE12~VU8e?Bi9@(h`%aDtmtB}$>DyaZX&OB=NfInFx zpIo!=%K(c(H5JfbTJEOK`;xu`Q8ij|a)Cv}f)M1QznYdEV#J`eVRpHB&n#yY?avR1 zHMBMu`$cRB&HH9zu4>Z}cmc1-dsg#RjtltA2QT@RU4f#W{YEzgfq^K%Z4PKCaOnd0 z4MH8X(6u#joSs1x{6;p^US zq#HN&8BrK>RYI>{zbu2QfU%)L)fx^tvpmi4WNhs>8`S@ZK2Th8m3?bqeR~$s-65P{>+j5SZ>* zBvh4yV~p=R;b45f7J;6H!D)j^Ak=rzc=bt<0hHW-)CZZ7mdLo*bih-1_>Cs@JRBB($X+`w96U@?84>H0&1yL%TUVH8iN$drzC*0;@xjaDbwg^wjZJS2}lW8wsQT4PF6*e z`)2*2>;Y75oI!ZzoHLt$$@RAH*h|2lOg}Rk0f$iE2n49CLthqPEGg07X$;PtTTxaU zJ5|%RgX`L3sH;1BMDrb0xoSt{s=IpYNM=w01Dr5U1zI@Y%f1X1LiSTdd9^!!WQV?& ztUuSp=VQA_+92m{z}hG5@>DeoG_^Tj7Ez-^uW+O_2JFAlNp)mH+wZ_jPV#$ zi`fGN($_AX7b{}N#`m=k0S`9xJ06JpIu-K9QkX!-y` zdexcHH|xpYQm^Z#6|br%ecq@4P%4m&oESIr)3P1(JuzN|zRAHOW+_Pri0eCKk}8D+ zX3V^U{x*HymsKeQfL=IzRFe6Kj;&k%vKu+!aorO%Q7V9?WtF0{VV{@3`;QuFH0hxi z)K|WB&0CraO#i%9^AkV%GiT|J7&VCCP(9tT?rj0;$kt?LShJpFOM_K=Zdnja`^@Gm z(vUoM>L=agN4}sLr#m+-Qvd%IFG{7kioyP7UYEaa0AQCM1Ko&;kIUDRm|+YE1JI%A zN=4bcq)((;6+JWIk^FN!hqvk7pBVy&)k?zTR3EdSkr?vJfU%l39dyP4$k+>M7Sz{k z912-;fv&eTmpn=I@T1`6+ky_K~Fhsfy za(#zQbnQCylntk)fVLjSd|bVBHd45!rGexP?5<-6w`ClA!gWNntN<33ferMTM0gtxM+B;ZlQcRb*)@P0SvbH2+2x6|o)@J< z>K&=*yg^_^17lk;%Z{M(q^b~rT^4~c9%Q;`8Yio5*Q8Xv|D^aDsbHKuywh#`@Tb0N znKKM!;+=4IVLw%Qx-NWRUi??>CW zn6bXz;>UmMlLHdED63H4BEW(m0}1-O^)~oegOa(ID|H&zfWejUOhR%#nHaF_V4UfX znJYd}3NF)AoKx53`&u{~DEkorAS#dqiz#5~<=`V4YQkVQubSwofPO3G>I1d_Frge; zTVEhw(YwrFxt0$g}Zd&gq{g| zinGwMb6TGU9#Ra0s^R|R1@hNyK(iB z+rMk2DjsC~`3?XCHpCdLP}=TDAc@f$R0E;F(*H`5q)j^;dxBap_Jp&0;mlD{m!V^m zoZ-F{HruuF+7y)K-+@)@RMC_Fp$Z} zmOeu!xM_30sKD;l%`5Iw-C6a^0-y-;*em%I{zN%Zg{kLiXU~OBs?d;YseOVP`0Ncz@{FbQ8@BQ>o zHC_N3;X{xArdzq-+p4aRgqZ#0@3=E3_Nx~Pn=*Rp({97EpGuUecHCS6(B*IcqdT;B zjh-7y-i&>L_S&QGaMx$>MA0;pkOKF9j$EUk(*w#L|37>09c9;boq6txKmk=Kpis!E02Ff086cP` zQlzqEIlE=I?RNKcnC_YGnbot_%s=C`W*pic%h|FmD_DV|D2fRr5{aC1&bg3N0fh>) ze&0FghF9-Zy$Yfz8E-8TDAarR-Fw15``i25->#W%rw(nB8mw9%$R!B2+<#}gS*rAI zq*R16Z}u`*tBAeXzx_>H_v61%a3Xw#7*fqmvVTjS`3?2Nq~=tgUHUm2IIPxoeekNC zJGEDzNwQ8lGrIYHCJu%;-wyi*D`5DTnNq$dfQDa19Vo#>>>^`JD;fj=2~eWidh7am z9~^Xa&~&gn2^Q18V?AP9u z!UUcX^Pyydq{W#NyX+Q0qfmaJ^`B{x+Zyd00qDnIG2bQn_z&URa&9j$3 zkmKzhoy!?F5yi|3ibVTT(^=nB5F^X8Or7(BjhnX2nV#gH^PrVF8S2=m^}|7h_J{)r zh{3=i1>LKnO7v0J+b^Cb2oW8jS5~V7OxCx9U@_qkb@(2`IAvruLvS5~3Yf;2;ij57PfR_9Fkx5 z)ICYys^4I>6aZWS1Q16dQ>EWk4G}OvI71XUmaST*G^w2i*#SU3>%646r}eI^RxegE zNT?=rNF$0v{Uq-LPy=$IMX^s{6I2ZvsUE4k573EV5R@nc8gAdXVArmkk)sBPW?j(l zQ5k2S6~!SUI0aZ?-*bKT`H&HlMT5L`^RjFlz!)F}?YXchT@#ZW!j9ImfSZH55R*vS{Z^xp)|5AS+k!X5mM^?)5F>)3zbNKqh) z(h>y+sA(h!f%E<0TYu%wEwaPOgT!a=2vQIr0hEy;MZzDu6ezjQG_R6Hb};qy&NpCCewlK@2Y$PIyG6yJsV#W5Dr=pZkKnC?UL_&M2P|qfx^j) z9iF%ROLq6}bvt`(hxRb63+jx?G~#Qa<_>tr50l?00$DaYnHd6gKVw@)jGJRqWLJcYbMqrPX&4DI95{2-!a(_m=re7AoS?u+zn)SuR05$*ssSW( zg_B1Fbo9gpj@pm`7WoIn3d(vTic_jg7IY?@)n2_T1!SoUmML=K>TZ+@A@SRf@eC4OyY2aMXZ z`WApr-vJ}EuE`KUM~#2$ZX~tLGvU~rV&SmXNBTAdcs20-cX;VHVvW&ml(~j$s#ci5ANNus(~Zq zR6<+jc?o)u*`)3nyVq7UxjVpOJ{iR@YsqyMIqW`w#xt_s0Ryv_eMU9t1aklZM99w^ z-=Q`^P(j-*Z73)Z@SiaK2^%?Xp4QXm_y56;?cboigu3r1zWl%2$wQm%%<-MJ*JYryUs;K+v)meoJ=my&wFMYzI9J0gG$j_^QC*lzE@9F%#z7 z@q>>sb5h5g>^!J1XWYMd+i&4o=}!d zjADUPf*d_*p}+(!4vy?wud@U-&fH)zuvEgIZs&H!t#9pi`tXrghz7(ie&*K%ddTXo z{^6gvy&k?S5dh7413vQt6G2TFWdB@y5Nsm*5!xnuknsXwlg-C&kllxNjAAaWo}`lM z*-K#*Q)AT8b0+ov#8~=s+NIY}dG4i*sP08Ahup)fb(6K&{3pJwjPkbi|18}B1me_V zv87qPC}%8s#mXzH?eN~!VjJP3w0fliq`BuZ6D(pU5MCjeg5N@b?ZdbK&Iu`rzMssJ z7TClYPpa;eHWL@m9I_b;U$VXfMrw_pKYc)=Hm*OZ&l7ZNRpmbsNmf}{#mp(H)-x8p zWCymd(z=scZfQ@~5{z1I##qY51bTf|GN-@MI*Sa^6d+hTZK>~@xY`cwTqV03uY?xW zGBdx}_iZ2iv)aCpNle@0j_$p%x8o#C@CUF{qiW|^QE`!ij!u;}Zc7to-18jb4ueHG z1o=YIJa6Lh+kWmxK&>-k2Qub)XMOT4fFl3+hog$&q(Rx7vFK&%H*l2I-??dIfiPaw zp^%a%qC0!ZXC$J5QXB{VoTZ;t#1n3}nzrX?TpAoAcdPF1IIIA3p;nRJUpQ?`pZg6v zacGN;96enMjoA)W?wNvjvRBk#u(^p0^{E^vu!!SF4GW+K2R15%_6Kc}N=x<&rxQ@< zq_kV??#()@yL{RSV0eJjtR}<{++9C9Q116 za1t%&kl_H6YOuaMj(f8vXmwJ5&#C5SJAd;5i;+XG3~Gti9ftw*zCbz3ym)5xotnDp zL8DxK<&DeP2R+MS!Sx3W8EqqK=ct_v^*Tu3Ly^RZBLjeQ!u~~B4}p&d^>;)yR3B2y z$f_j1IRzG*nw06IaWoj!Ehz>okJDuXw!LK||nfea{$oKRKeK$aOMYE=$=il+k^YJY~1uGZ06!uY{NTW6R=+L z{8w!Mwl~$ku4>?LTlw<86G*3(#>_>ps7`hBdtX=Jaq08FDcbS7-~R)x1%iT$pZRr( z*WjR$KXFp@p=YLXQkv_Np3Is5iZ}!%ay=!gy zf|tYyS^w5wX$=NO07K1s=3F4~Ic4s152Q*Yku@+QmPC}-H})AIDgq~r3Z_}^t2SfqJ}ynD#bZm(o<(SXAvS) zWckS)Gfvo5#*04W_j zF0gq|d`Uh7w0X1(LVYzhlOOPW9|6^ytSaXz!6VL_);Y}lJ?s3zVp2RV zfbV48XK;tw_lMf>jHjr|rLos{~C$POS;=p!&oL;t(~WD|A}9;jqm=Q9KzwFXSjpVJ2TpV z5~pbt@ZeyBPKFag1Qe&1-=m0zBg?@yX7Xau$}+)6vJR6PI}}cN*4wx0WF(3 zfGPA<>bh_s5wDEGR zADJ9Jw{^`oB%zKP9evt*_3CTqPVEuZuWCSz_8=5jXro*nRbRm3#nbx*79CZ~shJKR zJx!TtL~zJVF=xow4;)f!m(CqhwhxC1fgEfdwt;5sP;PMsc|mVQ$r11d%@$igeHo5F z*+{6W0GB|M<2`lfkBO>?kPD7D;tWvJaUcP^IG;$eV@IHx(<=~$Mb)4YR)q5Br4y-) zMkX*!0k1afLN5BL^TS+#BUwX~tzNE`^Oc~{xth*GDUBkA!de07L#@AZ?uZ@S{hnRF zeA;F5GbrXs+bX(dVWEwgL|?v@T1SWXuCbA0W?9XIc?xnUFfp)3U~b3y?`VF=76Q1) zEJCY)@|FKdS-&l7z9naR=HgEYWbXLj`!;RnNy4!ir1{MjPL5qe4IBmg8+PA1p(ptc&6UPjh z_8@@!JuQtw8A)rfh;0^|1y)F5u@#q=s>Kd-z!))?_y$y9LuI~t`J@66qLbfudpzlj zWOZkgHRoA@xX*z^7TXAtuiRR2*{so;chj+ebYu@;C1<^uaI#SW4pJ7Q) z&F7$Dc#Lgb{SDRO61WStsid@*&0g|pG1vBN{-K>dvQ2x_1@pV| zFUGMqWKUF;ZHW%h{5W8BKf7cO=TEFv(6U}KXQSE>G=i9lXw zUC+m#`}rLK3EU_e=W8p}dyo1bAJt1P+H9=wd>6EHR_Omn-OeN{Evt}xGZ96i!OK7K zuT|6V&Ub#_Ce40UG_*JV>HktsEc&`ZA6oPJpW4YI+idW#@uEHvmAP>Gfa(co;tW8* zk!6$91CBj6V(e_GX;C9V=JM{XtJ;J#fhCgo!CQZ=T7=rkOT4q|qLY9=oJndp_zc+x zB0+$=>sQaIUIh^q99gJz(40op&Q@Jh@)ZL`3_+0`)k|j%h}w7e)^+vlO9F)a(MubP zG6O8C=3(F{MR0FkKc6)|oDY!c5?IX0W&|)E#5~;jP47vhu8W0lpaSwAV*c$f;#Az7beV{5{;O>qF@r*JPGAQb=tRET(Bo0cdh>$;@`hU~?a=L7buR$~-9B zn_nFo-l?b8qNdH|-5QpM{nOjg&(O3S@FGyHR%k4^Kxl8j9Go`7c<{ zvP!#r{;-`swnJGq#tz4yRtC_f=}XFf#eu_t#!+@P$cYGL4vGuU=DyR>wh<2@)4;wY zV1(LW&tB!K=R#SM`=^mIW0nmp#+gM|v)EDqSag}iBv?eGhFTw5F97TUSPcEt7%S>k za26R`oW&#i*IA422}z)d>=hY7#+EiWnj3R#kPH_BIoB_r(pZtD;F^FReY~Qvw6r7NZe;dxS6XIwVNC!w!=e2js8+QBF6|1ZqBwOqH z*%nLKhP8m2CTn5wv%jGX363x|KjWsakn$>ZuLOahcX0-wT8Vux?NKh;9(D0hh-vEp z?U`sknQ;P>1V*@LK;VI0tD?Hx(G%xO)N1F3*Hr$1g#XB~vlMh7vk9XmWyb#q0 zv2zGWm534YNVL%FSI*ki%f}^-!x`WhB^hN5epyF*#Gip#5}fI$@EIlmAz4m>3pcKu z6{{kEMS?lAmV8>Ei_9V*Rw8VrJw!>KH1jEC!*`-GN;{uC!D9PvWr6JN)1Ubd60Lb~ z_of2q0E~#{nn9O@MKx#H=Zv1E1h0mTnr3HD?za8g-}dU!e%vBfOzSpVt=3E45!LKZ zlw`iBPP??HfMU(~xf)LxWCVya>8j~Wc6{cwb!3NYICr8&tcN+vz91ivRxm-FF8I6H zu-VH$Z;u|_lTs>7FP&3b7hT(l=|rd-Rcy?t@$;>?xL84|b0_z>HSLqCt~|)S^7XCT zyvvM$9c(z(GeLQRulS_Vcs>S;?Qh9{!S5)j89%oLwJnTxs4-v>!O3?onBPIv#{C=? zvU6gC(QbbfUH?H-lpP05MdbsX;^63si(~{5E`Z*I7{MFg04&~&z~bs3{;9wtnMtxs z+t<-!sKK89!he--g4{QbF%%54Xk;d!*5KTZteqn%a0$}%sj`)ybj_UURWyFuauxSS zSv`b8N_tvJk6wzhk{Q6+%w$_p)Wo5bc1|5^P|rFJ zyuxBD>scV@NWt?o=jISZNb%sP+E?+pMIKm~gMN17Tygh<$b)TNQd3)zjqBPUB_ zhAbl4JnRM;CTs?PkSss@$I0@yC=k`NccopSzM0zG!a|?97-r{A>{e#c(ZK<64RQ|I z`(z$rBLFm6FW3o~1UMTwW(cf6jZQ39Sy)>8K?pxS|qr-uX6rg2aT7hau$4*(S@uHOlwdw2~_I~I=iG5_enJ0oX zhyyKs{wua`+mF>g18{=9<$bPp)ihtMf7TC9sn{p=ceR_TBUL}#h6g_LS*QrV=+)F= zswXFPU`}j_bwogr)+T_)@zYld~zirXL5H@e=262++=rl1UT?!qE6`FEuteDlTyyL0`r&g6$)2rdL1Gq+48 z`y={&(kYI>B4H|_R~E2(ml?185IJdz|>#24hOAhXC5 ztb6k>MFm$sZr^qaHUVv!sF{T67TQobA1S}@%=zf8z*m7XzJo?g)LfA0xOVAyihJa~ z)@LH~tSfBA1c?{Ae+)l=EiJ0gk0`i46aN@2w!3&Azky{rYTR7;!)kOYXP0bEldJcE z?%8*c(Qgnz03G5P8z>1D1s-$IYZOnE8Y!8IChO6ow+$OTLlHZa4{3P+!P|eU3?P&X zB6gWz5sDDbB?Za*w!ERJOyBC^_R^RCyWP2c#Q>8~MrSSll+9f9X?y>*KUP!?0fm*H z{5?Cc^Bpx*9$GU^bR-(qB6AJZXy%eni?$b>HKK;S%lnHGQ-A-C^&ebgJxa^eC>k{~ zj0%x!UexE{==H4{tb--husu3#9qhmX$7$WY>4#AbRwh_E1iby6RtvR2@L4D9$Erc2GzMf( z5Y|Hc#{s(ni7Zej2UsDvM7=caHfXJYlTRj+u>jmb--dq6n!9uRn!o}XQP%CHvq$XV z0|a8jRLa&~eYG!{<3bV%!d}t>QY!EHkng0+#Osf{M?pRyUbEnR8 zPWF+#>qNl~Vj&@-?^pv)C?z}xKy~FSu14|5p4A#N>_AH7LuEk|A##&?z5TIn<_iTP$z#b=*>@isjKr#Y1P~=0ljGA6*9+^|> zDWOw3`{ctVa`dy?_%6Drsg;vS%Y&K09-&G3#2HWNo}ixY_~3iWo~G%}ZD$tUOvlzL z$}EPSx2axs?zTd(DE!pQ>PA66Y_|h%WXTA`vM)I&U?V9=apknK^aNy-AyG+!FA?yg zK;Wkp4L=1I({ljDyl2mH*$wt5feOkYW-tD%0@d5seaGtSZ^;LlI`0!w?}Z_CX!rZk z_;vKW&h~!hfdJhLU;JNH<3?uv-B!PQBRrZG$im7`xy{2)a z>_YY>;|tU4E$uzHfMoZ9Mb7;R(^pD?{@DHx?9k5lbT{~fxtI<)*GiUwb97EuJB%Lz zb7SGtzpB<-8{hky1B)JvpoI=wJj$O zZB*~C>GNL{72y3J{GlkNGZwxqu??~%fszYV3JN52JAei?lGKk~uRAYC6ekepi35@d z=bamutY>*&>s8iAbXEYS>OxA(S{WcBq|`S+^K*@Hy`V+HxWq=PagYVXVnw;UGdER*=F2x1pn^$-$!M66$hfa{!l6 z`EW9sOU4b=LIMOtU&#QFS%~^lA~4dsQo#+JN!2I%IzkP0kYvvV7DJ6z!kjWbWSx5T zsH`3LuQ?EB@4q?K?7r6*qbPV_U<#lnj0JJ;<-Z#=*YQO9a8>aF%F`b z^&d3S#!gvggNM^v;*OjxsHO^1xecK^W)Be%B7?_4PR1VxjtoD05b!o|_;?BBIFW<` zH3l#3Rbh<}>lK{gN(2_}+`6VUL8}F_d}=Y$yRWFaD0l)m5!S*vJ+S>vDG8E+A-iz< zMxB5T_fgTOO7vOAALrxFtt$e%tUs>bw`z#QbEtiD*-#i2?r(a$Y=e93_*!la%02Zq&I2MZbm9V@4s`G$^Gt6<8l4~7y+(mPKq0lKwbPbc zzy8COmC$)a2EV0Qy*Fpf|D^TlKg14fdt0Jy>>dArt;Q+SyXcVZZO1i<=3bNI*ez4$ zy;TR?cz8Gb911tF7!M z+B(jCW#2(kBgcNRuTZCks*0-W-5Zz1CV2P|RtlNqBCnX80T|l=i`)u;hI&o}jd&)Q z0y7r8te^&V3fo^bV7N_~@s!=Wb5)dNfGai;CI%GsuD)2iGnahE<}LrCp8xQ!Rkr$# zugcDcpnN(wuV%B>tD>L4B7s(VD(~9xswnQ*rJ(HE)_P0s|FECCXFa+sDE4#C($8y; z(B|gm)w2=h)9sJQRK{mk2Yitz*e0;}$cBxYBHs>yDk!gRj#%G?He&1y`F`vH7rf8R z3U|+whqDYn3>rHOB?26jdSteZ$@IxO;DtHYCKU?E2=*ju&$Id%;UDunSGu~!AAkO5 zYXk~v#?NnYbxEAi(11!svBY`7Ig+E}7Y{}YbvXy1I2bcyRB>D;bCHLLB@Pu%EKVHR z0Sr2a%8Uh{RQ|iMW#Y;! z`bX_ZoPwlVO9Z~76vrX2CaDB2qIEDhFQ9S@O zwMxw=byBYQC1gRIbL8Ia+i_$%F)c3B#kFZb&l+~0&rRJ)?~vB}#hs5?Mmuv%J;2R; zC*wu74dqUvv$_@_uX?x?N6CWTyzRylQL!?4WHkUy^eg2acWwNEqQ996cml3Hdn@Qt z!rt_)b^u}QH>idHx5h{H0v!a4h^_;mak%&yaLF_&V+u`u!aUI^*_$~3Cy#7aP=Ra0 zGC=I+@b1;BrNQ3eSm2~_9Y6#WS|_U2sDGnzw4(N&V$Xb#)h5%a;F}LB@NA)#fM`%i z#6Nl{Cx!cp>v!Ec=~l3)3`_Ppm`oaU+KRK6%Eb1-u_7Bs@PS%YXHVD2_97}ic(A%_VdeRThNiH-r!*h|j#A}Z#9V^pK-feUMgv1frY-cZ$1qm1s?gGCo0 zD9{?7!fK4n%XM-g_ki6S6Un z9=afl1lGzG=o~R-mYqGZOW70H9Qr;tscjhZ?E9u;)<6C35U6vkp=L1zsDXoa&3dP& zB=w>}kfTEf0yhyb4xp)ZfWqBnc4s^Z7PW@FlM8TU4RGcPI93gjeL|W1A?y(v zxL>~{TL#+)g>eN6Lm(jxO_oC)A&*E!z$9zA&#?RLXh=$4`@<{CkigaM(Y(2bx zTaFCInT(<~wdy!3?9l_nM!aL1=XeM#QkPIvEV*(1PSo{b!+kmY6g-m=eD!Ppn;f|@ zlNO}F;?fs>)3&ewt`yS%l0<@V=nz7nZUpBefW>($enEAQ-~H?VSz;A9r%!zH--wcN z>c|!~Yd&^xqk10VSWKP!3Gw{NY)GIcA@~y>k9rnr=BQ=B0fe$Zgo*=;YXCl|tElWZ z)SAsHP2s4b?3ly?5*H{cu~UaP+qQMz7ATGOYR0DRtm_biMf}`iQFn=!Vh{tM$OMad zPGk1BwF?%#~& z+%N9GymFu%4GA*Uoz-E*VU6QcJ9Vk3n1Hl1$G7X?R$Gn&C(uJyk;w0$q2sNr!qs#U zodzHf;E8F5t&g(oYu25D1YeLahhknq=Iz`e9oA$AwyphV)k`I_!|u!u(NUK%jkCf& zTjYhg!aM|(O{lrpl@Od@qR99U9yY;hr!5l=p65S(WQ+O(vX|M%)GyLv!L?9$-#LuR z6u2M<|A}g-Aezr+CD)NM3q`umOc5lFTX22@Do;?NGr{3U1s0R*G~O|8Rbn^BPk%zr zaz$me-MMpJ^sIR)?m5-^<)#B_zQHzu@e_b zxsWr2wLnV;Wifq5UBM#1Mrqqa;A0GRic^+o-;r%Zw8(w8&t$gg{l$C)H=G@D6|)Dd zl3Rsu6J$IdtaBjr^YK}6J4~l-OOTS8U3UXRGqlEWQF`gjm+R6<<;<`q4e>?DX+%*6`qgt1b7NJJ&sC z1B&5H$@eUa-`DzTl!QRtMK}trh|@>5Cj#k#Zti?hComXJll=EVSnmq`6cpLyInUeJ z$qVhkj#Z+rYwfg{4IMSvW-a-wf(ko6{9Y_BmJvM8|C^H|m@wJ>U7O|EP374(ak2e^->L zo7c{%f$qll{?RU++$#e*WzGw#okT&EEF`rw$wMX3J$MEjXCl^6$0&5C$X#_5jjqnF zsGvxhSsW4^YYym8upH`d0N`XiH?I17M-hySVkTq0qYi^V0}~lD+Ak!PF+(K1Tfw4t z>ay(@gdRAg8K0=RuBR8$Ym5GTWNKX2~CjAAySONg?k%_GuByqkP-I1^l>o+p?eAFK zg`-aJi9O;KD5HQW@qvOO8#H{pdPZ_>>J+bDJZa6%uC&83N4!1HO34f(=jcLV6xWQs!Fr@M!^D|Ss>}vf&aE34rTj~98#WZ@XR8`c z{{Wd3#2zKps3WQFMLrd_ymED>|JjyEeSjCL3>~vWaY-Tx}gjXk?d`J zeo>Y%YW!TIw=V27^$jKiAA%t9q3Uc!uIyh&fLy0D+}RmW9hrm2@BR53fr5#%o^BzM zg(8)UKDmf|5ToIdIRGN5W*^PP;pE_i3YyFKWI9>F8R|P=xa6kE(zp#(s6&|u8VZMV zyxQIm|M9=e*rQ}RebLM6lY^{3{n+L|@ns2I96j)X&06>=)f3Qkl}$Ed@u!r1eEZw~ zw-gQm7mJ?$HM?*cszHGb9y!rAz4wn2nc&_5qfiwP*g*A;I;bcMAgkxX*)EgSZ1g@t z{DVvj{o-f?f{}CeUX7x~sYbv{=DUcv7dP;cQPecy&=dKLvRlf8B#(OUTy${V1!qyT zs9qI{Xrcbd!I5-8+mBkc|Bl$kWy>-ZsJ|Fs1O+#DfVij|fScMb)N0AXMj=zLFbQCX zX6XJzxwBEqxya-{c;Ez=8Xi87<4z3#XNy|CkTJ+gk9KW299Z_QN*tyQ|B!X0gCj{6 zgvdGjL29jmewx$y%WvW`K~~6k<^v+*h`Uc(`NOvtwR}UyNaTgO&zf=bZ0M*d+OzbB zdMopC_0n;>dgZk1S?CYHXbrWBZhL1l@z|>KtEjRu6BpX3 zadQN?0g7i&xbL5}_%ouCAuzyx7I?_yGv=gZ(z?Pq7jZT@-ZLQ+Nd^MPVAz;xa<)z! z-fWl89g%nyjDaxDtR2KmW-tA`z`^c~uSF`l&J4JjahXP+eaQk6ThF?0fSjYPMXpuS z7FbLI#S~}^_mkKI@p@{{QoBHd`iZtQ%UNCW{8!Y!u>Sr{*-Px~(S7SB1{7MRB*iw| z=oct6r%X;kfg$!Xapp>aGgLuQW~81dkYbatzg>%y5d;c0B^9C1W7`EE&4D;iMU{`{ zD1ejaKBsd70S@*G_9p}iLfxaY>44oriJcK-AV_ok;6^bIpume3=j~1m7IP&Hy?Yum zUO6+1Nlrxj56e{vf-ZgGD{3u5P;=|rZ`%HC1VbK0?I;|U&DTlKlF9TyCRP=9&VH_p zRX#LS3D&5Gs%L-zAYcJBHY9r42I@SDswm#}79E%xF=&72B1qJWUcGm(sXmkT829g7 zvj-2nNLR8Qhc_V#wkQiVMf7ymJpV9a>`d7(#F-=>*6yNhXO1Fv0ol?rF|X!7`Aa$@ z5AS^6*1h@X0*&mmw!os+Sz)oVt%!p4A28A?`wuZ1(*uw>GdT|knBTd1Rf0X~7HMub zwMP!le46z8bIf*&2`rH)K-dLlSlAbFHqZ%7VbA@6+=-!e-w*I+4Io@d%c5;-za@Gy z0a0`h@E@_`o8JF=q*&eBh6J8P{Acc|j-Q+N5G-T9#3(30k$a?}$H4Dk!Ckw2(g&G-1f=RQUZXwbRkN}vuzHaW&2oYNs zp?2p8eXA5LWm6Xvh^m^GQyXGPUb+{-1dJGtK7t8=PAHxj_1Q~4E9dg{um2x%%E>%( zaFflW77&^ofDs248Ueop$nkmZpIR)ad6&)~(LF-BA<_uQAcMg5Fq*2>Y-$pqg2sYV zJ!8Qua$faHY%InCDhm!$Sy{Q%4H0#~Adv;5Zn5#<107b}3$;!-$~Uf_w?2Ibh=$;@ zXD$hD_J<>U6~LA|a4 zy%NcLE)ghS*~Tk!+LFJ_)weM59!GJE0ly;Aq7=3_EA76)EwhZvw4z~!-)9BE@rR=$ zjk>zhp4NZhXtg52=^s`zO#zu>2R^X#C-=Gb0Rq+>&czy64pB0Shy$^9p{D}iLVa?` z0tE*Er2X^_~!RV4{ z@Rxm@6?|e1les~PKLN(VJ)&9&P#igKj=mrIg71gR=hMKx_ z{dd)GEr79bPcbbr*ZgP6`gpsSD;wBqEZc|*r+{J*uW7YL;*4u zAq+8g@?zOZvJxnt9^Cn^=8v@$gkv(@LmXQ6H`jqZ0QHPDb#&i4yKr)!2PpLNb@iOV z&L-DRdpj%n`w$#!T`LxkK>#gDqNfY?IGVB82F)$9HBi?$Luey&{NM)Jo6xV-sfD`? zWaxp4z}CbWE0tLUDAL%QdcX)KrKoLT$7ik)X9eOJ$zomtC9|FEaB6IP{Wh%%PzmR} z-M8&67c9MdLwn!RGZSN#XGS6;mlA)i&#E{O-gbZ@n}uv0Fm1gWq99pf-3L3Zc_}Q2 zT5(XPj;Pgup|uiz;rIADQZ}zUt1Kmf5cYZiPYNnZU%+hign2e@$}*khtYhpZb)IDF zf{&!z==1{iJE+C1YTyWa=Cl7v0UAL4s#pKeP9NDCsU+vJz3%(H-=K5Sfo2JE^&MbU z14hXY!5?7X-MV>2eHf{|r*63Z&UI^oimkGkY&~_97q zg6e4W+3IRDS8rSQlLU*7MGyrSi;Bgn0ko1(p#GV?m*Z56{egV;Vag|n_i)Mc0R%xYN@it}8IAxJ%X;@yeFq{p62)nc zMwD^Ga>=~3ai|ke=JF9Wlf{ZiPn-9mHuUNr{h7-)c)t+DZe=wfnYe4}=oKxkkk3zo7Ys4z0#pymzmCEXTf3^&rmNHIXG=#!48j~A7+7;7V4jRT4`Ci zsLqk-O9F7WKDPWJDM62B(VwB6lGQ=%04gs<{xlR14$-4WkF=Ldic75@&eV`v>p>qn zjqeFZTcUrV_8&c(5|M2WvIBsO{3Ksv$UV?64X`n6)Kt5Dt4>ZdP3qYP%`HxZWYqY1 z61F}diQl*a^y_#|J)$#)x61A=haCyOx z$f5OX26fc=PyB*x#OC+^(f2+~I5JTUWilU@=N?JSari`gRMTu%4o-*wPO@$?8IZ~T z!T4XZWQD~lAyZ%6!)7o2j6fbQf^alzM|~9fu57Nd(XL)FD_ErNxWXx)Ru3Ab&!QR{ zYHLFcU&#J;Yy{hXcM>2+!A?Hr13fNq=lj%oU;sU>X5u`noxDu+%!9jDi8jl<26a@| z(!*sxoCr?2f*oTfEL6YA1KZzr%CMPjBeX%B`C&6_t9Cf=s^-|3=p&8 z#otj@@!0=$QhGbr(+vXfwu+hTh6SOxW^{tfAy;An?;DaE90q z0%Z7EBqRu4p?KY+XNB$B_#Lp2Vyp2A zmd=l)p1}pbQqR@Z%@$uQF=y?}&ttIIZKM8ixKP1}+Sx4>{R4>9i_X_0$`<%LOl}!> zXae}4hPYQpx3sH`bTZzOo0qh_tNWlv66bN&;!mrt;>hkblC{@&`R@$bD*gmKhI%W2 zV6Q&?bqE6LnwuJ|xU@|4T9*lRtquasA(@E?bRjY@2<<2n=%Y=p(Q^;Ged~%;VmWvy z=I8!#!nsefoBaojvRxZrvrFd=+T=OU*{E@I)en-$8q^Xfm!bDhL&F0d0vq1>ny#xe zAR)QkS+Efnm5Z`ATdzLVYPx>**p7&H=;qA*|0fL=vr$5m_ZR~&|2J>!sB6Q>qj1Tq zN3RO&+i!@n&}5f``mCP9JAfe)?7lOhgb{tAU$NO710gTR3@ca0v|~Ht1n}Z-pal~ zk)fv6Nr}7qiJ&r9H0lCN~a5>Uu)Uc03F8|)LG&z8~6%-GRpg}NPD9FQfY4lJg zGJ-h&I5m}3Lv7Qlzn6eZynI|k<8)@RmAljCtfw5>POJ|%HhvBGOsalPL~UKYSe8ge zW@OjD2PfFEY8_Yv;LTt83$k%IH|#Z75XTQWut#4=n8MB|$7?dmJPUA^+PLXYNbrR$ z0(FXx_8fcEfx*(2jp*bMwfa~T`1FpHTYpaU2$0BY*yw3Ce(DNkop*0}!?!jf`w=_n zE|}x%R?Te4h)FhS&a+~b?A!LH3vSAWW!yqmu$ayxwh?=Bd*1gcP6FXv;}iBKf?msB z_)UpQu@5%C_m67Q9#o>W{4*}nk@LK}=BG2)N#1wzB-8!FG?48gRP5?grAAC&U&QMA z^tbAPqm^|d14WRCb;#L*+BS7%2pZu>)J|EVvKHEi)tx(Hd$<1B^>z$_hpac>mW9sp zffmy}J@x5-Z==W0SAd3=CIn|#7f!7{$GO((a^6Eq^Z?f0E_U^v1R+t7t*jnu{rV46 zwv{VCynk2hDu5$F1u~A*^0{7>Zm&B-5q?abr`dDJA&^JQoAEPN*xt==*oi}%JqsvP z7^^EQFJx!kxld4M(6DhfZ{?T8BHOm++eYaRy?rOmd|Krd^cN)%nfnz#ldC6ftA;Yp z4kwA%_?%UPYHS!3)B@AEUOG>$ckXi|8ijU)0v@m@son_zsKmk5neCP1GigxXrpLPOfW?M)jza;E>QO&Jz>CeKYPe+5g1uR;NdRfw#mU|##7+xOlZkj_To$ZF zSz026ybwJi;_t*qST`>-%cF(P~*k*ii(S+=s3W{~`Lx}+by<;pf-*R} zWbj=Zj7F*FvIhelQ1^%vEfEp7hkExNAR!yt0|2&ZjX~6$41QFjmdK1I!3rz~L`sH_ znIW}LWbs1}z?kNx1=kM2F1v9LRMxJV{uC88;Yd3C)<&Qt`NbLofTFXC07dA+2-@_k z9xjl0>&9g}d3dv020%k)v$;NH84ja&%E?y1?m$!v6;po0#^qe*VZ~kRZ3L|6hPHP1dqBh0>e->u}_>c2-ra195if#ZkMtV0$Zul ziL4Kj-7CsEYYJc&+k}}0xgJEN4+T0bNx3kB0OMMl+f!Rwxr!u3xTi>wL$9Bd5Je$q* z9WD7LDIn(!7TxY-tO=S88$HwdRS(tqbNc8uF}&J(bqy?Yr zG0$Q98G2hf1ebCbhL4`n0${^Iw^iDz?e9pA&t~HT89k&H;-!3ET_W zm#ddgs|^9|MmDbc2Z7NAPyUi>A$F|)u4+S2{-Q7)!-VrZKy@(NZCK5Ws9`YCEwX-O zR8te9AKHsG=N@nYh?W*PeH?=4j_(veO}Z)FnpxECCbEO=t%V$!54S$T!4qGP0~Cjj zb-{Ds$g1ey%b^Fbt(ryJx+Lo^+PRmm98v8(W=DU|oB@>8Pmq8|A`_F#tt09TjT>4O zJp@s(#1S}mVwasdyj5*oTy(lgnRaq_j~+EBAcB}pS$SV&%u!7Z?J>g2YekccvQhpW zfp*%24JkD!Z^LV6Sw+PFJ9A>EojSBh^dFar3at&A5ps&enm7V+*~TzNe_K zA_9P7Cg8TPq}0kJ8r4I4ka`c-JJC5C0U$w1Mx12K5edRNf9eYnQ8>jsqzLVfWpZ+#=?(?c?gUNE@ z(57g8xd24kY7)Sq4vta-m?$t`2oh475ocfIlKT&~1?!Tt(fMaeUd7Eyi&P+2e)9KJ ze~EhY>ev6&E}uIp&4Hk3-m!1|IKMj!SWKQtsatnvOiYC?mhA$}02Ha+rk^i#O=`bY z>QGcHL7P*DHVZ`hjo|*w5=hI%w@UdxQ4r9qyw3o8<}?36;yKi{eel*_tM!WWQPTcT zdd1}S%YtnTLAsC>bauoo>K1FV;v$~0#L9a05kso7dYD)|h~w}+SRLpca5mh$dQJf( z%067pvOD(~AJw53!V+`$q$GfZZRXglrJvK-5lC0B(j?$?(cWMUI=#q}dz?(*xT(u* z%G~Ge(5_XsfBW0AZ}Xn`l7KLRH=)OC6ktoOmna(Mr`R#!a(iUy(>bV<_p0b;qsGp) zp1sQL){QH6_QVbaJX0Ckj3@3iSQJx&dU5BsM(4$2u-NG}^)Ky%&L48UKQsN}0)a(} z;7dy7U}6}4l3+1&@H4?<(qu%7J+VW>17ri8^hhK#aQnt(4?6vUpgu}DjA{b31m!BI zMYP`N(W_jWT9IU_vXR9o5C!Gn&iB+WXwcAcws-5BcJBBt(dnQZU=ZQv&t3L;WgNGy z|F%_B4pQVA6-X!`75xUwXm0=DJ9hEZeg_s4PF`nCXVMA7AP2#c3#ax|Sec?0cRN_@ zhMkoya>Y78$cDq4mKQ|m02KfR*MK{dCgxO6^L>5Xz@mSk+?lI{li_$)Eox1Hh|8FX zi?mkB=F!U&8WkDv5R3@M0C{$r1Otu~{J3<&Zqz|NZSX2>&gD#vV^*N(vUy0!<2ciL z0=m!4E}kf+`-sDp~oGp1o}7$jLT({5;XCP9EB%tUbULrDU3&!zQ4v3fXru zS{!~jGhCZ`7b5#^7~Q9kM&Qh;UN=2@WPJw=wS`apijA4L z*cu_X9 zUyW(psQ_}~E`CDepRX}cDx~!08TE3ck2EyR_kQq4P6Q>?`)57RGO~Hu1}`&F;Dc+9 z;o-7-P6W`Yc4FtSzfSaTu!3)ZNBSNk4p?7*$8KD8{VQ)>yJ!y|QhV6qT5@X~KUO%lp{g{T@ zd2{wt`ed*PO15Q$MhZrboh7iCjJC(r^msMrKJYqLv)CS3jBIztjmELCU}`cV>E zefWK=nXo`DK~5jrp+02er#)e{lNQ^)9d9eLyX3jAs97+M*zlU^cJJ;rwa>U&cdnbj zVw{)LtP~c>0mpdI3Lsg>6u@Y%dF?D%&A!HCs#QLFAly@+6|y{W-f-*~e`sU3Z`Ucq zqds|w8m%aEl;w-M_nGo}l8(P8d%aVt6M1w|?OGIX%lg>l+0WRZk@Qu(VP}r-R0|pu z{>UZ*l!EFcv_m4sL|LiNqvnAELnNZ#z!7Q#bN%W$*YYJNMXcj<-`*$k&MdZfq2M25BZ`Wp zE)6S!8dnDR=GC)OOGL!u`2G)7#}veG9M#*^?1jKXK#eHL0!~n>Ms*f7(IDg?$ILs~ z!AfZzB^{ZcV1_Y(#VD)jd%aRK3zLMNtuR1XGftQy&M3O);15+VTDegKY%&GHUu!T?mnw6IJu;T|d*!nmB%C`szwj|*S z{9HJ7ZGgq3-yHU91e(HT@apdY!1*yj=@#KHYEhvNru_RH0m)o2k#A}hvR41We)inw z{<94qJ4-6M@Bi>m?9k44eRRJt5*7=Z2AS7y9dK_e1d(`m7y~c%6{wQ|NJ8(2x=9wj zdT@;)G6zkSwn_x+V65Dt701={cK-BU*>{*+fr?H4+Cf7n*y3k@O|{RP-~T7C0_sP> z8}D=uuN(YH{DqPpHfzbJZ0M+|wr%aVr3v>kIze$J_WmP??6OL-|3001BWNkl9^d5@4I5p}XUHJvIednU5hwdaoelsIXNLRd_tZp?kz8*3+sqSdZH`MF71>nU@dRn`TYu6~LVg38Pw zcFfhxwG^VjSw42ti?EX<08jeR!+A^ZozF_pf$h zGO~?9;WCTA)oHMp9K@6uPH3CvMU~WkrH4fS@QwOckCMIb(Yr#b+q@{hxn6fh;L+LA zTgo<0objZ@{%E;#c+XnDSJGfHb1qwZe(hyYGm;uD2*g#|yeEFadiE^0Eo;B2Iiw}d zg;RTN_vY7Kf6OFZKO1#FZ|O!)YfkXCSbjarTo4sj)PwtX?99<^I+xlKMoRgk`LLrB z>sZ2#WQipL_c34#{9FW~+O;%4S8s5cMYnufWfp5DED%@>4tK62E+<&@4nSu|tjl0g z5#MG}MmVmCcKI-{yQRdTkzW?A#mdU7)EkZrNW}j(6O{qgyV|MC?C`Gl?AU=1C2B*B z&aMrw+Ql;mZTTnuwe_hQYTMU;TVRl$ZAi#Ng%~how6c#l7i1+6(4awZF8WeO#xxDe zoS^_zL6yCH?wH-aap7kYEP50zx@2JyQuP%wxTswc6u_~~?9-UvJa=Stf3ojwD{Jq) zRY#!=Ku4`&O4ZkG{M6;@p@rhHd8lU!LfSn7>Ed-b)3hI@AT z>|w7^`pDJzs>Z}Q*0KX$bcw%H(-YK-<#6Lj^{$k1AFVMEu%THyzyc@11wUMk2N7|E zYHFu0RdeuLSI^n8eIF=NuO5#671b^m7Ksu{fB-NzX!r#6A8TrCRM3NZMkurNMWZfj z!n75lj9)x`&`uxTVh?GfBDGh?21wQX_%VdGJ7mOU0YM_;PN_363#z3C$~EXm2e5S% zRR&V<`5us z|L%2t4u^*}C(wcE%Lcukx^~nwT~AXe&^<-ttew0>8M=eJ-V;c1t!_%>>^3#hHi#BP zxwuzxu%{b_FLenwLM_(Zih@wu=L^ZovKxS*OlWpeH89hG3-hoN+)TjQP4IeX0LD6+T z{;KWY@vgN{Ug3qL*gqlA5`+Mg-EI3UB?g4$n&A+Ru-{Vtz*cWAv^})_U^R3Pz2a*Mc)CdH&917C#1H5!ww=aiTZS*;>(? z5>M=+@`)iy^#F8KR_dvc(;hNnq70(*A`6toLX2kOtfxik*}CSNHfr2#8$aVoMQ(R* zcum>E+R2OU(4N(HaK|bcsZrzR$O+?n0ik3mQ9C=bXN_o-A=(|hi~LMfdWB_X@c5ZA z!68O~K~16)oA;y4vSkCZ*$%s8{4jZcICnVrElspsXcT}SHgc-fKe(;hi8MW{twSZi zfsfDb%*)mHQBMaJq1cqz&=FH4*}vzBJs#6Xt=-1$)~C{$z>fgnVn z9@M+67)ryg_Rayi)>(Epa|Ot)OZ=hIH?l9VzSYBZ5LWaXWcP00kbn|%(b)7*{V@am z5IPVJIkh5W)vsPWX(tYC6i@_Agr1LlPoOrs`*xYlV)b6_p&oIAhfffIWS?`t06j90 z&?qmS*{{r_vV&Hj%$P4;Y1MNIrwl;Ur)r2@CsX$37IoKTO}4H3 zj-2A@3qGlK7Z*o`z9MLFW8dErnI>JqX?4GD|pPLg*LKwj$J-~ zSXqzzcW?PjgS*ed!V-Jb_&|Y|!h&M!*}KAq*UXUc8G!h}&Q+qUhRkwI9}l~zGgdtN z3}%*KMDI#w&wOAAmcg>;f6IFHsj@Riw%fWl|57z(j=G&}sgi|;`qOeMyK&#-d#Rju zHvyV>Pp{tntZKk;?e)NB$+>p({c`_4N&+U#c*2%_;$O?AAO!W+KmWenrNqLEfw{~g ztv`Z|Y261i2^RAMirheJu$Wp`dW%1~eFil7duNWEl0A$nKx1Xq5bIshUyKa`YLq|_ z#BZp-Z-;lkr@aP?N&+`94G1PC+J$))vUFCgGnL^jCV;=-sb5y66W?sslFukexqZW{ zcJEeQDv8kQx#NGxE8x>=ElHre$cB$a1$DSJH8t3&BimJnpRbleM3?W#p3JPF?cjRs z^4oJULw?%#)#V3!d;$45BgW2BK}I<2^2;oy2QS|ZkZs62msw2159kp9MyLeH9I%_z($UpC1-QX+HY7%aSxlh z_)}JY_m*vX{~uMzjk85$ZTtG~sD5YW!dK+P^4(DEP9EN3$E6Z^T`H}Jc629rQ*Nla zSyWe)-Eg8+RIN?x0f2LH+t~$CbywGROG42t+xm*5=P|o3b3Bl$r>QcTsQP<1Y{1ZQ zD!!*a4^gJ@Y72aIpZnI4;b?md^8$;iO?15pX$>=e+AkpCk=h?Ltk%w*qK*<(zziXvjx3KH?{yAh0vNVIug>f1qWU1WvwBzd zwsz+z{eQ5sUKO_Z*?(nM&K_dde5dGsehTMP-I4YU87q|S(?3PqkaVkRd?B{!Yk{ewhb1&@~NC{M2#{Sj;}Z z;Y@QNSm)Q^F}D20-%+Oj&Ye12^ZK7DC>aOS(&HJ%BQ~D-jdxz_?PLC?e83{}T0vWh z%4!AIU^YO*c1tr$dzubCbAhh=Kr*#G{h+tr2T?>vf^#qo{iVr$sCr~3L=nne=TS0b>G6Ja&>7miYKQXDX^( z;3#g79^O-QIO$-2*!+W=F(KEjyr*+GkZ;BpALs}wk2t`17I&*BNsFd7? z;|B+Kr+elh0*lqd<*Wm!>9mbwIH(c2r2F z69=6dRchL3o{VZ-XlIZFo~_n(KD3VTAc?4I5P!;N%+li!3$f(dW38i-aa)IQE!HFy zxr#mmR3A99c9t@8G;F?f=72qTa8L9(=t6-mit|fNAK5dqVD!FYv0c7!)UIA~nIB$q z7zK9PcFkQcRI|auC#p3CSweyk#}96hBR~&R_6YTbyq7u+qPqZ$iaym6fjW6`v(?w% za=h|Z?FR|)Dqm^}%!|mV0^@yMYkZ3Cr#yvkLpuJtKq72maE9b0gz%X0-{BMeOx^3OJ6kO0)s`qKJ z=8|jy^FZw@&JYj`pbjmcx<5YS)|U@VMVaD|>2`l6>o8M~*1PF9v!_p ztaCEaljb}l$Cd`+m(HWk7(U_dDS)d`LtD|Ozt|*vmVSz-k8IZ&A!>N5769EvKy7=i z1iQigV%vL{_fs#s=?h-c)9>2+L)-Z7-^aa0-H2yb-2Q1hneA_jkL(>Gm>lYyEBg;q zRvi&AweiXV6f@6-d|(*#?1{6UvZc>{MLq&*>Z^Y6N3vs5k5fS$1nddc-@SQRbkyNvXV`;#x9s$BrvNWqiJs;1LLS!Nll{DT z?SjrS*difd69-=$+a*;-5ZE$)Fj|kbYvTdCi-0C)9rcU&go; z6&(e&dYFPz*iJMA&Y#{dyOPZX>FhU0&(T@BXGg(kd%N&4SZr^Eex`q4Fnr96mM$;W zk9Y_&!6I2cGI#tZ#~^V($sA-bwILdeLss5*fDIWwQM4Uo{o&bT#O~d@VddpjHfQRkF2amG)J2+Dt z#FvNmMno>u!?*(={(o18GaPtu=85bf`Vl#19mp((vFncY(V9xtdS-ZT6fx<$=K!D= zmi^=R{ive?grP=WzkJ$Bng@p{*LZdUEJB5JK*9HJ>_A{8%tJ)0%rdd9Mj@h{ zrZaBLB@{T+-fK-AcWb|lsf0CYK_iw2djsH*#76rDnht<^1wXsu{XdbEMy?XJu znmlVN3tdy__{Del*-L@+1iiDMKy|8&!N6e??9PqLcKXgoruogQax)W}UJJD1=HVN7(~E-=1=o3=D*9a%%Ka z*~Rw9HEr+XaSB;M1rQ61ZJA05Q20Ht z<8Ad*bV5CuukN(sIiA})WJ$1yog|C1?1kSFBtleSd z+n=kC`#Vx#5kas4BLvP6*h-CM8})7Ng2k2=>)mI7J@>i)Bmufd4~c-u+QyLisJ$<*XM713Iw45Xz=H2vBsi)}>hTnWf&@Z#d94Fux6D_3?DsR6jXxVXk9>u&2>n0 zdFOQnEXpi&6QkfUSj>A*{VcxmXBsSWNIG!Q!yZ1kqekPYx|k@oo!AT#5+uS?Bu8h! zuyM+gP!C6~z~u|a?B4Bb`Xu#=VC!P=+s_r=k6k9K#$@VzO{hv9yL-eU+ ztwsKBO>3Cfm4%)a9BBaD9k~n^VlHvx^Jw;bFDTy2K?Jx*eep)!8I5hbHJKgt=yj-9 zY0gj=EhJ!I&3QJo_8E?-$7c?MEZV3SNbz+=u2l<^M>2&yY{1YlHfAE3u8~?xG@7Re z-lIqLKFS=^6?qkdYT~c;whZN$IP%%+8+gWaOXP$we;>{y*E63puHM5#EwB@5;z3s z0MN_71K`F_TVX?nPqM3ZC++xwjdttWc~Q3LuUb85jCw3`uVfYpAkc2(X5IOy7g%!L zvbX7L5r3%$9IW+p+1>aL!_{Zjbq+jZR`a(jjm29wsFa4bVe|vl}0BFP11Rj zqA6LL!a}W!2{Ts8i92^{uN~dH&IP0bg*ec3)lauc`;Y9&u+h^cpagZAbwJ&EU>dZ( zy)L_b9e85T)o5v!pxTO;ep_NwcW+;}4e$P~TAsj0h&n~IOX>Y6@4W+$`4PWWtQ;Q{ zf%;xmJ<=K*A1DZ=M)Ij_RPyHH@oSsn>H>N6Twe0rZzyX?Fzwy%{lB7Ty6x+m-KP-D zPj7x4fHu`N0|E)0Ok40tdvN!b)m?Hyz}wd^*u#hQDit7zJ89;VvdshitI`&)5o53N_kajsoCt#gjxKX!!DlTfpr6)Yyfj@lvh6lHw$ zgn42)@Ogxu5a`Obce^sOnORp3%#t3xZ0w}PR@S@1?%lm?Tn95!-~v zU*|E(&unHf}HW z1;=^nQ>BeRV$3Y5eengC&mR*d5Xb8D@$Jew4jM6Dj{C!h_a(;C+|VHKc>d(xNQ&N{ z1d-5ys}t*rsmi{Ld1?+MD1*@CE}lE&sfKD&=Y@sDF@ha62yt z*b7wb&%Lv*qGr6|v;J8eNaA)|)Xxur7q+H)-KWH89}8nlNZ^@v2#>cdT94*H6ni0a9=_Z06wUU2p-(Of7A7KO!RV$ z#vxh(Edps!oybx`JHCDMl7J%hFHV@tfmOzdK8ySvV6R?ajgRcy$vt-Y{2`4QbH~eN z2uxyD)btVz0Q?d4X1wU3Sk-@oEqvxzlo36!W0isvy?ghy>(|by*3H$m#p^heM%!8N z80vwdOLrA41`t$GAhyHO=f9$07Ij2BH@s@w*8j6aYaG?9Ky>A~%fG1l)@^IPC3RiK zl(h@kFYVFOMo(O1VQ}n!5!~PK!wa5GWyW31`Ms0eeG3VsX8zE$|8tUcj1IG z38HYyDfd*-uvgm!i|No>wk;TEd1DG+QAw$d7&}`%aLHWk+V}&B^RTy*)*{fMrSjU` zES2l2^FErB>U&hjs+ZXWR``htG=&fjSd1bdJ@ z1Cu#=KdF0f&r*K8ejkBF#E?pR2rQCahaM`hsOiXFuNY37oG!5!Swe~T`7iue8#SJQ z@n%Ih+qyJzok*AIgN%ZbkV6mXk`cw_J znsIY=c5#-RJw_Q&qPUjIeU*k){znT8OtojFoI2wp+SkuDJwz~bO0~B zd~V10C3F8?R?$xa9b^@GKT*S**Dl%3y0fnKODzXH{mmZ=q1Tcm{0EE>5F?UKYk`)= zMtellaVxNfM-S{~-8s8@<&@M?iK;<`iwde$F6j@Ps05)qj{s*#d2Spb9B7=gE9VjM zXjZLdn_wzq<$Tm&F&NEkV9~iu>AFXL27oY+L@Xm}W3I8y1s1c>Ffu4<0^m58%wHa~ zjQ|!ANn*V~$#YJIn*#SFt=$S`aUL~T&+>jYcG4mnRx?#=l7p9eFw`e;z{4xZWjpZ| zQ}Bd!3dN8^{K|!+a`+#ihU@ENW7pHImCVCREi@2g>RoBIQsJU5p6Tt zXDuyKN39t*N3A)?%+VTyb{c>T?jI2+oNgk|2&QQ7J*ro|BlT_0$&WLv&1CEG;3(yu%ED7R5fkapkP&rGWeyi(Zy^($NDSDl&ZM<`vb}WXq6s7A$7g zXohvJrIA^?mrr)li)T%y=^#^@heL$NUT^kJ_s0nqk zA=5~$@8nreTc3VIwC+zG*&@0i4sPxm|1P_IS8EE|mj!?jpmSbG>LH%t7oLJvb ztI1@_Pm2Pj35JI`Mf*ih|Eg%9_wU}cecOJl@*j6z1fjp~8QTC>1?FLk5u_gp&33HL z)(a>1+O@hfv0s^Wk#x}qd<+)b-FlDT(Df1cnE{JgBRG8rD#Jk$HNLkKwMf>vxpgs2(!b%KKEwF~#YGDh0&|BNx|nL??1I!Z=Jl%KBKZ-Y5a~P;s}E9~&Fh487^m zBhlS(CS5~xCn%G8MfE1`U%O}`QkPD^Xu1D5LZc@v5Cse;yQr9qQY@O0KMl3(i!6DC zB$U^`M-Fi2XvI!h>?Ec~EdVl!5-CfS3Ou%*S&RT*Th5>VW`ENuneP}WWp#3+dsZD` zk<028y1K4RuozlmxDjYk%aifbpD^g0NR1!ew^q^7sHa=B#uGJtP-ZKu6;18ktJ3Np z+_CGIPD!XqwR=HGDb$T6R$vO8YabO$3Z0DR@S5qO_(CBfJINga0At}8S4%iy=9AiA zM1#5CTi35xL4gCOG)HPkv>{$s2WN zRp-gRhk6Qi3P2xd&}3|;%zIuxZ(aK>y+0ZB$)r>Ml=Cw}FXv9~bt=!yg=&dhu+BM92y_%`4*FIPwWafO7UtuH0 z&QbdiGUU{svLEpO=gLS0uJpz>7poB@aKah|*P zwD{<+7J)_VaCw#W8#q#wb^uHIyz1P&5!`(Cv;WyfjGZOM%KA6|LMp-mh(Nuo_^|_l;cm)Gv!YvT4oN#lpZCVFzl) z&$VguUbG{7*V(?UZk^Ji#<3~zzpx*!7b?_M0<8c(gvKiR4U|pC{$IUvTBRr0YXUfw z9k_%ecBfE1W9e@VJ)6wu?v1Z0Fy+i+ynnl6Y(v&nf$G9SB`*NRz02ukTrW{K){gVN zvWIKByz?G|#m+A6$DixK2>eWf#n9@4$Q$DuCEaYE^~weVy9jPhO7`IK`+KZM9eEh%5kQ(ftS_~&Q52kXdRe8cYY=5a2^Dp zN;zUIj{bQS=V#u_PYW!@qZ`jp=DlRgAjU8;QS(H;l-i<_9?BXtJiMDh*lL4@nh*}j zWvpHFo(AzHI`E+GrCv!2ZAP{+%n611K@7vQPFsOR(cZ|u6_q#StxkP&byFf|??KXsWhQ7E30g>jT24=9y2a@1G8(|vz|=Bucr zMD>+qx(N8x-@D}jS%K=`#!Xo&r-5e1M6$_l1_es8S3^fmvY|E8t)!$>Ad#9(gcg)F zDlWDn-=7mo>fqtyC9D8-ocp_Y=74C0{2jU>0#rBHCw^ZO>7KLnb86nc>HV*ZDG&g6 z@=xu*MC*){5JMgtIcH|E*@Lb;t`Rx0{$8T_RiwMbW-a=Z&0hX_wY;D=;QF`!Mykw# z3aa(tg=<(NlV?Ax8r9vKUl)y@Uqh`z7za8upQT+&Xjv2Lh$3cyvYXENL-Ce5Lme7N z8NgUIu*RyYhl}QS|MoS3MVvqCl~jBF@PV%nOP2X$r>AEQPl)uZwz90;rp)_<4I44p zE?+p}K%X-6uDz0K8g-v8E1(t>5=@$76K6gt>f!!vZ`qA&7koydy~*gZ+t=O~xZkTT ztA|v$=?4l$ni|ZtZ+umtRyEHVl*x#S`WP&>ImQ7j@+NF4V3F*))XUvw&slqx&*Y7p zy4;@n^uJfjtt%Igs;?s1GFSHE&hjD;JU*h;)b4F3{fpWu%WcMjmu&lo-?bA5Hb{() z^;U?obu)dWmub%(*}GPKrbBxS${(QlFIf4Ds%_l3>T7B@hAJ^9DZ8f<9*I%!@?AUzi|wxA$8YHR z2>gtI#aP7+#~px#8cA7IH1_vB%la2lfI0pqIG|PWR@<_ zI-{Z1FMV`M(LbkzsCr2`+g;xJ9iG)RSadJ|@PHGHvg?C;w_BI*Ij^I`-_>0oNSf`; zyT}BKxxUjK>@6ye$H@b15S0|AEqb;@CLn24^8t&fu9o&xgJGh;WKmR4p~mmtaq!Mt zP}ud}T%zR61u^1`Vln~h9AITMni{Qo2z1J4tp9*f%I1;1Av5S|B-5kBXQ=%O?J)pX zPPF8nT{(ByWfU9kX?$Fuz&XUp>}U{j2w;)D_5ZW?9#DQ=*Lm-rUI0wN02mB_LB|Yw zF9gv+f?cFUk!p4%xyy;8II)xX<-N7uTW_rwdnK{s5-W}(xk{E~ixMSLtRM-HMDJzL zdoP3DfhlkOzH`p~-+!5oMrme=A~^V$d(S;(fBXCPw+9RvXQL)8w4S9EVwHApdEZO0 zLR$f6gu-W44IXbJ$IlU?c>KT?^$wLB*n>g^zVh#C?fU2cm(qToGmey3IHHtx5R?pvBst*)zeWMgXt48 z^g?=eQlEI{u#6>69Nyu9wKG@ZIZvDSvLwChKl*{4JXDu#43uKj(%HmNDp(Bv9iB-% zI1NdamVyr5x2C)AY1rIkqo*vfIZu4mdi3g}fOpl>zn7yYfJ{IxCWj6^H)|&@w2|ZI z+pbMZWu}D5)3~Wm3Bd2!{-GV-z1D8tq$aK@GV5~l%k3!&_0?c}lDQbbU5Dv%S^C%L^heb)+-0=F~s{RFWv4JQBd7(?va~pEM1St`pO=IZJ*; ztlp~k{$2($D#^(*l?A~n(preb1-0@)3eWyXNx+yXk85vVyX?Dm;?VYtU@`1puGNG; zw>*IES<+W?zM|h?wS^)f#3-Q>BjJQOPS0L_tY-2e0ZEcQ^`{RxFq@%#q^n8u5UX$| zvA^{nG)CtaPaNYf#vrw=SLzeJ8&5g(v`vaj+L}6T)`++D0V#jq(&vTs(vI?-4t`_z z%kSd|d?LVN0EIZ(W#weqts72OC*8U)%}FEpo1AMO0eDI8N^MF=MUkCetUs#4@^ApP?&gCBFM@-=Q7<(CMm_;z2^j2 zYKz0|Dl5nOSJx_t0GI;yIA|~h0dP5)U#zB!Rv8VqW!8jL6UH3Na^^ILIPd3~tAVs0 zSE3=hYntq?F9h|jRxsO!jGAgA#>}yz9wlPl=p%|mlx!_y3Xmh)TUgY?DhH2IYl*^w zV)c+hB8sVv#-BC7>r=oY*=6_Rn1Aj`ih%4~v0g~MX^T-k9Ja7P{YZ}=+#&~JwK&Mm zwxXgEB|)gw;=f^3U=(2pb0zbQ_a=jR_NoBSa3X&tOO2tzz@Zal=z>fL1}!)tlSBfb zAekCDZmw-z^%Fa=Yju))vDTuiU<@sIw55~g%yywFJ6maG0qofWlP3P zJsZYABoPQqH-G#i^+eP)`)>`Or{`fN*IU>{7)08Wj2b)7sz*$+lSg+cfq{e+MlQMj znmOd3ZLHQZ+8MZ&EC(6^W`IV%mw=r5B-m`~OheM=%EeRap^B{eT>VjNqHm*5&iTdN zVy=t84VInO9w^hct$$OsyHcP4T(flva;kLNiR&=*fiX}ZmU1|uB42v4M@C8||?>!1HnY`QB? zNF-U*UC_(A@9xRkkx@^d@gyjTqo&PyS@Qnv8{SqMF-mbTlA%o#ZFkO{Ib@6pD(TeZTl2V$H8Iw)OBVB=lOvS^Y&y(guk!xZpBS&A zDk=-&S+TEBXH1fab5VPBlDSRdgVSezIs@6#$OR<>=VvZXu_LBv&QObw3+fFL^|8cs zrqB7gS$W-Hu_FuY6ZhIr3|M3_A|aE+EH6))aWdtRsZH2le3p)&yKmJ9Su|tS3^PH7 zkSsHsi4XIlxWk1xiT{s3$uuzf)5wVD_r++j~fMQ2a(=!4FuCi_iwSo zd)LZ_pI%o1Sg`gOi-E%?2q*$Z5ARv84DrnyS9B(zXV$ur$o2PVt0sgn2lXGB70 zK=oJ~IDE1sNc-w&&#^@yhtVXcFDmLKSJr+5Mri#XJG50bDY%>l@aY1LME1s=)5(WF zzw28yOzk$1x%Tcm$npz%N_L1jm1Aa)*^rS_)K7J9-N&|j%Li%B=Pf0MQl+SwWU9I< zZ=?}1d`X5j>4}^qW-*N+a&lii18cHA{f63tXMbCOk?+UNbItqTv1?b(`QdS{HmRxv zMvB@*dc|S{gQR)zsHt}0%rV=wnrn?W{q*A78It{u#bI)TvS< zTGqE(tO15YH2J1E`IQSNRbz=98n#huIJ9f=Moi)3VcD_YFRvIVcTm_=dMP?{8mA)R zl3e*flW$m$T-o){95H^L4X>GLM-OhXJzJLBwX5e-0CoJCB%pR{VP|I|f{+|_^^vYI zdH8|xoH+A2o4)9as;xu{_`&Pn(7EQ^wcT9Lv?sT|uioulyfb%xFW=MtQ^nPgH>)ov z2?S)Q5m=0E!W{vN0MA7)eBFkQnjxl%wlr%$_^xwv_WQD)Tmy@1YXTjpbbj&&# zO_PLz1p+c0>KW@#9aKQA8WCO_H!})AGY%B76rc%vd8G{=Io+xO z71pfa`sCp{wUU5sk;`RPmfdN%Z3X#7Hf+pn)wAIacyP~JxraJH2l%BW1x#UJ5FJ2F z28{`zDz>tzQOqqaoz){JTSG&G9o)Uz4)0zkRwtO%@ceM%#3bSRm5a82*Gd^rIJaSE z9*_W|anSFjnX$EwLII;I0t&zotZd(bBh_jqFE`&VUpgxZE`Vah*ts&qLCzEp7~2Ah zF8+%%kDl#TfRm@blibtI>z6csP9>3G6vO;W4l3L{O#~>3AO~X_vhI8iS@l_uec47& zUL=_^tnaFK|5g&MXfKVM(Zt{dBS(^L`n;EAl7xJhG1|WNXLj=FPK`BSUc97lw~?4$ zv4lo+;c@0P!En3X*Y7Ic!Ik-d18=X=N-HPmE334gWqrgZGpEm;J}9{`^Bhw#nCnP# zt2!r)lX}{?=}%c@^=Ppk@qUW&+FaIkQxmm|FdoRS$IGM%LyjFA-*I({s)Khw?povH z9shmUKe{gLkM=%&T>y)T?}iOu@Tq@keXB;w9dh{_|4a3}!Nof84RYo9=&{G;VO`Q?IVzNY<}`TOQS{h?ZQ z1>b`-HZ7D6+>4=T*Jq}J#mF*QNj~Jc)T&qXAEug1lqjeX=>5BT=|6}uMeU=SfA%}I zV45p1iL`ykrgzoyD%8M7ds?`*RCZCUl|QNd-;qEJFT?2_6%foPqyl>?=LC+|iQM7c z1dFlxr0d905*39+b8~~tzmUZyq_1v$-JN86@?O-g$Jza&?h)wX2xL_cpWHruMi;-R z^KW;{O949#$BRo8z!0p)`yM${i+rmbRAasSR7>7KFoVelw)q6qiGw%_Q<5&LC9s%! z?Fmqj2ogGfe|PttTpMG7kwjr3a>AXKo#TqnGi9AyIzm&&;(mg~j*N(#8!o8hut3st z=T2zF;2hi%#xP`zGs#5LS%N5Z!c0QF7AeAKj=A1!NN++AnHFZXAji;HH#G}XQP(kg z(qij3aFm=3$<6}OhK-&nIV81oQB5IoQW%CTlPne1c*w}!y{;0Ng-S$SG` z3>Z32?JIU|eow)Oljy=0X%_ftlb(x@|2@G3Y%Bl>fX%hyrdL>8DreRHgK8y1Bp^cC zirk5Y(%aU&o~T=j0l~DrA(jn~14@F4P?tnd0egpe4l>GqY>HJ6FY z^5Ihybdt@VI`>7JGUp{LE-q2M&a&74QnI&rax8Vux;f(hzqDeY%~Tr<^vre3{Q5dNn@TNHP?AIkonH__SY&4)$~QtIPiFkuS_X?h z@31iQ6Y2n1^h%+M${|XQTslYHncru;a-pb4xzq^&C7d?nTyE+&F^3nw@ULz7=-Enu z(I9^Hdw(w$Jk$wC*Bo054~|s~CtG49)7Gx!(3NsrA2fWjz%+>-02*zcF4Z5mTeokh zOoG~EST~qj+A6JI{sWDfGhy<{q_~u~U3Im|V9iO?-F2&e(EmB%0N-+$+v2_yt@%t( zA{k6m-Y{g;OttNx9u+l%b5M@@c(tfp>qxwlfSa+zTYO(>NebGrFX?`D_Xwnoz(Wca z6Pc6L>~qgvy%or*?nX_>U0n}yGNe~%*r`Lhb@RH_pWbihPPwdLFrRUI$U}~gyEswV zAOX!}_D&J__O@3@(rmn7I$a`z#ST%hXbsvVvyBNS||nwCUNKHckE*Q34I50P=a#T z0Nlyu63&fHlK#Me!5lNMaXm%OLtP(5{LWw`)G8+6hCU-EKP59xJ>Kv!k7#XR`h;sP zz3|SQJP-jFdP^b^1SHaE9X9UZ?zML1;%UE>d=TY|M}4ooTmd-(+Wh=NtE?U)EAasA zR5zAG#yQt|_Ufx(9hT?d?sak}*c1B#MAEKrv3Ss=adyM13@o1>*vX95SdAjvd^hX6It)+lb&Y*DrdBD0PIxCMdu{ zCQq`9apIrrSI?`5<=Nx=?DECauD&jV@*&gC75Y;GNU3{$WbrS{KAt^t<=cNPH`_b7 z;;LRX{G`v>&~=lR0RT>v2{`)guUip0>#Ba17DY;6c=HMWk*>8!ST}B;bqSB~YiF>O zyn5W5gH&3stbvUtQIVaax>%SAoCf<>yJTQiPOhE@y*%mJc)tFql~)XsJeq!)yEZPh zV+XfNM(q+B&Mbo@4|S{nT=oN8d`Xz}9Wc@k?OrQa-N?YIGy8CB^=oa-(-?yp_NFiv z$bH96e^M@wFvmysZIp=!HOj%XCpMCux$-W&r=|1s!NQ&78*1eY3(qBbc5Ys?53mv$N2Pq}x47mk`R#`Pl$_vaTheYy(|fvhfvKMX=-EpMje1JX_oID*I^+jS7aF_&?dTPG1r288iv8vi?hdsB0xWoP9I zykoopNTW|Dtna?Mj|3E{bKr0->pMuY+Dqq8=*vSZ2Us@dK24&T=luTcse|fMCmCp{ z1@rAh+`ZGU(8-6$wg#rl)ozhcsI`eRp4CB@lUFDSD{RuqL)&Eva-sgHA;qd0KVR1i z+j(I3TGjT2-lZA^Und;u&ycPLJ9M(ilV-nQmDRO|R44#O_Y9g<>qr2#zwTqny=0}1 zkxtVc^*I|key%_@wTb(7tPraNkaF&oz70rfW;HyFs0PqMnBtNOwfcZ5;2si8Y?hu; z7;h2>WW%Wq%gZmYotu{`I9E}u%0Jsa>=U5T)r&GF{RY<9n8}M(v(wz@SnlJ8wpekm z3iXl%gk8B*Zzm3IQ@ar4)EK+O6%h_uc}bRc8dXE=<|eBiHp%8b{Tq^o-MM+q)_wQ` z_1&YLh>N{ap*m z9IHlHkJ1XQo2!@4DdE$jXSw=E?%BHBu3SDV$6z@m=fGCFbuIwg)F`R<$O-eb9&z2> zx#>N-dHteG(A=#}I+ZbL<8$4!j_s(v(Kl@O!cYB6tEwKWv+v`#z9q@Hq|u&PchB(t z@5U{|u={^4?Ewc#$>Nx?4DV$PvQM#ANEThYRBt!@oM7Gn_>e3!*G?X()7nT@8YQ?N z=07slB`^KHSViXP#+5&^bsv1!Zr!@>Ov~bG3xBpg9HW*F7Wqv`VuVByi7xi%dC&ZY zz#xhfN8Qa^$`PM@RvI!r}O#?NUAH3_x{}QoG%i=bI7Yrk+RLV6lA@p!-!F8i7w3STxC! z2t+ZgVZ+7@fdH_es8}04CJ3-Cw{KjPDF#_B?2Rk1lb{= z=n_~AATccq+wvGaNbtsS1*97`9qpU7}# zq~2qabPyAp<^~1JWE=+!onXU9KcWmQfd(xf00&$jK?N;92q+x0k)_}})La7A98fIN zAq=nryz%|42c)-{@HnSO=QinT>Fn{nYK;NNqFn_CesCiu04ETqcUS<4!RUrHirsl(aZimY&ji-1 zdgK%43hs>ZaeVxVfR=_ST%=m&@#5{dEkE9acMt+$d- zfW^SkrX zoxX=RqGXC=2o8xUxODEM)(iEn{j0}_MZS6Sik&-s)b`bVXt!_Pu)M+|qs;?-E|HcZ zy}Nk!m{>pNer^uWdbpGjwEJOvuV1}nu(_AcAD0pU7JcB*iB?fLSjj-_`jH`1v&Z~k zU9s1xJ}M8!@wON@SRZ7~<$VX)_!-Ycj>2kHgRGEd;f1|)mh9T{zEmjI+~7r@ZSVc< zdPP^jqGy?kOM0v4C-PIC{r0tQ*t!q@$u)|Xx+eT&s&tKCWv05RNN>=JHI5?q6rQ_1 zci)w;xILfWk=MBE*I30&WL(`Fee&EMMjbIVxwmfKkmA9~oJm|b(;Mb#MZaNo{Logr za`CKhy^>*UBzS7JVYM^uiI@Jpk|}_uxBvN%w63F_%g>Jl2zwB4Khrq2LrtU-jRG4p z^>MjVQ`b!bgY${KB(&C1-Jo2l6Ov4QV~R{Yx{7EcZEgMp=<4QX;wR-j(fUhqoo;37 zbY!OUZIp8i8ZlXAAtay66KZQi`ikEh|fH=OLwzM(E19813ITH3PMf`|MAE^fk7IFA2DCnts zhiMJKCUGAj5ATl}?~(|p6qBKWN=P~*w$km&{$>Nm7-wi=2bVveXgoh;)HH!G0up3> zxX9hQemSbUB}hRMiPVYD$LSO!84e)828YenEA?^#J$quW10cgDTCdVRVsi+N5AIqk z)&b_FX5s?Xa$ybv_}ISg4eMPwOkj{k#Yi422h`Y-mwrzH_3EX6r@P9{$<>-7tB#2V zpLONJY1f`4A6L6OcKX;ZJFs(&4n)SNq^zIXP$1v>8Blbl)cX=*|CaXHM=DppKZ(RInJC+yLUUt^eRLHh%ikk{A=v0^X`e zOxE{PYg9F8jCwAL{kwThb57S>HC#29{5LFhRrMIv3m!YLMIdj|?B`VAH>Y%4{TB_bqMu z8MnLSKsBwpv5R1l=UF>xkzGbWDGJOUt}{ckbWaY)bqMt(hi6 zMb3&td)Mm>j15DpVPso(+ExtOQmc_R-`D+u?h)v~2z(;IVqEq|&4BEYOZr+-NrmO* z=1FFC_VfX}aOQ|M?+DzqkPq$h;*1UO!v+?)9s)>!(vX_zcJ|~xNyi+->6}n0)8^?8 z1ZQ8}T5J_(aXb6{9hlG2OJPDm9Br=N-;$_$TGb;Fe@j|1%J)WR@SH5W-k1qYLhSm zC@t?N*`175*8WU^`t$`~P|#j~`k-7&0Ymhy+PvaNk{>_u+25CW$NBmrk_YYH`o4{* zeZ zt98Y;b#JM;JL_@w<6jmNMF0x`=Fc#jTUP&6?K}XOj1%TDBgfAZlSx*-ZsXeu-syvd z+!JXgtsXGkDe76S=I=-LZxEvx=2@6`E^C_(7Tp6%1kkWeJcH8Sm1?kl8&Re8U`Rtdw`cd!^cKoc&CFr74EhbacU(mr9z z+?Q<1oX@DX_RO)p_R%}vvf~G~Iy?Ggg;sRY$;lw+BsyW{Gm=su-SMWnUAJ1*m zsvm1CO3JIOqF=RK|FEd<*{ec9^PcU??fAj%T1UutF}K+G(GP9(=bel5!)3$c`_tfSEbqdJ{WZ1~S_t&k| zdz1Gve@b|O9sONYQ|9)B))HxMuExUIj>yCO`>0Qz|LkvCzp5Gm-<5BF+jeYvPmYVp z3Yko-Vd~DAc#Y1~2&lB@bcoCTGP_Eq@6&hlr0vWp;NBBIzarDH<|gf3y(@=m|G#nV zk`jx7!AI_l!3{k{QBsh+DepbNP95K^H5d%{Tq#WEv0>gl{qld5?3}h;@Bie_?c~wA zNah;tQx8p@VtkBKPW=oC0)7QZBAJ6J+uCK{6)5&P3-4Xy%+b<7T}!0{u^p;)IcZzq zFP=mR^Pqk6v0Y#>tQ~r~4yutFgXf9STq60|zB${zt7_%5!XDGo{?gXpx9>9BcvVZH z-n;VQ-5>H0jKC)VEW#xCz)pemAZ4!ei;DGoEdI%$U%lwvwG^la*UQY}nJzER*n>;W z>ptjb%0|Zl#z9D%0~!inJbNVR(Cp~_yMQP;HfbMNj5BWT*p7nNlt10gag(elztC_f zyK(ihlM02PFXcvr*y%+7i{tT{?f-dh{$6Lv!ikDP^Xq&mA>kq1A18 zLjgL>()?$>CMIaFf9i98pmp%ko8MCXBfT~OoR~Ji^3aB0%A=pL$+JJLmI#1C zYQlPz^bvE9Y0i!f@5q4>=hgKe{XlFGPQ*(-`}>lCzW3^Xx4!*H*z6@=wtd?_7E6X~ z5WvCj00%4H`D>{FhK!mnrj)VfI%p8j>m`%*^_0{CA=4!ze{}yQJFshws}~|5iv=s1 zzkwM{WBQUq48RG^qN(k?CTWoSaV$cEt0y$-2}jxJ$&ZOiJ+Nz~9on}bBngIOKlb6`6#lK`F<(0~6uXy|0>I)g#N+cF;D^e{p)eFvE z@)gw;0rCM`+&6P~%AC*IrWHTdcaorhsRkrg4H;)+CN0)H<9*a3o;!P3e}{3*+GXFf zVKp-}Ki9nfU9~WxZ3zrCU=Z0F;|;^gYiWhT1M1PU!XA12U)ZG!r)<}z_iWm{m-VT(cIL!>0m{)+7Hf`TY;*ePE<3nqo%+53uvyRawi`2biEUl|Q}s^7 ziFWYtsdnM~ajRSRmZXNE3^cJ1rGv!)7?E|mx~p_nPa$k%&f#ZUhk`YiFk(#jO>N-}Koduf9BOb?X(tWN~;KBwZ0ui}uZrPCn=5NQ!55-zUA zP&{$?Aay0lr%6)q?*nS~IKUwLtr&aXgIBL@YL0*;b=$1wvc3aVhsPYI#vB7KmyF3Y zE?HVn^f_f8N6D~e+4pSoidTGZPx1YU`SU>gDYks_CT5XW7KJn0Pis^K^fN_OvSGz5 zO75Z1h`?fWkC_<2wod$xMk(>nYgsSVIskQ_(SES#TK&-eiam}!6DL?=(rEU_Ww0&W za#!xuA7=i-TUhrU+JD-5E-n52{iFgqdyU=i>&gf`q+l`JlFLdFC}Ivmpj+B!fHrM{ zD{4&$oUUCu7bRJP=}o{knOU*+Y#Ch{)(7`qfyL%#89@*vA(=UIa<78N&MxN`!D5=g zHy&y!nuvZ8io8`Lg5)#D1EqU9RPh7ZXVR0zE3Vl)haN#Cn|;D4#u<3H{AKdJw0Oxe znIH9TBgf8>oDugo7$uBc_)MfZu74rylV`cIvc!_-j9`#$zW?f2+AqcZd!>GU2&-g*I^Lc&#^p0y0q=)l=j1?vMUhEYYM{ z&q>-!1LPh($}KxD-$qTCuLkZPzVS^lMVO`Jbq2BJlUL4#BbU^ojkpeeLU#-Ekd&Xjtx@8<)yp2tdGEabULCrq2DW<{dIsoT_Ol zfP@sFON*1%<(5x;!lw309+SsZijOt2Vi5(WHE?QUY5MM4aj zc?XGjKN!)Re6jFzp7<3>{7^_NfBi4*)X_bX+oqXm6^hZk4C7+N9S^ZtP(YyK~8JNXz4*JL5yYCQtVkC@kV)|y`c?@nZzfD`I8CcwDl>i-R%7Vi|m1%??XmT6G+CH8Fde3A#t#noQ!E{ zRd(UwwFL${t8VDfCB>r4lq7nGKBoJ{5A6s%lwdJFS^@Y#^HaA%;WQgNfhkt{NDNgs z(8dIfAJkphh91r*nUn)`mzb5Mj2E`*r;qOz@C&~){Ppf&{ryaW>hz)_d2&yShc6W@Sh~JuG{dA+!?9EI(gW++QK@G8ar1R zYp@9}a{z*YL&hsefAa@_B!={fm;b#acdOt3jsoNG-LA&Q0UOwvnG3&U8(02VMoH)@9Z}og}Pv6Hc#Cz zw3x}x5m=l)|7F{=Wtr{Yxhit@Q!RK_mW`YKlvq8OQ`nY1{YOZ0&DEFvH{g&ZTp5dt*E$EvSs?tkxU`zqE43@JwV*%)j!c3teG%hzzhj*N$-A| zW5`&U|J5U>+MuBm6}ZuQ(!G6j8pgW$kNvPp0@b zVz5b8<`>wQDNC&1pc^QRBR_L#)VBXQKDS0Bl}NxZU`ac=R9i+hz>X<3zOVqv=3ll`WuRg0=;(R2UG zYNtG|XSx2Pf3o!-eqRZ?B#=xNO?=%(uype#Z80TW(v{yzbi> zxzWy?U`=^WNg(HLYP9Y>SafYsa;$Q|C>u02e&CP;96IOM1U4*t9)hVRndX9 z(hU~x?Q-b;bhnpR51-uf+43L;DJe^5*0Wb1>oZ`4Z1f2%u~e@=b68G%%HYHTx8(Y< z2XXNa<~uWOjcjIxJxf&|;cVzzt}X2NRVTiYpwU@?C)cs0fkgsz9MT%@DA0m^xz}JZ z4&=hzNFA%te=RFJPl3F`1wdP256fz9mf=Qg^C|#R<{@&!VWVfN?-VjqWTXdoud$m~ zFWH^OTb7fR8?jXZC4{(Z~N z&Qo(^m=oSRbI~u^fFa}TXW#vQ#R@(7@_&%Q$eQ=R&T3>WjK>=f`&T_jp5_cSy(^%Wjc9fj%{8^J>Q8$z$u0@ zwkmc1^ssaw8K61$iC+^lg2@mPI@(Q8(@Hy*`qPKB=D8lR<9dG#d}fG40BsAN`)$1! z8ES*?%Lq_=Wbv16=cacg3wEtfniODj?*MX=QY95ta1H6lo0S|PR^7MTq zK|lar)@Pt?UiGT#L;F{cmcbH95o$-7`^-D;YyXawGQh#OiKGk3L6}9HLHV4mYhHI| zXO+Wj^4u5g{Ha57Hl<%Frc&#d{lMza98^8($no=42TIK_a$agQasA!5{X_4Z9h2Kd z^UJkoq0eaT#Kqbdcs6PYl9eMf6r`=NrT}f`8#Tqzz7jPH_m4NtQ`D;;a87Q#tv!Ts zr6w8HmSn)5?H}1kZ~iYyYm5b)TjoF^!ZI=8=7qd8bvRI@o;c*MGQLvyeaw zU@^EAYN(mH&bI5bDZb?Iue%iBO z9`s1x!|!hiED|ir?JgRh4rHrZx!(Bq@zMDOh1wF4fVH0Ebv+9e`uZT_9u7;!kIp1X za*lwBv7vskxM!)1FkFN5(910OBLQHzd=k*%RETVheu4yxn3>=*N5}1$nEi5ns!BFP%#WS|-^}m$#hk$+Yr~i%C%Uj?7 zL)FDmS9s#^c3Zvl?*%mZegHv_UgdW6%6Z91XJ3%*8O~={FNQlE zZmZOG;hu?sPE*qzfk4;+4*CJZCd#3dmLB`+R!S<0$%%|+poKhxn3Rl4n^DwLyV@=O zh2(Pdq{mc0C^MU#t5x?H*j%yNFh`AzR@kG|rq6p>|3+%by(b(J)AJ~RN&pwE#gw_9 zRqsk#y&xAxHp?79q7Ps@clL-_JeXXVVpIju^iHJx6G4q+sJ(3Vl3&r>r9b1Ho7V+4 zk+?qc_?OjM<>-M;-tL~~;@-~Or+%EdrPdgCZp-w7_u-Dn^TXj4=_c1$*rP-;X}%Ac zHH;=kGh0^uMC>H(Uc_cjyGQ$hO>G^a_iBHn#%L%p@)BIj%Zt(oUelj& z|EN1#@6cTgHT|8|&;cd66cYU|qYwa4QLg-sO%oj9jkmTYg@S)p1n`KDnFi$j)}B%D zESuvDD=;w;}8r%mF@4SM?T^M!$jXNV(GF>Y~k z(<(X_eB`h-*gZW!_ZddW2q^Inq1iGP{pr_)#mVv#*{7|@*I9g>^GdjNWrDBB(6}65 z>p4mkBq1BUyBxc>(Xk6PWUfuC#{oWtwk(vg)4bHl<*Q!T2H)OQtJnmCrP+dUZyA|B zTWdd>V#clblf0-HzCLnJ4&RR{($Rp#d(0vKBjsOWw_CBZw#RF@wkK)aHkT&SV^>X-kAASk?Z zD{o{y1GDp2_8oeFMBqN7ObqBZpT`Z-o=O-c{x?sMIG3B%F#PLEiR!C_XHGfs`$PlZ z=);Y3fRRSGu>%4Oh$l7O1WbWL*ISSPvOR}vaY7;Xt%#kgCAKjK)e{s>?XLS9vFadh zPBu|m2mPVY%-cttMcyw3Nmdo2=?3OSR-=oS8CUH7Nyu;)YfApR6q^z!c4Pv0@oReS5bN1g5v+m!s*?(Ga{!v0zj501xUp_!zzXKNMG zWrLDin6ntJ`JM@kQ3Eqvcbl5I+T4;V0>IcIP+-0?w151wlsoXx2W>_R(nGstOE*jg8;;ecFq+TAknQIW1Q34UGjwb0kk>3F z2Et)+ZmZ8I)^0klka8>&RCcV%f$R)IlUk?Tn2k7kOMM(7j_QHVUz~+h`$RS5?}CIm z0s4OY+#R`-renFLVyDd<6Q{QSf%~7~B5NWU{PG-KAL7@dsK0}{3#J42Vh7)YO^diI z4eILwzUBXeKT5BHGh04g4)fBb1ndJNUT7*oj{Duf%jiFk1B;yh5@=se%V5;HVI6$F zCoNXT1&baFAR&1#bs5E<9tK1jLm-9A_FY4uHdK16hP6(K#XUP}n(pS~F;AE5-2!Y! zZ6GfS==Vh-EoFVOv1v^W^dTN?7ZoE~%{N&zP<&n3_6o>)j8yYGh+r}~%`gssu4&<$ zHlvi9riiwChOqMxPytqAD)V*(b!-{-{q*Y_!uZ=-o4^Tw)c}G0=G^176aA-2deuJ` z%9`J;#H1#t2tZ3D%dN`U!PqX}w{oPBJRWrolA?C0BHqN-AeNOb@9%0-b}?9-4?^Y&79mPHU5FfI$K8HGh^aJaF0wi9+Qyvcj!9!k zA(Yosg1RKhD~FzE6`>py`uv1@m%u6oy*GozNSf26&b;xveEN5OMTkD zO0Uo3-;9>V0o;AB2OYN}#^$G7(pX)m&8WoVGpUOfP>OD<@u(r2{%W7cWxKSnH7z67 zR;XTXtbmhVGNa*PudYL!1Fi-a!WuAoi4Z|UCIV#&Dl)+vpHNc~KckT_HL6ghN4gW3 zqSo%W`=gue;i+4J)6XW(R@qJdm}7?2`*WIe_-4pouTTTsUD1Ii_us3tvYy0oD)i%h zOKcB^iq)5D`=K(@-TLLX&-6(2?$I2bF2nwZ+VN2%tiI`8i{Ytf+U7cgLd!cEjX zDpjY7pcc*W8r2slC&>zul&>xc;7r3j4br9D36DtQg&zvOieKZ|PZ--6I8ct4tLik_ z;dgr(;GDm4GMIy`{niA>=J$@zIuU^x2BqDwRW#gYO47vznIiLf8aC7!IWfYorsfMy z)$gj5s#wzYHzwNlyNNoxbC1NYxGDV$Ze7y6GseCN@!2&W66{xGz4C8cbyM5ty?NgP zB>cs(u^(nO6uyQMEUY$GN}RG!oJbF)8bC1ioYxi_=lu+YJoAVl4(X(AZrttnr%lSf zC$R6lHaG*KHfOdFN(D&*b-o1a9~yO8K7c1CiZLA{ti05(#5CZ9p)^5Z;lnMI&gxpMuU?1C3iEvS zuRK=NIv3PB1V%`3%)M69-aqI?S%`Xml9q`dZg!w_rpBBl#65ivotmNh*Stsz#>4L2 zpYM@kRu&`6m^5dH?~!p1h*W*$bG{C^DZdX}=k>`IMd6%D4B;rhZt~#42Redqy8cuj zMb$hsx&NaZsizmYJ1zIdnHz&v3Z%3qp-pq%_@0x>1pbm|o(6Qo=|pS~=ki0#BBTvR zKoSuNAAAT`=~mP1k}J9H6Z7gLZj^Pnf3Y9L`ZrcB*idNKj9m0cj$SB){B%5(mWnv> zWAAGz>H_?i>A#g?GV=7wEURVoC5ub$3`24L!Rk3me5_5GUl}qP#9u2qca3;{Jn~8-`WRqpq(IyQ1do z(%{t~K%pQQs&Wi^&+l-&_MInsvU?9}>;;Yr{j!_@rV;kM*^oa0HymS{^+()UmV&;1 zhZO=GDxrO^PYhwX z4Wj+eaH-tPMPUENPCnd|r^(lbjKtLJ+dk9CkR-8e#;O#a+T1t{{{dX=#HCvag9Lf^ zakvk>Obvwn+XGz25T%ejTwAe{kcfFNA@6_SOablWeuxbo7gjNAT|4(TqPw8r!lmOJMj4n&u~fT7zkwKnzzheJPuyg21lTn@$__h& zh0cTj+DX@5?oi4DButG{!n&w_MwT!bP7_mxZIMa4Yqu=I!Qk{h^ju?O-C`lR2l;8A zJ<61qI*1Ik$7-{gT3W$PFOgYDMA&@Abk@+=t@#M6VMR-NDRliEUA6_X3& zZ>%WhnySY^n32;Mgu8Syj0MeqWWs5gwwV#+5lA0+A?C_XeIw)W==)Bn!Y}5U@Zw(X z6rrG%zeaClRH0YgH~_1$df+wCOh9DTqsE-l6xx->$;Byy!Eb(Tj9(8*G1RCW1^=d5 zkAy^L)s4XK+Uxsc>$clvZt=ctjR2zfdznHzmLe`T4 zi4j|mR+?%D{7%<~ta6`TcHFuBnDm121aoMQ4rNjBgm6Lm5qV=&CL?>x!+$||ms0eT zj}sGlh#HsccY{F17Jqq<_!J}kqcRtt$L5xj%Wp+B4yeMJb4PsSpBj10DM+c_y7AHz zbqvc(26EO7YuGX*(BNU9-3p#97!}OW#dKv74vTyK8Uap*zBh|0B<8|tXDmB*jDpR~ z#>nc(VsNeBGNzCGF8Sajx+RHg&BP^>H|-^w@#*&hCTDU6HKw^hAsdW`vRIkV@7;_r zPb|Gp$z@?#)MleUwI;(7%Y~a2%P7k2V`?TeFJU0m=N+*SdKr6LZx*LK%0E1- zcmEX9zvPISLtD zBy2akexT!PP1+Kbk*=B5=JjLv$AZ^=$>qMmhZx2~PTDWp-jxT_6-TA@+2luMIU?gU z-wZA1>}Ql#x2LjlKL9BpL`Fobl!)BxQ%UV>&HUU{2oiA zhES4l7BhcxS;u&d__>+tpE*Kxx!S5icfW(ty>@}p;86ksyOAQQVbAH!P(t*FBh!Bn zW4(hDNdlKkf64)pGwk$L`z z1U0*P(vcJeT%dkEolV^M5h8Fs47h+93HNl+Kh3tQ3W3XP0m<$7(QdWnnR9WF2`sVh z9|erOVD8v+g&v>lZ|=7VH|wDI)sO2TgVR{f^@ns%UVKMCo%;h2+Wgml$NjYpCbRq{ z2GC7P;Y)?WzH~@tePT|iRcLh1r+F`HAe_71AaSmS5Q>;=0=NQje~bu%cQn+_pVKz2 z8FQgPaK;J?I~Enkk8X(3#oW5DBcLVk^FQx%er!&t^2#jgWQ*!uG$Dj|cU$Id-lH!i z;d^87%#Epmyjds_=+~+h3FiUv3*eLkqJ-B_#1R|V)6{4O`|f2ryT2JZfCEy7m^uFxyc z;YZvgXn*;67&{z!3F+cg@IwFU@2!}_cT6slDud9UX+uPUo4<+j!ST91J|l!vA$}H4 z)hb1eG8{;5gvE(P;=>hpkOqI!BP`uD$-A5MQZi&iPC&ZFB%^KiV|V4rUGp+^g7AnB zlL1N%y=Hct{PQ+`OfKxXU7adZ^AN@F;{AD44H4$9@adl=v`$bezMbh|R6$ z9&ZS0n~N-R)^p|=fHC-7^>7y|3cH^KIU@juV(EPxuBQpe2e*Iy9bxmEEQEk*$(x&b zIVnAz_MV2D)?hPMLn&uPdW zN%l%6iT=~kclyaF>=ipA`O?6wQ-F>KcqXz!92JZO(iQ4|aK_^l!=mk5Og5O6C_2%Q zjxWq@jSHzHNoaZoaPB%o%*-D6P5|^Cc|4(29ZaGigMiamE*EeRG$p`9wl!>CBJ~Ub zrSNECrJpQoAIk&nWdHfj=4D~XqUD%}!)UBApaL1=vK)qli%WBp*ZOY?GsK^EMS--D zF^2bFsTc}N*-dZuI-aWw=h3O4)uwI5HKNf)=w>gTm20eGn%Motl)>B2M;6UbPbw)} zT%PxR`mH(7qx@X9=c94e6t(%(aK0oDHg8jQ8%?Jyf_r~{IP#(wxbC2o4k-9*gCUNN zyE8i;%-tHgXus7-n>u0@aLrVozB|7O2H%lT{fmW&AcfnFE{i4+9Q^`k7>VSaVENjN z2D-|3rkx9cGQT-a3=i`vs=}>eDaNYUd*gny@3B{DdZt3~_)WFe`GwV?Sf=E$MMgN| zT#)An@K4pi;;kk0!h`^Mzwsj)VEl!2cylC=Lq}5@AD@P69Uo3~_C1nZyS5w~cJnti ze2@EY2Iu|nFV9_tEOAf_U2ds@`giLd)_=jZyyIV~^25WVQDYB+!^Gh#R;iLRkTX3K zpUeD(x{S4r1sHS+bRV&E+=AA4+U#=~1c&OP)+Tn6i^Ex3Qu`|=r_L3dJ}9S*s!~9R z#BfBPBPPciXExrjSx2k7(tyBcZJby&FD*=wU;IE71izm=qQl>KaTZvdb*IzEyS0z) z4(`n*0!?JmN~F1SR3Kc->;u||P%H|N`^kxR&nsb)*i!w%i$yBerT5J)D)E7su~9LF zipu*I+ND6Qqf?#rZ8&BR^(JnN0)u3Y3_=m~8Ly*u@PSVXAPLC9_}x?)uxj4Pl#(^E zeqlA|Zk!IFK@am}0*U5WE^h6M5hI{!i^!K2Uh?AfnemU(WJ^mLk%mDM z%OE!{p6AxiUrV#i;Tklc@;oFWgJyWAd)@kMDPSCuZwRuNlia&cKXZ|2y|Ekhyhm^T z?ga_8U0I13DqQAT@uEiVGQ`B%5un=vSZg*Dw$-U0e~0X>HzRO`MS~&5R#46hDGwD- zsM}7jy{rMb%AFnYs^0hcoJaHahSQOLI8MV4t@exCF$T<|z(>oSJ-jXq7$+h-a9iS- z@9L-Z?zf1auFpLzzarP$t_LA+A>Wpl<3yPK-VILP4GUsaW-3wClPr>lj9X8Tb7C#h z(lty0c)Wf)*P^r^M&bCVReIfy^=OMARZOCNq%5y4JH_r;w)jmf4OxlT*Ctt48Nxhn zaiIGzY0*NLaa$5g)hPtyGuq9}e3b=N?Nfk6C`=Cz0tmU)VA{V(?UvXEMuM81e0#0Q zsaPL^$O^k6tbrbw-S<`KienJJ=-LWLk-OEqh2hZW`@*jLJW|y0?EK^Qx@ErF>&T?F|=u}SOq*)<2aV0iYsHacnhi{gJvGI;Bn7<3KyaTpNFDqWd`#+4>Br#vPL zBwY&|)~AOjD>v(@aUK>m>C3)Fi!=l=kq@Rvrc{Y40KT zd>f6n>ytM9tNz6Jip{pvLLYIIiM!U`JbzRAIG;FsQsd3I{)5J^4=obpS8lHuoJ!Cl z+za3tF%Mo06+faTDoppawWHg7{##ccBMdP@*6tu1J(@|S z^xwBN?1;_1MH$3=YVtQ!u4&9#XtZiN<{Fw{e;7vHi8x40Ezq=mF^q~}4v$wrOii>t zBpG#b59&u%SZwvA%7+!Lut5zKIo>StrF=Vs(teoYb1BdCbsUO>^&mPcC;u@D!V&D> zt9PU^{Nl0u9k4Oa{`N}xo!TvW3v8d2^)w%|rl6QurLLZ29HdN~bfpo##6FR~!bG-tfUwkqAHC`M&NY0B+{X1%{ zs+9XumMv)s^JjhUL*o?j$s+Vu@yU_J1Ws;FX*UGbP|VLv2v#%`xQ9inmkm~jE(&#F zKiW)y(9d#?5#}x!0e%I@jXnVR$peC;uD_LGx3#@8v`=~t`FR@^n#-qw|McT7t{#rL z7uOiM>gs&Jngy7l4W-HWU0C=O17b}k`ppg__w(ggF{VIsT80k`^`%1CKTHcNiXoE^ z@+u2?pg`D;-_UZB=qjMm#FCmf;V8T{I)c+o!7h3y-uwR87Qhfh@vWY<0f$<_Wbdcv zY3fd6z)QAZ9h*6`MN%8t1s~eAZdR9`VZ+U!bBwe!r@Vu!sp=d=Bw+gN1r9qGZ7TX7#1&1{C~ z4kAfau82fvuz=+;Lwk?)!SP6e3fu$j!&A|D(LV?1K7^Oq3 zP85GK@?=O>3>Qhka9wen_U8lpbgPdWn{X}paFZ2cy*gi%s|#3G2(O{v1{$o+48~4> zyLOoU+^sbhd8-bQ0jZTUY0U(wu#}TBq`3(0^?D31dR0h-a5rK-c&AX9i3@3XyWe@R%nq2rdI0zS{%GIlP1ym3ajG~? z@YybJHZ}-G{2zO>_o%nk&^N;)zd*KFG*FFmyl4re(;!WY7pGpPu0}a~$mkmi4a%w_$vQo2A4de#w)oFX zR%_X$P#BV_`s_a+WG}d&*aMK^E=N<+6kk9P|MX`{!9RPXqFA92Q#69lmZ{Lw@hJDd z>N#G*DpwA}!a46*6)xJJ3)uxBPMhA{I&jp>c?ssUVK^w?E6jU*?zW&Y=WKmeqs}+~ z5lX!HdFWFg^9KEjMJ^z%TB;a4Fx_1EyGC%arfe^7_28h~Pd7L(M}s{)aPQ!Mp=`M0 z8QLVzF<{sGv*cXnyt=WD22a(>D)XhdR1O&d#^QKKgw7g~*47FumU6SnPlAa)4KZl_9_R=raBB5ECaMzV5^C-rY(IvCyk1t_-VkjabO|w2*0S=qcA%v39!i=E;%;MsyD7g*elfy&MI zIV-2SEs|1v4hxW2I&W5dFNw^4%DAs+cO_k}$$k&6T#X`sgwJaXJ|>N#qe;{fKkM>) zJ;dy!*y{z@(|jlLg)(8rS9C$5#Z9-lnQD!n;*cjeJ4_&sS#T}LT-n=!P?#xF{`VI5 zJ^j&z(t56zf`JLd_AXVZI`itW+zL{NCoOu?}uL_ehA%Plf`sI9BR%9(Gh9z0TEKKqD5z} ziNTJzwa0gg|6&Q^`0P+Hg(zMk-Iwtf;uu-yUwU3x zV(6wiCNMTwqEi+LFE4#VTzsE=BPCC9URvjI%|6@~tVSWqZa%W3zLqkw=#2L)Pw{@}Q^#+(#eN?lVEHF;-{GJ-9955#U)v^Q~B z+H$o2{K#im_=s(+u>4mkdq25UH4NdVv7|eEQ!y!p|CTnU;u0!{wJrLD+ zhI1|^v@+02kO*_vYACgTv&?|%4ogm{H$xj@I_N7wN>YF#wbkwD)l#@K=qHn!G2Y9? zm!lZ8q4}vc85?S6lv;RXaKWVSZ~@a}8#c~87M;%h%10G2lL+4v`;IaDTZH@^(oMpkSk)ES z&J<T~w4u#i%`Fg|tK4ZD?KEMdIQgap#niZ8gH>M+N29{cBcQ7BhvN@-Hf3h6I z=4H!lYTf0XuXxPiNcT$Kh=2O5>d#P{*9J*F$Xba=!$~jm4d+62~{G`Fk6ei$nRP!L5ewBOZd0LMPw+3J7$q8(xu& zZNM{naU@6iNMLB*;#_p+D-TM!bio!)sk_xvZf;y#V~$a1J^KU@tVmwQH>6^ccB_Bk zW+2O52%j+tsrmb*V^Uv})+eV;5$qU;Avj{f>=rCs(F@3HupQiMXb51V8v2Y~KhQtY^I;!=dY->7WN^_d87g zQwsv>1IC4&+v#;lN_U&*=+jlQ`^bnNZ(+V87*GT74iiM{ObC>cbp7q06S{btyz8yH zYM53(ms;EI_pl&bl1ua<2PdKU!1+&%4A-Pl@&ii958v=F= z_Hhr9lb|>ttpfeUQM_PW%wZd;oE+2$k~j{+Q$)1|pDqzeGG{YwD3udaJr=;6^!?BK+b}SOF4_7`!f*-xUl5+Js!iX^!A8O z)LjgFJndxaUCY4|Af^Ydr)k`BgL!Fw&j|h03(H8@gRc))=Lo9Y{ALpt-{IPvXIs-& zWh^vS+^~e{i5rJbAo8QzFYSq-fY#0|jySsoPvF7IKCpSH?fXI*%FI++<2TRAuJtu) z-Q%S}uf;_+!s@M9%xc?d=Xq~8%Wfo^T31ac18Q0q<=Ut)=9iphJmpR{Wfh+H1S%uR z<(X;P)@^(jMY~(7>&+M{Hmd!vaea{*QsjN>yl|@@^fG~R{_V`w z693?FGN?9M%r+Y_L){;RiaVt2>Y^L*@f$vzNJ=zXs>$hD>)b--kmmwPm+I9yXNy&) zqJ)mRbQ=zmFbRS+*^63nss+Us-_n?)L>9Y@tt8oTUaPy&ACyQd=V;VjrZ!P4$F~ZdU;oUf!+opla^HZoEmA>+uX9-q-H5PtYM`%!t>wp)W`{ zPm<3s$}Dn9=|@X$^~zc$*M9`owo}q${qV6>cex_KTN;e(B>{4(HGzdi5 zkqYj8B!-654hKVUmCndglygUI9fQ#T43_$UI7_Ba}8;MED*QNqjW*TbiWdF&5Z@xVRWA72ii*~xL zKb|B6p+yiLn+Ml=zA}7fZUn@sOG%u<^}rmV7$+iv{Z4gA5XdzD7kX3|M9YSn>c_8i zy8KaYFYn@J?`L2b<>zwI0qop|-p9|N!wbBrtdXW#T~A6h_2(fl7#Y+@m2;wyabd9~ z0i8-rB%bi#vwD^7eo|kJUn2?=@pzi7>(9zxG;L{iw=w3C3#7$zB~pz92O|6*NfsJ*i`$&J6&dZs zzB{?;cDO7wlzS?)k3F7J6+6U;6f_mnjE1SYwUMFx79&|U(R7< zl(-oj(^@vyMrn!Ft5#QZmS!(D=Z@YB401jV!Q<#aqFHuMCL}hP-`R=vNL_Hu8*_4& zNQN7x=74A@bLXr6wqV5*nz?+Ydix`ps}th&U}2%rMKS){G4*?EdR@AeGDycBz~y1ImK`ae_$5J&xV5`L8Fn0`KYehLz0;>J;}@M#plP(mVH+?{k=EXQV7m5IL>fIzkA`LtT-?6 z6^4kc>y${M&|9|Aji+sY)mF$cS97NKxb~agkI(3$N?C?D#Jw0qI6gq{jWY(P+; zWAG;*7k6Nt_8*#tzg8(~Cq&gEX-Y+{EoTgf}Ial#L4Wl@jC8O@a z@7lu6bdyHU82Ve#>-?zDtPyI>KN{ZNZy9%GYHHDH3eJF6H!(@$Gw8CE(1t@szs+MdXoOWrgocV9m9Ub5^4%|y-odB*q z*ZmkWK0k+6!2ZNKKtY?;E$BVNbT*%z!nsuMx$<@n#}BC$6ryNVxW${V$xxy60LS`4 zu_HgFx|Ew7NOAnx5CVQTE!`;H7`SZEG=Ifl6MQdhUIrNGSj!M#2u3aA{?Drl>M8vB zj1N8DN~=fU>cdUK$8PgTgnhPC2>{+h_@9`5O^zKbd?F5Yk-1aEufJU_~twu_WcC6(;$wOkkvHfc*~)~Y{Sq= zEN<&IOfc5l0$xO|b#ZqklQq<10<3M?L>qNlrw3U5x<6@tM0`tSg274sPBHD|f?9tr z)7+wn!8jyQj47f0+b2D(14szNuMrDZDGZB#r@E!{y$v&{2SOcj_U9Yd0o{B(+Rf?= z@3ltX+HEo&X`Uc**=)w-hm{vuJ`TitXd`S8OP7vOF;0e8OWU$nKvOsemszgB{ZOSI z8NtT6Xj#GZB9osTWf&rS4XRy&t#6nv3H~Lka+DfDNk!lCCi|VK`R;Gq(&ZJyf5bfu zyY8eiw+_WUVEAVBg4J41$~G_sT1{enUKh$wAh#koWhmp+sQx;z7MLe?Y8c28r4(Bx zUH8tL(!7bg_S+56$RU`r`kDS0s&2*SZeEcuVlC3WnUeX-8aRK zThhIJ5eCBhW+;A*N2OKCB$eAFO!O>NTYiS>@-J;v z2Zgf*rPJa0kdfu(ioH2MKR@2cd!eG?F&3DQnRM$I29J0>H2&9z0z_l6MYg4-eX*8J zHBMmT6Qp(fPR{>=bw}8Cqn3&mOZ@37!s@EPo?;jw;_`RW%q#aEoGHa$bnpileM|bG zb(>uVvff|)XR?#uP6^|h(Yq)Rd;!@A8Nw7G{TT^HgDtarOE0m`ZGHxln^AbgntZ!o z(>2~SPtbGt%qGI)LOMR;g*9H#s1ktAVzrsB{K|LtR+sk#Z0x(5=E>IrD*~BwB{@lk z2mlEmyk9K;juaj|`Nj}{b!Rg+tVRL9@8EI9sPlZBy)xYE%H?`4#|7AT?#~(gDR7rT zF*}B00Na3Twewi<9Ph2RNc0TLcU>{;m3Wtkd_6Y&23a*^6-%EbP@~HHv#MCyo9!7a z(QWx6PF_URau}y+}frQU?jU*d||n z%_U1jI+6q|>w?Wwops7p-HH$TD=yAMT*Tv4*4?+H)b!lvp{}2DsA-9mA-@+Pb-f<& z8DXK(2YfkNiE_rPCL06Btvnoy&DQ_WO?eD>;|+*-N=mXY$k}?(O!|pB8!Z;(8{aA;u|`!L z-x4r&V--53EHH$TVQ5PSEAx_BbZYv4<kJgE&d3!>! zhBU@&s8fFo?yrg(=QU&Txwnoh;*e6xVe~#DOuLxDd#px2ko372<$)(Qe{N+>sJ@V$ zQ)`(-x?xl^6W2)wZV58JRf|j?0i@B$h`|n8*|(aEw$U!u$r#x8Z1?cTi(jaPn9XKKU zS>>I5oexoIQkEqkdWz_=rFp!cb0LN&{K`)B6U=7nd|Q|cM;gF^OhGn$*Y6zpkGl2# zPKBB32053zlI~cU<_T|r<|g~ec9elG#t4$^7Z}U%_BHuKI6wwW#e~7rwdoDyORs}x z)j2F<1@C(n&GsVKlC;w}Nndj_yNuWv z&W8$TDP=y%)OcTN^pQU2O-XQlm_#|kWhXT)1H z#SMpjXyg!o7@g;X`{|1JA#g+o0Ta;j?(*cx(`5!QfL=Q0>M&c@YHpz&kTK^gX?L+9 zxq+|Zuv>{=@E_s{&_cF_H~bpu0MdqZ(c(3Z{puZ!6Tek#$hMHxD-~~tWfGzm@PZ3IfBQJa3h0rL)H`7}|!!fIiPp9=f0bHS+`utpNOh=3e#1?~NHHB5#BCKB^*Oo9O{*(rK0SgtXR#Vzl+O zyt;+Y!zYU@M+Byy=jQ0TzB%OCXnxPQPGzVjpR8i*{hMVr zTK?_}1xYNBAi(a{qBPoT1Lm1&Na%gm&ZcDSU0mzR-n_CuS4okX*FPhsxhlQX*xd`E z9lVV`Z{3DJcM#n?oXW9-C5F&4I+QD797Mk=S`NQ;Zn|*2W<`oUz_~|@jKI4PFqWJb z44b{q;{YCAvx9wlrCteSjjyOP;yKeD)$ZwbKFX$HYTYhB!JPWFODH(2+yxJ}YQ)gt z4@6%>q$fYpL4+DZWTeo*#N3LOF-AAs^LO6qZCHDj!l7nG#x8sT16Jq39?qdRD6=92 zo@;uv!m&1@{u2V6LQDZ-p9cqm6-?pyM+Q~ykSqd^Bp|4P>$ldJWN7LI2V8i5(E1l} zLTL77+TYD|VxBZ!s&-N`ys2IIOTn$yHD_b*z%@a`JL=7G&M2Zi(Wyw9+On!cBLbEM za{%tl9nJHFTGZfo{F62W^`8na+F0Fgy^R@e66l&)8npLQ^(Br)g{>N@rve*5f@$T% zGfkM{wMww5~Fx!*(HBinoQv}8*-z<6Qwu_IuT=Tzbmu!g{)4v^6*QEz%=UVDtfxHadH=!bI)>8i&%xF!8+n3AGOV6WmU6j)NuP!PBw|{pS>>b9$E%Rx zx1_>WS2ul>oUDl@BwLZZFr2<$ei&Q3Nlp!TWm zD+)NrKB^iIoA-8q@eZyxbz-yzF?LpIPGTI)0UC}{cS`2I+Y*=T_!Z%ETqwpF5_oW= z4kw6@itC5Y&Ebv#&>SjM3QacikYD*)z20$Vg^hop#BjP~nw@4DY1=w!$QFldF>6;a z^?XZcr6xA0^$}3dZh*+{Fvp2kx(ym38U$#s&tM7aY?V3k2U3Ch`eXj92S%>?BMoRl9@b7kw@=cD|J4OtBt|%HnIQMnOUO&wRn}F zPBM@&z~}NgC4%`#2B>Gr%&s^?-<7sWnVH7x%+7kT)w4xE zT{vj{;Nq}qCpBCXN3B9Z&-RNK6WI`i014eq1hRR{x_FroeAv?8f`kmR>B_GW*U#{t zaPPPjy0~eZeEHq}7XLw4o9atcmTtb&K3?dI(YxC zZZ53Cp_!%E?4u2i^LIBFr>9JN^owOa8J!hKY25WJElDqRAE@m?EM*G0aK}wu?#s`F zlHub3_iyQr+*}I~8a%msk;qFK!XPZT+rL@h9}V?|@M&)Pt3wdjC>vFCviMFA>{rBI zO>eK;F9&mk=2C^G@BH~WaF%bUh{9frOrxN+-yA>9OGY%}RCh6JEa}Xt)_DZ7tvvo_ zbdKk9Z@JHCmkE;EKiubjmz~5%_EX9$Te%G_+0I=@sIQ*OgGFFk3?9#&w6NX5sQw3* zcxN2))YCiJLLeD{#QX!p(D`HDbzD~3r{$~=h*QF$zc6`E=K*?h9-=j>=s6QfMkLWqFpMG)FT+Q}C4sCp$3r zOE(l^)Xa-Ap@w=XV#&IR!rGDMA%z7-BP$q6Z1c_&o;5Z?y|_c1wK$JOe`e!7lu;v~ z*)Dz{<4$xjKEKdjMM5aAKIJZ8t`0Jkny(~xymiX#iA40i!#X(F8mxJuXNTik7sPj6 zDTDiez9!ts45ROxV`G+bvRF>`X30(JQeBy0tKPbwM$ffT(jKgdHcyLfuF`#zlPQ8r zT=NTQywmiXCtQk6+4I?bYKh6oS~>YQB}LJUvXib@7oiX z=Zbu3Nh+lY5~_d|i-UfyI)jt)&2k}YSM!Ma-`9Nht0#8EUI9s+jV6?BNhWf`aCp9Ol!8zL|*%DU33fqWS?#ipQ8n39N*&;SC@0i~Tc7QcWIbq;!YNjc2&W*zo)^geZ7k1Lot-{#0A!2rF;= zZu^hS!<8-kEGzR-NQe<=XV3MC5v2(NY5~=0Jr5)2*&^vTPTeIeVTrj7pK`IsTn>dL z9sHlxV&NI@bsC4qT=YA-K1Ystl2%3Ffyk$^f0SjEtgz=*LRSsp8fimlvSvi_Iv4O9 zm5lTO2hiOZgYi$fO}eNZb+UgNvyr0orXo+MRCbDBS>X&Zp06e3vvwz=Vkud5-cCu2 zB}SLx*drH%XJ6_Ejg*3rxtkpMShr2bnqqohohsKz?K0|EjQ$VvKn%Z(+&&1i=!5sP z-hvUiow<%N<77{`O^g+4sdP78XgWOs`GclBv-H$nM?xGX>WG zT8x}#E!t>H)_mDIE}yoY@BgFSxZV+yQufLTcIK>=>hadqdBHw>^S|hv5wjR;W0MUm z##vtyAvovK+mQLb@8e&})G5w9$LqC{fqqC1H7|Wu?}56~!@GZD_wHo@i=K_7ea;JC z{U2>g&1~&8)FB_=|AF=hJ#3KO`u7kAi~3F(tGM?%wq%0(JXTdVS=+gzTI-y*uEh*4 zxiSB)M8YEcrE3Y|5(%ua((#ot9>TN*rA6`BaOYNfO3Nj0N$G`g?l!Pv+s8P2bTT*m8JVB;R+>pGw5& zJ@hNv2`@OY_dkm9Njx8|YnVrMGZ$OysXcc2{0Zy4(kgEWfFbqXl~ZTf;x%7Ztt*KQ z%zRJ>uzpV+-Y#Y>RkxfnYa)J^9DiRegNkg%tYtQ#a=KYxkDWVx&^j-lie&vc zUTGK~3&lLK@`+(wW%O4@M_{BzAP2A*&m3`Jk&$eYe2N2~tR@BXxH;a7J3hwlFjtTm zekCq;A;>^F7^GQIAQm^FdL$X1ks9*fvFkjcV9`n0oRo|Jy>aeZtDC(-G7{vQEr++- zt()Ce08lI_)aM53nHHDb@OfMm$v7gDBS_ML3%hmit_zerV-OgDOj*}R8tI@(1W*Wu z)pM?rX7gXL$u&*Z(RNBq0tYwJpl4qF3pED*@Hc;>H3(}-3xhj1yX4>p`$BKYl5rEn zz`^>EF}`{Is$4!{S(dK*nw*OX1dr@}S8EuM+4rDFAcWtA(E$kZdw?10t#CiZbrgvf z&BDh|sM2@QqJsc);i@mmQ0J{5{hzMgLF91h+ZsfIfJEQ~0Kl$&%vc$wAWNk+18q-e ziGX1iEF8i9&F(8|FM=~&P#dIJN(UI@3{{HJbTvdIxf+|-TK$}rcK_~OJAU8;Yim8M z;4pv>$v=bKG8d2-mUd{V5|@4UIXBJ4YhSh1oBl}O&-1`C5qviiC4g8$Tf zz_4VDSlzh`pSHXAZrSnuo9$f7KIdo|J!W8g(v5>6iEI?S54QgVw#YYShe@P^iSL^# zFyNgbgB4)(etUbg9(ZR9R=zAZQxbgCmxk6gv}vIhta08t_5HkctIIxq=Wp%ug<}fL z06nl@yoc$HOKjEC-_}{f@A2H4b6VRmnO_nHCz-FlK5Lk}*5)mLUU!cf5cO9N00L1^ zpWcTvX@ca2xle2e45{bW3U^3;lE<)&}jvbA5)Jc9Ax^6USs`of5fBq2&o zvuAhJu#;@JU5 zfW=_G#2)v`cm8+p$b8*Cdh@^7!QF3VZXq$yUh$Zi#c&Ssu2~C9)_q0wztkeqq9?G& zygS}uL-T6Mwc9VAk`p$HkD1MD42dquI^@rsrA~hPy8#wc$~G+`B}6!DsaHfjhg|*C z(H(Y+q?Y$T7;I_{@9#%z6Nfi$qrdeqM_^E}@qudc001BWNklUV4_F zuOO6qi5u72y==-gnoj-<2P}r);lP9yB3O@tqlY;nqu2iYjX*!CvpIu@o(DSg=PiBS zWk&DZQk@Aw!2SD37M-Dm7)UR#$~ag3!NC?z;sUk~IT!#886jDIq>)DJbXqKUgPeW? znFtj6gGJBM^z}(@iMasA6gYfxI1?OFH!-fF%AWm$|6V~HwIpPDVHg~)am;%Z!26_% ztHt84AK3WvDK>Y>vvN>{?Z8y!()r_&Y5>-Q?|~VrpS?=$5D0VuC>YEjc?*EXU6+w` zPJ#R&k)oZgVM_TaxUn?W85u$2+VgZsJLY2DLJ&ZWHEyb~bfNAm)WN06l9Nf1!N6l+c48oH_To*p?u9=VQ%t?t z*0;ZJ`**xBE1H0s+8Q0b(VnuUV z*)gCCpb@jk*MuhAv=88I$BK`shvPjkCrEJM@JibiSXyL~^OnCTXHHDYsEY&iG5<(d zY=7@>B|io5lgxnmqMnd3;rC#=cW?QT<{!z(IBguI8ZrgozU>5a1gGKU8^2*VtDZc( z-Hz^kSJL$8$1}5$$~c9W9S(|t&sp=<>-jLbpsp9`a=*FkYg2L7rCklrdHKRgd++D} zmj@t$c=LcfdH)()_jEAZNPO`HSi1HrR$MyH4uATNojJZ!XQE4J_@0`vgp+&ysbq}S zzT}cV`Rg7`2{qPdXf?z2_-|U`U@8Pqhk+kEwoER?v;sn=N;@EuHfp0HWra_+iG3`{ z-d^EJOzg(NVt&4j8$U@t2{^fHKYDOqvic1#{h1N~IM4q2AO8;}#zLYoeJ=U`%Ctv3 zj^~fbk^w#Rz@;?^ty`!&XW!G#SWuu=Fa<@$w(6O0T3yp}`}CuKwll|fxCCD1bk+J( zpHJUiq}Z(6-zBi<_D#-7cZMQ4re`we9Oti-pgOiW^BI=QCOgBQ*N=kA4I) zg2i}-g@1=_ppO0Omup>@bns)M5wdT|`itQ{PFjY?OzwXiYy`xkKcgd%aRlOZ z88}D6{!OlxWNcDZgI&9NUWXgfGqUBb-38#xH;4~yU^4X%^D#N{P#8t(J&@LMXb?0} z_)kq%kc~NsRtBl5|Fd+Ph?LyXnGfWNiNVAIX;|CYBX(rpdt%hMB7r%Q#f@M5H&$LT z&Ca*%Rb3%T8+XY0+J?06cOaDSt(aV`K7wWCQ|$WHHamS{r?q3|qK4gWEC{Y=%v!Ei z6xX}kRmTTI=nQ9^iH2PD0?>wO>g|zacHXiVt*Lpff+|`aU~uDrM9M59{g6$ejv)1e zb;EIT_M(j%eVbHYn{d<`pR1=PvWSMT_N%?>Ei z1D2#f7{36Tl1`@)2phakE-uMxY<^0>0oIM5eILJWJKq0$v7<1k)Ok`zcj(i%oy3cG zU07sI^Vh5Xlzw^C$hG29E8`t6jU5cM4t2Xo1B(t^>q!A6{@LTLE8H4#$$*N=YHLz$ z?QCnmaKaAmep~N-`TEzi7LiR?*Uz_t{31OY?O6bUG`9x)7LP4cFEb2_xE7K)fYE_Z z-mp7LhNR4IvOZQA4-XcpmxP_KYg%fZmq@z2p`b5rj1wgpG)+=9klGu9L6w*JHqKkC zKB9o&J==et5iACY`irmqdnJ`H3!&}6{*Qm*`}U<|F#)`Jx-=aO`x>~iaT9IPnpd4e zXX{bh_sOr^_vYuPz+!wr!WcLT*8PodLDL`DhJ=}81TowR#yHell31caJ++PWa3qPu zd%=+zB?4oKWEGZ)Jwe7U8QooTa0VUfTpg*;$G{>k#^cK;+xUr7mF(c0AaVE7H~&|w zYh0%1{P4}cu}`=DRK0C8nU+Pj^@M=M=u9v(%vz{LC-L<0dw*}&uU(3a#CUfP?%h>l z6=2L<*#6EB1d3hVd7m7yS8Vu({(aj!-fGDP5Ay~F zJMihSpKaykRSJq*Pww(E zJr~p_f5P~Lu~V2?P++wUi)_xqXA}%mN5~<~c=z-G@Z-UJXrbV0n^Qk7K#mdu1qIqe zU_f9?sX^iJ2Ph&ZbZrwb#-Tp3e;bSpH=a>J(eL^ESTPrAIZ|EQtan1YkFD=~->!FE zl5Ba>w3)Vi{lAcmchAtrM{LrJFMG}?)j~Zi2$>~ofjEDG-oHjsM-_%gSS?0!r0hNJ;Z9LYxJ8_630VenZc$v_go?eF9}+Wh zu*jULpS?o;63?GLV0*XyJk4+|tb5ky>Sw-fOV_=oRyx#1Z+ZQ%6j+CZYQOr(0PMu} zIcAa1!ssA_y@Y#PWVvb$nj{0bx z_u|=u`fqB#H@y6Bq;@#hvR}1|^v{**s{f{z`jaORETU>y_k};v9`fO@zbke)zrec- z`={ZIpw&|A@!ht2>(5-`Q}W^-Ii@aK_f@NzxzIj(^KTRfrmdqVEfyOVSafKSvJR4p zfJPENr;gx)N}YZV^EgV_WcDY>ZPI2+yQKf-pld(3FB<*S=m-ot0{y^Z0A|#W5R4KW zqv2Zkan^reZfB=(% zv&VK?%h8Y3d>gPq@T0gT*wu%*;{jt@s{qfc07Ni?sB2uJrh!)PKDk&s@6$S}*wCfe!aJ0wv>G8;9p&$0&GA7=&+If2FaGr+WZ zAmSJ>5)f|nL>{R=sKPv|p?R$ghguH8bRXB8Eh-wLb|=V*IXjvbtdp4#z>RlI+Zpv3 zEh?6*ngIPu+bO%H+S)ERKSN)|!15+#qp^DqwW-`|RqY&Gyy_JxV`z1OvLN)Yj8;zs zo>E{jj2}UC8d$u4Up2hTHoPVlI1^Z;c9^l)_@zIW-1vHDn|<)>zqZpyK1pju5!EOL zxo83`O8VQ|D<+m_U=AZuZaK1D>`ydj2LpF=R=DaHRQHm!cXZGZdwlGKvW2u|I&hp%}0 z>w50J+kPSUVb&&lIekiD7-8FJ!^Ge1-|>cO=c9N0q`lwaf<+AMrq-+PF7uySUCyFt z?F~?S8tOx3B9&~Hm1Fp(nr31HoUwCR<2hb;^kYxx2#iQ_;o&}8UTwo-cQW|NPjE?a zMQzvkJ0X{(<3mfi!Bz4u@Lf9=xQBle(&VAIK72~05rA}P0P z^FOKo*`igi%1nYbCe$h3z11!GU)=mAE0`TqmJek`3PJQEN;_P>x{;a|S~j zm}rcGcsDR#tu1@3u%Jj|N&VBjrO&A^B;bj&0|_6jt}}T_DMlDe)`FZpc@16`8r@^2 zv5!4K9Du=qEn0&caGio$8FJj}cJ;)1UoK%3{dfF*`hSln5j0nNdTe^bLb1RA+T9=h zBu$3OyTlv@a4~Iqvl!AHoBzpnfB0j8rfdK&lA@+Pi&@$DiITkH2z>eC2|KX!*HRhy z;$(d~?1O_P0>bA~UlEwouur8J`;6C&HJJ}AF#peUb+q^a)Mpgv+WKS6(T0^7hSc z+ws9aNC^>Q$j`!~J&Z9*dryPyeX%kT&WyUIB{re5M*CP>>rt_&nUd7;`;O8qn1c27 z=)4*1cQQS9IP-_|yANX=N3Z!XN5H8_;_m4W^V^1d?F3k)3Gx^LMK(+_h6Dv{j>t>^ zjF_Cc1vuLGWw?Vr`g@;!1SDMyfviY@0-G>tnw%za=0w5<=t6$xWF!7Oi+Xvc?jgBgYL;a=#CO@Vr z37MA}dbThmQzOHV_%jC3l)S-A88c5z1>+kz^vzkVzF%ybFeqnF?3N=dL8deCNYAgj zfYpOVFF{QY?%f8=VO`s>R8qv^;xd60?B6k%iPsdWR?(XS#X(2LgFKd1&IT44!}-fz zwAIi3kpk-5H?P{ZxBu3T?SEf;YG`;4dxX2}il@INi5~$ej1B*^pFeI#_r9m5=}w+` zw?B(LjHQ%QVCw;JV4R%9($~H!=yEJ0tvqHed|KxQ&vyFQE}6%WaA15HbJ#?Z0MxvZ zyupnWMn29e`=UCnCHKBV?NDX~LELmEJ_OtuHSS1aF=)AV^@8pHO>(i+rAq zH8FSbCTm)-L2_m4HtB;G)@ic8WcdAT(;=uA;(xE6m_DeD2c=Q6hYu%|7XcKw+Rk1{ zw@K1fR8F&s$#pU~qNba%pbnaZ*ZG!xcJk0ilJey=_l7a2hx;qhIpQ8n@Vj#I3?<4i z)_eYI|6Y=R0M+I`9@WhWjngQ$J~}nje(7(tz=29g>8A(WhT6{UkXP07y7Q z)B1>W=-{q5W0GyB5CK%8{#d#3n=*Mixa-$a3WT4>@qPzVQuI^4bgF%>DKXHf@|ae5Y(fDFkn_en27fHLhPU}XSY&KSq@ys__f2>{0`W@2mu zYgF5?SnjMa1Ju94SOV76A|tp*#-*oTdYKaW`gR`!O?vJ_VA+8YfFK4v&wk~9kXaDH z#-6P|wcQ{7#O@g-Wo-@= zz(hfcXWs%KaCK?BEmsd>fp8sD6%;V3PwwC)$%sh34%}bxtd3D4)hpK+n%V_m(y#dZZiGg@s zp$i0iRg(!Iq=n5+z+#Z0=jGX~dFyQBD}OGA_|}as`|!>0D)Et;Ybo|F{tN*u(oYda zi~FR1>*Cd4wlQN%?8x5tWHJRH5B0%uBc9~7GU+272=^i)&&JEZC((m11ibxavi*%~ zU`}w)WSk3&i#0cJw1o*J;aom(s>TATH+v5)i|jnrEpMU+&X*E~b)eeo{Cw56vX1X#L>4o48_F||g2kbX)}#4scqb17*gcGE zj`XPH)ix|q&K`hRHLXcf66zJniXgSYu}*!=QnbQI-$TahW!eaGTj-DE_C~+tF^@nT zEQa88!OAZxGa48k<3c6 zQ?lv`d`8 zO;0RbNy!FNm(p@*n=`>d@+sqv3^LLzl1hEp1I7UXW)d6@02ZA^e}P(9044y(4j{c3 z)xapG?+FTq1hW|3QwFf;!3xq|3~e~faW*`*f3xZVO+m7g-=%^@AM6RRq<(^FNw(>( zx#P!;u>}}lPDE=H0y6HJ{)t=O{H}msF!@LYm#!yg^U@crY5qC|8_4$#eDb=ae4zTThwm&GKVJH6kID-q%3Xl{-& zp82ZvTJqFat+23AtTz2TVf$gVLdz3LTLY^bSY&VXlB&Z^C1a9zAK1vA`}ehG=^u)O z_sogiVom@nyraOFyLaZUHzcrVeR2pESZr^#U7LR-1ptFmKB3B<{?eaY{oK{sXAbRr z(>{6sAH)i$F^Yb2_1lBI;sM}QI=;e|t$R(+LQl$rw9V-_Z$*X0t|g9V_2T1@#vCTr zo!cK$V3F1*m=Z}9k!E<~uIQGAYqQ~&SupfSpILHF^|h7x-Z@q!D%PjEYh>lK7i^HM z`t;GAVw8iKQGEY-oIoqdqVnv3Mf@6&V@|7?BapCb^ABz3hd*}7t4yj9zaKs3V{yP( zN@r$YpAu3TDkz(37N{(X>pCxV-E0xS+P3ieiCqExw=g6>~3~fT<}j9XHV) zJh-cUfkX*F8d>&`ezKjLL%PW5hevt@++OL-{Gxqvgudi+0T$~Tm-XSsM<$RgKR*OD zm#9zdzM`yQw7lY(vurHH2oGNTa*uK&8llG+z05-zfv~tj5QID$hc^2Aakvv`li?UdA~Uo7>pLQ{2vaAh^NR5!o5nb-_CUG#2xY1xPyoWqRZ&ILssSSf=_! zf+?)H5AS);HMyrXM1U$`V~QD!xIiuiWuls^l*U$v6>S<|K)8SE-7u=5^#GY;=NjsQ z2905S9VZh)@&As4#kk~ju-{MHC!Exd@p880i)_|{^|}xGF}9sMrk;}VHXCVRE;g_} zj7`hthy4K{sy=p=eP#?`xxSWpa)jOZ z#eXa5Z&6W+ojbkPHoyMYdM*qi;$YGBs5Bc}I$m{un7}Y^5A1kDj5v&=E8BCuGqcqw zjyPEKfv@u?@(GcA%#BJ00?df84L-EK$ryyr9U1ujb;n`6;)#F@n~w>`Lv0<|=^Vkeg_EvvAFYhF>UJz$Pz z;sn5~RXtJ$$}O3M84NsP{v_wx?hY}Fw{LcddBQPs<jB9-$0eN+cBWbnth{oXT9(i!7E=`z69S9goF`I3IQKfYE*}FkmkBIl z-ZOvM^R{5sD`Iomqu>7Vf3z!YE$RDB>|J9Xw2mzLXu^o2zHZ9_Oy|W+ipva^1EXgoP7WNMkpCs5yO3MYzS;x8mgg&SttJGhH zpZm2&KRJ>kkeqLia;}f$a}4)dd8;>lr;i58uCZ>Pm_%F>>7N*drVkkyX1n?LL7wff zAMS&X{@&+*1Y9;fl`*Hi%j#$U&~S7+yytC$X_&QOot2KCEXIx^b)5RTyV_mNS{!`j z(X72l&8P{22>|&FZDOuoY4uVY4>5dZKRP_J1UZqJj;DnPiK=R6`}P&J>P1I`a%!5~ z#zXMj9}LFl{y<={bo@l45qRCq#cH69kqd1#2;K?cqE-M=#GUyda^Ep5ek$XnN(JB! zEJ}VmXO-2~FVvw*YYZ5e){~zq=q&QBNurA-WM9#EB*xv1VV+gbm}j#WJ}nS-{`5gR zbL5uE}U7#q`8ksU%R$wyNW@+VGhH z->}baGiH2_wE;LNub3(z3>d%G*`}U!}X#Txw)3;TN8W{Pub4O*;;v6zX z8>b}3F|dAIjaQ_4}9_~yL_?5^-;~#J2f%G2c84|4*JX{S2w87 z9Lk%WTmDHVAFvSXzVNSY($ogEBG~%&e^u{O*X+DMlaVRN5aaXUo=vM?U<;PNXk$w! zsLs#HSiQ_I0@gxvX|Fm;nq~Irj6NG$>cr)sab-es{%H35xsbYV$5b+|DRo6^R>8JV zD^1NM>!6@$j1(TU;fc$?b!{ZzBqF?o`%#}t$>ab@9~id{Fa4=iOsQ3%zhg5!GJmP_ zM74^s1m0lEgGc>51AU)M5Mrd^ovrf<#8mT+n&v+xg$K{)YBB?Z(q~0QWA(&0u3fRN z&hx4#r{Aa4CUVp5FHwFJ&z;;S2HOjBInmh1D<;(lK=WMqb(}rn&ZV#yrjE~$uyOk% zY&zhYy@3Q(ex7SHHKd=I3D0oA@Q}W1^uwbgFoY4vd+D41p^rturigI|8F1Ja79Jb; z#AooE5JiWa)rKO9p}{xFP&8PhpxsgWuB9H82ePuKofG9BLb*#^Yqpy=u35{Gtu}7_B)f9?wDuoox8wZ zWU7P9FYkdGUNYr#m%U(A1X$~ftw(eLY6Sy$AV8x1$;yr2vi7!<)^cd8&78Z+ zI@`|)Ffix!D6#srOz$Ea6BvIm$+hzftbW!Co3r?7898BML~E1>kppSwHJUAW?6*c@ ztZwC$8Mfl-Z^*0#gPYh3=fKW4+}!n&+!PDzP*%(J001BWNkl5b-;7)i&r13DfDVC)AL3kviO)=;Zh zR4g^h`>+2$QkNu?4sN~l+p>qe?jF@I1c2`~;!Y9c-(f@Z8e96**K{tyWYbTPzPv~* zZ*_Od1Ay2N5&^bMZK(QOk}S;UT)@~!KI>4yqC2ez-Z&vma6GPm&-bncUG}+kzjLk@W-{^HdpCb?li!N@#`O?Y3>SwRAlLxm*!o}v#p+B*z z&So^a-i!P)&vblez?fzcM<$F`% z8aa0CI7xg??B8PDU2Xa_uB%avQ0y#A9XSJo#mcEOZSJCHRAV{W zdyMfDCfmg`hwbpE??^7FrqhY{5}@NyX1|^zCYy9^CEVPrpR>v~zVv5SURkZ0wY}Sa zVY@!~p?VEQKb{3wU|djSP4m`TWAi%I2Aw~>Pk`ro_Z9o}!=K3HD12911RNWFM%UQmdYryq`TE z{mhycZm`vxzAaXn@80spcU8~j^}{}y6p5z&dhZ{w5}aeq(=>m*_4Pim;|D%eLW>${ zw@1WenwoQtmBmyB&?Pgdz8)umQ!S!vxx=5s95E;Lyy}R8gx-P0WWY^w2~`D>_@o&P za~2aS-ZOE6z!R)DbDSQmzJ6==!i{1UX|n~(LhU8&`k`HKDItP<4`9ge-SoXQc|MsZ z=@y5V2}#bAT(0Bx6b~cv^Q~fHjct78-`cd=X3f!^AN-?g^8%=igY;akpTlx{WFK*0 z(Y{&9+-CPo( z+1^=@f#YOa*SO4zOG>3Cf<>j)Kil&$7W80d4$)&a^c7`{Subvp<#zri*Wx1`%+W6! z9f3hcAaDK4f7(ZV4D~!ZfHJtFJ<3t+-{;I9lo<}TM|oeP-}PjTKoUrWBm+PZ>u-A6 z?cDrB)!%X;63msAS6X%5JZqfyl1pv%aw{_;kF1vq+9*T~k3@s!wjd1+>>C8`__4YlGWOl*wmu%dG zD%DkDB679;tOvOsC_aW-pyacZj;mCAkV#W#Dv+nn4e4oBb(7u!4cO_mC~y_bNB~v- zm=3{#JM2AECKvG~w!}kk-<>gD})V%b0%>in;ka8m1gmv4!<;NNi zSFaeVD-$&=NeS*C0d_8dR2Y*uScFkThDLoY20Yvktw*SX1yJz!LH-M4#QR(A`g&8v}dPx#I_v)C_tpDEel*Ccg{j3ez0kaHj2{kF_t z(t@-R8Y_SiN(I0o=2_=X?YEWBe9Nk;XNgJt=&k>%B$aBJ;-JSH>O^v8KN+HWxx9Rv zGJUo!TKTf%yD&Sf3I1WNFkc*4lqS^IOZRH7Pnc9~Ww_3wAn56lITCZp?RiC3UQwmi zE&Lhv*8u7}x2|b!rUl&WRRx7cP3E}rNn+)1b$57OL!THXdPt7vTAgjy(bf{}U#I}a zmQ`5Aq-v|GnWJDE&&>;G_A5?Ca(?#Y9yyAV7-BExFPQ7px=Otv_hY9%7%sy&EU>7( z#>Mk;C0_S6ITHhlsX6`aFaFXxE}u@@EdiaoN;oad^vF^n`Q7z(*-~OE> z`xzBwk(}Gt)yW~%_qol1wHxUOVkE&;NX(J!qm>mVaM!POSnJ8%E-^CT^QCHeo%x;H ztIH==*}c1Wlw8Z@Cwd;w_~!CEqn{Zafk!n0d5!a)>cgEbk|_9Z9!hXAqBk35Ve*uP zBy*!IyAPZm+kK7bLk{6$84N;(@Y@4_G{~fem&hHl+ZgtRLLlv*gG}}0X-&3rXHe>b*^-pxo>mP`LqFxtP0I)?M6Qo>edBH68Pth~@dm&JR z!KD5L2_B$<0GptRU@bVECJ*II;4oZU*?1*%@~m)7u~k*iR;>v&$8D`gWFA5$pP;;- zo1sp-9A9)Y6PoMqC0?YH2fq`Oa|@XITQ;OXrX3`g{*Rvhz_i=v_`jX1(8}i%Au;W`eyzPq?eR zd^zTAc?K%~ z>8UgK!7_gNhHqHYyr)zzyJy=^6)2G?ShnFcD=ZjepKkrB6fCeBjvaG=IPLsN-d~ny zXRMIV&6u@P-*e)?W@|ft%rRX_Mtqr!`^e`(|483g4wuo>6CgEIx`>#7M+{rSOvA*6LpdgdhSW~ ziE^Rq%6Yrq-EP#wR!(iO+c!GZWSykcl$zOkr_?fsa+44US60omsncian)J}4MvXZ@ z-%4C>nXe^f&+b=NvC$VD=hkm)bU&-IlJ>2s09*d(8Q?yLWk%*}YV-5>tg_I~^e zv9)PG!`u&tbYCO=;SBp;IN#{E)&D2`CbnckWlk^rpgWQc+f43%ZWM+*;N#}unHS#rZC*JQ}oI9+S zJo-zIas={f>KFFKnT^LjNn>Rm<14BpiRtRR5arE79nGU0q>=fqAORUd(C#9sEMK2P zaG34JeNdP(Xc?I&e6&|dji&=#)OYnLFvYEqtloj0Z>q_8FkuL+H9=VAlsd^F2@J@V zGtSgyoI1Q++4;~e#w97@g(+To82%_xQx|He#+H@~z#z%PC>( zz!(5RVR`^a+%J91x;ihqW5!F&;;lE*WNd@Is7zpSP_UA?sOs&U4gIY7>lAEW>$+qu zN48l<+i5GCFv%uPs#P5ftW1yr(G0sFzbK|0j2lY0ur~Z<=toDOLqL16^^l!7@S$pK zRO9D+gGIGQgFQn`Vj4h9+^sVHg#3BQxJp~~%(oP1A$Nw&-u%X239!Iu#xvglDv}b@ z>gKBlAmEVRT{!KLn1F3ry7tRzVMJ{g0dz!24Y&`)?rN|gHavg4_KZJEbNO@ZDU2cO zYD#sJOrq$Sh$M>^FD{sL^-h77;r{7oxn#|&)_M7?ef-|vSy#t-1zH#l!S++v1GA_m z^Oc7uNl=8bSsYF6& zlD-dilHZ|LFUarMQ=NRYM=TWW5@0>K9ISZ z_V<7Bmxd|Rpzm|A{q%AFeJrUOua{MumT?np?eqWAIIli__rK{Z(JnjKUJ{-u(S!GK zKk9&zPvNjY>pMv1{!^<+m)jUxVZJC;uR2ll$KZ8toa+{%8Aj*nPWTc z!r22lfZ~n8Gs$QM1B(RTb&ZRye(o9@TU;i|CD*5MFttvpx)jgM`TCNa5C37jtE9<; z>VWbJ#2n0C{EQmYUp{|ab#6DVT~;jztO!A8SI4=CRTOCO627$ChzOCY1|d++61^U{BrCnu-hL*igD zW^@t(V_3z$UYlIqWOEj65|Frj?wB3j|AF1Q-kEMZ5dy?vhQCRnpP`SK%AiJKU@G z46a-6J~`)GqGa4La{`O5B?Rmppm=J{Y^$ERK;O4>%Mb0)&bP$)Mc)^H8Ck(%sJDDc z$rIX3Feh-`L=sP;slBbmfo`89aS4Px)oCIxZNGTJ_2Z{p&p@37?;*IWhxicffzjWcabzW}OcdFN^V?<-XF1y5zk5rL#3)nl-n!A>!RB*yPNovhQQY9!d=e|Q zjmvDshSvlVcW?QLN(0=I$sAi`{PQPiJO)Y#2C0T;=+lw_d3j18!;Ay+Zd_}(bEo&Y z7%8>+XFftS$6P$%=C5fT6c&xOyLVi#%B(-3jy;jUlZ*2pr3HhYXQLk&9f1)XfxPK6 z7kR=yQ4=$QUow@r3a;bgvUqQ`d?aYPNxL||8KKHgon0JLY?1@{WU9Nx1inwM3a_W@2Jy z+i#M8E(Wc)M|Eq|Z&CBsak7U2SvB9r9ufP2^T<25?)w=?`tfq#E0|{a1E) z&s#EPVO(JxY3RLh^((q2#y|1?gWP%mi^;uGf0vMf0w_w$CW@U!eth-nMX~CgfDLa} zk~T(Bdz0+$p9AiDs!PS#10Z7pzH^p5YqgC_t*WNU&b92b?eBcwH7DnW15nL0+2Y9v z5)NZZr9PNBd!=NU0BO!T_9!HuGn$s`&#$ymGv}nbA+b+k4;IFP;*xlp#oO zkM;=GMW_#cSm%=FiEpgFaMhP=)id8#U&XE~7vzA-81&ompCn+E=($2U@s05@2!=yJq5_zn`qZUC4N5$l@vJ?(3Cl2{JyiT*~rtkg6WXkApwBhPtT) z_9nQ}{jPvT2NZg(Vp6Rwd+Mt?_&(kG&r$svfdBywO_#~S!y=NkN9K%0J?vu5%!LYw zN=hfl5Q0O4Ku1zA-^w7=qD8Y&a>snDm{MnrbJo~|$u)NE$^|=qXp82qYs%|DPU>9+ z!wN6ubCIzwnaTir(3fXcQc`X+n^#-)j0FndXf#j#7(rif5zNFuxu9!g*G&?Trd^#R z57N_x8&w13+E=`9cW>X4D=FX#pa)|@VC)Q1QfoUfM@}Nt|HgUNDK)dKv3a$PpHL-G z597tP!uV><#eOveg}H#mtiguo_W6$5hQ+q-3x8r0DyyyM{$1O@;|<&Q@vl-fU_K!v zTX{3}?wqx7gH=>gTY5;n6hk|YFsBIY=Pr3p?N#XQMPE7?7mQS#<7AHl`ds!C7we^u zT_#W%9}nG!pM!vcSqnDGLY{Ue$M(K2pvY%1APRD5_GC&07OZ&58s@GQb4+UtSXOrr zIB|}#qA|rbf8`f#Qq>IGyZx8ee&KlkcN;TSOAF*;Yl3IMcmx2_*!+}CRF3Zbtt6MM z)wG|mzj}6YAdo%K{s}`~I=;g0-MMY|?%a?YEXkna;!-IHcD(-&)_QWU_4PfF&1-i5o=cQ599#qWGxfE1?%cGt*28iRo;Z1ifFiY|Ftvb3WTEVha=7(l ziJ1^%f1|72E?;zkH1|?7V}a&3<~65}@3xC)4hVFT5UQ?Us3ZY0;hWu^lHIZ&GFA$v zZ(rB*!C2$IseX3Mbtyr755F7%TJjxdd#`Dq>+6$T_nBA!LaY+!D~X)#zx_MAd#l?k z9a8)DP|wCAiP8)trUe`J3p zF^^L>i53#Otta*chE!KbQ!NCQ%>J-JyR%^VeK6>%;l#hw?kgEL8ZC z7+CE0y)jnu4>~rQAl>Q5ybgN60!W8YoA6KuXXG!+ z`~Z-weEJ(!GH#+B-1&xGIDOEYG*sK9X^qMrv$@k#iol%UgabuAk}O}Ye_|P@H7J|j z-FZnF{0nCeDY%I;g|S*FKqzd-xCv7QV##8~Y3z7MP&lc*jT#RsmRqEDI-(9=(me|QHwHvgmcYS-V;J-?cM7Zlmt zrO#VU{d~;_L8CD*lahiby{ID23$?nfLz|Q|I{r~---E7=*LJx^y=lazP{Bpf_F(w_N|9x zo)Wzu*G!$ZD=XH2-3p7xiZw-k3UH6wulN=u!`(ZdnBR-73;HBtL^W^ui*~+cuN~a| zmJ(ml&k)wh6Z3rW*vkKVX#ay`8&G%WR%Tf!B`GB8V7!sya>lA{R$4u`GxI{(fLaM) zdH41W{X2;ghL?59UOBX%ppQ-L9Yedw=%+_V;GvE{8d%IFfPJWU6FX=*Fe#Ylu!LEQ z9I0{*iXQrn=J*BuBnue~YvLPo$fWx~k`0MIK4f*t(%-vx%kJE|Vb{AZMKy;GG`j1G zT?v`0&+~?#$$5l)=>+Q3fH?P{sgCEJPK_(x4CRb7zqxv~31u|hdIB4i8mzSwdD*3Jx z(zGbp^vq1jxCu6U!A7g9ZPsB&piMuwyLWD-8H~7>??)pGAjrk?eONWYeWsv`Of@$7 z03_TNk00FPSyfnqJ~1BDS^=6OY4sohVPM`^|Cql}r&cksTE;jyZi?}W*x2A0*?)~? z1&hfElwmCra1fx68$a3Bz5FLOy?&8^5OtW_-u;0yg$VNUu!ot+OaucKTrRt=w2HCl zzSf?qZIg5fhss&jyl9hThNqA1)E!mV%@xZ7K!Ek3PaQ$JGb*8vUaHQ|^U-PY;{n;< z@XUHvC!YfNnT~N1Ol~d#}9s}_2Ci>e!}{7l8G4)^O5H*DJ=nG2%Pt~<|WTLgO)3;>Zb@el`Iwu zf4=}SJ$p{$k#Hdl22sc(Crz1Q3s${sHT8@1-MA+691cj|?-x|Yr&TJ^qRAm9al!I0 zC=rOYKJ$oo+<6&Lc+dKJdX(Iv4wSQxKgayW88$ijFSUts|2=n9U|CXTvF=R*kr?A} zUhwZY10zKhvsf}t?~MSLu|tke5&$-ZcV0MVjEyUwBGA-vsl~eGD(vdRxhKHlwazvr zg7`z)#w=Lz1wGTjUB6KR&IQYPHm$DN<}Z6u21i#eozcEU;_kr%=QK@w74}z>N!)Kx zyu{T-!#V~M$%5z_F{X(z$CxWl{_Tv+ko5B7*3lqR-k760%sgkC4E17XhY#i+`qUWxg3%Gk zbp-ON>*i&%+sySEBl@|(F6cm%^IC^%tQ{J`e$L8%lT1vUp~-5g9_r3~Fo*1c&7Bqm z1PC0&7QS+vNr+7jTgEfE!>F9?=&*LKh1Gvo6=$XVvxdWk=t2<)Q*@ z+)?QlM@AiaRmbJC3UYZLY}k=mbqsW?9YD!AtFCL7Aq#94bvM-DQ7?#;uyOuVlCAdj z^jd4nr*{7I0lUSaq+mJspGbb`-y7=y(1q-6THRc`bMv~LI`**wOXt+eEypsF?sUl@ zfy?w~x!zZB+znDLM@2ww|;YHVI3#^?N*1I}#b_I2;7*()};X67R6?zmvru3nae z&`r~UTzvz}*yoHzmcF1~ZZICy*R-paD+W43kdXEcInSMZFMb%O&6n741O_-IIqnnd z3|mcI9yMkFCxYm0Z-37&oH-b=XbuXv>@bpM%x^FbxpD219pAr2Nd`W_^#Z_^q!#w2 zv|NdRGbeT{*oIA>RyRihH+3|C#LkX$djHhtku;L*Iu5!L^{GA3M8@)qBbkhN*-{M$M?o$ zeQaps;%er&bb&R_TVrdU`&R;BfOc5Ll?ACu@#?8x&Y)tQm?*gxy@R<(P&wP z0znPm&17n%fVQ{SyNk|}fek$pLn|CPE7G#1e6kE;_&X%>1o}wpNlXCh0hwjxlWg4h zN^5UBWw&p3>3fh))06c2)i#xQ&>vA!aIwIJ0`^=RB@5sVCPr()8{x3mk?cVtJ+`D= ztQA>rB?yZ`_M9Z5t%RJkBfTTmzyAl@134C)wpmdh7g)XIao%bK2AJ4av_ zLmohK%uQrS`{%$fJALirCRbU{Plr3+Qi=GQCR?)R%Q9fYkcz!p<}A_krS|$K<;kM^Pg`fvuA8=t z2LmnMAFLm>wEaMwCmuMnW;8CdqOm24r6`@?{ipqSfX9ATT0TjCpymaSAnaN%>fivE>)2uBBnlYB{H}snaX$_N^{uBgxvg zp4_JzAjt)Db>9r&#s?oEQ3Cr(P&ae#Y6XNi@=@~xn}IYY-qvHVSNqxiJ}z%fHya6c zP=G)HPt&}00@i@&Q-`Pdx(CrX5)jCWxgBx<~25XO1)j} zXtfguw^~={`3RgurZ!>DCNt1+hsDI0C&wp}hvw%;uBK#-VS;G?Kwv?_V9)lS*@^vI zq9jeYju^1A2?9nKupqeu*j~AOM!`Vyk#$FZ)rXGsaQqHNcoK1Q8B)8Qf+|k(sf_8 z`dKSfr+8@BZ`5BfwV$OY07(4t{&-f{xZ?-5^b5oyP?}-FiZQEhwAqWEk<%yaV^N#rq#{UoIq{~y9TovOk$izsjK@;q*S7MWsv8D ziPd7;$|h9Wxl{Y4RKPR`862`u$(b>oscF*uzH+I>?%lp=<(1PER3g15nLr&VQdY+H z#20fA;m*`0^ - + diff --git a/launch/tier4_sensing_launch/package.xml b/launch/tier4_sensing_launch/package.xml index 81808f60876f5..9002d37c13488 100644 --- a/launch/tier4_sensing_launch/package.xml +++ b/launch/tier4_sensing_launch/package.xml @@ -9,9 +9,6 @@ Apache License 2.0 ament_cmake_auto - aip_x1_launch - aip_x2_launch - aip_xx1_launch common_sensor_launch vehicle_info_util ament_lint_auto diff --git a/launch/tier4_vehicle_launch/README.md b/launch/tier4_vehicle_launch/README.md index c2d0dcbb8a3e5..3857ce4e4e951 100644 --- a/launch/tier4_vehicle_launch/README.md +++ b/launch/tier4_vehicle_launch/README.md @@ -13,8 +13,8 @@ Please see `` in `package.xml`. You can include as follows in `*.launch.xml` to use `vehicle.launch.xml`. ```xml - - + + @@ -50,8 +50,8 @@ ex.) You can write as follows in `*.launch.xml`. ```xml - - + + From b145d4e7ba187eedf15c970924dd525774cfa9c9 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 21 Feb 2022 21:28:04 +0900 Subject: [PATCH 23/37] fix: replace tier4_autoware_launch with autoware_launch (#427) * fix: replace tier4_autoware_launch with autoware_launch Signed-off-by: Kenji Miyake * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- launch/tier4_integration_launch/README.md | 2 +- launch/tier4_integration_launch/integration_launch.drawio.svg | 4 ++-- .../launch/ci_planning_simulator.launch.xml | 2 +- launch/tier4_integration_launch/launch/release.launch.xml | 2 +- launch/tier4_integration_launch/package.xml | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/launch/tier4_integration_launch/README.md b/launch/tier4_integration_launch/README.md index f9edf806081b4..634c73fed14bb 100644 --- a/launch/tier4_integration_launch/README.md +++ b/launch/tier4_integration_launch/README.md @@ -6,7 +6,7 @@ ## Package Dependencies -- tier4_autoware_launch +- autoware_launch ## Notes diff --git a/launch/tier4_integration_launch/integration_launch.drawio.svg b/launch/tier4_integration_launch/integration_launch.drawio.svg index 39572e24e2a14..c47744ff98b82 100644 --- a/launch/tier4_integration_launch/integration_launch.drawio.svg +++ b/launch/tier4_integration_launch/integration_launch.drawio.svg @@ -102,7 +102,7 @@
    - package: tier4_autoware_launch + package: autoware_launch
    @@ -202,7 +202,7 @@
    - package: tier4_autoware_launch + package: autoware_launch
    diff --git a/launch/tier4_integration_launch/launch/ci_planning_simulator.launch.xml b/launch/tier4_integration_launch/launch/ci_planning_simulator.launch.xml index d909c615051ee..ce4c98437346c 100644 --- a/launch/tier4_integration_launch/launch/ci_planning_simulator.launch.xml +++ b/launch/tier4_integration_launch/launch/ci_planning_simulator.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/launch/tier4_integration_launch/launch/release.launch.xml b/launch/tier4_integration_launch/launch/release.launch.xml index 42655e3e3371a..3a27a1fa20dcb 100644 --- a/launch/tier4_integration_launch/launch/release.launch.xml +++ b/launch/tier4_integration_launch/launch/release.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/launch/tier4_integration_launch/package.xml b/launch/tier4_integration_launch/package.xml index a160256a9c685..eca4031062e52 100644 --- a/launch/tier4_integration_launch/package.xml +++ b/launch/tier4_integration_launch/package.xml @@ -8,10 +8,10 @@ Apache 2 ament_cmake_auto + autoware_launch python3-bson python3-tornado rviz2 - tier4_autoware_launch ament_lint_auto autoware_lint_common From 9c4b6648ab86efbddde580290f321118cbac3410 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 22 Feb 2022 10:13:17 +0900 Subject: [PATCH 24/37] chore: sync files (#429) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/check-build-depends.yaml | 7 ------- 1 file changed, 7 deletions(-) diff --git a/.github/workflows/check-build-depends.yaml b/.github/workflows/check-build-depends.yaml index 65c72372e59fb..d8f731787f4f0 100644 --- a/.github/workflows/check-build-depends.yaml +++ b/.github/workflows/check-build-depends.yaml @@ -29,10 +29,3 @@ jobs: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} build-depends-repos: build_depends.repos - - - name: Test - uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal - with: - rosdistro: galactic - target-packages: ${{ steps.get-self-packages.outputs.self-packages }} - build-depends-repos: build_depends.repos From 9ce55c7875fd38e60fb9596e82c24aa97ddc314a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 22 Feb 2022 10:36:01 +0900 Subject: [PATCH 25/37] fix(ekf_localizer): update predict frequency with measured timer rate (#399) * fix(ekf_localizer): update predict frequency with measured timer rate Signed-off-by: kosuke55 * Remove timer smoothing Signed-off-by: kosuke55 * Remove deque Signed-off-by: kosuke55 * Remove clock_ Signed-off-by: kosuke55 --- .../include/ekf_localizer/ekf_localizer.hpp | 14 +++++++ .../ekf_localizer/src/ekf_localizer.cpp | 41 ++++++++++++++----- 2 files changed, 45 insertions(+), 10 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index e500e5b91a49a..c813369c67b77 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -78,6 +78,9 @@ class EKFLocalizer : public rclcpp::Node sub_twist_with_cov_; //!< @brief time for ekf calculation callback rclcpp::TimerBase::SharedPtr timer_control_; + //!< @brief last predict time + std::shared_ptr last_predict_time_; + //!< @brief timer to send transform rclcpp::TimerBase::SharedPtr timer_tf_; //!< @brief tf broadcaster @@ -113,6 +116,12 @@ class EKFLocalizer : public rclcpp::Node //!< @brief measurement is ignored if the mahalanobis distance is larger than this value. double twist_gate_dist_; + /* process noise standard deviation */ + double proc_stddev_yaw_c_; //!< @brief yaw process noise + double proc_stddev_yaw_bias_c_; //!< @brief yaw bias process noise + double proc_stddev_vx_c_; //!< @brief vx process noise + double proc_stddev_wz_c_; //!< @brief wz process noise + /* process noise variance for discrete model */ double proc_cov_yaw_d_; //!< @brief discrete yaw process noise double proc_cov_yaw_bias_d_; //!< @brief discrete yaw bias process noise @@ -169,6 +178,11 @@ class EKFLocalizer : public rclcpp::Node */ void initEKF(); + /** + * @brief update predict frequency + */ + void updatePredictFrequency(); + /** * @brief compute EKF prediction */ diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 08b0f4b4f33b3..9c5cb34eab8d6 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -55,20 +55,19 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti twist_gate_dist_ = declare_parameter("twist_gate_dist", 10000.0); // Mahalanobis limit /* process noise */ - double proc_stddev_yaw_c, proc_stddev_yaw_bias_c, proc_stddev_vx_c, proc_stddev_wz_c; - proc_stddev_yaw_c = declare_parameter("proc_stddev_yaw_c", 0.005); - proc_stddev_yaw_bias_c = declare_parameter("proc_stddev_yaw_bias_c", 0.001); - proc_stddev_vx_c = declare_parameter("proc_stddev_vx_c", 5.0); - proc_stddev_wz_c = declare_parameter("proc_stddev_wz_c", 1.0); + proc_stddev_yaw_c_ = declare_parameter("proc_stddev_yaw_c", 0.005); + proc_stddev_yaw_bias_c_ = declare_parameter("proc_stddev_yaw_bias_c", 0.001); + proc_stddev_vx_c_ = declare_parameter("proc_stddev_vx_c", 5.0); + proc_stddev_wz_c_ = declare_parameter("proc_stddev_wz_c", 1.0); if (!enable_yaw_bias_estimation_) { - proc_stddev_yaw_bias_c = 0.0; + proc_stddev_yaw_bias_c_ = 0.0; } /* convert to continuous to discrete */ - proc_cov_vx_d_ = std::pow(proc_stddev_vx_c * ekf_dt_, 2.0); - proc_cov_wz_d_ = std::pow(proc_stddev_wz_c * ekf_dt_, 2.0); - proc_cov_yaw_d_ = std::pow(proc_stddev_yaw_c * ekf_dt_, 2.0); - proc_cov_yaw_bias_d_ = std::pow(proc_stddev_yaw_bias_c * ekf_dt_, 2.0); + proc_cov_vx_d_ = std::pow(proc_stddev_vx_c_ * ekf_dt_, 2.0); + proc_cov_wz_d_ = std::pow(proc_stddev_wz_c_ * ekf_dt_, 2.0); + proc_cov_yaw_d_ = std::pow(proc_stddev_yaw_c_ * ekf_dt_, 2.0); + proc_cov_yaw_bias_d_ = std::pow(proc_stddev_yaw_bias_c_ * ekf_dt_, 2.0); /* initialize ros system */ auto period_control_ns = @@ -111,6 +110,25 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti pub_measured_pose_ = create_publisher("debug/measured_pose", 1); } +/* + * updatePredictFrequency + */ +void EKFLocalizer::updatePredictFrequency() +{ + if (last_predict_time_) { + ekf_rate_ = 1.0 / (get_clock()->now() - *last_predict_time_).seconds(); + DEBUG_INFO(get_logger(), "[EKF] update ekf_rate_ to %f hz", ekf_rate_); + ekf_dt_ = 1.0 / std::max(ekf_rate_, 0.1); + + /* Update discrete proc_cov*/ + proc_cov_vx_d_ = std::pow(proc_stddev_vx_c_ * ekf_dt_, 2.0); + proc_cov_wz_d_ = std::pow(proc_stddev_wz_c_ * ekf_dt_, 2.0); + proc_cov_yaw_d_ = std::pow(proc_stddev_yaw_c_ * ekf_dt_, 2.0); + proc_cov_yaw_bias_d_ = std::pow(proc_stddev_yaw_bias_c_ * ekf_dt_, 2.0); + } + last_predict_time_ = std::make_shared(get_clock()->now()); +} + /* * timerCallback */ @@ -118,6 +136,9 @@ void EKFLocalizer::timerCallback() { DEBUG_INFO(get_logger(), "========================= timer called ========================="); + /* update predict frequency with measured timer rate */ + updatePredictFrequency(); + /* predict model in EKF */ stop_watch_.tic(); DEBUG_INFO(get_logger(), "------------------------- start prediction -------------------------"); From eb35961b1ee16f37c756b08e28d7e7cbcf177902 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 22 Feb 2022 13:38:16 +0900 Subject: [PATCH 26/37] test(simple_planning_simulator): add node test (#422) * test(simple_planning_simulator): add node test Signed-off-by: Takamasa Horibe * use TEST_P Signed-off-by: Takamasa Horibe --- .../simple_planning_simulator/CMakeLists.txt | 9 + .../test/test_simple_planning_simulator.cpp | 367 ++++++------------ 2 files changed, 137 insertions(+), 239 deletions(-) diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 0b5ebbd482db8..cc128ecc9126c 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -37,6 +37,15 @@ rclcpp_components_register_node(${PROJECT_NAME} if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + + ament_add_gtest(test_simple_planning_simulator + test/test_simple_planning_simulator.cpp + TIMEOUT 120 + ) + + target_link_libraries(test_simple_planning_simulator + ${PROJECT_NAME} + ) endif() 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 62dbd964cff31..ad872909740b3 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -12,111 +12,75 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include #include "gtest/gtest.h" - #include "simple_planning_simulator/simple_planning_simulator_core.hpp" -#include "motion_common/motion_common.hpp" +#include "tf2/utils.h" + +#include using autoware_auto_control_msgs::msg::AckermannControlCommand; using autoware_auto_vehicle_msgs::msg::GearCommand; -using autoware_auto_vehicle_msgs::msg::VehicleControlCommand; -using autoware_auto_vehicle_msgs::msg::VehicleKinematicState; using geometry_msgs::msg::PoseWithCovarianceStamped; +using nav_msgs::msg::Odometry; using simulation::simple_planning_simulator::SimplePlanningSimulator; -std::string toStrInfo(const VehicleKinematicState & state) +std::string toStrInfo(const Odometry & o) { - const auto & s = state.state; + const auto & p = o.pose.pose; + const auto & t = o.twist.twist; std::stringstream ss; - ss << "state x: " << s.pose.position.x << ", y: " << s.pose.position.y << ", yaw: " << - motion::motion_common::to_angle( - s.pose.orientation) << ", vx = " << s.longitudinal_velocity_mps << ", vy: " << - s.lateral_velocity_mps << - ", ax: " << s.acceleration_mps2 << ", steer: " << s.front_wheel_angle_rad; + ss << "state x: " << p.position.x << ", y: " << p.position.y + << ", yaw: " << tf2::getYaw(p.orientation) << ", vx = " << t.linear.x << ", vy: " << t.linear.y + << ", wz: " << t.angular.z; return ss.str(); } -const std::vector vehicle_model_type_vec = { // NOLINT - "IDEAL_STEER_VEL", - "IDEAL_STEER_ACC", - "IDEAL_STEER_ACC_GEARED", - "DELAY_STEER_VEL", - "DELAY_STEER_ACC", - "DELAY_STEER_ACC_GEARED", -}; - -static constexpr float64_t COM_TO_BASELINK = 1.5; class PubSubNode : public rclcpp::Node { public: - PubSubNode() - : Node{"test_simple_planning_simulator_pubsub"} + PubSubNode() : Node{"test_simple_planning_simulator_pubsub"} { - kinematic_state_sub_ = create_subscription( - "output/kinematic_state", rclcpp::QoS{1}, - [this](const VehicleKinematicState::SharedPtr msg) { - current_state_ = msg; + current_odom_sub_ = create_subscription( + "output/odometry", rclcpp::QoS{1}, [this](const Odometry::SharedPtr msg) { + current_odom_ = msg; }); - pub_control_command_ = create_publisher( - "input/vehicle_control_command", - rclcpp::QoS{1}); - pub_ackermann_command_ = create_publisher( - "input/ackermann_control_command", - rclcpp::QoS{1}); - pub_initialpose_ = create_publisher( - "/initialpose", - rclcpp::QoS{1}); - pub_state_cmd_ = create_publisher( - "/input/vehicle_state_command", - rclcpp::QoS{1}); + pub_ackermann_command_ = + create_publisher("input/ackermann_control_command", rclcpp::QoS{1}); + pub_initialpose_ = create_publisher("/initialpose", rclcpp::QoS{1}); + pub_gear_cmd_ = create_publisher("/input/gear_command", rclcpp::QoS{1}); } - rclcpp::Publisher::SharedPtr pub_control_command_; + rclcpp::Subscription::SharedPtr current_odom_sub_; rclcpp::Publisher::SharedPtr pub_ackermann_command_; - rclcpp::Publisher::SharedPtr pub_state_cmd_; + rclcpp::Publisher::SharedPtr pub_gear_cmd_; rclcpp::Publisher::SharedPtr pub_initialpose_; - rclcpp::Subscription::SharedPtr kinematic_state_sub_; - VehicleKinematicState::SharedPtr current_state_; + Odometry::SharedPtr current_odom_; }; -/** - * @brief Generate a VehicleControlCommand message - * @param [in] t timestamp - * @param [in] steer [rad] steering - * @param [in] vel [m/s] velocity - * @param [in] acc [m/s²] acceleration - */ -VehicleControlCommand cmdGen( - const builtin_interfaces::msg::Time & t, float32_t steer, float32_t vel, float32_t acc) -{ - VehicleControlCommand cmd; - cmd.stamp = t; - cmd.front_wheel_angle_rad = steer; - cmd.velocity_mps = vel; - cmd.long_accel_mps2 = acc; - return cmd; -} - /** * @brief Generate an AckermannControlCommand message * @param [in] t timestamp * @param [in] steer [rad] steering + * @param [in] steer_rate [rad/s] steering rotation rate * @param [in] vel [m/s] velocity * @param [in] acc [m/s²] acceleration + * @param [in] jerk [m/s3] jerk */ -AckermannControlCommand ackermannCmdGen( - const builtin_interfaces::msg::Time & t, float32_t steer, float32_t vel, float32_t acc) +AckermannControlCommand cmdGen( + const builtin_interfaces::msg::Time & t, float32_t steer, float32_t steer_rate, float32_t vel, + float32_t acc, float32_t jerk) { AckermannControlCommand cmd; cmd.stamp = t; cmd.lateral.stamp = t; cmd.lateral.steering_tire_angle = steer; + cmd.lateral.steering_tire_rotation_rate = steer_rate; cmd.longitudinal.stamp = t; cmd.longitudinal.speed = vel; cmd.longitudinal.acceleration = acc; + cmd.longitudinal.jerk = jerk; return cmd; } @@ -135,32 +99,13 @@ void resetInitialpose(rclcpp::Node::SharedPtr sim_node, std::shared_ptr pub_sub_node) + uint8_t gear, rclcpp::Node::SharedPtr sim_node, std::shared_ptr pub_sub_node) { GearCommand cmd; cmd.stamp = sim_node->now(); - cmd.gear = gear; + cmd.command = gear; for (int i = 0; i < 10; ++i) { - pub_sub_node->pub_state_cmd_->publish(cmd); - rclcpp::spin_some(sim_node); - rclcpp::spin_some(pub_sub_node); - std::this_thread::sleep_for(std::chrono::milliseconds{10LL}); - } -} - -/** - * @brief publish the given command message - * @param [in] cmd command to publish - * @param [in] sim_node pointer to the simulation node - * @param [in] pub_sub_node pointer to the node used for communication - */ -void sendCommand( - const VehicleControlCommand & cmd, rclcpp::Node::SharedPtr sim_node, - std::shared_ptr pub_sub_node) -{ - for (int i = 0; i < 150; ++i) { - pub_sub_node->pub_control_command_->publish(cmd); + pub_sub_node->pub_gear_cmd_->publish(cmd); rclcpp::spin_some(sim_node); rclcpp::spin_some(pub_sub_node); std::this_thread::sleep_for(std::chrono::milliseconds{10LL}); @@ -185,16 +130,6 @@ void sendCommand( } } -VehicleKinematicState comToBaselink(const VehicleKinematicState & com) -{ - auto baselink = com; - float64_t yaw = motion::motion_common::to_angle(com.state.pose.orientation); - baselink.state.pose.position.x -= COM_TO_BASELINK * std::cos(yaw); - baselink.state.pose.position.y -= COM_TO_BASELINK * std::sin(yaw); - return baselink; -} - - // Check which direction the vehicle is heading on the baselink coordinates. // y // | @@ -205,183 +140,137 @@ VehicleKinematicState comToBaselink(const VehicleKinematicState & com) // (Bwd-Right) | // | // -void isOnForward(const VehicleKinematicState & _state, const VehicleKinematicState & _init) +void isOnForward(const Odometry & state, const Odometry & init) { float64_t forward_thr = 1.0; - auto state = comToBaselink(_state); - auto init = comToBaselink(_init); - float64_t dx = state.state.pose.position.x - init.state.pose.position.x; + float64_t dx = state.pose.pose.position.x - init.pose.pose.position.x; EXPECT_GT(dx, forward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } -void isOnBackward(const VehicleKinematicState & _state, const VehicleKinematicState & _init) +void isOnBackward(const Odometry & state, const Odometry & init) { float64_t backward_thr = -1.0; - auto state = comToBaselink(_state); - auto init = comToBaselink(_init); - float64_t dx = state.state.pose.position.x - init.state.pose.position.x; + float64_t dx = state.pose.pose.position.x - init.pose.pose.position.x; EXPECT_LT(dx, backward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } -void isOnForwardLeft(const VehicleKinematicState & _state, const VehicleKinematicState & _init) +void isOnForwardLeft(const Odometry & state, const Odometry & init) { float64_t forward_thr = 1.0; float64_t left_thr = 0.1f; - auto state = comToBaselink(_state); - auto init = comToBaselink(_init); - float64_t dx = state.state.pose.position.x - init.state.pose.position.x; - float64_t dy = state.state.pose.position.y - init.state.pose.position.y; + float64_t dx = state.pose.pose.position.x - init.pose.pose.position.x; + float64_t dy = state.pose.pose.position.y - init.pose.pose.position.y; EXPECT_GT(dx, forward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); EXPECT_GT(dy, left_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } -void isOnBackwardRight(const VehicleKinematicState & _state, const VehicleKinematicState & _init) +void isOnBackwardRight(const Odometry & state, const Odometry & init) { float64_t backward_thr = -1.0; float64_t right_thr = -0.1; - auto state = comToBaselink(_state); - auto init = comToBaselink(_init); - float64_t dx = state.state.pose.position.x - init.state.pose.position.x; - float64_t dy = state.state.pose.position.y - init.state.pose.position.y; + float64_t dx = state.pose.pose.position.x - init.pose.pose.position.x; + float64_t dy = state.pose.pose.position.y - init.pose.pose.position.y; EXPECT_LT(dx, backward_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); EXPECT_LT(dy, right_thr) << "[curr] " << toStrInfo(state) << ", [init] " << toStrInfo(init); } -// Send a control command and run the simulation. -// Then check if the vehicle is moving in the desired direction. -TEST(TestSimplePlanningSimulatorIdealSteerVel, TestMoving) +void declareVehicleInfoParams(rclcpp::NodeOptions & node_options) { - rclcpp::init(0, nullptr); + node_options.append_parameter_override("wheel_radius", 0.5); + node_options.append_parameter_override("wheel_width", 0.2); + node_options.append_parameter_override("wheel_base", 3.0); + node_options.append_parameter_override("wheel_tread", 2.0); + node_options.append_parameter_override("front_overhang", 1.0); + node_options.append_parameter_override("rear_overhang", 1.0); + node_options.append_parameter_override("left_overhang", 0.5); + node_options.append_parameter_override("right_overhang", 0.5); + node_options.append_parameter_override("vehicle_height", 1.5); +} - for (const auto & vehicle_model_type : vehicle_model_type_vec) { - std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; - rclcpp::NodeOptions node_options; - node_options.append_parameter_override("initialize_source", "INITIAL_POSE_TOPIC"); - node_options.append_parameter_override("cg_to_rear_m", COM_TO_BASELINK); - node_options.append_parameter_override("vehicle_model_type", vehicle_model_type); - const auto sim_node = std::make_shared(node_options); - - const auto pub_sub_node = std::make_shared(); - - const float32_t target_vel = 5.0f; - const float32_t target_acc = 5.0f; - const float32_t target_steer = 0.2f; - - auto _resetInitialpose = [&]() {resetInitialpose(sim_node, pub_sub_node);}; - auto _sendFwdGear = [&]() {sendGear(GearCommand::DRIVE, sim_node, pub_sub_node);}; - auto _sendBwdGear = [&]() {sendGear(GearCommand::REVERSE, sim_node, pub_sub_node);}; - auto _sendCommand = [&](const auto & _cmd) { - sendCommand(_cmd, sim_node, pub_sub_node); - }; - - // check pub-sub connections - { - size_t expected = 1; - EXPECT_EQ(pub_sub_node->pub_control_command_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->pub_ackermann_command_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->pub_state_cmd_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->pub_initialpose_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->kinematic_state_sub_->get_publisher_count(), expected); - } - - // check initial pose - _resetInitialpose(); - const auto init_state = *(pub_sub_node->current_state_); - - // go forward - _resetInitialpose(); - _sendFwdGear(); - _sendCommand(cmdGen(sim_node->now(), 0.0f, target_vel, target_acc)); - isOnForward(*(pub_sub_node->current_state_), init_state); - - // go backward - _resetInitialpose(); - _sendBwdGear(); - _sendCommand(cmdGen(sim_node->now(), 0.0f, -target_vel, -target_acc)); - isOnBackward(*(pub_sub_node->current_state_), init_state); - - // go forward left - _resetInitialpose(); - _sendFwdGear(); - _sendCommand(cmdGen(sim_node->now(), target_steer, target_vel, target_acc)); - isOnForwardLeft(*(pub_sub_node->current_state_), init_state); - - // go backward right - _resetInitialpose(); - _sendBwdGear(); - _sendCommand(cmdGen(sim_node->now(), -target_steer, -target_vel, -target_acc)); - isOnBackwardRight(*(pub_sub_node->current_state_), init_state); - } - rclcpp::shutdown(); -} // Send a control command and run the simulation. // Then check if the vehicle is moving in the desired direction. -TEST(test_simple_planning_simulator, test_moving_ackermann) +class TestSimplePlanningSimulator : public ::testing::TestWithParam +{ +}; + +TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) { rclcpp::init(0, nullptr); - for (const auto & vehicle_model_type : vehicle_model_type_vec) { - std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; - rclcpp::NodeOptions node_options; - node_options.append_parameter_override("initialize_source", "INITIAL_POSE_TOPIC"); - node_options.append_parameter_override("cg_to_rear_m", COM_TO_BASELINK); - node_options.append_parameter_override("vehicle_model_type", vehicle_model_type); - const auto sim_node = std::make_shared(node_options); - - const auto pub_sub_node = std::make_shared(); - - const float32_t target_vel = 5.0f; - const float32_t target_acc = 5.0f; - const float32_t target_steer = 0.2f; - - auto _resetInitialpose = [&]() {resetInitialpose(sim_node, pub_sub_node);}; - auto _sendFwdGear = [&]() {sendGear(GearCommand::DRIVE, sim_node, pub_sub_node);}; - auto _sendBwdGear = - [&]() {sendGear(GearCommand::REVERSE, sim_node, pub_sub_node);}; - auto _sendCommand = [&](const auto & _cmd) { - sendCommand(_cmd, sim_node, pub_sub_node); - }; - - // check pub-sub connections - { - size_t expected = 1; - EXPECT_EQ(pub_sub_node->pub_control_command_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->pub_ackermann_command_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->pub_state_cmd_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->pub_initialpose_->get_subscription_count(), expected); - EXPECT_EQ(pub_sub_node->kinematic_state_sub_->get_publisher_count(), expected); - } - - // check initial pose - _resetInitialpose(); - const auto init_state = *(pub_sub_node->current_state_); - - // go forward - _resetInitialpose(); - _sendFwdGear(); - _sendCommand(ackermannCmdGen(sim_node->now(), 0.0f, target_vel, target_acc)); - isOnForward(*(pub_sub_node->current_state_), init_state); - - // go backward - _resetInitialpose(); - _sendBwdGear(); - _sendCommand(ackermannCmdGen(sim_node->now(), 0.0f, -target_vel, -target_acc)); - isOnBackward(*(pub_sub_node->current_state_), init_state); - - // go forward left - _resetInitialpose(); - _sendFwdGear(); - _sendCommand(ackermannCmdGen(sim_node->now(), target_steer, target_vel, target_acc)); - isOnForwardLeft(*(pub_sub_node->current_state_), init_state); - - // go backward right - _resetInitialpose(); - _sendBwdGear(); - _sendCommand(ackermannCmdGen(sim_node->now(), -target_steer, -target_vel, -target_acc)); - isOnBackwardRight(*(pub_sub_node->current_state_), init_state); + const auto vehicle_model_type = GetParam(); + + std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; + rclcpp::NodeOptions node_options; + node_options.append_parameter_override("initialize_source", "INITIAL_POSE_TOPIC"); + node_options.append_parameter_override("vehicle_model_type", vehicle_model_type); + node_options.append_parameter_override("initial_engage_state", true); + node_options.append_parameter_override("add_measurement_noise", false); + declareVehicleInfoParams(node_options); + const auto sim_node = std::make_shared(node_options); + + const auto pub_sub_node = std::make_shared(); + + const float32_t target_vel = 5.0f; + const float32_t target_acc = 5.0f; + const float32_t target_steer = 0.2f; + + auto _resetInitialpose = [&]() { resetInitialpose(sim_node, pub_sub_node); }; + auto _sendFwdGear = [&]() { sendGear(GearCommand::DRIVE, sim_node, pub_sub_node); }; + auto _sendBwdGear = [&]() { sendGear(GearCommand::REVERSE, sim_node, pub_sub_node); }; + auto _sendCommand = [&](const auto & _cmd) { sendCommand(_cmd, sim_node, pub_sub_node); }; + + // check pub-sub connections + { + size_t expected = 1; + EXPECT_EQ(pub_sub_node->pub_ackermann_command_->get_subscription_count(), expected); + EXPECT_EQ(pub_sub_node->pub_gear_cmd_->get_subscription_count(), expected); + EXPECT_EQ(pub_sub_node->pub_initialpose_->get_subscription_count(), expected); + EXPECT_EQ(pub_sub_node->current_odom_sub_->get_publisher_count(), expected); } + // check initial pose + _resetInitialpose(); + const auto init_state = *(pub_sub_node->current_odom_); + + // go forward + _resetInitialpose(); + _sendFwdGear(); + _sendCommand(cmdGen(sim_node->now(), 0.0f, 0.0f, target_vel, target_acc, 0.0f)); + isOnForward(*(pub_sub_node->current_odom_), init_state); + + // go backward + // NOTE: positive acceleration with reverse gear drives the vehicle backward. + _resetInitialpose(); + _sendBwdGear(); + _sendCommand(cmdGen(sim_node->now(), 0.0f, 0.0f, -target_vel, target_acc, 0.0f)); + isOnBackward(*(pub_sub_node->current_odom_), init_state); + + // go forward left + _resetInitialpose(); + _sendFwdGear(); + _sendCommand(cmdGen(sim_node->now(), target_steer, 0.0f, target_vel, target_acc, 0.0f)); + isOnForwardLeft(*(pub_sub_node->current_odom_), init_state); + + // go backward right + // NOTE: positive acceleration with reverse gear drives the vehicle backward. + _resetInitialpose(); + _sendBwdGear(); + _sendCommand(cmdGen(sim_node->now(), -target_steer, 0.0f, -target_vel, target_acc, 0.0f)); + isOnBackwardRight(*(pub_sub_node->current_odom_), init_state); + rclcpp::shutdown(); } + +const std::string VEHICLE_MODEL_LIST[] = { + "IDEAL_STEER_VEL", + "IDEAL_STEER_ACC", + "IDEAL_STEER_ACC_GEARED", + "DELAY_STEER_VEL", + "DELAY_STEER_ACC", + "DELAY_STEER_ACC_GEARED", +}; + +INSTANTIATE_TEST_CASE_P( + TestForEachVehicleModel, TestSimplePlanningSimulator, ::testing::ValuesIn(VEHICLE_MODEL_LIST)); From 7f2b646eead8439f6c6e8a0342b30b0b830db9ae Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Tue, 22 Feb 2022 17:05:40 +0900 Subject: [PATCH 27/37] refactor(behavior_velocity)!: unite spline interpolation (#411) * refactor(behavior_velocity)!: unite spline interpolation Signed-off-by: tanaka3 * chore(behavior_velocity): to namespace interpolation Signed-off-by: tanaka3 --- .../scene_module/intersection/util.hpp | 4 - .../include/utilization/interpolate.hpp | 10 ++- .../src/scene_module/blind_spot/scene.cpp | 2 +- .../intersection/scene_intersection.cpp | 1 + .../src/scene_module/intersection/util.cpp | 78 +---------------- .../scene_no_stopping_area.cpp | 79 +---------------- .../occlusion_spot/occlusion_spot_utils.cpp | 81 ----------------- .../scene_occlusion_spot_in_private_road.cpp | 3 +- .../scene_occlusion_spot_in_public_road.cpp | 3 +- .../src/utilization/interpolate.cpp | 86 +++++++++++++++++++ .../test/src/test_occlusion_spot_utils.cpp | 24 ------ 11 files changed, 104 insertions(+), 267 deletions(-) diff --git a/planning/behavior_velocity_planner/include/scene_module/intersection/util.hpp b/planning/behavior_velocity_planner/include/scene_module/intersection/util.hpp index 2610f2e7efe30..77342c1e6219a 100644 --- a/planning/behavior_velocity_planner/include/scene_module/intersection/util.hpp +++ b/planning/behavior_velocity_planner/include/scene_module/intersection/util.hpp @@ -33,10 +33,6 @@ namespace util bool setVelocityFrom( const size_t idx, const double vel, autoware_auto_planning_msgs::msg::PathWithLaneId * input); -bool splineInterpolate( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, - autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger); - int insertPoint( const geometry_msgs::msg::Pose & in_pose, autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path); diff --git a/planning/behavior_velocity_planner/include/utilization/interpolate.hpp b/planning/behavior_velocity_planner/include/utilization/interpolate.hpp index 63254de4f1168..ed61198b2180d 100644 --- a/planning/behavior_velocity_planner/include/utilization/interpolate.hpp +++ b/planning/behavior_velocity_planner/include/utilization/interpolate.hpp @@ -15,6 +15,11 @@ #ifndef UTILIZATION__INTERPOLATE_HPP_ #define UTILIZATION__INTERPOLATE_HPP_ +#include + +#include +#include + #include #include @@ -22,8 +27,9 @@ namespace behavior_velocity_planner { namespace interpolation { -// template -// bool splineInterpolateWithFixInterval(const T & input, const double interval, T * output); +bool splineInterpolate( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, + autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger); class LinearInterpolate { diff --git a/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp index d9580e0c617f5..dd9f48a4e76e2 100644 --- a/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp @@ -200,7 +200,7 @@ bool BlindSpotModule::generateStopLine( /* spline interpolation */ autoware_auto_planning_msgs::msg::PathWithLaneId path_ip; - if (!util::splineInterpolate(*path, interval, &path_ip, logger_)) { + if (!interpolation::splineInterpolate(*path, interval, &path_ip, logger_)) { return false; } debug_data_.spline_path = path_ip; diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp index fb9cb9071153c..576b769ec8a78 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp index 57023f4f26555..f9f68fb4bea7c 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp @@ -60,82 +60,6 @@ int insertPoint( return insert_idx; } -bool splineInterpolate( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, - autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger) -{ - *output = input; - - if (input.points.size() <= 1) { - RCLCPP_WARN(logger, "Do not interpolate because path size is 1."); - return false; - } - - static constexpr double ep = 1.0e-8; - - // calc arclength for path - std::vector base_x; - std::vector base_y; - std::vector base_z; - for (const auto & p : input.points) { - base_x.push_back(p.point.pose.position.x); - base_y.push_back(p.point.pose.position.y); - base_z.push_back(p.point.pose.position.z); - } - std::vector base_s = interpolation::calcEuclidDist(base_x, base_y); - - // remove duplicating sample points - { - size_t Ns = base_s.size(); - size_t i = 1; - while (i < Ns) { - if (std::fabs(base_s[i - 1] - base_s[i]) < ep) { - base_s.erase(base_s.begin() + i); - base_x.erase(base_x.begin() + i); - base_y.erase(base_y.begin() + i); - base_z.erase(base_z.begin() + i); - Ns -= 1; - i -= 1; - } - ++i; - } - } - - std::vector resampled_s; - for (double d = 0.0; d < base_s.back() - ep; d += interval) { - resampled_s.push_back(d); - } - - // do spline for xy - const std::vector resampled_x = ::interpolation::slerp(base_s, base_x, resampled_s); - const std::vector resampled_y = ::interpolation::slerp(base_s, base_y, resampled_s); - const std::vector resampled_z = ::interpolation::slerp(base_s, base_z, resampled_s); - - // set xy - output->points.clear(); - for (size_t i = 0; i < resampled_s.size(); i++) { - autoware_auto_planning_msgs::msg::PathPointWithLaneId p; - p.point.pose.position.x = resampled_x.at(i); - p.point.pose.position.y = resampled_y.at(i); - p.point.pose.position.z = resampled_z.at(i); - output->points.push_back(p); - } - - // set yaw - for (int i = 1; i < static_cast(resampled_s.size()) - 1; i++) { - auto p = output->points.at(i - 1).point.pose.position; - auto n = output->points.at(i + 1).point.pose.position; - double yaw = std::atan2(n.y - p.y, n.x - p.x); - output->points.at(i).point.pose.orientation = planning_utils::getQuaternionFromYaw(yaw); - } - if (output->points.size() > 1) { - size_t l = output->points.size(); - output->points.front().point.pose.orientation = output->points.at(1).point.pose.orientation; - output->points.back().point.pose.orientation = output->points.at(l - 2).point.pose.orientation; - } - return true; -} - geometry_msgs::msg::Pose getAheadPose( const size_t start_idx, const double ahead_dist, const autoware_auto_planning_msgs::msg::PathWithLaneId & path) @@ -261,7 +185,7 @@ bool generateStopLine( /* spline interpolation */ autoware_auto_planning_msgs::msg::PathWithLaneId path_ip; - if (!util::splineInterpolate(target_path, interval, &path_ip, logger)) { + if (!interpolation::splineInterpolate(target_path, interval, &path_ip, logger)) { return false; } diff --git a/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp index 2511b2eb8ac43..ae58fe1a0cbf3 100644 --- a/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp @@ -16,6 +16,7 @@ #include "utilization/arc_lane_util.hpp" #include "utilization/interpolate.hpp" +#include "utilization/path_utilization.hpp" #include "utilization/util.hpp" #include @@ -33,81 +34,6 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -bool splineInterpolate( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, - autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger) -{ - *output = input; - - if (input.points.size() <= 1) { - RCLCPP_DEBUG(logger, "Do not interpolate because path size is 1."); - return false; - } - - static constexpr double ep = 1.0e-8; - - // calc arclength for path - std::vector base_x; - std::vector base_y; - std::vector base_z; - for (const auto & p : input.points) { - base_x.push_back(p.point.pose.position.x); - base_y.push_back(p.point.pose.position.y); - base_z.push_back(p.point.pose.position.z); - } - std::vector base_s = interpolation::calcEuclidDist(base_x, base_y); - - // remove duplicating sample points - { - size_t Ns = base_s.size(); - size_t i = 1; - while (i < Ns) { - if (std::fabs(base_s[i - 1] - base_s[i]) < ep) { - base_s.erase(base_s.begin() + i); - base_x.erase(base_x.begin() + i); - base_y.erase(base_y.begin() + i); - base_z.erase(base_z.begin() + i); - Ns -= 1; - i -= 1; - } - ++i; - } - } - - std::vector resampled_s; - for (double d = 0.0; d < base_s.back() - ep; d += interval) { - resampled_s.push_back(d); - } - - // do spline for xy - const std::vector resampled_x = ::interpolation::slerp(base_s, base_x, resampled_s); - const std::vector resampled_y = ::interpolation::slerp(base_s, base_y, resampled_s); - const std::vector resampled_z = ::interpolation::slerp(base_s, base_z, resampled_s); - - // set xy - output->points.clear(); - for (size_t i = 0; i < resampled_s.size(); i++) { - autoware_auto_planning_msgs::msg::PathPointWithLaneId p; - p.point.pose.position.x = resampled_x.at(i); - p.point.pose.position.y = resampled_y.at(i); - p.point.pose.position.z = resampled_z.at(i); - output->points.push_back(p); - } - - // set yaw - for (int i = 1; i < static_cast(resampled_s.size()) - 1; i++) { - auto p = output->points.at(i - 1).point.pose.position; - auto n = output->points.at(i + 1).point.pose.position; - double yaw = std::atan2(n.y - p.y, n.x - p.x); - output->points.at(i).point.pose.orientation = planning_utils::getQuaternionFromYaw(yaw); - } - if (output->points.size() > 1) { - size_t l = output->points.size(); - output->points.front().point.pose.orientation = output->points.at(1).point.pose.orientation; - output->points.back().point.pose.orientation = output->points.at(l - 2).point.pose.orientation; - } - return true; -} NoStoppingAreaModule::NoStoppingAreaModule( const int64_t module_id, const lanelet::autoware::NoStoppingArea & no_stopping_area_reg_elem, @@ -341,7 +267,8 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( const double interpolation_interval = 0.5; bool is_in_area = false; autoware_auto_planning_msgs::msg::PathWithLaneId interpolated_path; - if (!splineInterpolate(path, interpolation_interval, &interpolated_path, logger_)) { + if (!interpolation::splineInterpolate( + path, interpolation_interval, &interpolated_path, logger_)) { return ego_area; } auto & pp = interpolated_path.points; diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp index 6b07021e50d5f..76c9db5b421ef 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp @@ -51,87 +51,6 @@ lanelet::ConstLanelet toPathLanelet(const PathWithLaneId & path) return lanelet::ConstLanelet(path_lanelet); } -bool splineInterpolate( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, - autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger) -{ - *output = input; - - if (input.points.size() <= 1) { - RCLCPP_DEBUG(logger, "Do not interpolate because path size is 1."); - return false; - } - - static constexpr double ep = 1.0e-8; - - // calc arclength for path - std::vector base_x; - std::vector base_y; - std::vector base_z; - std::vector base_v; - for (const auto & p : input.points) { - base_x.push_back(p.point.pose.position.x); - base_y.push_back(p.point.pose.position.y); - base_z.push_back(p.point.pose.position.z); - base_v.push_back(p.point.longitudinal_velocity_mps); - } - std::vector base_s = interpolation::calcEuclidDist(base_x, base_y); - - // remove duplicating sample points - { - size_t Ns = base_s.size(); - size_t i = 1; - while (i < Ns) { - if (std::fabs(base_s[i - 1] - base_s[i]) < ep) { - base_s.erase(base_s.begin() + i); - base_x.erase(base_x.begin() + i); - base_y.erase(base_y.begin() + i); - base_z.erase(base_z.begin() + i); - base_v.erase(base_v.begin() + i); - Ns -= 1; - i -= 1; - } - ++i; - } - } - - std::vector resampled_s; - for (double d = 0.0; d < base_s.back() - ep; d += interval) { - resampled_s.push_back(d); - } - - // do spline for xy - const std::vector resampled_x = ::interpolation::slerp(base_s, base_x, resampled_s); - const std::vector resampled_y = ::interpolation::slerp(base_s, base_y, resampled_s); - const std::vector resampled_z = ::interpolation::slerp(base_s, base_z, resampled_s); - const std::vector resampled_v = ::interpolation::slerp(base_s, base_v, resampled_s); - - // set xy - output->points.clear(); - for (size_t i = 0; i < resampled_s.size(); i++) { - PathPointWithLaneId p; - p.point.pose.position.x = resampled_x.at(i); - p.point.pose.position.y = resampled_y.at(i); - p.point.pose.position.z = resampled_z.at(i); - p.point.longitudinal_velocity_mps = resampled_v.at(i); - output->points.push_back(p); - } - - // set yaw - for (int i = 1; i < static_cast(resampled_s.size()) - 1; i++) { - auto p = output->points.at(i - 1).point.pose.position; - auto n = output->points.at(i + 1).point.pose.position; - double yaw = std::atan2(n.y - p.y, n.x - p.x); - output->points.at(i).point.pose.orientation = planning_utils::getQuaternionFromYaw(yaw); - } - if (output->points.size() > 1) { - size_t l = output->points.size(); - output->points.front().point.pose.orientation = output->points.at(1).point.pose.orientation; - output->points.back().point.pose.orientation = output->points.at(l - 2).point.pose.orientation; - } - return true; -} - ROAD_TYPE getCurrentRoadType( const lanelet::ConstLanelet & current_lanelet, [[maybe_unused]] const lanelet::LaneletMapPtr & lanelet_map_ptr) diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp index b8e7a3a9f77da..fe900e0d7b533 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -73,7 +74,7 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( utils::clipPathByLength(*path, clipped_path, max_range); PathWithLaneId interp_path; //! never change this interpolation interval(will affect module accuracy) - utils::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); + interpolation::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); debug_data_.interp_path = interp_path; int closest_idx = -1; if (!planning_utils::calcClosestIndex( diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp index 99aebf5ad60d8..d35bf1c68c456 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -72,7 +73,7 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( PathWithLaneId clipped_path; utils::clipPathByLength(*path, clipped_path, param_.detection_area_length); PathWithLaneId interp_path; - utils::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); + interpolation::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); int closest_idx = -1; if (!planning_utils::calcClosestIndex( interp_path, ego_pose, closest_idx, param_.dist_thr, param_.angle_thr)) { diff --git a/planning/behavior_velocity_planner/src/utilization/interpolate.cpp b/planning/behavior_velocity_planner/src/utilization/interpolate.cpp index c6b1932d2b41b..3753c110a6d80 100644 --- a/planning/behavior_velocity_planner/src/utilization/interpolate.cpp +++ b/planning/behavior_velocity_planner/src/utilization/interpolate.cpp @@ -12,15 +12,101 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include +#include +#include + #include namespace behavior_velocity_planner { namespace interpolation { +bool splineInterpolate( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, + autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger) +{ + *output = input; + + if (input.points.size() <= 1) { + RCLCPP_DEBUG(logger, "Do not interpolate because path size is 1."); + return false; + } + + static constexpr double ep = 1.0e-8; + + // calc arclength for path + std::vector base_x; + std::vector base_y; + std::vector base_z; + std::vector base_v; + for (const auto & p : input.points) { + base_x.push_back(p.point.pose.position.x); + base_y.push_back(p.point.pose.position.y); + base_z.push_back(p.point.pose.position.z); + base_v.push_back(p.point.longitudinal_velocity_mps); + } + std::vector base_s = interpolation::calcEuclidDist(base_x, base_y); + + // remove duplicating sample points + { + size_t Ns = base_s.size(); + size_t i = 1; + while (i < Ns) { + if (std::fabs(base_s[i - 1] - base_s[i]) < ep) { + base_s.erase(base_s.begin() + i); + base_x.erase(base_x.begin() + i); + base_y.erase(base_y.begin() + i); + base_z.erase(base_z.begin() + i); + base_v.erase(base_v.begin() + i); + Ns -= 1; + i -= 1; + } + ++i; + } + } + + std::vector resampled_s; + for (double d = 0.0; d < base_s.back() - ep; d += interval) { + resampled_s.push_back(d); + } + + // do spline for xy + const std::vector resampled_x = ::interpolation::slerp(base_s, base_x, resampled_s); + const std::vector resampled_y = ::interpolation::slerp(base_s, base_y, resampled_s); + const std::vector resampled_z = ::interpolation::slerp(base_s, base_z, resampled_s); + const std::vector resampled_v = ::interpolation::slerp(base_s, base_v, resampled_s); + + // set xy + output->points.clear(); + for (size_t i = 0; i < resampled_s.size(); i++) { + autoware_auto_planning_msgs::msg::PathPointWithLaneId p; + p.point.pose.position.x = resampled_x.at(i); + p.point.pose.position.y = resampled_y.at(i); + p.point.pose.position.z = resampled_z.at(i); + p.point.longitudinal_velocity_mps = resampled_v.at(i); + output->points.push_back(p); + } + + // set yaw + for (int i = 1; i < static_cast(resampled_s.size()) - 1; i++) { + auto p = output->points.at(i - 1).point.pose.position; + auto n = output->points.at(i + 1).point.pose.position; + double yaw = std::atan2(n.y - p.y, n.x - p.x); + output->points.at(i).point.pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(yaw); + } + if (output->points.size() > 1) { + size_t l = output->points.size(); + output->points.front().point.pose.orientation = output->points.at(1).point.pose.orientation; + output->points.back().point.pose.orientation = output->points.at(l - 2).point.pose.orientation; + } + return true; +} + // TODO(murooka) delete these functions /* * linear interpolation diff --git a/planning/behavior_velocity_planner/test/src/test_occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/test/src/test_occlusion_spot_utils.cpp index 004d192d90a3e..4540d534350d1 100644 --- a/planning/behavior_velocity_planner/test/src/test_occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/test/src/test_occlusion_spot_utils.cpp @@ -30,30 +30,6 @@ using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathPoint; using autoware_auto_planning_msgs::msg::PathWithLaneId; -autoware_auto_planning_msgs::msg::Path toPath( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path_with_id) -{ - autoware_auto_planning_msgs::msg::Path path; - for (const auto & p : path_with_id.points) { - path.points.push_back(p.point); - } - return path; -} - -TEST(spline, splineInterpolate) -{ - using std::chrono::duration; - using std::chrono::duration_cast; - using std::chrono::high_resolution_clock; - using std::chrono::microseconds; - autoware_auto_planning_msgs::msg::PathWithLaneId path = test::generatePath(0, 0.0, 6.0, 0.0, 7); - const auto path_interp = behavior_velocity_planner::interpolatePath(toPath(path), 100, 0.5); - for (const auto & p : path_interp.points) { - std::cout << "interp" << p.pose.position.x << std::endl; - } - ASSERT_EQ(path_interp.points.size(), path.points.size() * 2 - +1); -} - TEST(calcSlowDownPointsForPossibleCollision, TooManyPossibleCollisions) { using behavior_velocity_planner::occlusion_spot_utils::calcSlowDownPointsForPossibleCollision; From 5839f6bbc989382c951129e353a2355253c09497 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 22 Feb 2022 18:59:21 +0900 Subject: [PATCH 28/37] chore: remove unnecessary comments for uncrustify (#431) Signed-off-by: Kenji Miyake --- ...el_based_approximate_compare_map_filter_nodelet.cpp | 6 ++---- .../occupancy_grid_map_outlier_filter_nodelet.hpp | 5 +---- .../motion_velocity_smoother_node.hpp | 9 +++------ .../analytical_jerk_constrained_smoother.hpp | 9 ++------- .../velocity_planning_utils.hpp | 2 -- .../analytical_jerk_constrained_smoother.cpp | 10 ++-------- .../velocity_planning_utils.cpp | 6 ++---- .../occupancy_grid_map_binary_bayes_filter_updater.hpp | 2 -- 8 files changed, 12 insertions(+), 37 deletions(-) diff --git a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp index 77e5d649d3478..78bdf191f3d8a 100644 --- a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp @@ -12,16 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include - -// *INDENT-OFF* #include "compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp" -// *INDENT-ON* #include #include #include +#include + namespace compare_map_segmentation { using pointcloud_preprocessor::get_param; diff --git a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp index 52e3f22344e8b..4ae0fde705e18 100644 --- a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp +++ b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp @@ -81,16 +81,13 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node private: class Debugger { - // *INDENT-OFF* public: - // *INDENT-ON* explicit Debugger(OccupancyGridMapOutlierFilterComponent & node); void publishOutlier(const PclPointCloud & input, const Header & header); void publishHighConfidence(const PclPointCloud & input, const Header & header); void publishLowConfidence(const PclPointCloud & input, const Header & header); - // *INDENT-OFF* + private: - // *INDENT-ON* void transformToBaseLink( const PclPointCloud & input, const Header & header, PointCloud2 & output); rclcpp::Publisher::SharedPtr outlier_pointcloud_pub_; diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp index 8191ce9d4ac59..7c8c3f660bf07 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/motion_velocity_smoother_node.hpp @@ -16,9 +16,12 @@ #define MOTION_VELOCITY_SMOOTHER__MOTION_VELOCITY_SMOOTHER_NODE_HPP_ #include "motion_velocity_smoother/resample.hpp" +#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" #include "motion_velocity_smoother/smoother/jerk_filtered_smoother.hpp" #include "motion_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp" #include "motion_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp" +#include "motion_velocity_smoother/smoother/smoother_base.hpp" +#include "motion_velocity_smoother/trajectory_utils.hpp" #include "osqp_interface/osqp_interface.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/utils.h" @@ -43,12 +46,6 @@ #include #include -// *INDENT-OFF* -#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" -// *INDENT-ON* -#include "motion_velocity_smoother/smoother/smoother_base.hpp" -#include "motion_velocity_smoother/trajectory_utils.hpp" - namespace motion_velocity_smoother { using autoware_auto_planning_msgs::msg::Trajectory; diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp index a8e6c20ca6276..a02d0508ac977 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -// *INDENT-OFF* #ifndef MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT #define MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT -// *INDENT-ON* +#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp" +#include "motion_velocity_smoother/smoother/smoother_base.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/utils.h" #include "tier4_autoware_utils/trajectory/trajectory.hpp" @@ -28,11 +28,6 @@ #include #include -// *INDENT-OFF* -#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp" -// *INDENT-ON* -#include "motion_velocity_smoother/smoother/smoother_base.hpp" - namespace motion_velocity_smoother { class AnalyticalJerkConstrainedSmoother : public SmootherBase diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp index 4875fac23e18d..3f1aea85d94df 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp @@ -12,10 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -// *INDENT-OFF* #ifndef MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__VELOCITY_PLANNING_UTILS_HPP_ // NOLINT #define MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__VELOCITY_PLANNING_UTILS_HPP_ // NOLINT -// *INDENT-ON* #include "motion_velocity_smoother/linear_interpolation.hpp" #include "rclcpp/rclcpp.hpp" diff --git a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp index 31792e1322f45..5c49a88986b39 100644 --- a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp +++ b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp @@ -12,16 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" + #include #include #include #include #include -// *INDENT-OFF* -#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp" -// *INDENT-ON* - namespace { using TrajectoryPoints = std::vector; @@ -544,14 +542,12 @@ bool AnalyticalJerkConstrainedSmoother::calcEnoughDistForDecel( const double a0 = trajectory.at(start_index).acceleration_mps2; const double jerk_acc = std::abs(planning_jerk); const double jerk_dec = planning_jerk; - // *INDENT-OFF* auto calcMinAcc = [¶ms](const double planning_jerk) { if (planning_jerk < params.backward.min_jerk_mild_stop) { return params.backward.min_acc; } return params.backward.min_acc_mild_stop; }; - // *INDENT-ON* const double min_acc = calcMinAcc(planning_jerk); type = 0; times.clear(); @@ -589,14 +585,12 @@ bool AnalyticalJerkConstrainedSmoother::applyDecelVelocityFilter( const double a0 = output_trajectory.at(decel_start_index).acceleration_mps2; const double jerk_acc = std::abs(planning_jerk); const double jerk_dec = planning_jerk; - // *INDENT-OFF* auto calcMinAcc = [¶ms](const double planning_jerk) { if (planning_jerk < params.backward.min_jerk_mild_stop) { return params.backward.min_acc; } return params.backward.min_acc_mild_stop; }; - // *INDENT-ON* const double min_acc = calcMinAcc(planning_jerk); if (!analytical_velocity_planning_utils::calcStopVelocityWithConstantJerkAccLimit( diff --git a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp index 8fabcb13be0f3..9a55dbe673f63 100644 --- a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp +++ b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp @@ -12,13 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp" + #include #include -// *INDENT-OFF* -#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp" -// *INDENT-ON* - namespace motion_velocity_smoother { namespace analytical_velocity_planning_utils diff --git a/sensing/laserscan_to_occupancy_grid_map/include/laserscan_to_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp b/sensing/laserscan_to_occupancy_grid_map/include/laserscan_to_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp index 2e351df7b6a78..91610a70ae869 100644 --- a/sensing/laserscan_to_occupancy_grid_map/include/laserscan_to_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp +++ b/sensing/laserscan_to_occupancy_grid_map/include/laserscan_to_occupancy_grid_map/updater/occupancy_grid_map_binary_bayes_filter_updater.hpp @@ -12,10 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -// *INDENT-OFF* #ifndef LASERSCAN_TO_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ #define LASERSCAN_TO_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_ -// *INDENT-ON* #include "laserscan_to_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp" From a8d03527270f1a26f61510a4716b5a8fd3f854cb Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 22 Feb 2022 21:13:45 +0900 Subject: [PATCH 29/37] feat(detection_by_tracker, shape_estimation): modify reference yaw to add search range (#428) * modify ref yaw to add search range in shape estimation * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/detection_by_tracker_core.cpp | 24 +++++-- .../corrector/bus_corrector.hpp | 3 +- .../corrector/car_corrector.hpp | 3 +- .../corrector/corrector_interface.hpp | 3 +- .../corrector/no_corrector.hpp | 3 +- .../corrector/truck_corrector.hpp | 3 +- .../shape_estimation/model/bounding_box.hpp | 5 +- .../shape_estimation/shape_estimator.hpp | 21 ++++-- .../lib/corrector/bus_corrector.cpp | 6 +- .../lib/corrector/car_corrector.cpp | 6 +- .../lib/corrector/truck_corrector.cpp | 6 +- .../shape_estimation/lib/corrector/utils.cpp | 72 +++++++++---------- .../lib/model/bounding_box.cpp | 14 ++-- .../shape_estimation/lib/shape_estimator.cpp | 30 ++++---- perception/shape_estimation/src/node.cpp | 9 ++- 15 files changed, 113 insertions(+), 95 deletions(-) diff --git a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp index 390734e93cedd..25227c7a0fa08 100644 --- a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp +++ b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp @@ -26,6 +26,7 @@ #include #include +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; namespace { std::optional getTransform( @@ -119,6 +120,16 @@ autoware_auto_perception_msgs::msg::DetectedObjects toDetectedObjects( return out_objects; } +boost::optional getReferenceYawInfo(const uint8_t label, const float yaw) +{ + const bool is_vehicle = + Label::CAR == label || Label::TRUCK == label || Label::BUS == label || Label::TRAILER == label; + if (is_vehicle) { + return ReferenceYawInfo{yaw, tier4_autoware_utils::deg2rad(30)}; + } else { + return boost::none; + } +} } // namespace void TrackerHandler::onTrackedObjects( @@ -321,6 +332,8 @@ float DetectionByTracker::optimizeUnderSegmentedObject( constexpr float initial_voxel_size = initial_cluster_range / 2.0f; float voxel_size = initial_voxel_size; + const auto & label = target_object.classification.front().label; + // initialize clustering parameters euclidean_cluster::VoxelGridBasedEuclideanCluster cluster( false, 4, 10000, initial_cluster_range, initial_voxel_size, 0); @@ -346,8 +359,9 @@ float DetectionByTracker::optimizeUnderSegmentedObject( highest_iou_object_in_current_iter.object.classification = target_object.classification; for (const auto & divided_cluster : divided_clusters) { bool is_shape_estimated = shape_estimator_->estimateShapeAndPose( - target_object.classification.front().label, divided_cluster, - tf2::getYaw(target_object.kinematics.pose_with_covariance.pose.orientation), + label, divided_cluster, + getReferenceYawInfo( + label, tf2::getYaw(target_object.kinematics.pose_with_covariance.pose.orientation)), highest_iou_object_in_current_iter.object.shape, highest_iou_object_in_current_iter.object.kinematics.pose_with_covariance.pose); if (!is_shape_estimated) { @@ -391,6 +405,7 @@ void DetectionByTracker::mergeOverSegmentedObjects( out_no_found_tracked_objects.header = tracked_objects.header; for (const auto & tracked_object : tracked_objects.objects) { + const auto & label = tracked_object.classification.front().label; // extend shape autoware_auto_perception_msgs::msg::DetectedObject extended_tracked_object = tracked_object; extended_tracked_object.shape = extendShape(tracked_object.shape, /*scale*/ 1.1); @@ -426,8 +441,9 @@ void DetectionByTracker::mergeOverSegmentedObjects( feature_object.object.classification = tracked_object.classification; bool is_shape_estimated = shape_estimator_->estimateShapeAndPose( - tracked_object.classification.front().label, pcl_merged_cluster, - tf2::getYaw(tracked_object.kinematics.pose_with_covariance.pose.orientation), + label, pcl_merged_cluster, + getReferenceYawInfo( + label, tf2::getYaw(tracked_object.kinematics.pose_with_covariance.pose.orientation)), feature_object.object.shape, feature_object.object.kinematics.pose_with_covariance.pose); if (!is_shape_estimated) { out_no_found_tracked_objects.objects.push_back(tracked_object); diff --git a/perception/shape_estimation/include/shape_estimation/corrector/bus_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/bus_corrector.hpp index 2c9fc7cd05c6a..a4d3654056211 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/bus_corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/bus_corrector.hpp @@ -38,8 +38,7 @@ class BusCorrector : public ShapeEstimationCorrectorInterface ~BusCorrector() = default; bool correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) override; + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override; }; #endif // SHAPE_ESTIMATION__CORRECTOR__BUS_CORRECTOR_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp index d8ec6dcba8a0c..566887b7860ef 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/car_corrector.hpp @@ -38,8 +38,7 @@ class CarCorrector : public ShapeEstimationCorrectorInterface ~CarCorrector() = default; bool correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) override; + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override; }; #endif // SHAPE_ESTIMATION__CORRECTOR__CAR_CORRECTOR_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/corrector/corrector_interface.hpp b/perception/shape_estimation/include/shape_estimation/corrector/corrector_interface.hpp index 3c3651a73b870..301db132e3e2e 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/corrector_interface.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/corrector_interface.hpp @@ -28,8 +28,7 @@ class ShapeEstimationCorrectorInterface virtual ~ShapeEstimationCorrectorInterface() {} virtual bool correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) = 0; + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) = 0; }; #endif // SHAPE_ESTIMATION__CORRECTOR__CORRECTOR_INTERFACE_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/corrector/no_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/no_corrector.hpp index e68da9fba2f68..faea19e4168bd 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/no_corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/no_corrector.hpp @@ -26,8 +26,7 @@ class NoCorrector : public ShapeEstimationCorrectorInterface ~NoCorrector() {} bool correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) override; + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override; }; #endif // SHAPE_ESTIMATION__CORRECTOR__NO_CORRECTOR_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp index 3ecf0e7272560..1f05d1ece29c4 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/truck_corrector.hpp @@ -38,8 +38,7 @@ class TruckCorrector : public ShapeEstimationCorrectorInterface ~TruckCorrector() = default; bool correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) override; + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) override; }; #endif // SHAPE_ESTIMATION__CORRECTOR__TRUCK_CORRECTOR_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/model/bounding_box.hpp b/perception/shape_estimation/include/shape_estimation/model/bounding_box.hpp index a4a3c8ce32677..255cf64176b12 100644 --- a/perception/shape_estimation/include/shape_estimation/model/bounding_box.hpp +++ b/perception/shape_estimation/include/shape_estimation/model/bounding_box.hpp @@ -16,6 +16,7 @@ #define SHAPE_ESTIMATION__MODEL__BOUNDING_BOX_HPP_ #include "shape_estimation/model/model_interface.hpp" +#include "shape_estimation/shape_estimator.hpp" #include @@ -30,8 +31,8 @@ class BoundingBoxShapeModel : public ShapeEstimationModelInterface public: BoundingBoxShapeModel(); - explicit BoundingBoxShapeModel(const boost::optional & reference_yaw); - boost::optional reference_yaw_; + explicit BoundingBoxShapeModel(const boost::optional & ref_yaw_info); + boost::optional ref_yaw_info_; ~BoundingBoxShapeModel() {} diff --git a/perception/shape_estimation/include/shape_estimation/shape_estimator.hpp b/perception/shape_estimation/include/shape_estimation/shape_estimator.hpp index 73e3c602fd251..af43c02f7bedd 100644 --- a/perception/shape_estimation/include/shape_estimation/shape_estimator.hpp +++ b/perception/shape_estimation/include/shape_estimation/shape_estimator.hpp @@ -27,20 +27,26 @@ #include +struct ReferenceYawInfo +{ + float yaw; + float search_angle_range; +}; + class ShapeEstimator { private: - bool estimateShape( + bool estimateOriginalShapeAndPose( const uint8_t label, const pcl::PointCloud & cluster, - const boost::optional & yaw, autoware_auto_perception_msgs::msg::Shape & shape_output, + const boost::optional & ref_yaw_info, + autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output); bool applyFilter( - const uint8_t label, const autoware_auto_perception_msgs::msg::Shape & shape_output, - const geometry_msgs::msg::Pose & pose_output); + const uint8_t label, const autoware_auto_perception_msgs::msg::Shape & shape, + const geometry_msgs::msg::Pose & pose); bool applyCorrector( const uint8_t label, const bool use_reference_yaw, - autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output); + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose); bool use_corrector_; bool use_filter_; @@ -52,7 +58,8 @@ class ShapeEstimator virtual bool estimateShapeAndPose( const uint8_t label, const pcl::PointCloud & cluster, - const boost::optional & yaw, autoware_auto_perception_msgs::msg::Shape & shape_output, + const boost::optional & ref_yaw_info, + autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output); }; diff --git a/perception/shape_estimation/lib/corrector/bus_corrector.cpp b/perception/shape_estimation/lib/corrector/bus_corrector.cpp index 9a031efbf6f5e..5a1e7833d5723 100644 --- a/perception/shape_estimation/lib/corrector/bus_corrector.cpp +++ b/perception/shape_estimation/lib/corrector/bus_corrector.cpp @@ -15,10 +15,10 @@ #include "shape_estimation/corrector/bus_corrector.hpp" bool BusCorrector::correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) { if (use_reference_yaw_) { - return correctVehicleBoundingBoxWithReferenceYaw(params_, shape_output, pose_output); + return correctVehicleBoundingBoxWithReferenceYaw(params_, shape, pose); } - return correctVehicleBoundingBox(params_, shape_output, pose_output); + return correctVehicleBoundingBox(params_, shape, pose); } diff --git a/perception/shape_estimation/lib/corrector/car_corrector.cpp b/perception/shape_estimation/lib/corrector/car_corrector.cpp index 3fd8776cb298d..b2500529d339d 100644 --- a/perception/shape_estimation/lib/corrector/car_corrector.cpp +++ b/perception/shape_estimation/lib/corrector/car_corrector.cpp @@ -15,10 +15,10 @@ #include "shape_estimation/corrector/car_corrector.hpp" bool CarCorrector::correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) { if (use_reference_yaw_) { - return correctVehicleBoundingBoxWithReferenceYaw(params_, shape_output, pose_output); + return correctVehicleBoundingBoxWithReferenceYaw(params_, shape, pose); } - return correctVehicleBoundingBox(params_, shape_output, pose_output); + return correctVehicleBoundingBox(params_, shape, pose); } diff --git a/perception/shape_estimation/lib/corrector/truck_corrector.cpp b/perception/shape_estimation/lib/corrector/truck_corrector.cpp index 3bb3b42a50833..17f911eec8012 100644 --- a/perception/shape_estimation/lib/corrector/truck_corrector.cpp +++ b/perception/shape_estimation/lib/corrector/truck_corrector.cpp @@ -15,10 +15,10 @@ #include "shape_estimation/corrector/truck_corrector.hpp" bool TruckCorrector::correct( - autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) { if (use_reference_yaw_) { - return correctVehicleBoundingBoxWithReferenceYaw(params_, shape_output, pose_output); + return correctVehicleBoundingBoxWithReferenceYaw(params_, shape, pose); } - return correctVehicleBoundingBox(params_, shape_output, pose_output); + return correctVehicleBoundingBox(params_, shape, pose); } diff --git a/perception/shape_estimation/lib/corrector/utils.cpp b/perception/shape_estimation/lib/corrector/utils.cpp index 8829ccb9cf9a8..82ce5e1b587b9 100644 --- a/perception/shape_estimation/lib/corrector/utils.cpp +++ b/perception/shape_estimation/lib/corrector/utils.cpp @@ -30,14 +30,14 @@ namespace utils { bool correctVehicleBoundingBox( - const CorrectionParameters & param, autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) + const CorrectionParameters & param, autoware_auto_perception_msgs::msg::Shape & shape, + geometry_msgs::msg::Pose & pose) { // TODO(Yukihiro Saito): refactor following code Eigen::Translation trans = - Eigen::Translation(pose_output.position.x, pose_output.position.y); - Eigen::Rotation2Dd rotate(tf2::getYaw(pose_output.orientation)); + Eigen::Translation(pose.position.x, pose.position.y); + Eigen::Rotation2Dd rotate(tf2::getYaw(pose.orientation)); Eigen::Affine2d affine_mat; affine_mat = trans * rotate.toRotationMatrix(); @@ -52,10 +52,10 @@ bool correctVehicleBoundingBox( * | */ std::vector v_point; - v_point.push_back(Eigen::Vector2d(shape_output.dimensions.x / 2.0, 0.0)); - v_point.push_back(Eigen::Vector2d(0.0, shape_output.dimensions.y / 2.0)); - v_point.push_back(Eigen::Vector2d(-shape_output.dimensions.x / 2.0, 0.0)); - v_point.push_back(Eigen::Vector2d(0.0, -shape_output.dimensions.y / 2.0)); + v_point.push_back(Eigen::Vector2d(shape.dimensions.x / 2.0, 0.0)); + v_point.push_back(Eigen::Vector2d(0.0, shape.dimensions.y / 2.0)); + v_point.push_back(Eigen::Vector2d(-shape.dimensions.x / 2.0, 0.0)); + v_point.push_back(Eigen::Vector2d(0.0, -shape.dimensions.y / 2.0)); // most distant index from base link size_t first_most_distant_index = 0; @@ -223,27 +223,27 @@ bool correctVehicleBoundingBox( return false; } - shape_output.dimensions.x += std::abs(correction_vector.x()) * 2.0; - shape_output.dimensions.y += std::abs(correction_vector.y()) * 2.0; - pose_output.position.x += (rotate.toRotationMatrix() * correction_vector).x(); - pose_output.position.y += (rotate.toRotationMatrix() * correction_vector).y(); + shape.dimensions.x += std::abs(correction_vector.x()) * 2.0; + shape.dimensions.y += std::abs(correction_vector.y()) * 2.0; + pose.position.x += (rotate.toRotationMatrix() * correction_vector).x(); + pose.position.y += (rotate.toRotationMatrix() * correction_vector).y(); // correct to set long length is x, short length is y - if (shape_output.dimensions.x < shape_output.dimensions.y) { - geometry_msgs::msg::Vector3 rpy = tier4_autoware_utils::getRPY(pose_output.orientation); + if (shape.dimensions.x < shape.dimensions.y) { + geometry_msgs::msg::Vector3 rpy = tier4_autoware_utils::getRPY(pose.orientation); rpy.z = rpy.z + M_PI_2; - pose_output.orientation = tier4_autoware_utils::createQuaternionFromRPY(rpy.x, rpy.y, rpy.z); - double temp = shape_output.dimensions.x; - shape_output.dimensions.x = shape_output.dimensions.y; - shape_output.dimensions.y = temp; + pose.orientation = tier4_autoware_utils::createQuaternionFromRPY(rpy.x, rpy.y, rpy.z); + double temp = shape.dimensions.x; + shape.dimensions.x = shape.dimensions.y; + shape.dimensions.y = temp; } return true; } bool correctVehicleBoundingBoxWithReferenceYaw( - const CorrectionParameters & param, autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) + const CorrectionParameters & param, autoware_auto_perception_msgs::msg::Shape & shape, + geometry_msgs::msg::Pose & pose) { /* c1 is nearest point and other points are arranged like below @@ -259,21 +259,18 @@ bool correctVehicleBoundingBoxWithReferenceYaw( Eigen::Vector3d c1, c2, c3, c4; Eigen::Affine3d base2obj_transform; - tf2::fromMsg(pose_output, base2obj_transform); + tf2::fromMsg(pose, base2obj_transform); std::vector v_point; v_point.push_back( - base2obj_transform * - Eigen::Vector3d(shape_output.dimensions.x * 0.5, shape_output.dimensions.y * 0.5, 0.0)); + base2obj_transform * Eigen::Vector3d(shape.dimensions.x * 0.5, shape.dimensions.y * 0.5, 0.0)); v_point.push_back( - base2obj_transform * - Eigen::Vector3d(-shape_output.dimensions.x * 0.5, shape_output.dimensions.y * 0.5, 0.0)); + base2obj_transform * Eigen::Vector3d(-shape.dimensions.x * 0.5, shape.dimensions.y * 0.5, 0.0)); v_point.push_back( - base2obj_transform * - Eigen::Vector3d(shape_output.dimensions.x * 0.5, -shape_output.dimensions.y * 0.5, 0.0)); + base2obj_transform * Eigen::Vector3d(shape.dimensions.x * 0.5, -shape.dimensions.y * 0.5, 0.0)); v_point.push_back( base2obj_transform * - Eigen::Vector3d(-shape_output.dimensions.x * 0.5, -shape_output.dimensions.y * 0.5, 0.0)); + Eigen::Vector3d(-shape.dimensions.x * 0.5, -shape.dimensions.y * 0.5, 0.0)); double distance = std::pow(24, 24); size_t nearest_idx = 0; @@ -295,15 +292,14 @@ bool correctVehicleBoundingBoxWithReferenceYaw( Eigen::Vector3d e1 = (Eigen::Vector3d(0, -ey, 0) - local_c1).normalized(); Eigen::Vector3d e2 = (Eigen::Vector3d(-ex, 0, 0) - local_c1).normalized(); double length = 0; - if ( - param.min_length < shape_output.dimensions.x && shape_output.dimensions.x < param.max_length) { - length = shape_output.dimensions.x; + if (param.min_length < shape.dimensions.x && shape.dimensions.x < param.max_length) { + length = shape.dimensions.x; } else { length = param.avg_length; } double width = 0; - if (param.min_width < shape_output.dimensions.y && shape_output.dimensions.y < param.max_width) { - width = shape_output.dimensions.y; + if (param.min_width < shape.dimensions.y && shape.dimensions.y < param.max_width) { + width = shape.dimensions.y; } else { width = param.avg_width; } @@ -312,12 +308,12 @@ bool correctVehicleBoundingBoxWithReferenceYaw( c3 = c1 + base2obj_transform.rotation() * (e2 * width); c4 = c1 + (c2 - c1) + (c3 - c1); - shape_output.dimensions.x = (c2 - c1).norm(); - shape_output.dimensions.y = (c3 - c1).norm(); + shape.dimensions.x = (c2 - c1).norm(); + shape.dimensions.y = (c3 - c1).norm(); Eigen::Vector3d new_centroid = c1 + ((c4 - c1) * 0.5); - pose_output.position.x = new_centroid.x(); - pose_output.position.y = new_centroid.y(); - pose_output.position.z = new_centroid.z(); + pose.position.x = new_centroid.x(); + pose.position.y = new_centroid.y(); + pose.position.z = new_centroid.z(); return true; } diff --git a/perception/shape_estimation/lib/model/bounding_box.cpp b/perception/shape_estimation/lib/model/bounding_box.cpp index c8f6344748bc9..71f9a8d48b7d6 100644 --- a/perception/shape_estimation/lib/model/bounding_box.cpp +++ b/perception/shape_estimation/lib/model/bounding_box.cpp @@ -37,10 +37,10 @@ constexpr float epsilon = 0.001; -BoundingBoxShapeModel::BoundingBoxShapeModel() : reference_yaw_(boost::none) {} +BoundingBoxShapeModel::BoundingBoxShapeModel() : ref_yaw_info_(boost::none) {} -BoundingBoxShapeModel::BoundingBoxShapeModel(const boost::optional & reference_yaw) -: reference_yaw_(reference_yaw) +BoundingBoxShapeModel::BoundingBoxShapeModel(const boost::optional & ref_yaw_info) +: ref_yaw_info_(ref_yaw_info) { } @@ -49,12 +49,12 @@ bool BoundingBoxShapeModel::estimate( autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) { float min_angle, max_angle; - if (reference_yaw_) { - min_angle = reference_yaw_.get() - tier4_autoware_utils::deg2rad(3); - max_angle = reference_yaw_.get() + tier4_autoware_utils::deg2rad(3); + if (ref_yaw_info_) { + min_angle = ref_yaw_info_.get().yaw - ref_yaw_info_.get().search_angle_range; + max_angle = ref_yaw_info_.get().yaw + ref_yaw_info_.get().search_angle_range; } else { min_angle = 0.0; - max_angle = M_PI / 2.0; + max_angle = M_PI * 0.5; } return fitLShape(cluster, min_angle, max_angle, shape_output, pose_output); } diff --git a/perception/shape_estimation/lib/shape_estimator.cpp b/perception/shape_estimation/lib/shape_estimator.cpp index 3fe342603755d..5e337a3790ca4 100644 --- a/perception/shape_estimation/lib/shape_estimator.cpp +++ b/perception/shape_estimation/lib/shape_estimator.cpp @@ -30,13 +30,13 @@ ShapeEstimator::ShapeEstimator(bool use_corrector, bool use_filter) bool ShapeEstimator::estimateShapeAndPose( const uint8_t label, const pcl::PointCloud & cluster, - const boost::optional & yaw, autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) + const boost::optional & ref_yaw_info, + autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) { autoware_auto_perception_msgs::msg::Shape shape; geometry_msgs::msg::Pose pose; // estimate shape - if (!estimateShape(label, cluster, yaw, shape, pose)) { + if (!estimateOriginalShapeAndPose(label, cluster, ref_yaw_info, shape, pose)) { return false; } @@ -49,7 +49,7 @@ bool ShapeEstimator::estimateShapeAndPose( // rule based corrector if (use_corrector_) { - bool use_reference_yaw = yaw ? true : false; + bool use_reference_yaw = ref_yaw_info ? true : false; if (!applyCorrector(label, use_reference_yaw, shape, pose)) { return false; } @@ -60,23 +60,23 @@ bool ShapeEstimator::estimateShapeAndPose( return true; } -bool ShapeEstimator::estimateShape( +bool ShapeEstimator::estimateOriginalShapeAndPose( const uint8_t label, const pcl::PointCloud & cluster, - const boost::optional & yaw, autoware_auto_perception_msgs::msg::Shape & shape_output, - geometry_msgs::msg::Pose & pose_output) + const boost::optional & ref_yaw_info, + autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) { // estimate shape std::unique_ptr model_ptr; if ( label == Label::CAR || label == Label::TRUCK || label == Label::BUS || label == Label::TRAILER) { - model_ptr.reset(new BoundingBoxShapeModel(yaw)); + model_ptr.reset(new BoundingBoxShapeModel(ref_yaw_info)); } else if (label == Label::PEDESTRIAN) { model_ptr.reset(new CylinderShapeModel()); } else if (label == Label::MOTORCYCLE) { - model_ptr.reset(new BoundingBoxShapeModel(yaw)); + model_ptr.reset(new BoundingBoxShapeModel(ref_yaw_info)); } else if (label == Label::BICYCLE) { - model_ptr.reset(new BoundingBoxShapeModel(yaw)); + model_ptr.reset(new BoundingBoxShapeModel(ref_yaw_info)); } else { model_ptr.reset(new ConvexHullShapeModel()); } @@ -85,8 +85,8 @@ bool ShapeEstimator::estimateShape( } bool ShapeEstimator::applyFilter( - const uint8_t label, const autoware_auto_perception_msgs::msg::Shape & shape_output, - const geometry_msgs::msg::Pose & pose_output) + const uint8_t label, const autoware_auto_perception_msgs::msg::Shape & shape, + const geometry_msgs::msg::Pose & pose) { std::unique_ptr filter_ptr; if (label == Label::CAR) { @@ -99,12 +99,12 @@ bool ShapeEstimator::applyFilter( filter_ptr.reset(new NoFilter); } - return filter_ptr->filter(shape_output, pose_output); + return filter_ptr->filter(shape, pose); } bool ShapeEstimator::applyCorrector( const uint8_t label, const bool use_reference_yaw, - autoware_auto_perception_msgs::msg::Shape & shape_output, geometry_msgs::msg::Pose & pose_output) + autoware_auto_perception_msgs::msg::Shape & shape, geometry_msgs::msg::Pose & pose) { std::unique_ptr corrector_ptr; if (label == Label::CAR) { @@ -117,5 +117,5 @@ bool ShapeEstimator::applyCorrector( corrector_ptr.reset(new NoCorrector); } - return corrector_ptr->correct(shape_output, pose_output); + return corrector_ptr->correct(shape, pose); } diff --git a/perception/shape_estimation/src/node.cpp b/perception/shape_estimation/src/node.cpp index b83c1c012ca45..c2db0b532333f 100644 --- a/perception/shape_estimation/src/node.cpp +++ b/perception/shape_estimation/src/node.cpp @@ -15,6 +15,7 @@ #include "shape_estimation/shape_estimator.hpp" #include +#include #include @@ -72,12 +73,14 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared // estimate shape and pose autoware_auto_perception_msgs::msg::Shape shape; geometry_msgs::msg::Pose pose; - boost::optional yaw = boost::none; + boost::optional ref_yaw_info = boost::none; if (use_vehicle_reference_yaw_ && is_vehicle) { - yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + ref_yaw_info = ReferenceYawInfo{ + static_cast(tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)), + tier4_autoware_utils::deg2rad(10)}; } const bool estimated_success = - estimator_->estimateShapeAndPose(label, *cluster, yaw, shape, pose); + estimator_->estimateShapeAndPose(label, *cluster, ref_yaw_info, shape, pose); // If the shape estimation fails, ignore it. if (!estimated_success) { From 3f5d49935831db16f1cda4fc2701b116c8a8eef7 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Tue, 22 Feb 2022 21:30:11 +0900 Subject: [PATCH 30/37] fix(behavior_path_planner): fix utility function (#434) Signed-off-by: tomoya.kimura --- planning/behavior_path_planner/src/utilities.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/utilities.cpp b/planning/behavior_path_planner/src/utilities.cpp index 51a05797e4c34..bdaa5adae8bb0 100644 --- a/planning/behavior_path_planner/src/utilities.cpp +++ b/planning/behavior_path_planner/src/utilities.cpp @@ -484,7 +484,7 @@ bool lerpByTimeStamp(const PredictedPath & path, const double t_query, Pose * le return false; } - const double t_final = time_step.seconds() * static_cast(path.path.size()); + const double t_final = time_step.seconds() * static_cast(path.path.size() - 1); if (t_query > t_final) { RCLCPP_DEBUG_STREAM( rclcpp::get_logger("behavior_path_planner").get_child("utilities"), From 800c6c32e647c1ccd4efabf2a613ca4c7400cee7 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 23 Feb 2022 00:14:02 +0900 Subject: [PATCH 31/37] refactor(behavior_velocity_planner): remove unused local interpolate function (#435) * move functions from interpolate.cpp to path_utilization.cpp Signed-off-by: Takamasa Horibe * remove unused LinearInterpolate library Signed-off-by: Takamasa Horibe * fix format Signed-off-by: Takamasa Horibe * fix cpplint Signed-off-by: Takamasa Horibe --- .../behavior_velocity_planner/CMakeLists.txt | 1 - .../include/utilization/interpolate.hpp | 55 ----- .../include/utilization/path_utilization.hpp | 7 + .../src/scene_module/blind_spot/scene.cpp | 4 +- .../intersection/scene_intersection.cpp | 1 - .../scene_merge_from_private_road.cpp | 2 +- .../src/scene_module/intersection/util.cpp | 4 +- .../scene_no_stopping_area.cpp | 4 +- .../occlusion_spot/occlusion_spot_utils.cpp | 1 - .../scene_occlusion_spot_in_private_road.cpp | 4 +- .../scene_occlusion_spot_in_public_road.cpp | 4 +- .../src/utilization/interpolate.cpp | 220 ------------------ .../src/utilization/path_utilization.cpp | 99 ++++++++ 13 files changed, 116 insertions(+), 290 deletions(-) delete mode 100644 planning/behavior_velocity_planner/include/utilization/interpolate.hpp delete mode 100644 planning/behavior_velocity_planner/src/utilization/interpolate.cpp diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/CMakeLists.txt index fc78e3ca328b3..c589624e56f61 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/CMakeLists.txt @@ -53,7 +53,6 @@ set(BEHAVIOR_VELOCITY_PLANNER_DEPENDENCIES ament_auto_add_library(scene_module_lib SHARED src/utilization/path_utilization.cpp src/utilization/util.cpp - src/utilization/interpolate.cpp ) target_include_directories(scene_module_lib diff --git a/planning/behavior_velocity_planner/include/utilization/interpolate.hpp b/planning/behavior_velocity_planner/include/utilization/interpolate.hpp deleted file mode 100644 index ed61198b2180d..0000000000000 --- a/planning/behavior_velocity_planner/include/utilization/interpolate.hpp +++ /dev/null @@ -1,55 +0,0 @@ -// Copyright 2020 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 UTILIZATION__INTERPOLATE_HPP_ -#define UTILIZATION__INTERPOLATE_HPP_ - -#include - -#include -#include - -#include -#include - -namespace behavior_velocity_planner -{ -namespace interpolation -{ -bool splineInterpolate( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, - autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger); - -class LinearInterpolate -{ -public: - LinearInterpolate() {} - static bool interpolate( - const std::vector & base_index, const std::vector & base_value, - const std::vector & return_index, std::vector & return_value); -}; - -/* - * helper functions - */ -bool isIncrease(const std::vector & x); -bool isValidInput( - const std::vector & base_index, const std::vector & base_value, - const std::vector & return_index); -std::vector calcEuclidDist(const std::vector & x, const std::vector & y); - -} // namespace interpolation -} // namespace behavior_velocity_planner - -#endif // UTILIZATION__INTERPOLATE_HPP_ diff --git a/planning/behavior_velocity_planner/include/utilization/path_utilization.hpp b/planning/behavior_velocity_planner/include/utilization/path_utilization.hpp index cb233c236d2b1..75adbd4af55f8 100644 --- a/planning/behavior_velocity_planner/include/utilization/path_utilization.hpp +++ b/planning/behavior_velocity_planner/include/utilization/path_utilization.hpp @@ -19,9 +19,15 @@ #include #include +#include + +#include namespace behavior_velocity_planner { +bool splineInterpolate( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, + autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger); autoware_auto_planning_msgs::msg::Path interpolatePath( const autoware_auto_planning_msgs::msg::Path & path, const double length, const double interval = 1.0); @@ -29,6 +35,7 @@ autoware_auto_planning_msgs::msg::Path filterLitterPathPoint( const autoware_auto_planning_msgs::msg::Path & path); autoware_auto_planning_msgs::msg::Path filterStopPathPoint( const autoware_auto_planning_msgs::msg::Path & path); +std::vector calcEuclidDist(const std::vector & x, const std::vector & y); } // namespace behavior_velocity_planner #endif // UTILIZATION__PATH_UTILIZATION_HPP_ diff --git a/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp b/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp index dd9f48a4e76e2..3070e4b4ed82f 100644 --- a/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/blind_spot/scene.cpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include @@ -200,7 +200,7 @@ bool BlindSpotModule::generateStopLine( /* spline interpolation */ autoware_auto_planning_msgs::msg::PathWithLaneId path_ip; - if (!interpolation::splineInterpolate(*path, interval, &path_ip, logger_)) { + if (!splineInterpolate(*path, interval, &path_ip, logger_)) { return false; } debug_data_.spline_path = path_ip; diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp index 576b769ec8a78..5ea098e885a56 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp @@ -18,7 +18,6 @@ #include #include #include -#include #include #include diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_merge_from_private_road.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_merge_from_private_road.cpp index 00af9463f3f02..ceccb05d2659b 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/scene_merge_from_private_road.cpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include diff --git a/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp b/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp index f9f68fb4bea7c..95946a6ba61be 100644 --- a/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/intersection/util.cpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include @@ -185,7 +185,7 @@ bool generateStopLine( /* spline interpolation */ autoware_auto_planning_msgs::msg::PathWithLaneId path_ip; - if (!interpolation::splineInterpolate(target_path, interval, &path_ip, logger)) { + if (!splineInterpolate(target_path, interval, &path_ip, logger)) { return false; } diff --git a/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp index ae58fe1a0cbf3..00eb4b319fe92 100644 --- a/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/no_stopping_area/scene_no_stopping_area.cpp @@ -15,7 +15,6 @@ #include "scene_module/no_stopping_area/scene_no_stopping_area.hpp" #include "utilization/arc_lane_util.hpp" -#include "utilization/interpolate.hpp" #include "utilization/path_utilization.hpp" #include "utilization/util.hpp" @@ -267,8 +266,7 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( const double interpolation_interval = 0.5; bool is_in_area = false; autoware_auto_planning_msgs::msg::PathWithLaneId interpolated_path; - if (!interpolation::splineInterpolate( - path, interpolation_interval, &interpolated_path, logger_)) { + if (!splineInterpolate(path, interpolation_interval, &interpolated_path, logger_)) { return ego_area; } auto & pp = interpolated_path.points; diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp index 76c9db5b421ef..002306a91e7f6 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp @@ -19,7 +19,6 @@ #include #include #include -#include #include #include diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp index fe900e0d7b533..4ce2b34b60c60 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_private_road.cpp @@ -17,7 +17,7 @@ #include #include #include -#include +#include #include #include @@ -74,7 +74,7 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( utils::clipPathByLength(*path, clipped_path, max_range); PathWithLaneId interp_path; //! never change this interpolation interval(will affect module accuracy) - interpolation::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); + splineInterpolate(clipped_path, 1.0, &interp_path, logger_); debug_data_.interp_path = interp_path; int closest_idx = -1; if (!planning_utils::calcClosestIndex( diff --git a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp index d35bf1c68c456..15b5029d39b3f 100644 --- a/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp @@ -17,7 +17,7 @@ #include #include #include -#include +#include #include #include @@ -73,7 +73,7 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( PathWithLaneId clipped_path; utils::clipPathByLength(*path, clipped_path, param_.detection_area_length); PathWithLaneId interp_path; - interpolation::splineInterpolate(clipped_path, 1.0, &interp_path, logger_); + splineInterpolate(clipped_path, 1.0, &interp_path, logger_); int closest_idx = -1; if (!planning_utils::calcClosestIndex( interp_path, ego_pose, closest_idx, param_.dist_thr, param_.angle_thr)) { diff --git a/planning/behavior_velocity_planner/src/utilization/interpolate.cpp b/planning/behavior_velocity_planner/src/utilization/interpolate.cpp deleted file mode 100644 index 3753c110a6d80..0000000000000 --- a/planning/behavior_velocity_planner/src/utilization/interpolate.cpp +++ /dev/null @@ -1,220 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include - -#include -#include - -#include - -namespace behavior_velocity_planner -{ -namespace interpolation -{ -bool splineInterpolate( - const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, - autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger) -{ - *output = input; - - if (input.points.size() <= 1) { - RCLCPP_DEBUG(logger, "Do not interpolate because path size is 1."); - return false; - } - - static constexpr double ep = 1.0e-8; - - // calc arclength for path - std::vector base_x; - std::vector base_y; - std::vector base_z; - std::vector base_v; - for (const auto & p : input.points) { - base_x.push_back(p.point.pose.position.x); - base_y.push_back(p.point.pose.position.y); - base_z.push_back(p.point.pose.position.z); - base_v.push_back(p.point.longitudinal_velocity_mps); - } - std::vector base_s = interpolation::calcEuclidDist(base_x, base_y); - - // remove duplicating sample points - { - size_t Ns = base_s.size(); - size_t i = 1; - while (i < Ns) { - if (std::fabs(base_s[i - 1] - base_s[i]) < ep) { - base_s.erase(base_s.begin() + i); - base_x.erase(base_x.begin() + i); - base_y.erase(base_y.begin() + i); - base_z.erase(base_z.begin() + i); - base_v.erase(base_v.begin() + i); - Ns -= 1; - i -= 1; - } - ++i; - } - } - - std::vector resampled_s; - for (double d = 0.0; d < base_s.back() - ep; d += interval) { - resampled_s.push_back(d); - } - - // do spline for xy - const std::vector resampled_x = ::interpolation::slerp(base_s, base_x, resampled_s); - const std::vector resampled_y = ::interpolation::slerp(base_s, base_y, resampled_s); - const std::vector resampled_z = ::interpolation::slerp(base_s, base_z, resampled_s); - const std::vector resampled_v = ::interpolation::slerp(base_s, base_v, resampled_s); - - // set xy - output->points.clear(); - for (size_t i = 0; i < resampled_s.size(); i++) { - autoware_auto_planning_msgs::msg::PathPointWithLaneId p; - p.point.pose.position.x = resampled_x.at(i); - p.point.pose.position.y = resampled_y.at(i); - p.point.pose.position.z = resampled_z.at(i); - p.point.longitudinal_velocity_mps = resampled_v.at(i); - output->points.push_back(p); - } - - // set yaw - for (int i = 1; i < static_cast(resampled_s.size()) - 1; i++) { - auto p = output->points.at(i - 1).point.pose.position; - auto n = output->points.at(i + 1).point.pose.position; - double yaw = std::atan2(n.y - p.y, n.x - p.x); - output->points.at(i).point.pose.orientation = - tier4_autoware_utils::createQuaternionFromYaw(yaw); - } - if (output->points.size() > 1) { - size_t l = output->points.size(); - output->points.front().point.pose.orientation = output->points.at(1).point.pose.orientation; - output->points.back().point.pose.orientation = output->points.at(l - 2).point.pose.orientation; - } - return true; -} - -// TODO(murooka) delete these functions -/* - * linear interpolation - */ -bool LinearInterpolate::interpolate( - const std::vector & base_index, const std::vector & base_value, - const std::vector & return_index, std::vector & return_value) -{ - if (!isValidInput(base_index, base_value, return_index)) { - std::cerr << "[interpolate] invalid input. interpolation failed." << std::endl; - return false; - } - - // calculate linear interpolation - int i = 0; - for (const auto idx : return_index) { - if (base_index[i] == idx) { - return_value.push_back(base_value[i]); - continue; - } - while (base_index[i] < idx) { - ++i; - } - if (i <= 0 || static_cast(base_index.size()) - 1 < i) { - std::cerr << "[interpolate] undesired condition. skip this idx!" << std::endl; - continue; - } - - const double base_dist = base_index[i] - base_index[i - 1]; - const double to_forward = base_index[i] - idx; - const double to_backward = idx - base_index[i - 1]; - if (to_forward < 0.0 || to_backward < 0.0) { - std::cerr << "[interpolate] undesired condition. skip this idx!!" << std::endl; - std::cerr << "i = " << i << ", base_index[i - 1] = " << base_index[i - 1] << ", idx = " << idx - << ", base_index[i] = " << base_index[i] << std::endl; - continue; - } - - const double value = (to_backward * base_value[i] + to_forward * base_value[i - 1]) / base_dist; - return_value.push_back(value); - } - return true; -} - -/* - * helper functions - */ -bool isIncrease(const std::vector & x) -{ - for (int i = 0; i < static_cast(x.size()) - 1; ++i) { - if (x[i] > x[i + 1]) { - return false; - } - } - return true; -} - -bool isValidInput( - const std::vector & base_index, const std::vector & base_value, - const std::vector & return_index) -{ - if (base_index.empty() || base_value.empty() || return_index.empty()) { - std::cout << "bad index : some vector is empty. base_index: " << base_index.size() - << ", base_value: " << base_value.size() << ", return_index: " << return_index.size() - << std::endl; - return false; - } - if (!isIncrease(base_index)) { - std::cout << "bad index : base_index is not monotonically increasing. base_index = [" - << base_index.front() << ", " << base_index.back() << "]" << std::endl; - return false; - } - if (!isIncrease(return_index)) { - std::cout << "bad index : base_index is not monotonically increasing. return_index = [" - << return_index.front() << ", " << return_index.back() << "]" << std::endl; - return false; - } - if (return_index.front() < base_index.front()) { - std::cout << "bad index : return_index.front() < base_index.front()" << std::endl; - return false; - } - if (base_index.back() < return_index.back()) { - std::cout << "bad index : base_index.back() < return_index.back()" << std::endl; - return false; - } - if (base_index.size() != base_value.size()) { - std::cout << "bad index : base_index.size() != base_value.size()" << std::endl; - return false; - } - - return true; -} - -std::vector calcEuclidDist(const std::vector & x, const std::vector & y) -{ - if (x.size() != y.size()) { - std::cerr << "x y vector size should be the same." << std::endl; - } - - std::vector dist_v; - dist_v.push_back(0.0); - for (unsigned int i = 0; i < x.size() - 1; ++i) { - const double dx = x.at(i + 1) - x.at(i); - const double dy = y.at(i + 1) - y.at(i); - dist_v.push_back(dist_v.at(i) + std::hypot(dx, dy)); - } - - return dist_v; -} -} // namespace interpolation -} // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/src/utilization/path_utilization.cpp b/planning/behavior_velocity_planner/src/utilization/path_utilization.cpp index d54c3fae48b10..7513346ed93d2 100644 --- a/planning/behavior_velocity_planner/src/utilization/path_utilization.cpp +++ b/planning/behavior_velocity_planner/src/utilization/path_utilization.cpp @@ -27,6 +27,88 @@ constexpr double DOUBLE_EPSILON = 1e-6; namespace behavior_velocity_planner { +bool splineInterpolate( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input, const double interval, + autoware_auto_planning_msgs::msg::PathWithLaneId * output, const rclcpp::Logger logger) +{ + *output = input; + + if (input.points.size() <= 1) { + RCLCPP_DEBUG(logger, "Do not interpolate because path size is 1."); + return false; + } + + static constexpr double ep = 1.0e-8; + + // calc arclength for path + std::vector base_x; + std::vector base_y; + std::vector base_z; + std::vector base_v; + for (const auto & p : input.points) { + base_x.push_back(p.point.pose.position.x); + base_y.push_back(p.point.pose.position.y); + base_z.push_back(p.point.pose.position.z); + base_v.push_back(p.point.longitudinal_velocity_mps); + } + std::vector base_s = calcEuclidDist(base_x, base_y); + + // remove duplicating sample points + { + size_t Ns = base_s.size(); + size_t i = 1; + while (i < Ns) { + if (std::fabs(base_s[i - 1] - base_s[i]) < ep) { + base_s.erase(base_s.begin() + i); + base_x.erase(base_x.begin() + i); + base_y.erase(base_y.begin() + i); + base_z.erase(base_z.begin() + i); + base_v.erase(base_v.begin() + i); + Ns -= 1; + i -= 1; + } + ++i; + } + } + + std::vector resampled_s; + for (double d = 0.0; d < base_s.back() - ep; d += interval) { + resampled_s.push_back(d); + } + + // do spline for xy + const std::vector resampled_x = ::interpolation::slerp(base_s, base_x, resampled_s); + const std::vector resampled_y = ::interpolation::slerp(base_s, base_y, resampled_s); + const std::vector resampled_z = ::interpolation::slerp(base_s, base_z, resampled_s); + const std::vector resampled_v = ::interpolation::slerp(base_s, base_v, resampled_s); + + // set xy + output->points.clear(); + for (size_t i = 0; i < resampled_s.size(); i++) { + autoware_auto_planning_msgs::msg::PathPointWithLaneId p; + p.point.pose.position.x = resampled_x.at(i); + p.point.pose.position.y = resampled_y.at(i); + p.point.pose.position.z = resampled_z.at(i); + p.point.longitudinal_velocity_mps = resampled_v.at(i); + output->points.push_back(p); + } + + // set yaw + for (int i = 1; i < static_cast(resampled_s.size()) - 1; i++) { + auto p = output->points.at(i - 1).point.pose.position; + auto n = output->points.at(i + 1).point.pose.position; + double yaw = std::atan2(n.y - p.y, n.x - p.x); + output->points.at(i).point.pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(yaw); + } + if (output->points.size() > 1) { + size_t l = output->points.size(); + output->points.front().point.pose.orientation = output->points.at(1).point.pose.orientation; + output->points.back().point.pose.orientation = output->points.at(l - 2).point.pose.orientation; + } + return true; +} + autoware_auto_planning_msgs::msg::Path interpolatePath( const autoware_auto_planning_msgs::msg::Path & path, const double length, const double interval) { @@ -179,4 +261,21 @@ autoware_auto_planning_msgs::msg::Path filterStopPathPoint( } return filtered_path; } + +std::vector calcEuclidDist(const std::vector & x, const std::vector & y) +{ + if (x.size() != y.size()) { + std::cerr << "x y vector size should be the same." << std::endl; + } + + std::vector dist_v; + dist_v.push_back(0.0); + for (unsigned int i = 0; i < x.size() - 1; ++i) { + const double dx = x.at(i + 1) - x.at(i); + const double dy = y.at(i + 1) - y.at(i); + dist_v.push_back(dist_v.at(i) + std::hypot(dx, dy)); + } + + return dist_v; +} } // namespace behavior_velocity_planner From 68af1bae029de07cc3631045313aa0d6fd7d96d1 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 24 Feb 2022 10:53:46 +0900 Subject: [PATCH 32/37] fix(tier4_vehicle_launch): remove unnecessary config_dir (#436) * fix(tier4_vehicle_launch): remove unnecessary config_dir Signed-off-by: Kenji Miyake * refactor: rename arg Signed-off-by: Kenji Miyake * remove vehicle_description.launch.xml to simplify the structure Signed-off-by: Kenji Miyake * chore: simplify vehicle.xacro Signed-off-by: Kenji Miyake --- .../launch/vehicle.launch.xml | 10 ++++------ .../launch/vehicle_description.launch.xml | 15 --------------- launch/tier4_vehicle_launch/urdf/vehicle.xacro | 5 +---- 3 files changed, 5 insertions(+), 25 deletions(-) delete mode 100644 launch/tier4_vehicle_launch/launch/vehicle_description.launch.xml diff --git a/launch/tier4_vehicle_launch/launch/vehicle.launch.xml b/launch/tier4_vehicle_launch/launch/vehicle.launch.xml index 6da803cf04aad..3593e2cab3c4a 100644 --- a/launch/tier4_vehicle_launch/launch/vehicle.launch.xml +++ b/launch/tier4_vehicle_launch/launch/vehicle.launch.xml @@ -8,14 +8,12 @@ - - - - - - + + + + diff --git a/launch/tier4_vehicle_launch/launch/vehicle_description.launch.xml b/launch/tier4_vehicle_launch/launch/vehicle_description.launch.xml deleted file mode 100644 index 8a05079ea84f1..0000000000000 --- a/launch/tier4_vehicle_launch/launch/vehicle_description.launch.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/launch/tier4_vehicle_launch/urdf/vehicle.xacro b/launch/tier4_vehicle_launch/urdf/vehicle.xacro index 30db9c6a7cba4..8c3ecf94cf43a 100644 --- a/launch/tier4_vehicle_launch/urdf/vehicle.xacro +++ b/launch/tier4_vehicle_launch/urdf/vehicle.xacro @@ -1,7 +1,5 @@ - - + @@ -12,5 +10,4 @@ - From 1efab68e937a2ba61bf14144510bfc56df1c3bee Mon Sep 17 00:00:00 2001 From: TakumiKozaka-T4 <70260442+TakumiKozaka-T4@users.noreply.github.com> Date: Thu, 24 Feb 2022 17:16:49 +0900 Subject: [PATCH 33/37] feat: add cpu usage topic (#353) * modified for publishing cpu_usage_api Signed-off-by: TakumiKozaka-T4 * modified for calib error output and cpu usage output Signed-off-by: TakumiKozaka-T4 * modified push_back condition Signed-off-by: TakumiKozaka-T4 * modified topic name Signed-off-by: TakumiKozaka-T4 * Delete unnecessary comments Signed-off-by: TakumiKozaka-T4 * Delete unnecessary comments Signed-off-by: TakumiKozaka-T4 * modified for publishing cpu_usage_api * Delete unnecessary comments Signed-off-by: TakumiKozaka-T4 * ci(pre-commit): autofix * ci(pre-commit): autofix * run pre-commit Signed-off-by: TakumiKozaka-T4 * remove unnecessary comments Signed-off-by: TakumiKozaka-T4 * modify unnecessary change for pull request Signed-off-by: TakumiKozaka-T4 * run pre-commit Signed-off-by: TakumiKozaka-T4 * modify unnecessary change Signed-off-by: TakumiKozaka-T4 * modified along the comments on PR #353 Signed-off-by: TakumiKozaka-T4 * modified along the comments on PR #353 Signed-off-by: TakumiKozaka-T4 * remove unnecessary process Signed-off-by: TakumiKozaka-T4 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../cpu_monitor/cpu_monitor_base.hpp | 8 ++++ system/system_monitor/package.xml | 1 + .../src/cpu_monitor/cpu_monitor_base.cpp | 44 +++++++++++++++++++ 3 files changed, 53 insertions(+) diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp b/system/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp index 32ba097c475d2..f53ba45d043b9 100644 --- a/system/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp +++ b/system/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp @@ -22,6 +22,9 @@ #include +#include +#include + #include #include #include @@ -161,6 +164,11 @@ class CPUMonitorBase : public rclcpp::Node */ const std::map thermal_dict_ = { {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "unused"}, {DiagStatus::ERROR, "throttling"}}; + + // Publisher + rclcpp::Publisher::SharedPtr pub_cpu_usage_; + + virtual void publishCpuUsage(tier4_external_api_msgs::msg::CpuUsage usage); }; #endif // SYSTEM_MONITOR__CPU_MONITOR__CPU_MONITOR_BASE_HPP_ diff --git a/system/system_monitor/package.xml b/system/system_monitor/package.xml index 3e44457ebdfb6..e25a200fc0d95 100644 --- a/system/system_monitor/package.xml +++ b/system/system_monitor/package.xml @@ -17,6 +17,7 @@ rclcpp rclcpp_components std_msgs + tier4_external_api_msgs chrony sysstat diff --git a/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp b/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp index 19ecec4bdba1f..44e375052c542 100644 --- a/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp +++ b/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp @@ -64,6 +64,12 @@ CPUMonitorBase::CPUMonitorBase(const std::string & node_name, const rclcpp::Node updater_.add("CPU Load Average", this, &CPUMonitorBase::checkLoad); updater_.add("CPU Thermal Throttling", this, &CPUMonitorBase::checkThrottling); updater_.add("CPU Frequency", this, &CPUMonitorBase::checkFrequency); + + // Publisher + rclcpp::QoS durable_qos{1}; + durable_qos.transient_local(); + pub_cpu_usage_ = + this->create_publisher("~/cpu_usage", durable_qos); } void CPUMonitorBase::update() { updater_.force_update(); } @@ -113,10 +119,15 @@ void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & st // Remember start time to measure elapsed time const auto t_start = SystemMonitorUtility::startMeasurement(); + tier4_external_api_msgs::msg::CpuUsage cpu_usage; + using CpuStatus = tier4_external_api_msgs::msg::CpuStatus; + if (!mpstat_exists_) { stat.summary(DiagStatus::ERROR, "mpstat error"); stat.add( "mpstat", "Command 'mpstat' not found, but can be installed with: sudo apt install sysstat"); + cpu_usage.all.status = CpuStatus::STALE; + publishCpuUsage(cpu_usage); return; } @@ -131,6 +142,8 @@ void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & st is_err >> os.rdbuf(); stat.summary(DiagStatus::ERROR, "mpstat error"); stat.add("mpstat", os.str().c_str()); + cpu_usage.all.status = CpuStatus::STALE; + publishCpuUsage(cpu_usage); return; } @@ -159,21 +172,28 @@ void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & st for (const pt::ptree::value_type & child3 : statistics.get_child("cpu-load")) { const pt::ptree & cpu_load = child3.second; bool get_cpu_name = false; + + CpuStatus cpu_status; + if (boost::optional v = cpu_load.get_optional("cpu")) { cpu_name = v.get(); get_cpu_name = true; } if (boost::optional v = cpu_load.get_optional("usr")) { usr = v.get(); + cpu_status.usr = usr; } if (boost::optional v = cpu_load.get_optional("nice")) { nice = v.get(); + cpu_status.nice = nice; } if (boost::optional v = cpu_load.get_optional("sys")) { sys = v.get(); + cpu_status.sys = sys; } if (boost::optional v = cpu_load.get_optional("idle")) { idle = v.get(); + cpu_status.idle = idle; } total = 100.0 - iowait - idle; @@ -184,6 +204,9 @@ void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & st level = CpuUsageToLevel(std::string("err"), usage); } + cpu_status.total = total; + cpu_status.status = level; + stat.add(fmt::format("CPU {}: status", cpu_name), load_dict_.at(level)); stat.addf(fmt::format("CPU {}: total", cpu_name), "%.2f%%", total); stat.addf(fmt::format("CPU {}: usr", cpu_name), "%.2f%%", usr); @@ -198,6 +221,12 @@ void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & st } else { whole_level = std::max(whole_level, level); } + + if (cpu_name == "all") { + cpu_usage.all = cpu_status; + } else { + cpu_usage.cpus.push_back(cpu_status); + } } } } @@ -205,11 +234,17 @@ void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & st stat.summary(DiagStatus::ERROR, "mpstat exception"); stat.add("mpstat", e.what()); std::fill(usage_check_cnt_.begin(), usage_check_cnt_.end(), 0); + cpu_usage.all.status = CpuStatus::STALE; + cpu_usage.cpus.clear(); + publishCpuUsage(cpu_usage); return; } stat.summary(whole_level, load_dict_.at(whole_level)); + // Publish msg + publishCpuUsage(cpu_usage); + // Measure elapsed time since start time and report SystemMonitorUtility::stopMeasurement(t_start, stat); } @@ -366,3 +401,12 @@ void CPUMonitorBase::getFreqNames() return c1.index_ < c2.index_; }); // NOLINT } + +void CPUMonitorBase::publishCpuUsage(tier4_external_api_msgs::msg::CpuUsage usage) +{ + // Create timestamp + const auto stamp = this->now(); + + usage.stamp = stamp; + pub_cpu_usage_->publish(usage); +} From 1435677ef66c7c6ebaa0cf36e46693ca1c69bde2 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 24 Feb 2022 19:23:16 +0900 Subject: [PATCH 34/37] fix(tier4_vehicle_launch): refer to launch packages to find vehicle_interface.launch.xml (#439) Signed-off-by: Kenji Miyake --- launch/tier4_vehicle_launch/launch/vehicle.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/tier4_vehicle_launch/launch/vehicle.launch.xml b/launch/tier4_vehicle_launch/launch/vehicle.launch.xml index 3593e2cab3c4a..f696e6b33d73d 100644 --- a/launch/tier4_vehicle_launch/launch/vehicle.launch.xml +++ b/launch/tier4_vehicle_launch/launch/vehicle.launch.xml @@ -6,7 +6,7 @@ - + @@ -18,7 +18,7 @@ - + From 5f058a8a4cbb3b583ceccb1d28c0f05e54351c51 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 24 Feb 2022 21:42:24 +0900 Subject: [PATCH 35/37] chore: remove filesystem.hpp (#440) Signed-off-by: Kenji Miyake --- common/autoware_auto_common/CMakeLists.txt | 2 - .../include/common/filesystem.hpp | 5558 ----------------- 2 files changed, 5560 deletions(-) delete mode 100644 common/autoware_auto_common/include/common/filesystem.hpp diff --git a/common/autoware_auto_common/CMakeLists.txt b/common/autoware_auto_common/CMakeLists.txt index acfa3cbb7ef08..45284843f5644 100644 --- a/common/autoware_auto_common/CMakeLists.txt +++ b/common/autoware_auto_common/CMakeLists.txt @@ -42,8 +42,6 @@ if(BUILD_TESTING) ${CMAKE_CURRENT_SOURCE_DIR}/test/* ) - list(FILTER FILES_MINUS_SOME EXCLUDE REGEX ".*filesystem.hpp") - # Re-enable cpplint find_package(ament_cmake_cpplint) ament_cpplint(${FILES_MINUS_SOME}) diff --git a/common/autoware_auto_common/include/common/filesystem.hpp b/common/autoware_auto_common/include/common/filesystem.hpp deleted file mode 100644 index 7fe16d8df8084..0000000000000 --- a/common/autoware_auto_common/include/common/filesystem.hpp +++ /dev/null @@ -1,5558 +0,0 @@ -//--------------------------------------------------------------------------------------- -// -// ghc::filesystem - A C++17-like filesystem implementation for C++11/C++14/C++17 -// -//--------------------------------------------------------------------------------------- -// -// Copyright (c) 2018, Steffen Schümann -// -// Permission is hereby granted, free of charge, to any person obtaining a copy -// of this software and associated documentation files (the "Software"), to deal -// in the Software without restriction, including without limitation the rights -// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -// copies of the Software, and to permit persons to whom the Software is -// furnished to do so, subject to the following conditions: -// -// The above copyright notice and this permission notice shall be included in all -// copies or substantial portions of the Software. -// -// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -// SOFTWARE. -// -//--------------------------------------------------------------------------------------- -// -// To dynamically select std::filesystem where available, you could use: -// -// #if defined(__cplusplus) && __cplusplus >= 201703L && defined(__has_include) && __has_include() -// #include -// namespace fs = std::filesystem; -// #else -// #include -// namespace fs = ghc::filesystem; -// #endif -// -//--------------------------------------------------------------------------------------- -#ifndef GHC_FILESYSTEM_H -#define GHC_FILESYSTEM_H - -// #define BSD manifest constant only in -// sys/param.h -#ifndef _WIN32 -#include -#endif - -#ifndef GHC_OS_DETECTED -#if defined(__APPLE__) && defined(__MACH__) -#define GHC_OS_MACOS -#elif defined(__linux__) -#define GHC_OS_LINUX -#if defined(__ANDROID__) -#define GHC_OS_ANDROID -#endif -#elif defined(_WIN64) -#define GHC_OS_WINDOWS -#define GHC_OS_WIN64 -#elif defined(_WIN32) -#define GHC_OS_WINDOWS -#define GHC_OS_WIN32 -#elif defined(__svr4__) -#define GHC_OS_SYS5R4 -#elif defined(BSD) -#define GHC_OS_BSD -#elif defined(__EMSCRIPTEN__) -#define GHC_OS_WEB -#include -#else -#error "Operating system currently not supported!" -#endif -#define GHC_OS_DETECTED -#endif - -#if defined(GHC_FILESYSTEM_IMPLEMENTATION) -#define GHC_EXPAND_IMPL -#define GHC_INLINE -#ifdef GHC_OS_WINDOWS -#define GHC_FS_API -#define GHC_FS_API_CLASS -#else -#define GHC_FS_API __attribute__((visibility("default"))) -#define GHC_FS_API_CLASS __attribute__((visibility("default"))) -#endif -#elif defined(GHC_FILESYSTEM_FWD) -#define GHC_INLINE -#ifdef GHC_OS_WINDOWS -#define GHC_FS_API extern -#define GHC_FS_API_CLASS -#else -#define GHC_FS_API extern -#define GHC_FS_API_CLASS -#endif -#else -#define GHC_EXPAND_IMPL -#define GHC_INLINE inline -#define GHC_FS_API -#define GHC_FS_API_CLASS -#endif - -#ifdef GHC_EXPAND_IMPL - -#ifdef GHC_OS_WINDOWS -#include -// additional includes -#include -#include -#include -#include -#include -#else -#include -#include -#include -#include -#include -#include -#include -#include -#ifdef GHC_OS_ANDROID -#include -#if __ANDROID_API__ < 12 -#include -#endif -#include -#define statvfs statfs -#else -#include -#endif -#if !defined(__ANDROID__) || __ANDROID_API__ >= 26 -#include -#endif -#endif -#ifdef GHC_OS_MACOS -#include -#endif - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#else // GHC_EXPAND_IMPL -#include -#include -#include -#include -#include -#include -#include -#ifdef GHC_OS_WINDOWS -#include -#endif -#endif // GHC_EXPAND_IMPL - -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// Behaviour Switches (see README.md, should match the config in test/filesystem_test.cpp): -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// LWG #2682 disables the since then invalid use of the copy option create_symlinks on directories -// configure LWG conformance () -#define LWG_2682_BEHAVIOUR -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// LWG #2395 makes crate_directory/create_directories not emit an error if there is a regular -// file with that name, it is superceded by P1164R1, so only activate if really needed -// #define LWG_2935_BEHAVIOUR -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// LWG #2937 enforces that fs::equivalent emits an error, if !fs::exists(p1)||!exists(p2) -#define LWG_2937_BEHAVIOUR -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// UTF8-Everywhere is the original behaviour of ghc::filesystem. With this define you can -// enable the more standard conforming implementation option that uses wstring on Windows -// as ghc::filesystem::string_type. -// #define GHC_WIN_WSTRING_STRING_TYPE -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// Raise errors/exceptions when invalid unicode codepoints or UTF-8 sequences are found, -// instead of replacing them with the unicode replacement character (U+FFFD). -// #define GHC_RAISE_UNICODE_ERRORS -//- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -// ghc::filesystem version in decimal (major * 10000 + minor * 100 + patch) -#define GHC_FILESYSTEM_VERSION 10304L - -#if !defined(GHC_WITH_EXCEPTIONS) && (defined(__EXCEPTIONS) || defined(__cpp_exceptions) || defined(_CPPUNWIND)) -#define GHC_WITH_EXCEPTIONS -#endif -#if !defined(GHC_WITH_EXCEPTIONS) && defined(GHC_RAISE_UNICODE_ERRORS) -#error "Can't raise unicode errors whith exception support disabled" -#endif - -namespace ghc { -namespace filesystem { - -// temporary existing exception type for yet unimplemented parts -class GHC_FS_API_CLASS not_implemented_exception : public std::logic_error -{ -public: - not_implemented_exception() - : std::logic_error("function not implemented yet.") - { - } -}; - -template -class path_helper_base -{ -public: - using value_type = char_type; -#ifdef GHC_OS_WINDOWS - static constexpr value_type preferred_separator = '\\'; -#else - static constexpr value_type preferred_separator = '/'; -#endif -}; - -#if __cplusplus < 201703L -template -constexpr char_type path_helper_base::preferred_separator; -#endif - -// 30.10.8 class path -class GHC_FS_API_CLASS path -#if defined(GHC_OS_WINDOWS) && defined(GHC_WIN_WSTRING_STRING_TYPE) -#define GHC_USE_WCHAR_T - : private path_helper_base -{ -public: - using path_helper_base::value_type; -#else - : private path_helper_base -{ -public: - using path_helper_base::value_type; -#endif - using string_type = std::basic_string; - using path_helper_base::preferred_separator; - - // 30.10.10.1 enumeration format - /// The path format in wich the constructor argument is given. - enum format { - generic_format, ///< The generic format, internally used by - ///< ghc::filesystem::path with slashes - native_format, ///< The format native to the current platform this code - ///< is build for - auto_format, ///< Try to auto-detect the format, fallback to native - }; - - template - struct _is_basic_string : std::false_type - { - }; - template - struct _is_basic_string> : std::true_type - { - }; -#ifdef __cpp_lib_string_view - template - struct _is_basic_string> : std::true_type - { - }; -#endif - - template - using path_type = typename std::enable_if::value, path>::type; -#ifdef GHC_USE_WCHAR_T - template - using path_from_string = typename std::enable_if<_is_basic_string::value || std::is_same::type>::value || std::is_same::type>::value || - std::is_same::type>::value || std::is_same::type>::value, - path>::type; - template - using path_type_EcharT = typename std::enable_if::value || std::is_same::value || std::is_same::value, path>::type; -#else - template - using path_from_string = typename std::enable_if<_is_basic_string::value || std::is_same::type>::value || std::is_same::type>::value, path>::type; - template - using path_type_EcharT = typename std::enable_if::value || std::is_same::value || std::is_same::value || std::is_same::value, path>::type; -#endif - // 30.10.8.4.1 constructors and destructor - path() noexcept; - path(const path& p); - path(path&& p) noexcept; - path(string_type&& source, format fmt = auto_format); - template > - path(const Source& source, format fmt = auto_format); - template - path(InputIterator first, InputIterator last, format fmt = auto_format); -#ifdef GHC_WITH_EXCEPTIONS - template > - path(const Source& source, const std::locale& loc, format fmt = auto_format); - template - path(InputIterator first, InputIterator last, const std::locale& loc, format fmt = auto_format); -#endif - ~path(); - - // 30.10.8.4.2 assignments - path& operator=(const path& p); - path& operator=(path&& p) noexcept; - path& operator=(string_type&& source); - path& assign(string_type&& source); - template - path& operator=(const Source& source); - template - path& assign(const Source& source); - template - path& assign(InputIterator first, InputIterator last); - - // 30.10.8.4.3 appends - path& operator/=(const path& p); - template - path& operator/=(const Source& source); - template - path& append(const Source& source); - template - path& append(InputIterator first, InputIterator last); - - // 30.10.8.4.4 concatenation - path& operator+=(const path& x); - path& operator+=(const string_type& x); -#ifdef __cpp_lib_string_view - path& operator+=(std::basic_string_view x); -#endif - path& operator+=(const value_type* x); - path& operator+=(value_type x); - template - path_from_string& operator+=(const Source& x); - template - path_type_EcharT& operator+=(EcharT x); - template - path& concat(const Source& x); - template - path& concat(InputIterator first, InputIterator last); - - // 30.10.8.4.5 modifiers - void clear() noexcept; - path& make_preferred(); - path& remove_filename(); - path& replace_filename(const path& replacement); - path& replace_extension(const path& replacement = path()); - void swap(path& rhs) noexcept; - - // 30.10.8.4.6 native format observers - const string_type& native() const; // this implementation doesn't support noexcept for native() - const value_type* c_str() const; // this implementation doesn't support noexcept for c_str() - operator string_type() const; - template , class Allocator = std::allocator> - std::basic_string string(const Allocator& a = Allocator()) const; - std::string string() const; - std::wstring wstring() const; - std::string u8string() const; - std::u16string u16string() const; - std::u32string u32string() const; - - // 30.10.8.4.7 generic format observers - template , class Allocator = std::allocator> - std::basic_string generic_string(const Allocator& a = Allocator()) const; - const std::string& generic_string() const; // this is different from the standard, that returns by value - std::wstring generic_wstring() const; - std::string generic_u8string() const; - std::u16string generic_u16string() const; - std::u32string generic_u32string() const; - - // 30.10.8.4.8 compare - int compare(const path& p) const noexcept; - int compare(const string_type& s) const; -#ifdef __cpp_lib_string_view - int compare(std::basic_string_view s) const; -#endif - int compare(const value_type* s) const; - - // 30.10.8.4.9 decomposition - path root_name() const; - path root_directory() const; - path root_path() const; - path relative_path() const; - path parent_path() const; - path filename() const; - path stem() const; - path extension() const; - - // 30.10.8.4.10 query - bool empty() const noexcept; - bool has_root_name() const; - bool has_root_directory() const; - bool has_root_path() const; - bool has_relative_path() const; - bool has_parent_path() const; - bool has_filename() const; - bool has_stem() const; - bool has_extension() const; - bool is_absolute() const; - bool is_relative() const; - - // 30.10.8.4.11 generation - path lexically_normal() const; - path lexically_relative(const path& base) const; - path lexically_proximate(const path& base) const; - - // 30.10.8.5 iterators - class iterator; - using const_iterator = iterator; - iterator begin() const; - iterator end() const; - -private: - using impl_value_type = std::string::value_type; - using impl_string_type = std::basic_string; - friend class directory_iterator; - void append_name(const char* name); - static constexpr impl_value_type generic_separator = '/'; - template - class input_iterator_range - { - public: - typedef InputIterator iterator; - typedef InputIterator const_iterator; - typedef typename InputIterator::difference_type difference_type; - - input_iterator_range(const InputIterator& first, const InputIterator& last) - : _first(first) - , _last(last) - { - } - - InputIterator begin() const { return _first; } - InputIterator end() const { return _last; } - - private: - InputIterator _first; - InputIterator _last; - }; - friend void swap(path& lhs, path& rhs) noexcept; - friend size_t hash_value(const path& p) noexcept; - static void postprocess_path_with_format(impl_string_type& p, format fmt); - impl_string_type _path; -#ifdef GHC_OS_WINDOWS - impl_string_type native_impl() const; - mutable string_type _native_cache; -#else - const impl_string_type& native_impl() const; -#endif -}; - -// 30.10.8.6 path non-member functions -GHC_FS_API void swap(path& lhs, path& rhs) noexcept; -GHC_FS_API size_t hash_value(const path& p) noexcept; -GHC_FS_API bool operator==(const path& lhs, const path& rhs) noexcept; -GHC_FS_API bool operator!=(const path& lhs, const path& rhs) noexcept; -GHC_FS_API bool operator<(const path& lhs, const path& rhs) noexcept; -GHC_FS_API bool operator<=(const path& lhs, const path& rhs) noexcept; -GHC_FS_API bool operator>(const path& lhs, const path& rhs) noexcept; -GHC_FS_API bool operator>=(const path& lhs, const path& rhs) noexcept; - -GHC_FS_API path operator/(const path& lhs, const path& rhs); - -// 30.10.8.6.1 path inserter and extractor -template -std::basic_ostream& operator<<(std::basic_ostream& os, const path& p); -template -std::basic_istream& operator>>(std::basic_istream& is, path& p); - -// 30.10.8.6.2 path factory functions -template > -path u8path(const Source& source); -template -path u8path(InputIterator first, InputIterator last); - -// 30.10.9 class filesystem_error -class GHC_FS_API_CLASS filesystem_error : public std::system_error -{ -public: - filesystem_error(const std::string& what_arg, std::error_code ec); - filesystem_error(const std::string& what_arg, const path& p1, std::error_code ec); - filesystem_error(const std::string& what_arg, const path& p1, const path& p2, std::error_code ec); - const path& path1() const noexcept; - const path& path2() const noexcept; - const char* what() const noexcept override; - -private: - std::string _what_arg; - std::error_code _ec; - path _p1, _p2; -}; - -class GHC_FS_API_CLASS path::iterator -{ -public: - using value_type = const path; - using difference_type = std::ptrdiff_t; - using pointer = const path*; - using reference = const path&; - using iterator_category = std::bidirectional_iterator_tag; - - iterator(); - iterator(const impl_string_type::const_iterator& first, const impl_string_type::const_iterator& last, const impl_string_type::const_iterator& pos); - iterator& operator++(); - iterator operator++(int); - iterator& operator--(); - iterator operator--(int); - bool operator==(const iterator& other) const; - bool operator!=(const iterator& other) const; - reference operator*() const; - pointer operator->() const; - -private: - impl_string_type::const_iterator increment(const std::string::const_iterator& pos) const; - impl_string_type::const_iterator decrement(const std::string::const_iterator& pos) const; - void updateCurrent(); - impl_string_type::const_iterator _first; - impl_string_type::const_iterator _last; - impl_string_type::const_iterator _root; - impl_string_type::const_iterator _iter; - path _current; -}; - -struct space_info -{ - uintmax_t capacity; - uintmax_t free; - uintmax_t available; -}; - -// 30.10.10, enumerations -enum class file_type { - none, - not_found, - regular, - directory, - symlink, - block, - character, - fifo, - socket, - unknown, -}; - -enum class perms : uint16_t { - none = 0, - - owner_read = 0400, - owner_write = 0200, - owner_exec = 0100, - owner_all = 0700, - - group_read = 040, - group_write = 020, - group_exec = 010, - group_all = 070, - - others_read = 04, - others_write = 02, - others_exec = 01, - others_all = 07, - - all = 0777, - set_uid = 04000, - set_gid = 02000, - sticky_bit = 01000, - - mask = 07777, - unknown = 0xffff -}; - -enum class perm_options : uint16_t { - replace = 3, - add = 1, - remove = 2, - nofollow = 4, -}; - -enum class copy_options : uint16_t { - none = 0, - - skip_existing = 1, - overwrite_existing = 2, - update_existing = 4, - - recursive = 8, - - copy_symlinks = 0x10, - skip_symlinks = 0x20, - - directories_only = 0x40, - create_symlinks = 0x80, -#ifndef GHC_OS_WEB - create_hard_links = 0x100 -#endif -}; - -enum class directory_options : uint16_t { - none = 0, - follow_directory_symlink = 1, - skip_permission_denied = 2, -}; - -// 30.10.11 class file_status -class GHC_FS_API_CLASS file_status -{ -public: - // 30.10.11.1 constructors and destructor - file_status() noexcept; - explicit file_status(file_type ft, perms prms = perms::unknown) noexcept; - file_status(const file_status&) noexcept; - file_status(file_status&&) noexcept; - ~file_status(); - // assignments: - file_status& operator=(const file_status&) noexcept; - file_status& operator=(file_status&&) noexcept; - // 30.10.11.3 modifiers - void type(file_type ft) noexcept; - void permissions(perms prms) noexcept; - // 30.10.11.2 observers - file_type type() const noexcept; - perms permissions() const noexcept; - -private: - file_type _type; - perms _perms; -}; - -using file_time_type = std::chrono::time_point; - -// 30.10.12 Class directory_entry -class GHC_FS_API_CLASS directory_entry -{ -public: - // 30.10.12.1 constructors and destructor - directory_entry() noexcept = default; - directory_entry(const directory_entry&) = default; - directory_entry(directory_entry&&) noexcept = default; -#ifdef GHC_WITH_EXCEPTIONS - explicit directory_entry(const path& p); -#endif - directory_entry(const path& p, std::error_code& ec); - ~directory_entry(); - - // assignments: - directory_entry& operator=(const directory_entry&) = default; - directory_entry& operator=(directory_entry&&) noexcept = default; - - // 30.10.12.2 modifiers -#ifdef GHC_WITH_EXCEPTIONS - void assign(const path& p); -#endif - void assign(const path& p, std::error_code& ec); -#ifdef GHC_WITH_EXCEPTIONS - void replace_filename(const path& p); -#endif - void replace_filename(const path& p, std::error_code& ec); -#ifdef GHC_WITH_EXCEPTIONS - void refresh(); -#endif - void refresh(std::error_code& ec) noexcept; - - // 30.10.12.3 observers - const filesystem::path& path() const noexcept; - operator const filesystem::path&() const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool exists() const; -#endif - bool exists(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_block_file() const; -#endif - bool is_block_file(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_character_file() const; -#endif - bool is_character_file(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_directory() const; -#endif - bool is_directory(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_fifo() const; -#endif - bool is_fifo(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_other() const; -#endif - bool is_other(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_regular_file() const; -#endif - bool is_regular_file(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_socket() const; -#endif - bool is_socket(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - bool is_symlink() const; -#endif - bool is_symlink(std::error_code& ec) const noexcept; -#ifdef GHC_WITH_EXCEPTIONS - uintmax_t file_size() const; -#endif - uintmax_t file_size(std::error_code& ec) const noexcept; - -#ifndef GHC_OS_WEB -#ifdef GHC_WITH_EXCEPTIONS - uintmax_t hard_link_count() const; -#endif - uintmax_t hard_link_count(std::error_code& ec) const noexcept; -#endif - -#ifdef GHC_WITH_EXCEPTIONS - file_time_type last_write_time() const; -#endif - file_time_type last_write_time(std::error_code& ec) const noexcept; - -#ifdef GHC_WITH_EXCEPTIONS - file_status status() const; -#endif - file_status status(std::error_code& ec) const noexcept; - -#ifdef GHC_WITH_EXCEPTIONS - file_status symlink_status() const; -#endif - file_status symlink_status(std::error_code& ec) const noexcept; - bool operator<(const directory_entry& rhs) const noexcept; - bool operator==(const directory_entry& rhs) const noexcept; - bool operator!=(const directory_entry& rhs) const noexcept; - bool operator<=(const directory_entry& rhs) const noexcept; - bool operator>(const directory_entry& rhs) const noexcept; - bool operator>=(const directory_entry& rhs) const noexcept; - -private: - friend class directory_iterator; - filesystem::path _path; - file_status _status; - file_status _symlink_status; - uintmax_t _file_size = 0; -#ifndef GHC_OS_WINDOWS - uintmax_t _hard_link_count = 0; -#endif - time_t _last_write_time = 0; -}; - -// 30.10.13 Class directory_iterator -class GHC_FS_API_CLASS directory_iterator -{ -public: - class GHC_FS_API_CLASS proxy - { - public: - const directory_entry& operator*() const& noexcept { return _dir_entry; } - directory_entry operator*() && noexcept { return std::move(_dir_entry); } - - private: - explicit proxy(const directory_entry& dir_entry) - : _dir_entry(dir_entry) - { - } - friend class directory_iterator; - friend class recursive_directory_iterator; - directory_entry _dir_entry; - }; - using iterator_category = std::input_iterator_tag; - using value_type = directory_entry; - using difference_type = std::ptrdiff_t; - using pointer = const directory_entry*; - using reference = const directory_entry&; - - // 30.10.13.1 member functions - directory_iterator() noexcept; -#ifdef GHC_WITH_EXCEPTIONS - explicit directory_iterator(const path& p); - directory_iterator(const path& p, directory_options options); -#endif - directory_iterator(const path& p, std::error_code& ec) noexcept; - directory_iterator(const path& p, directory_options options, std::error_code& ec) noexcept; - directory_iterator(const directory_iterator& rhs); - directory_iterator(directory_iterator&& rhs) noexcept; - ~directory_iterator(); - directory_iterator& operator=(const directory_iterator& rhs); - directory_iterator& operator=(directory_iterator&& rhs) noexcept; - const directory_entry& operator*() const; - const directory_entry* operator->() const; -#ifdef GHC_WITH_EXCEPTIONS - directory_iterator& operator++(); -#endif - directory_iterator& increment(std::error_code& ec) noexcept; - - // other members as required by 27.2.3, input iterators -#ifdef GHC_WITH_EXCEPTIONS - proxy operator++(int) - { - proxy p{**this}; - ++*this; - return p; - } -#endif - bool operator==(const directory_iterator& rhs) const; - bool operator!=(const directory_iterator& rhs) const; - -private: - friend class recursive_directory_iterator; - class impl; - std::shared_ptr _impl; -}; - -// 30.10.13.2 directory_iterator non-member functions -GHC_FS_API directory_iterator begin(directory_iterator iter) noexcept; -GHC_FS_API directory_iterator end(const directory_iterator&) noexcept; - -// 30.10.14 class recursive_directory_iterator -class GHC_FS_API_CLASS recursive_directory_iterator -{ -public: - using iterator_category = std::input_iterator_tag; - using value_type = directory_entry; - using difference_type = std::ptrdiff_t; - using pointer = const directory_entry*; - using reference = const directory_entry&; - - // 30.10.14.1 constructors and destructor - recursive_directory_iterator() noexcept; -#ifdef GHC_WITH_EXCEPTIONS - explicit recursive_directory_iterator(const path& p); - recursive_directory_iterator(const path& p, directory_options options); -#endif - recursive_directory_iterator(const path& p, directory_options options, std::error_code& ec) noexcept; - recursive_directory_iterator(const path& p, std::error_code& ec) noexcept; - recursive_directory_iterator(const recursive_directory_iterator& rhs); - recursive_directory_iterator(recursive_directory_iterator&& rhs) noexcept; - ~recursive_directory_iterator(); - - // 30.10.14.1 observers - directory_options options() const; - int depth() const; - bool recursion_pending() const; - - const directory_entry& operator*() const; - const directory_entry* operator->() const; - - // 30.10.14.1 modifiers recursive_directory_iterator& - recursive_directory_iterator& operator=(const recursive_directory_iterator& rhs); - recursive_directory_iterator& operator=(recursive_directory_iterator&& rhs) noexcept; -#ifdef GHC_WITH_EXCEPTIONS - recursive_directory_iterator& operator++(); -#endif - recursive_directory_iterator& increment(std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS - void pop(); -#endif - void pop(std::error_code& ec); - void disable_recursion_pending(); - - // other members as required by 27.2.3, input iterators -#ifdef GHC_WITH_EXCEPTIONS - directory_iterator::proxy operator++(int) - { - directory_iterator::proxy proxy{**this}; - ++*this; - return proxy; - } -#endif - bool operator==(const recursive_directory_iterator& rhs) const; - bool operator!=(const recursive_directory_iterator& rhs) const; - -private: - struct recursive_directory_iterator_impl - { - directory_options _options; - bool _recursion_pending; - std::stack _dir_iter_stack; - recursive_directory_iterator_impl(directory_options options, bool recursion_pending) - : _options(options) - , _recursion_pending(recursion_pending) - { - } - }; - std::shared_ptr _impl; -}; - -// 30.10.14.2 directory_iterator non-member functions -GHC_FS_API recursive_directory_iterator begin(recursive_directory_iterator iter) noexcept; -GHC_FS_API recursive_directory_iterator end(const recursive_directory_iterator&) noexcept; - -// 30.10.15 filesystem operations -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path absolute(const path& p); -#endif -GHC_FS_API path absolute(const path& p, std::error_code& ec); - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path canonical(const path& p); -#endif -GHC_FS_API path canonical(const path& p, std::error_code& ec); - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void copy(const path& from, const path& to); -#endif -GHC_FS_API void copy(const path& from, const path& to, std::error_code& ec) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void copy(const path& from, const path& to, copy_options options); -#endif -GHC_FS_API void copy(const path& from, const path& to, copy_options options, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool copy_file(const path& from, const path& to); -#endif -GHC_FS_API bool copy_file(const path& from, const path& to, std::error_code& ec) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool copy_file(const path& from, const path& to, copy_options option); -#endif -GHC_FS_API bool copy_file(const path& from, const path& to, copy_options option, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void copy_symlink(const path& existing_symlink, const path& new_symlink); -#endif -GHC_FS_API void copy_symlink(const path& existing_symlink, const path& new_symlink, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool create_directories(const path& p); -#endif -GHC_FS_API bool create_directories(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool create_directory(const path& p); -#endif -GHC_FS_API bool create_directory(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool create_directory(const path& p, const path& attributes); -#endif -GHC_FS_API bool create_directory(const path& p, const path& attributes, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void create_directory_symlink(const path& to, const path& new_symlink); -#endif -GHC_FS_API void create_directory_symlink(const path& to, const path& new_symlink, std::error_code& ec) noexcept; - -#ifndef GHC_OS_WEB -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void create_hard_link(const path& to, const path& new_hard_link); -#endif -GHC_FS_API void create_hard_link(const path& to, const path& new_hard_link, std::error_code& ec) noexcept; -#endif - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void create_symlink(const path& to, const path& new_symlink); -#endif -GHC_FS_API void create_symlink(const path& to, const path& new_symlink, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path current_path(); -#endif -GHC_FS_API path current_path(std::error_code& ec); -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void current_path(const path& p); -#endif -GHC_FS_API void current_path(const path& p, std::error_code& ec) noexcept; - -GHC_FS_API bool exists(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool exists(const path& p); -#endif -GHC_FS_API bool exists(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool equivalent(const path& p1, const path& p2); -#endif -GHC_FS_API bool equivalent(const path& p1, const path& p2, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API uintmax_t file_size(const path& p); -#endif -GHC_FS_API uintmax_t file_size(const path& p, std::error_code& ec) noexcept; - -#ifndef GHC_OS_WEB -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API uintmax_t hard_link_count(const path& p); -#endif -GHC_FS_API uintmax_t hard_link_count(const path& p, std::error_code& ec) noexcept; -#endif - -GHC_FS_API bool is_block_file(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_block_file(const path& p); -#endif -GHC_FS_API bool is_block_file(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_character_file(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_character_file(const path& p); -#endif -GHC_FS_API bool is_character_file(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_directory(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_directory(const path& p); -#endif -GHC_FS_API bool is_directory(const path& p, std::error_code& ec) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_empty(const path& p); -#endif -GHC_FS_API bool is_empty(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_fifo(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_fifo(const path& p); -#endif -GHC_FS_API bool is_fifo(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_other(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_other(const path& p); -#endif -GHC_FS_API bool is_other(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_regular_file(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_regular_file(const path& p); -#endif -GHC_FS_API bool is_regular_file(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_socket(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_socket(const path& p); -#endif -GHC_FS_API bool is_socket(const path& p, std::error_code& ec) noexcept; -GHC_FS_API bool is_symlink(file_status s) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool is_symlink(const path& p); -#endif -GHC_FS_API bool is_symlink(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API file_time_type last_write_time(const path& p); -#endif -GHC_FS_API file_time_type last_write_time(const path& p, std::error_code& ec) noexcept; -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void last_write_time(const path& p, file_time_type new_time); -#endif -GHC_FS_API void last_write_time(const path& p, file_time_type new_time, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void permissions(const path& p, perms prms, perm_options opts = perm_options::replace); -#endif -GHC_FS_API void permissions(const path& p, perms prms, std::error_code& ec) noexcept; -GHC_FS_API void permissions(const path& p, perms prms, perm_options opts, std::error_code& ec); - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path proximate(const path& p, std::error_code& ec); -GHC_FS_API path proximate(const path& p, const path& base = current_path()); -#endif -GHC_FS_API path proximate(const path& p, const path& base, std::error_code& ec); - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path read_symlink(const path& p); -#endif -GHC_FS_API path read_symlink(const path& p, std::error_code& ec); - -GHC_FS_API path relative(const path& p, std::error_code& ec); -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path relative(const path& p, const path& base = current_path()); -#endif -GHC_FS_API path relative(const path& p, const path& base, std::error_code& ec); - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API bool remove(const path& p); -#endif -GHC_FS_API bool remove(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API uintmax_t remove_all(const path& p); -#endif -GHC_FS_API uintmax_t remove_all(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void rename(const path& from, const path& to); -#endif -GHC_FS_API void rename(const path& from, const path& to, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API void resize_file(const path& p, uintmax_t size); -#endif -GHC_FS_API void resize_file(const path& p, uintmax_t size, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API space_info space(const path& p); -#endif -GHC_FS_API space_info space(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API file_status status(const path& p); -#endif -GHC_FS_API file_status status(const path& p, std::error_code& ec) noexcept; - -GHC_FS_API bool status_known(file_status s) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API file_status symlink_status(const path& p); -#endif -GHC_FS_API file_status symlink_status(const path& p, std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path temp_directory_path(); -#endif -GHC_FS_API path temp_directory_path(std::error_code& ec) noexcept; - -#ifdef GHC_WITH_EXCEPTIONS -GHC_FS_API path weakly_canonical(const path& p); -#endif -GHC_FS_API path weakly_canonical(const path& p, std::error_code& ec) noexcept; - -// Non-C++17 add-on std::fstream wrappers with path -template > -class basic_filebuf : public std::basic_filebuf -{ -public: - basic_filebuf() {} - ~basic_filebuf() override {} - basic_filebuf(const basic_filebuf&) = delete; - const basic_filebuf& operator=(const basic_filebuf&) = delete; - basic_filebuf* open(const path& p, std::ios_base::openmode mode) - { -#if defined(GHC_OS_WINDOWS) && !defined(__GLIBCXX__) - return std::basic_filebuf::open(p.wstring().c_str(), mode) ? this : 0; -#else - return std::basic_filebuf::open(p.string().c_str(), mode) ? this : 0; -#endif - } -}; - -template > -class basic_ifstream : public std::basic_ifstream -{ -public: - basic_ifstream() {} -#if defined(GHC_OS_WINDOWS) && !defined(__GLIBCXX__) - explicit basic_ifstream(const path& p, std::ios_base::openmode mode = std::ios_base::in) - : std::basic_ifstream(p.wstring().c_str(), mode) - { - } - void open(const path& p, std::ios_base::openmode mode = std::ios_base::in) { std::basic_ifstream::open(p.wstring().c_str(), mode); } -#else - explicit basic_ifstream(const path& p, std::ios_base::openmode mode = std::ios_base::in) - : std::basic_ifstream(p.string().c_str(), mode) - { - } - void open(const path& p, std::ios_base::openmode mode = std::ios_base::in) { std::basic_ifstream::open(p.string().c_str(), mode); } -#endif - basic_ifstream(const basic_ifstream&) = delete; - const basic_ifstream& operator=(const basic_ifstream&) = delete; - ~basic_ifstream() override {} -}; - -template > -class basic_ofstream : public std::basic_ofstream -{ -public: - basic_ofstream() {} -#if defined(GHC_OS_WINDOWS) && !defined(__GLIBCXX__) - explicit basic_ofstream(const path& p, std::ios_base::openmode mode = std::ios_base::out) - : std::basic_ofstream(p.wstring().c_str(), mode) - { - } - void open(const path& p, std::ios_base::openmode mode = std::ios_base::out) { std::basic_ofstream::open(p.wstring().c_str(), mode); } -#else - explicit basic_ofstream(const path& p, std::ios_base::openmode mode = std::ios_base::out) - : std::basic_ofstream(p.string().c_str(), mode) - { - } - void open(const path& p, std::ios_base::openmode mode = std::ios_base::out) { std::basic_ofstream::open(p.string().c_str(), mode); } -#endif - basic_ofstream(const basic_ofstream&) = delete; - const basic_ofstream& operator=(const basic_ofstream&) = delete; - ~basic_ofstream() override {} -}; - -template > -class basic_fstream : public std::basic_fstream -{ -public: - basic_fstream() {} -#if defined(GHC_OS_WINDOWS) && !defined(__GLIBCXX__) - explicit basic_fstream(const path& p, std::ios_base::openmode mode = std::ios_base::in | std::ios_base::out) - : std::basic_fstream(p.wstring().c_str(), mode) - { - } - void open(const path& p, std::ios_base::openmode mode = std::ios_base::in | std::ios_base::out) { std::basic_fstream::open(p.wstring().c_str(), mode); } -#else - explicit basic_fstream(const path& p, std::ios_base::openmode mode = std::ios_base::in | std::ios_base::out) - : std::basic_fstream(p.string().c_str(), mode) - { - } - void open(const path& p, std::ios_base::openmode mode = std::ios_base::in | std::ios_base::out) { std::basic_fstream::open(p.string().c_str(), mode); } -#endif - basic_fstream(const basic_fstream&) = delete; - const basic_fstream& operator=(const basic_fstream&) = delete; - ~basic_fstream() override {} -}; - -typedef basic_filebuf filebuf; -typedef basic_filebuf wfilebuf; -typedef basic_ifstream ifstream; -typedef basic_ifstream wifstream; -typedef basic_ofstream ofstream; -typedef basic_ofstream wofstream; -typedef basic_fstream fstream; -typedef basic_fstream wfstream; - -class GHC_FS_API_CLASS u8arguments -{ -public: - u8arguments(int& argc, char**& argv); - ~u8arguments() - { - _refargc = _argc; - _refargv = _argv; - } - - bool valid() const { return _isvalid; } - -private: - int _argc; - char** _argv; - int& _refargc; - char**& _refargv; - bool _isvalid; -#ifdef GHC_OS_WINDOWS - std::vector _args; - std::vector _argp; -#endif -}; - -//------------------------------------------------------------------------------------------------- -// Implementation -//------------------------------------------------------------------------------------------------- - -namespace detail { -// GHC_FS_API void postprocess_path_with_format(path::impl_string_type& p, path::format fmt); -enum utf8_states_t { S_STRT = 0, S_RJCT = 8 }; -GHC_FS_API void appendUTF8(std::string& str, uint32_t unicode); -GHC_FS_API bool is_surrogate(uint32_t c); -GHC_FS_API bool is_high_surrogate(uint32_t c); -GHC_FS_API bool is_low_surrogate(uint32_t c); -GHC_FS_API unsigned consumeUtf8Fragment(const unsigned state, const uint8_t fragment, uint32_t& codepoint); -enum class portable_error { - none = 0, - exists, - not_found, - not_supported, - not_implemented, - invalid_argument, - is_a_directory, -}; -GHC_FS_API std::error_code make_error_code(portable_error err); -#ifdef GHC_OS_WINDOWS -GHC_FS_API std::error_code make_system_error(uint32_t err = 0); -#else -GHC_FS_API std::error_code make_system_error(int err = 0); -#endif -} // namespace detail - -namespace detail { - -#ifdef GHC_EXPAND_IMPL - -GHC_INLINE std::error_code make_error_code(portable_error err) -{ -#ifdef GHC_OS_WINDOWS - switch (err) { - case portable_error::none: - return std::error_code(); - case portable_error::exists: - return std::error_code(ERROR_ALREADY_EXISTS, std::system_category()); - case portable_error::not_found: - return std::error_code(ERROR_PATH_NOT_FOUND, std::system_category()); - case portable_error::not_supported: - return std::error_code(ERROR_NOT_SUPPORTED, std::system_category()); - case portable_error::not_implemented: - return std::error_code(ERROR_CALL_NOT_IMPLEMENTED, std::system_category()); - case portable_error::invalid_argument: - return std::error_code(ERROR_INVALID_PARAMETER, std::system_category()); - case portable_error::is_a_directory: -#ifdef ERROR_DIRECTORY_NOT_SUPPORTED - return std::error_code(ERROR_DIRECTORY_NOT_SUPPORTED, std::system_category()); -#else - return std::error_code(ERROR_NOT_SUPPORTED, std::system_category()); -#endif - } -#else - switch (err) { - case portable_error::none: - return std::error_code(); - case portable_error::exists: - return std::error_code(EEXIST, std::system_category()); - case portable_error::not_found: - return std::error_code(ENOENT, std::system_category()); - case portable_error::not_supported: - return std::error_code(ENOTSUP, std::system_category()); - case portable_error::not_implemented: - return std::error_code(ENOSYS, std::system_category()); - case portable_error::invalid_argument: - return std::error_code(EINVAL, std::system_category()); - case portable_error::is_a_directory: - return std::error_code(EISDIR, std::system_category()); - } -#endif - return std::error_code(); -} - -#ifdef GHC_OS_WINDOWS -GHC_INLINE std::error_code make_system_error(uint32_t err) -{ - return std::error_code(err ? static_cast(err) : static_cast(::GetLastError()), std::system_category()); -} -#else -GHC_INLINE std::error_code make_system_error(int err) -{ - return std::error_code(err ? err : errno, std::system_category()); -} -#endif - -#endif // GHC_EXPAND_IMPL - -template -using EnableBitmask = typename std::enable_if::value || std::is_same::value || std::is_same::value || std::is_same::value, Enum>::type; -} // namespace detail - -template -detail::EnableBitmask operator&(Enum X, Enum Y) -{ - using underlying = typename std::underlying_type::type; - return static_cast(static_cast(X) & static_cast(Y)); -} - -template -detail::EnableBitmask operator|(Enum X, Enum Y) -{ - using underlying = typename std::underlying_type::type; - return static_cast(static_cast(X) | static_cast(Y)); -} - -template -detail::EnableBitmask operator^(Enum X, Enum Y) -{ - using underlying = typename std::underlying_type::type; - return static_cast(static_cast(X) ^ static_cast(Y)); -} - -template -detail::EnableBitmask operator~(Enum X) -{ - using underlying = typename std::underlying_type::type; - return static_cast(~static_cast(X)); -} - -template -detail::EnableBitmask& operator&=(Enum& X, Enum Y) -{ - X = X & Y; - return X; -} - -template -detail::EnableBitmask& operator|=(Enum& X, Enum Y) -{ - X = X | Y; - return X; -} - -template -detail::EnableBitmask& operator^=(Enum& X, Enum Y) -{ - X = X ^ Y; - return X; -} - -#ifdef GHC_EXPAND_IMPL - -namespace detail { - -GHC_INLINE bool in_range(uint32_t c, uint32_t lo, uint32_t hi) -{ - return (static_cast(c - lo) < (hi - lo + 1)); -} - -GHC_INLINE bool is_surrogate(uint32_t c) -{ - return in_range(c, 0xd800, 0xdfff); -} - -GHC_INLINE bool is_high_surrogate(uint32_t c) -{ - return (c & 0xfffffc00) == 0xd800; -} - -GHC_INLINE bool is_low_surrogate(uint32_t c) -{ - return (c & 0xfffffc00) == 0xdc00; -} - -GHC_INLINE void appendUTF8(std::string& str, uint32_t unicode) -{ - if (unicode <= 0x7f) { - str.push_back(static_cast(unicode)); - } - else if (unicode >= 0x80 && unicode <= 0x7ff) { - str.push_back(static_cast((unicode >> 6) + 192)); - str.push_back(static_cast((unicode & 0x3f) + 128)); - } - else if ((unicode >= 0x800 && unicode <= 0xd7ff) || (unicode >= 0xe000 && unicode <= 0xffff)) { - str.push_back(static_cast((unicode >> 12) + 224)); - str.push_back(static_cast(((unicode & 0xfff) >> 6) + 128)); - str.push_back(static_cast((unicode & 0x3f) + 128)); - } - else if (unicode >= 0x10000 && unicode <= 0x10ffff) { - str.push_back(static_cast((unicode >> 18) + 240)); - str.push_back(static_cast(((unicode & 0x3ffff) >> 12) + 128)); - str.push_back(static_cast(((unicode & 0xfff) >> 6) + 128)); - str.push_back(static_cast((unicode & 0x3f) + 128)); - } - else { -#ifdef GHC_RAISE_UNICODE_ERRORS - throw filesystem_error("Illegal code point for unicode character.", str, std::make_error_code(std::errc::illegal_byte_sequence)); -#else - appendUTF8(str, 0xfffd); -#endif - } -} - -// Thanks to Bjoern Hoehrmann (https://bjoern.hoehrmann.de/utf-8/decoder/dfa/) -// and Taylor R Campbell for the ideas to this DFA approach of UTF-8 decoding; -// Generating debugging and shrinking my own DFA from scratch was a day of fun! -GHC_INLINE unsigned consumeUtf8Fragment(const unsigned state, const uint8_t fragment, uint32_t& codepoint) -{ - static const uint32_t utf8_state_info[] = { - // encoded states - 0x11111111u, 0x11111111u, 0x77777777u, 0x77777777u, 0x88888888u, 0x88888888u, 0x88888888u, 0x88888888u, 0x22222299u, 0x22222222u, 0x22222222u, 0x22222222u, 0x3333333au, 0x33433333u, 0x9995666bu, 0x99999999u, - 0x88888880u, 0x22818108u, 0x88888881u, 0x88888882u, 0x88888884u, 0x88888887u, 0x88888886u, 0x82218108u, 0x82281108u, 0x88888888u, 0x88888883u, 0x88888885u, 0u, 0u, 0u, 0u, - }; - uint8_t category = fragment < 128 ? 0 : (utf8_state_info[(fragment >> 3) & 0xf] >> ((fragment & 7) << 2)) & 0xf; - codepoint = (state ? (codepoint << 6) | (fragment & 0x3fu) : (0xffu >> category) & fragment); - return state == S_RJCT ? static_cast(S_RJCT) : static_cast((utf8_state_info[category + 16] >> (state << 2)) & 0xf); -} - -GHC_INLINE bool validUtf8(const std::string& utf8String) -{ - std::string::const_iterator iter = utf8String.begin(); - unsigned utf8_state = S_STRT; - std::uint32_t codepoint = 0; - while (iter < utf8String.end()) { - if ((utf8_state = consumeUtf8Fragment(utf8_state, static_cast(*iter++), codepoint)) == S_RJCT) { - return false; - } - } - if (utf8_state) { - return false; - } - return true; -} - -} // namespace detail - -#endif - -namespace detail { - -template ::type* = nullptr> -inline StringType fromUtf8(const std::string& utf8String, const typename StringType::allocator_type& alloc = typename StringType::allocator_type()) -{ - return StringType(utf8String.begin(), utf8String.end(), alloc); -} - -template ::type* = nullptr> -inline StringType fromUtf8(const std::string& utf8String, const typename StringType::allocator_type& alloc = typename StringType::allocator_type()) -{ - StringType result(alloc); - result.reserve(utf8String.length()); - std::string::const_iterator iter = utf8String.begin(); - unsigned utf8_state = S_STRT; - std::uint32_t codepoint = 0; - while (iter < utf8String.end()) { - if ((utf8_state = consumeUtf8Fragment(utf8_state, static_cast(*iter++), codepoint)) == S_STRT) { - if (codepoint <= 0xffff) { - result += static_cast(codepoint); - } - else { - codepoint -= 0x10000; - result += static_cast((codepoint >> 10) + 0xd800); - result += static_cast((codepoint & 0x3ff) + 0xdc00); - } - codepoint = 0; - } - else if (utf8_state == S_RJCT) { -#ifdef GHC_RAISE_UNICODE_ERRORS - throw filesystem_error("Illegal byte sequence for unicode character.", utf8String, std::make_error_code(std::errc::illegal_byte_sequence)); -#else - result += static_cast(0xfffd); - utf8_state = S_STRT; - codepoint = 0; -#endif - } - } - if (utf8_state) { -#ifdef GHC_RAISE_UNICODE_ERRORS - throw filesystem_error("Illegal byte sequence for unicode character.", utf8String, std::make_error_code(std::errc::illegal_byte_sequence)); -#else - result += static_cast(0xfffd); -#endif - } - return result; -} - -template ::type* = nullptr> -inline StringType fromUtf8(const std::string& utf8String, const typename StringType::allocator_type& alloc = typename StringType::allocator_type()) -{ - StringType result(alloc); - result.reserve(utf8String.length()); - std::string::const_iterator iter = utf8String.begin(); - unsigned utf8_state = S_STRT; - std::uint32_t codepoint = 0; - while (iter < utf8String.end()) { - if ((utf8_state = consumeUtf8Fragment(utf8_state, static_cast(*iter++), codepoint)) == S_STRT) { - result += static_cast(codepoint); - codepoint = 0; - } - else if (utf8_state == S_RJCT) { -#ifdef GHC_RAISE_UNICODE_ERRORS - throw filesystem_error("Illegal byte sequence for unicode character.", utf8String, std::make_error_code(std::errc::illegal_byte_sequence)); -#else - result += static_cast(0xfffd); - utf8_state = S_STRT; - codepoint = 0; -#endif - } - } - if (utf8_state) { -#ifdef GHC_RAISE_UNICODE_ERRORS - throw filesystem_error("Illegal byte sequence for unicode character.", utf8String, std::make_error_code(std::errc::illegal_byte_sequence)); -#else - result += static_cast(0xfffd); -#endif - } - return result; -} - -template ::type size = 1> -inline std::string toUtf8(const std::basic_string& unicodeString) -{ - return std::string(unicodeString.begin(), unicodeString.end()); -} - -template ::type size = 2> -inline std::string toUtf8(const std::basic_string& unicodeString) -{ - std::string result; - for (auto iter = unicodeString.begin(); iter != unicodeString.end(); ++iter) { - char32_t c = *iter; - if (is_surrogate(c)) { - ++iter; - if (iter != unicodeString.end() && is_high_surrogate(c) && is_low_surrogate(*iter)) { - appendUTF8(result, (char32_t(c) << 10) + *iter - 0x35fdc00); - } - else { -#ifdef GHC_RAISE_UNICODE_ERRORS - throw filesystem_error("Illegal code point for unicode character.", result, std::make_error_code(std::errc::illegal_byte_sequence)); -#else - appendUTF8(result, 0xfffd); - if(iter == unicodeString.end()) { - break; - } -#endif - } - } - else { - appendUTF8(result, c); - } - } - return result; -} - -template ::type size = 4> -inline std::string toUtf8(const std::basic_string& unicodeString) -{ - std::string result; - for (auto c : unicodeString) { - appendUTF8(result, static_cast(c)); - } - return result; -} - -template -inline std::string toUtf8(const charT* unicodeString) -{ - return toUtf8(std::basic_string>(unicodeString)); -} - -} // namespace detail - -#ifdef GHC_EXPAND_IMPL - -namespace detail { - -GHC_INLINE bool startsWith(const std::string& what, const std::string& with) -{ - return with.length() <= what.length() && equal(with.begin(), with.end(), what.begin()); -} - -} // namespace detail - -GHC_INLINE void path::postprocess_path_with_format(path::impl_string_type& p, path::format fmt) -{ -#ifdef GHC_RAISE_UNICODE_ERRORS - if(!detail::validUtf8(p)) { - path t; - t._path = p; - throw filesystem_error("Illegal byte sequence for unicode character.", t, std::make_error_code(std::errc::illegal_byte_sequence)); - } -#endif - switch (fmt) { -#ifndef GHC_OS_WINDOWS - case path::auto_format: - case path::native_format: -#endif - case path::generic_format: - // nothing to do - break; -#ifdef GHC_OS_WINDOWS - case path::auto_format: - case path::native_format: - if (detail::startsWith(p, std::string("\\\\?\\"))) { - // remove Windows long filename marker - p.erase(0, 4); - if (detail::startsWith(p, std::string("UNC\\"))) { - p.erase(0, 2); - p[0] = '\\'; - } - } - for (auto& c : p) { - if (c == '\\') { - c = '/'; - } - } - break; -#endif - } - if (p.length() > 2 && p[0] == '/' && p[1] == '/' && p[2] != '/') { - std::string::iterator new_end = std::unique(p.begin() + 2, p.end(), [](path::value_type lhs, path::value_type rhs) { return lhs == rhs && lhs == '/'; }); - p.erase(new_end, p.end()); - } - else { - std::string::iterator new_end = std::unique(p.begin(), p.end(), [](path::value_type lhs, path::value_type rhs) { return lhs == rhs && lhs == '/'; }); - p.erase(new_end, p.end()); - } -} - -#endif // GHC_EXPAND_IMPL - -template -inline path::path(const Source& source, format fmt) - : _path(detail::toUtf8(source)) -{ - postprocess_path_with_format(_path, fmt); -} -template <> -inline path::path(const std::wstring& source, format fmt) -{ - _path = detail::toUtf8(source); - postprocess_path_with_format(_path, fmt); -} -template <> -inline path::path(const std::u16string& source, format fmt) -{ - _path = detail::toUtf8(source); - postprocess_path_with_format(_path, fmt); -} -template <> -inline path::path(const std::u32string& source, format fmt) -{ - _path = detail::toUtf8(source); - postprocess_path_with_format(_path, fmt); -} - -#ifdef __cpp_lib_string_view -template <> -inline path::path(const std::string_view& source, format fmt) -{ - _path = detail::toUtf8(std::string(source)); - postprocess_path_with_format(_path, fmt); -} -#ifdef GHC_USE_WCHAR_T -template <> -inline path::path(const std::wstring_view& source, format fmt) -{ - _path = detail::toUtf8(std::wstring(source).c_str()); - postprocess_path_with_format(_path, fmt); -} -#endif -#endif - -template -inline path u8path(const Source& source) -{ - return path(source); -} -template -inline path u8path(InputIterator first, InputIterator last) -{ - return path(first, last); -} - -template -inline path::path(InputIterator first, InputIterator last, format fmt) - : path(std::basic_string::value_type>(first, last), fmt) -{ - // delegated -} - -#ifdef GHC_EXPAND_IMPL - -namespace detail { - -GHC_INLINE bool equals_simple_insensitive(const char* str1, const char* str2) -{ -#ifdef GHC_OS_WINDOWS -#ifdef __GNUC__ - while (::tolower((unsigned char)*str1) == ::tolower((unsigned char)*str2++)) { - if (*str1++ == 0) - return true; - } - return false; -#else - return 0 == ::_stricmp(str1, str2); -#endif -#else - return 0 == ::strcasecmp(str1, str2); -#endif -} - -GHC_INLINE const char* strerror_adapter(char* gnu, char*) -{ - return gnu; -} - -GHC_INLINE const char* strerror_adapter(int posix, char* buffer) -{ - if(posix) { - return "Error in strerror_r!"; - } - return buffer; -} - -template -GHC_INLINE std::string systemErrorText(ErrorNumber code = 0) -{ -#if defined(GHC_OS_WINDOWS) - LPVOID msgBuf; - DWORD dw = code ? static_cast(code) : ::GetLastError(); - FormatMessageW(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, NULL, dw, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPWSTR)&msgBuf, 0, NULL); - std::string msg = toUtf8(std::wstring((LPWSTR)msgBuf)); - LocalFree(msgBuf); - return msg; -#else - char buffer[512]; - return strerror_adapter(strerror_r(code ? code : errno, buffer, sizeof(buffer)), buffer); -#endif -} - -#ifdef GHC_OS_WINDOWS -using CreateSymbolicLinkW_fp = BOOLEAN(WINAPI*)(LPCWSTR, LPCWSTR, DWORD); -using CreateHardLinkW_fp = BOOLEAN(WINAPI*)(LPCWSTR, LPCWSTR, LPSECURITY_ATTRIBUTES); - -GHC_INLINE void create_symlink(const path& target_name, const path& new_symlink, bool to_directory, std::error_code& ec) -{ - std::error_code tec; - auto fs = status(target_name, tec); - if ((fs.type() == file_type::directory && !to_directory) || (fs.type() == file_type::regular && to_directory)) { - ec = detail::make_error_code(detail::portable_error::not_supported); - return; - } -#if defined(__GNUC__) && __GNUC__ >= 8 -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wcast-function-type" -#endif - static CreateSymbolicLinkW_fp api_call = reinterpret_cast(GetProcAddress(GetModuleHandleW(L"kernel32.dll"), "CreateSymbolicLinkW")); -#if defined(__GNUC__) && __GNUC__ >= 8 -#pragma GCC diagnostic pop -#endif - if (api_call) { - if (api_call(detail::fromUtf8(new_symlink.u8string()).c_str(), detail::fromUtf8(target_name.u8string()).c_str(), to_directory ? 1 : 0) == 0) { - auto result = ::GetLastError(); - if (result == ERROR_PRIVILEGE_NOT_HELD && api_call(detail::fromUtf8(new_symlink.u8string()).c_str(), detail::fromUtf8(target_name.u8string()).c_str(), to_directory ? 3 : 2) != 0) { - return; - } - ec = detail::make_system_error(result); - } - } - else { - ec = detail::make_system_error(ERROR_NOT_SUPPORTED); - } -} - -GHC_INLINE void create_hardlink(const path& target_name, const path& new_hardlink, std::error_code& ec) -{ -#if defined(__GNUC__) && __GNUC__ >= 8 -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wcast-function-type" -#endif - static CreateHardLinkW_fp api_call = reinterpret_cast(GetProcAddress(GetModuleHandleW(L"kernel32.dll"), "CreateHardLinkW")); -#if defined(__GNUC__) && __GNUC__ >= 8 -#pragma GCC diagnostic pop -#endif - if (api_call) { - if (api_call(detail::fromUtf8(new_hardlink.u8string()).c_str(), detail::fromUtf8(target_name.u8string()).c_str(), NULL) == 0) { - ec = detail::make_system_error(); - } - } - else { - ec = detail::make_system_error(ERROR_NOT_SUPPORTED); - } -} -#else -GHC_INLINE void create_symlink(const path& target_name, const path& new_symlink, bool, std::error_code& ec) -{ - if (::symlink(target_name.c_str(), new_symlink.c_str()) != 0) { - ec = detail::make_system_error(); - } -} - -#ifndef GHC_OS_WEB -GHC_INLINE void create_hardlink(const path& target_name, const path& new_hardlink, std::error_code& ec) -{ - if (::link(target_name.c_str(), new_hardlink.c_str()) != 0) { - ec = detail::make_system_error(); - } -} -#endif -#endif - -template -GHC_INLINE file_status file_status_from_st_mode(T mode) -{ -#ifdef GHC_OS_WINDOWS - file_type ft = file_type::unknown; - if ((mode & _S_IFDIR) == _S_IFDIR) { - ft = file_type::directory; - } - else if ((mode & _S_IFREG) == _S_IFREG) { - ft = file_type::regular; - } - else if ((mode & _S_IFCHR) == _S_IFCHR) { - ft = file_type::character; - } - perms prms = static_cast(mode & 0xfff); - return file_status(ft, prms); -#else - file_type ft = file_type::unknown; - if (S_ISDIR(mode)) { - ft = file_type::directory; - } - else if (S_ISREG(mode)) { - ft = file_type::regular; - } - else if (S_ISCHR(mode)) { - ft = file_type::character; - } - else if (S_ISBLK(mode)) { - ft = file_type::block; - } - else if (S_ISFIFO(mode)) { - ft = file_type::fifo; - } - else if (S_ISLNK(mode)) { - ft = file_type::symlink; - } - else if (S_ISSOCK(mode)) { - ft = file_type::socket; - } - perms prms = static_cast(mode & 0xfff); - return file_status(ft, prms); -#endif -} - -GHC_INLINE path resolveSymlink(const path& p, std::error_code& ec) -{ -#ifdef GHC_OS_WINDOWS -#ifndef REPARSE_DATA_BUFFER_HEADER_SIZE - typedef struct _REPARSE_DATA_BUFFER - { - ULONG ReparseTag; - USHORT ReparseDataLength; - USHORT Reserved; - union - { - struct - { - USHORT SubstituteNameOffset; - USHORT SubstituteNameLength; - USHORT PrintNameOffset; - USHORT PrintNameLength; - ULONG Flags; - WCHAR PathBuffer[1]; - } SymbolicLinkReparseBuffer; - struct - { - USHORT SubstituteNameOffset; - USHORT SubstituteNameLength; - USHORT PrintNameOffset; - USHORT PrintNameLength; - WCHAR PathBuffer[1]; - } MountPointReparseBuffer; - struct - { - UCHAR DataBuffer[1]; - } GenericReparseBuffer; - } DUMMYUNIONNAME; - } REPARSE_DATA_BUFFER; -#ifndef MAXIMUM_REPARSE_DATA_BUFFER_SIZE -#define MAXIMUM_REPARSE_DATA_BUFFER_SIZE (16 * 1024) -#endif -#endif - - std::shared_ptr file(CreateFileW(p.wstring().c_str(), 0, FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE, 0, OPEN_EXISTING, FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS, 0), CloseHandle); - if (file.get() == INVALID_HANDLE_VALUE) { - ec = detail::make_system_error(); - return path(); - } - - std::shared_ptr reparseData((REPARSE_DATA_BUFFER*)std::calloc(1, MAXIMUM_REPARSE_DATA_BUFFER_SIZE), std::free); - ULONG bufferUsed; - path result; - if (DeviceIoControl(file.get(), FSCTL_GET_REPARSE_POINT, 0, 0, reparseData.get(), MAXIMUM_REPARSE_DATA_BUFFER_SIZE, &bufferUsed, 0)) { - if (IsReparseTagMicrosoft(reparseData->ReparseTag)) { - switch (reparseData->ReparseTag) { - case IO_REPARSE_TAG_SYMLINK: - result = std::wstring(&reparseData->SymbolicLinkReparseBuffer.PathBuffer[reparseData->SymbolicLinkReparseBuffer.PrintNameOffset / sizeof(WCHAR)], reparseData->SymbolicLinkReparseBuffer.PrintNameLength / sizeof(WCHAR)); - break; - case IO_REPARSE_TAG_MOUNT_POINT: - result = std::wstring(&reparseData->MountPointReparseBuffer.PathBuffer[reparseData->MountPointReparseBuffer.PrintNameOffset / sizeof(WCHAR)], reparseData->MountPointReparseBuffer.PrintNameLength / sizeof(WCHAR)); - break; - default: - break; - } - } - } - else { - ec = detail::make_system_error(); - } - return result; -#else - size_t bufferSize = 256; - while (true) { - std::vector buffer(bufferSize, static_cast(0)); - auto rc = ::readlink(p.c_str(), buffer.data(), buffer.size()); - if (rc < 0) { - ec = detail::make_system_error(); - return path(); - } - else if (rc < static_cast(bufferSize)) { - return path(std::string(buffer.data(), static_cast(rc))); - } - bufferSize *= 2; - } - return path(); -#endif -} - -#ifdef GHC_OS_WINDOWS -GHC_INLINE time_t timeFromFILETIME(const FILETIME& ft) -{ - ULARGE_INTEGER ull; - ull.LowPart = ft.dwLowDateTime; - ull.HighPart = ft.dwHighDateTime; - return static_cast(ull.QuadPart / 10000000ULL - 11644473600ULL); -} - -GHC_INLINE void timeToFILETIME(time_t t, FILETIME& ft) -{ - LONGLONG ll; - ll = Int32x32To64(t, 10000000) + 116444736000000000; - ft.dwLowDateTime = static_cast(ll); - ft.dwHighDateTime = static_cast(ll >> 32); -} - -template -GHC_INLINE uintmax_t hard_links_from_INFO(const INFO* info) -{ - return static_cast(-1); -} - -template <> -GHC_INLINE uintmax_t hard_links_from_INFO(const BY_HANDLE_FILE_INFORMATION* info) -{ - return info->nNumberOfLinks; -} - -template -GHC_INLINE file_status status_from_INFO(const path& p, const INFO* info, std::error_code&, uintmax_t* sz = nullptr, time_t* lwt = nullptr) noexcept -{ - file_type ft = file_type::unknown; - if ((info->dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) { - ft = file_type::symlink; - } - else { - if ((info->dwFileAttributes & FILE_ATTRIBUTE_DIRECTORY)) { - ft = file_type::directory; - } - else { - ft = file_type::regular; - } - } - perms prms = perms::owner_read | perms::group_read | perms::others_read; - if (!(info->dwFileAttributes & FILE_ATTRIBUTE_READONLY)) { - prms = prms | perms::owner_write | perms::group_write | perms::others_write; - } - std::string ext = p.extension().generic_string(); - if (equals_simple_insensitive(ext.c_str(), ".exe") || equals_simple_insensitive(ext.c_str(), ".cmd") || equals_simple_insensitive(ext.c_str(), ".bat") || equals_simple_insensitive(ext.c_str(), ".com")) { - prms = prms | perms::owner_exec | perms::group_exec | perms::others_exec; - } - if (sz) { - *sz = static_cast(info->nFileSizeHigh) << (sizeof(info->nFileSizeHigh) * 8) | info->nFileSizeLow; - } - if (lwt) { - *lwt = detail::timeFromFILETIME(info->ftLastWriteTime); - } - return file_status(ft, prms); -} - -#endif - -GHC_INLINE bool is_not_found_error(std::error_code& ec) -{ -#ifdef GHC_OS_WINDOWS - return ec.value() == ERROR_FILE_NOT_FOUND || ec.value() == ERROR_PATH_NOT_FOUND || ec.value() == ERROR_INVALID_NAME; -#else - return ec.value() == ENOENT || ec.value() == ENOTDIR; -#endif -} - -GHC_INLINE file_status symlink_status_ex(const path& p, std::error_code& ec, uintmax_t* sz = nullptr, uintmax_t* nhl = nullptr, time_t* lwt = nullptr) noexcept -{ -#ifdef GHC_OS_WINDOWS - file_status fs; - WIN32_FILE_ATTRIBUTE_DATA attr; - if (!GetFileAttributesExW(detail::fromUtf8(p.u8string()).c_str(), GetFileExInfoStandard, &attr)) { - ec = detail::make_system_error(); - } - else { - ec.clear(); - fs = detail::status_from_INFO(p, &attr, ec, sz, lwt); - if (nhl) { - *nhl = 0; - } - if (attr.dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT) { - fs.type(file_type::symlink); - } - } - if (detail::is_not_found_error(ec)) { - return file_status(file_type::not_found); - } - return ec ? file_status(file_type::none) : fs; -#else - (void)sz; - (void)nhl; - (void)lwt; - struct ::stat fs; - auto result = ::lstat(p.c_str(), &fs); - if (result == 0) { - ec.clear(); - file_status f_s = detail::file_status_from_st_mode(fs.st_mode); - return f_s; - } - ec = detail::make_system_error(); - if (detail::is_not_found_error(ec)) { - return file_status(file_type::not_found, perms::unknown); - } - return file_status(file_type::none); -#endif -} - -GHC_INLINE file_status status_ex(const path& p, std::error_code& ec, file_status* sls = nullptr, uintmax_t* sz = nullptr, uintmax_t* nhl = nullptr, time_t* lwt = nullptr, int recurse_count = 0) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - if (recurse_count > 16) { - ec = detail::make_system_error(0x2A9 /*ERROR_STOPPED_ON_SYMLINK*/); - return file_status(file_type::unknown); - } - WIN32_FILE_ATTRIBUTE_DATA attr; - if (!::GetFileAttributesExW(p.wstring().c_str(), GetFileExInfoStandard, &attr)) { - ec = detail::make_system_error(); - } - else if (attr.dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT) { - path target = resolveSymlink(p, ec); - file_status result; - if (!ec && !target.empty()) { - if (sls) { - *sls = status_from_INFO(p, &attr, ec); - } - return detail::status_ex(target, ec, nullptr, sz, nhl, lwt, recurse_count + 1); - } - return file_status(file_type::unknown); - } - if (ec) { - if (detail::is_not_found_error(ec)) { - return file_status(file_type::not_found); - } - return file_status(file_type::none); - } - if (nhl) { - *nhl = 0; - } - return detail::status_from_INFO(p, &attr, ec, sz, lwt); -#else - (void)recurse_count; - struct ::stat st; - auto result = ::lstat(p.c_str(), &st); - if (result == 0) { - ec.clear(); - file_status fs = detail::file_status_from_st_mode(st.st_mode); - if (fs.type() == file_type::symlink) { - result = ::stat(p.c_str(), &st); - if (result == 0) { - if (sls) { - *sls = fs; - } - fs = detail::file_status_from_st_mode(st.st_mode); - } - } - if (sz) { - *sz = static_cast(st.st_size); - } - if (nhl) { - *nhl = st.st_nlink; - } - if (lwt) { - *lwt = st.st_mtime; - } - return fs; - } - else { - ec = detail::make_system_error(); - if (detail::is_not_found_error(ec)) { - return file_status(file_type::not_found, perms::unknown); - } - return file_status(file_type::none); - } -#endif -} - -} // namespace detail - -GHC_INLINE u8arguments::u8arguments(int& argc, char**& argv) - : _argc(argc) - , _argv(argv) - , _refargc(argc) - , _refargv(argv) - , _isvalid(false) -{ -#ifdef GHC_OS_WINDOWS - LPWSTR* p; - p = ::CommandLineToArgvW(::GetCommandLineW(), &argc); - _args.reserve(static_cast(argc)); - _argp.reserve(static_cast(argc)); - for (size_t i = 0; i < static_cast(argc); ++i) { - _args.push_back(detail::toUtf8(std::wstring(p[i]))); - _argp.push_back((char*)_args[i].data()); - } - argv = _argp.data(); - ::LocalFree(p); - _isvalid = true; -#else - std::setlocale(LC_ALL, ""); -#if defined(__ANDROID__) && __ANDROID_API__ < 26 - _isvalid = true; -#else - if (detail::equals_simple_insensitive(::nl_langinfo(CODESET), "UTF-8")) { - _isvalid = true; - } -#endif -#endif -} - -//----------------------------------------------------------------------------- -// 30.10.8.4.1 constructors and destructor - -GHC_INLINE path::path() noexcept {} - -GHC_INLINE path::path(const path& p) - : _path(p._path) -{ -} - -GHC_INLINE path::path(path&& p) noexcept - : _path(std::move(p._path)) -{ -} - -GHC_INLINE path::path(string_type&& source, format fmt) -#ifdef GHC_USE_WCHAR_T - : _path(detail::toUtf8(source)) -#else - : _path(std::move(source)) -#endif -{ - postprocess_path_with_format(_path, fmt); -} - -#endif // GHC_EXPAND_IMPL - -#ifdef GHC_WITH_EXCEPTIONS -template -inline path::path(const Source& source, const std::locale& loc, format fmt) - : path(source, fmt) -{ - std::string locName = loc.name(); - if (!(locName.length() >= 5 && (locName.substr(locName.length() - 5) == "UTF-8" || locName.substr(locName.length() - 5) == "utf-8"))) { - throw filesystem_error("This implementation only supports UTF-8 locales!", path(_path), detail::make_error_code(detail::portable_error::not_supported)); - } -} - -template -inline path::path(InputIterator first, InputIterator last, const std::locale& loc, format fmt) - : path(std::basic_string::value_type>(first, last), fmt) -{ - std::string locName = loc.name(); - if (!(locName.length() >= 5 && (locName.substr(locName.length() - 5) == "UTF-8" || locName.substr(locName.length() - 5) == "utf-8"))) { - throw filesystem_error("This implementation only supports UTF-8 locales!", path(_path), detail::make_error_code(detail::portable_error::not_supported)); - } -} -#endif - -#ifdef GHC_EXPAND_IMPL - -GHC_INLINE path::~path() {} - -//----------------------------------------------------------------------------- -// 30.10.8.4.2 assignments - -GHC_INLINE path& path::operator=(const path& p) -{ - _path = p._path; - return *this; -} - -GHC_INLINE path& path::operator=(path&& p) noexcept -{ - _path = std::move(p._path); - return *this; -} - -GHC_INLINE path& path::operator=(path::string_type&& source) -{ - return assign(source); -} - -GHC_INLINE path& path::assign(path::string_type&& source) -{ -#ifdef GHC_USE_WCHAR_T - _path = detail::toUtf8(source); -#else - _path = std::move(source); -#endif - postprocess_path_with_format(_path, native_format); - return *this; -} - -#endif // GHC_EXPAND_IMPL - -template -inline path& path::operator=(const Source& source) -{ - return assign(source); -} - -template -inline path& path::assign(const Source& source) -{ - _path.assign(detail::toUtf8(source)); - postprocess_path_with_format(_path, native_format); - return *this; -} - -template <> -inline path& path::assign(const path& source) -{ - _path = source._path; - return *this; -} - -template -inline path& path::assign(InputIterator first, InputIterator last) -{ - _path.assign(first, last); - postprocess_path_with_format(_path, native_format); - return *this; -} - -#ifdef GHC_EXPAND_IMPL - -//----------------------------------------------------------------------------- -// 30.10.8.4.3 appends - -GHC_INLINE path& path::operator/=(const path& p) -{ - if (p.empty()) { - // was: if ((!has_root_directory() && is_absolute()) || has_filename()) - if (!_path.empty() && _path[_path.length() - 1] != '/' && _path[_path.length() - 1] != ':') { - _path += '/'; - } - return *this; - } - if ((p.is_absolute() && (_path != root_name() || p._path != "/")) || (p.has_root_name() && p.root_name() != root_name())) { - assign(p); - return *this; - } - if (p.has_root_directory()) { - assign(root_name()); - } - else if ((!has_root_directory() && is_absolute()) || has_filename()) { - _path += '/'; - } - auto iter = p.begin(); - bool first = true; - if (p.has_root_name()) { - ++iter; - } - while (iter != p.end()) { - if (!first && !(!_path.empty() && _path[_path.length() - 1] == '/')) { - _path += '/'; - } - first = false; - _path += (*iter++).generic_string(); - } - return *this; -} - -GHC_INLINE void path::append_name(const char* name) -{ - if (_path.empty()) { - this->operator/=(path(name)); - } - else { - if (_path.back() != path::generic_separator) { - _path.push_back(path::generic_separator); - } - _path += name; - } -} - -#endif // GHC_EXPAND_IMPL - -template -inline path& path::operator/=(const Source& source) -{ - return append(source); -} - -template -inline path& path::append(const Source& source) -{ - return this->operator/=(path(detail::toUtf8(source))); -} - -template <> -inline path& path::append(const path& p) -{ - return this->operator/=(p); -} - -template -inline path& path::append(InputIterator first, InputIterator last) -{ - std::basic_string::value_type> part(first, last); - return append(part); -} - -#ifdef GHC_EXPAND_IMPL - -//----------------------------------------------------------------------------- -// 30.10.8.4.4 concatenation - -GHC_INLINE path& path::operator+=(const path& x) -{ - return concat(x._path); -} - -GHC_INLINE path& path::operator+=(const string_type& x) -{ - return concat(x); -} - -#ifdef __cpp_lib_string_view -GHC_INLINE path& path::operator+=(std::basic_string_view x) -{ - return concat(x); -} -#endif - -GHC_INLINE path& path::operator+=(const value_type* x) -{ - return concat(string_type(x)); -} - -GHC_INLINE path& path::operator+=(value_type x) -{ -#ifdef GHC_OS_WINDOWS - if (x == '\\') { - x = generic_separator; - } -#endif - if (_path.empty() || _path.back() != generic_separator) { -#ifdef GHC_USE_WCHAR_T - _path += detail::toUtf8(string_type(1, x)); -#else - _path += x; -#endif - } - return *this; -} - -#endif // GHC_EXPAND_IMPL - -template -inline path::path_from_string& path::operator+=(const Source& x) -{ - return concat(x); -} - -template -inline path::path_type_EcharT& path::operator+=(EcharT x) -{ - std::basic_string part(1, x); - concat(detail::toUtf8(part)); - return *this; -} - -template -inline path& path::concat(const Source& x) -{ - path p(x); - postprocess_path_with_format(p._path, native_format); - _path += p._path; - return *this; -} -template -inline path& path::concat(InputIterator first, InputIterator last) -{ - _path.append(first, last); - postprocess_path_with_format(_path, native_format); - return *this; -} - -#ifdef GHC_EXPAND_IMPL - -//----------------------------------------------------------------------------- -// 30.10.8.4.5 modifiers -GHC_INLINE void path::clear() noexcept -{ - _path.clear(); -} - -GHC_INLINE path& path::make_preferred() -{ - // as this filesystem implementation only uses generic_format - // internally, this must be a no-op - return *this; -} - -GHC_INLINE path& path::remove_filename() -{ - if (has_filename()) { - _path.erase(_path.size() - filename()._path.size()); - } - return *this; -} - -GHC_INLINE path& path::replace_filename(const path& replacement) -{ - remove_filename(); - return append(replacement); -} - -GHC_INLINE path& path::replace_extension(const path& replacement) -{ - if (has_extension()) { - _path.erase(_path.size() - extension()._path.size()); - } - if (!replacement.empty() && replacement._path[0] != '.') { - _path += '.'; - } - return concat(replacement); -} - -GHC_INLINE void path::swap(path& rhs) noexcept -{ - _path.swap(rhs._path); -} - -//----------------------------------------------------------------------------- -// 30.10.8.4.6, native format observers -#ifdef GHC_OS_WINDOWS -GHC_INLINE path::impl_string_type path::native_impl() const -{ - impl_string_type result; - if (is_absolute() && _path.length() > MAX_PATH - 10) { - // expand long Windows filenames with marker - if (has_root_name() && _path[0] == '/') { - result = "\\\\?\\UNC" + _path.substr(1); - } - else { - result = "\\\\?\\" + _path; - } - } - else { - result = _path; - } - /*if (has_root_name() && root_name()._path[0] == '/') { - return _path; - }*/ - for (auto& c : result) { - if (c == '/') { - c = '\\'; - } - } - return result; -} -#else -GHC_INLINE const path::impl_string_type& path::native_impl() const -{ - return _path; -} -#endif - -GHC_INLINE const path::string_type& path::native() const -{ -#ifdef GHC_OS_WINDOWS -#ifdef GHC_USE_WCHAR_T - _native_cache = detail::fromUtf8(native_impl()); -#else - _native_cache = native_impl(); -#endif - return _native_cache; -#else - return _path; -#endif -} - -GHC_INLINE const path::value_type* path::c_str() const -{ - return native().c_str(); -} - -GHC_INLINE path::operator path::string_type() const -{ - return native(); -} - -#endif // GHC_EXPAND_IMPL - -template -inline std::basic_string path::string(const Allocator& a) const -{ - return detail::fromUtf8>(native_impl(), a); -} - -#ifdef GHC_EXPAND_IMPL - -GHC_INLINE std::string path::string() const -{ - return native_impl(); -} - -GHC_INLINE std::wstring path::wstring() const -{ -#ifdef GHC_USE_WCHAR_T - return native(); -#else - return detail::fromUtf8(native()); -#endif -} - -GHC_INLINE std::string path::u8string() const -{ - return native_impl(); -} - -GHC_INLINE std::u16string path::u16string() const -{ - return detail::fromUtf8(native_impl()); -} - -GHC_INLINE std::u32string path::u32string() const -{ - return detail::fromUtf8(native_impl()); -} - -#endif // GHC_EXPAND_IMPL - -//----------------------------------------------------------------------------- -// 30.10.8.4.7, generic format observers -template -inline std::basic_string path::generic_string(const Allocator& a) const -{ - return detail::fromUtf8>(_path, a); -} - -#ifdef GHC_EXPAND_IMPL - -GHC_INLINE const std::string& path::generic_string() const -{ - return _path; -} - -GHC_INLINE std::wstring path::generic_wstring() const -{ - return detail::fromUtf8(_path); -} - -GHC_INLINE std::string path::generic_u8string() const -{ - return _path; -} - -GHC_INLINE std::u16string path::generic_u16string() const -{ - return detail::fromUtf8(_path); -} - -GHC_INLINE std::u32string path::generic_u32string() const -{ - return detail::fromUtf8(_path); -} - -//----------------------------------------------------------------------------- -// 30.10.8.4.8, compare -GHC_INLINE int path::compare(const path& p) const noexcept -{ - return native().compare(p.native()); -} - -GHC_INLINE int path::compare(const string_type& s) const -{ - return native().compare(path(s).native()); -} - -#ifdef __cpp_lib_string_view -GHC_INLINE int path::compare(std::basic_string_view s) const -{ - return native().compare(path(s).native()); -} -#endif - -GHC_INLINE int path::compare(const value_type* s) const -{ - return native().compare(path(s).native()); -} - -//----------------------------------------------------------------------------- -// 30.10.8.4.9, decomposition -GHC_INLINE path path::root_name() const -{ -#ifdef GHC_OS_WINDOWS - if (_path.length() >= 2 && std::toupper(static_cast(_path[0])) >= 'A' && std::toupper(static_cast(_path[0])) <= 'Z' && _path[1] == ':') { - return path(_path.substr(0, 2)); - } -#endif - if (_path.length() > 2 && _path[0] == '/' && _path[1] == '/' && _path[2] != '/' && std::isprint(_path[2])) { - impl_string_type::size_type pos = _path.find_first_of("/\\", 3); - if (pos == impl_string_type::npos) { - return path(_path); - } - else { - return path(_path.substr(0, pos)); - } - } - return path(); -} - -GHC_INLINE path path::root_directory() const -{ - path root = root_name(); - if (_path.length() > root._path.length() && _path[root._path.length()] == '/') { - return path("/"); - } - return path(); -} - -GHC_INLINE path path::root_path() const -{ - return root_name().generic_string() + root_directory().generic_string(); -} - -GHC_INLINE path path::relative_path() const -{ - std::string root = root_path()._path; - return path(_path.substr((std::min)(root.length(), _path.length())), generic_format); -} - -GHC_INLINE path path::parent_path() const -{ - if (has_relative_path()) { - if (empty() || begin() == --end()) { - return path(); - } - else { - path pp; - for (string_type s : input_iterator_range(begin(), --end())) { - if (s == "/") { - // don't use append to join a path- - pp += s; - } - else { - pp /= s; - } - } - return pp; - } - } - else { - return *this; - } -} - -GHC_INLINE path path::filename() const -{ - return relative_path().empty() ? path() : path(*--end()); -} - -GHC_INLINE path path::stem() const -{ - impl_string_type fn = filename().string(); - if (fn != "." && fn != "..") { - impl_string_type::size_type n = fn.rfind('.'); - if (n != impl_string_type::npos && n != 0) { - return path{fn.substr(0, n)}; - } - } - return path{fn}; -} - -GHC_INLINE path path::extension() const -{ - impl_string_type fn = filename().string(); - impl_string_type::size_type pos = fn.find_last_of('.'); - if (pos == std::string::npos || pos == 0) { - return ""; - } - return fn.substr(pos); -} - -//----------------------------------------------------------------------------- -// 30.10.8.4.10, query -GHC_INLINE bool path::empty() const noexcept -{ - return _path.empty(); -} - -GHC_INLINE bool path::has_root_name() const -{ - return !root_name().empty(); -} - -GHC_INLINE bool path::has_root_directory() const -{ - return !root_directory().empty(); -} - -GHC_INLINE bool path::has_root_path() const -{ - return !root_path().empty(); -} - -GHC_INLINE bool path::has_relative_path() const -{ - return !relative_path().empty(); -} - -GHC_INLINE bool path::has_parent_path() const -{ - return !parent_path().empty(); -} - -GHC_INLINE bool path::has_filename() const -{ - return !filename().empty(); -} - -GHC_INLINE bool path::has_stem() const -{ - return !stem().empty(); -} - -GHC_INLINE bool path::has_extension() const -{ - return !extension().empty(); -} - -GHC_INLINE bool path::is_absolute() const -{ -#ifdef GHC_OS_WINDOWS - return has_root_name() && has_root_directory(); -#else - return has_root_directory(); -#endif -} - -GHC_INLINE bool path::is_relative() const -{ - return !is_absolute(); -} - -//----------------------------------------------------------------------------- -// 30.10.8.4.11, generation -GHC_INLINE path path::lexically_normal() const -{ - path dest; - bool lastDotDot = false; - for (string_type s : *this) { - if (s == ".") { - dest /= ""; - continue; - } - else if (s == ".." && !dest.empty()) { - auto root = root_path(); - if (dest == root) { - continue; - } - else if (*(--dest.end()) != "..") { - if (dest._path.back() == generic_separator) { - dest._path.pop_back(); - } - dest.remove_filename(); - continue; - } - } - if (!(s.empty() && lastDotDot)) { - dest /= s; - } - lastDotDot = s == ".."; - } - if (dest.empty()) { - dest = "."; - } - return dest; -} - -GHC_INLINE path path::lexically_relative(const path& base) const -{ - if (root_name() != base.root_name() || is_absolute() != base.is_absolute() || (!has_root_directory() && base.has_root_directory())) { - return path(); - } - const_iterator a = begin(), b = base.begin(); - while (a != end() && b != base.end() && *a == *b) { - ++a; - ++b; - } - if (a == end() && b == base.end()) { - return path("."); - } - int count = 0; - for (const auto& element : input_iterator_range(b, base.end())) { - if (element != "." && element != "" && element != "..") { - ++count; - } - else if (element == "..") { - --count; - } - } - if (count < 0) { - return path(); - } - path result; - for (int i = 0; i < count; ++i) { - result /= ".."; - } - for (const auto& element : input_iterator_range(a, end())) { - result /= element; - } - return result; -} - -GHC_INLINE path path::lexically_proximate(const path& base) const -{ - path result = lexically_relative(base); - return result.empty() ? *this : result; -} - -//----------------------------------------------------------------------------- -// 30.10.8.5, iterators -GHC_INLINE path::iterator::iterator() {} - -GHC_INLINE path::iterator::iterator(const path::impl_string_type::const_iterator& first, const path::impl_string_type::const_iterator& last, const path::impl_string_type::const_iterator& pos) - : _first(first) - , _last(last) - , _iter(pos) -{ - updateCurrent(); - // find the position of a potential root directory slash -#ifdef GHC_OS_WINDOWS - if (_last - _first >= 3 && std::toupper(static_cast(*first)) >= 'A' && std::toupper(static_cast(*first)) <= 'Z' && *(first + 1) == ':' && *(first + 2) == '/') { - _root = _first + 2; - } - else -#endif - { - if (_first != _last && *_first == '/') { - if (_last - _first >= 2 && *(_first + 1) == '/' && !(_last - _first >= 3 && *(_first + 2) == '/')) { - _root = increment(_first); - } - else { - _root = _first; - } - } - else { - _root = _last; - } - } -} - -GHC_INLINE path::impl_string_type::const_iterator path::iterator::increment(const path::impl_string_type::const_iterator& pos) const -{ - path::impl_string_type::const_iterator i = pos; - bool fromStart = i == _first; - if (i != _last) { - // we can only sit on a slash if it is a network name or a root - if (*i++ == '/') { - if (i != _last && *i == '/') { - if (fromStart && !(i + 1 != _last && *(i + 1) == '/')) { - // leadind double slashes detected, treat this and the - // following until a slash as one unit - i = std::find(++i, _last, '/'); - } - else { - // skip redundant slashes - while (i != _last && *i == '/') { - ++i; - } - } - } - } - else { - if (fromStart && i != _last && *i == ':') { - ++i; - } - else { - i = std::find(i, _last, '/'); - } - } - } - return i; -} - -GHC_INLINE path::impl_string_type::const_iterator path::iterator::decrement(const path::impl_string_type::const_iterator& pos) const -{ - path::impl_string_type::const_iterator i = pos; - if (i != _first) { - --i; - // if this is now the root slash or the trailing slash, we are done, - // else check for network name - if (i != _root && (pos != _last || *i != '/')) { -#ifdef GHC_OS_WINDOWS - static const std::string seps = "/:"; - i = std::find_first_of(std::reverse_iterator(i), std::reverse_iterator(_first), seps.begin(), seps.end()).base(); - if (i > _first && *i == ':') { - i++; - } -#else - i = std::find(std::reverse_iterator(i), std::reverse_iterator(_first), '/').base(); -#endif - // Now we have to check if this is a network name - if (i - _first == 2 && *_first == '/' && *(_first + 1) == '/') { - i -= 2; - } - } - } - return i; -} - -GHC_INLINE void path::iterator::updateCurrent() -{ - if (_iter != _first && _iter != _last && (*_iter == '/' && _iter != _root) && (_iter + 1 == _last)) { - _current = ""; - } - else { - _current.assign(_iter, increment(_iter)); - if (_current.generic_string().size() > 1 && _current.generic_string()[0] == '/' && _current.generic_string()[_current.generic_string().size() - 1] == '/') { - // shrink successive slashes to one - _current = "/"; - } - } -} - -GHC_INLINE path::iterator& path::iterator::operator++() -{ - _iter = increment(_iter); - while (_iter != _last && // we didn't reach the end - _iter != _root && // this is not a root position - *_iter == '/' && // we are on a slash - (_iter + 1) != _last // the slash is not the last char - ) { - ++_iter; - } - updateCurrent(); - return *this; -} - -GHC_INLINE path::iterator path::iterator::operator++(int) -{ - path::iterator i{*this}; - ++(*this); - return i; -} - -GHC_INLINE path::iterator& path::iterator::operator--() -{ - _iter = decrement(_iter); - updateCurrent(); - return *this; -} - -GHC_INLINE path::iterator path::iterator::operator--(int) -{ - auto i = *this; - --(*this); - return i; -} - -GHC_INLINE bool path::iterator::operator==(const path::iterator& other) const -{ - return _iter == other._iter; -} - -GHC_INLINE bool path::iterator::operator!=(const path::iterator& other) const -{ - return _iter != other._iter; -} - -GHC_INLINE path::iterator::reference path::iterator::operator*() const -{ - return _current; -} - -GHC_INLINE path::iterator::pointer path::iterator::operator->() const -{ - return &_current; -} - -GHC_INLINE path::iterator path::begin() const -{ - return iterator(_path.begin(), _path.end(), _path.begin()); -} - -GHC_INLINE path::iterator path::end() const -{ - return iterator(_path.begin(), _path.end(), _path.end()); -} - -//----------------------------------------------------------------------------- -// 30.10.8.6, path non-member functions -GHC_INLINE void swap(path& lhs, path& rhs) noexcept -{ - swap(lhs._path, rhs._path); -} - -GHC_INLINE size_t hash_value(const path& p) noexcept -{ - return std::hash()(p.generic_string()); -} - -GHC_INLINE bool operator==(const path& lhs, const path& rhs) noexcept -{ - return lhs.generic_string() == rhs.generic_string(); -} - -GHC_INLINE bool operator!=(const path& lhs, const path& rhs) noexcept -{ - return lhs.generic_string() != rhs.generic_string(); -} - -GHC_INLINE bool operator<(const path& lhs, const path& rhs) noexcept -{ - return lhs.generic_string() < rhs.generic_string(); -} - -GHC_INLINE bool operator<=(const path& lhs, const path& rhs) noexcept -{ - return lhs.generic_string() <= rhs.generic_string(); -} - -GHC_INLINE bool operator>(const path& lhs, const path& rhs) noexcept -{ - return lhs.generic_string() > rhs.generic_string(); -} - -GHC_INLINE bool operator>=(const path& lhs, const path& rhs) noexcept -{ - return lhs.generic_string() >= rhs.generic_string(); -} - -GHC_INLINE path operator/(const path& lhs, const path& rhs) -{ - path result(lhs); - result /= rhs; - return result; -} - -#endif // GHC_EXPAND_IMPL - -//----------------------------------------------------------------------------- -// 30.10.8.6.1 path inserter and extractor -template -inline std::basic_ostream& operator<<(std::basic_ostream& os, const path& p) -{ - os << "\""; - auto ps = p.string(); - for (auto c : ps) { - if (c == '"' || c == '\\') { - os << '\\'; - } - os << c; - } - os << "\""; - return os; -} - -template -inline std::basic_istream& operator>>(std::basic_istream& is, path& p) -{ - std::basic_string tmp; - charT c; - is >> c; - if (c == '"') { - auto sf = is.flags(); - is >> std::noskipws; - while (is) { - auto c2 = is.get(); - if (is) { - if (c2 == '\\') { - c2 = is.get(); - if (is) { - tmp += static_cast(c2); - } - } - else if (c2 == '"') { - break; - } - else { - tmp += static_cast(c2); - } - } - } - if ((sf & std::ios_base::skipws) == std::ios_base::skipws) { - is >> std::skipws; - } - p = path(tmp); - } - else { - is >> tmp; - p = path(static_cast(c) + tmp); - } - return is; -} - -#ifdef GHC_EXPAND_IMPL - -//----------------------------------------------------------------------------- -// 30.10.9 Class filesystem_error -GHC_INLINE filesystem_error::filesystem_error(const std::string& what_arg, std::error_code ec) - : std::system_error(ec, what_arg) - , _what_arg(what_arg) - , _ec(ec) -{ -} - -GHC_INLINE filesystem_error::filesystem_error(const std::string& what_arg, const path& p1, std::error_code ec) - : std::system_error(ec, what_arg) - , _what_arg(what_arg) - , _ec(ec) - , _p1(p1) -{ - if (!_p1.empty()) { - _what_arg += ": '" + _p1.u8string() + "'"; - } -} - -GHC_INLINE filesystem_error::filesystem_error(const std::string& what_arg, const path& p1, const path& p2, std::error_code ec) - : std::system_error(ec, what_arg) - , _what_arg(what_arg) - , _ec(ec) - , _p1(p1) - , _p2(p2) -{ - if (!_p1.empty()) { - _what_arg += ": '" + _p1.u8string() + "'"; - } - if (!_p2.empty()) { - _what_arg += ", '" + _p2.u8string() + "'"; - } -} - -GHC_INLINE const path& filesystem_error::path1() const noexcept -{ - return _p1; -} - -GHC_INLINE const path& filesystem_error::path2() const noexcept -{ - return _p2; -} - -GHC_INLINE const char* filesystem_error::what() const noexcept -{ - return _what_arg.c_str(); -} - -//----------------------------------------------------------------------------- -// 30.10.15, filesystem operations -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path absolute(const path& p) -{ - std::error_code ec; - path result = absolute(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE path absolute(const path& p, std::error_code& ec) -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - if (p.empty()) { - return absolute(current_path(ec), ec) / ""; - } - ULONG size = ::GetFullPathNameW(p.wstring().c_str(), 0, 0, 0); - if (size) { - std::vector buf(size, 0); - ULONG s2 = GetFullPathNameW(p.wstring().c_str(), size, buf.data(), nullptr); - if (s2 && s2 < size) { - path result = path(std::wstring(buf.data(), s2)); - if (p.filename() == ".") { - result /= "."; - } - return result; - } - } - ec = detail::make_system_error(); - return path(); -#else - path base = current_path(ec); - if (!ec) { - if (p.empty()) { - return base / p; - } - if (p.has_root_name()) { - if (p.has_root_directory()) { - return p; - } - else { - return p.root_name() / base.root_directory() / base.relative_path() / p.relative_path(); - } - } - else { - if (p.has_root_directory()) { - return base.root_name() / p; - } - else { - return base / p; - } - } - } - ec = detail::make_system_error(); - return path(); -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path canonical(const path& p) -{ - std::error_code ec; - auto result = canonical(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE path canonical(const path& p, std::error_code& ec) -{ - if (p.empty()) { - ec = detail::make_error_code(detail::portable_error::not_found); - return path(); - } - path work = p.is_absolute() ? p : absolute(p, ec); - path root = work.root_path(); - path result; - - auto fs = status(work, ec); - if (ec) { - return path(); - } - if (fs.type() == file_type::not_found) { - ec = detail::make_error_code(detail::portable_error::not_found); - return path(); - } - bool redo; - do { - redo = false; - result.clear(); - for (auto pe : work) { - if (pe.empty() || pe == ".") { - continue; - } - else if (pe == "..") { - result = result.parent_path(); - continue; - } - else if ((result / pe).string().length() <= root.string().length()) { - result /= pe; - continue; - } - auto sls = symlink_status(result / pe, ec); - if (ec) { - return path(); - } - if (is_symlink(sls)) { - redo = true; - auto target = read_symlink(result / pe, ec); - if (ec) { - return path(); - } - if (target.is_absolute()) { - result = target; - continue; - } - else { - result /= target; - continue; - } - } - else { - result /= pe; - } - } - work = result; - } while (redo); - ec.clear(); - return result; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void copy(const path& from, const path& to) -{ - copy(from, to, copy_options::none); -} -#endif - -GHC_INLINE void copy(const path& from, const path& to, std::error_code& ec) noexcept -{ - copy(from, to, copy_options::none, ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void copy(const path& from, const path& to, copy_options options) -{ - std::error_code ec; - copy(from, to, options, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), from, to, ec); - } -} -#endif - -GHC_INLINE void copy(const path& from, const path& to, copy_options options, std::error_code& ec) noexcept -{ - std::error_code tec; - file_status fs_from, fs_to; - ec.clear(); - if ((options & (copy_options::skip_symlinks | copy_options::copy_symlinks | copy_options::create_symlinks)) != copy_options::none) { - fs_from = symlink_status(from, ec); - } - else { - fs_from = status(from, ec); - } - if (!exists(fs_from)) { - if (!ec) { - ec = detail::make_error_code(detail::portable_error::not_found); - } - return; - } - if ((options & (copy_options::skip_symlinks | copy_options::create_symlinks)) != copy_options::none) { - fs_to = symlink_status(to, tec); - } - else { - fs_to = status(to, tec); - } - if (is_other(fs_from) || is_other(fs_to) || (is_directory(fs_from) && is_regular_file(fs_to)) || (exists(fs_to) && equivalent(from, to, ec))) { - ec = detail::make_error_code(detail::portable_error::invalid_argument); - } - else if (is_symlink(fs_from)) { - if ((options & copy_options::skip_symlinks) == copy_options::none) { - if (!exists(fs_to) && (options & copy_options::copy_symlinks) != copy_options::none) { - copy_symlink(from, to, ec); - } - else { - ec = detail::make_error_code(detail::portable_error::invalid_argument); - } - } - } - else if (is_regular_file(fs_from)) { - if ((options & copy_options::directories_only) == copy_options::none) { - if ((options & copy_options::create_symlinks) != copy_options::none) { - create_symlink(from.is_absolute() ? from : canonical(from, ec), to, ec); - } -#ifndef GHC_OS_WEB - else if ((options & copy_options::create_hard_links) != copy_options::none) { - create_hard_link(from, to, ec); - } -#endif - else if (is_directory(fs_to)) { - copy_file(from, to / from.filename(), options, ec); - } - else { - copy_file(from, to, options, ec); - } - } - } -#ifdef LWG_2682_BEHAVIOUR - else if (is_directory(fs_from) && (options & copy_options::create_symlinks) != copy_options::none) { - ec = detail::make_error_code(detail::portable_error::is_a_directory); - } -#endif - else if (is_directory(fs_from) && (options == copy_options::none || (options & copy_options::recursive) != copy_options::none)) { - if (!exists(fs_to)) { - create_directory(to, from, ec); - if (ec) { - return; - } - } - for (auto iter = directory_iterator(from, ec); iter != directory_iterator(); iter.increment(ec)) { - if (!ec) { - copy(iter->path(), to / iter->path().filename(), options | static_cast(0x8000), ec); - } - if (ec) { - return; - } - } - } - return; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool copy_file(const path& from, const path& to) -{ - return copy_file(from, to, copy_options::none); -} -#endif - -GHC_INLINE bool copy_file(const path& from, const path& to, std::error_code& ec) noexcept -{ - return copy_file(from, to, copy_options::none, ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool copy_file(const path& from, const path& to, copy_options option) -{ - std::error_code ec; - auto result = copy_file(from, to, option, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), from, to, ec); - } - return result; -} -#endif - -GHC_INLINE bool copy_file(const path& from, const path& to, copy_options options, std::error_code& ec) noexcept -{ - std::error_code tecf, tect; - auto sf = status(from, tecf); - auto st = status(to, tect); - bool overwrite = false; - ec.clear(); - if (!is_regular_file(sf)) { - ec = tecf; - return false; - } - if (exists(st) && (!is_regular_file(st) || equivalent(from, to, ec) || (options & (copy_options::skip_existing | copy_options::overwrite_existing | copy_options::update_existing)) == copy_options::none)) { - ec = tect ? tect : detail::make_error_code(detail::portable_error::exists); - return false; - } - if (exists(st)) { - if ((options & copy_options::update_existing) == copy_options::update_existing) { - auto from_time = last_write_time(from, ec); - if (ec) { - ec = detail::make_system_error(); - return false; - } - auto to_time = last_write_time(to, ec); - if (ec) { - ec = detail::make_system_error(); - return false; - } - if (from_time <= to_time) { - return false; - } - } - overwrite = true; - } -#ifdef GHC_OS_WINDOWS - if (!::CopyFileW(detail::fromUtf8(from.u8string()).c_str(), detail::fromUtf8(to.u8string()).c_str(), !overwrite)) { - ec = detail::make_system_error(); - return false; - } - return true; -#else - std::vector buffer(16384, '\0'); - int in = -1, out = -1; - if ((in = ::open(from.c_str(), O_RDONLY)) < 0) { - ec = detail::make_system_error(); - return false; - } - int mode = O_CREAT | O_WRONLY | O_TRUNC; - if (!overwrite) { - mode |= O_EXCL; - } - if ((out = ::open(to.c_str(), mode, static_cast(sf.permissions() & perms::all))) < 0) { - ec = detail::make_system_error(); - ::close(in); - return false; - } - ssize_t br, bw; - while ((br = ::read(in, buffer.data(), buffer.size())) > 0) { - ssize_t offset = 0; - do { - if ((bw = ::write(out, buffer.data() + offset, static_cast(br))) > 0) { - br -= bw; - offset += bw; - } - else if (bw < 0) { - ec = detail::make_system_error(); - ::close(in); - ::close(out); - return false; - } - } while (br); - } - ::close(in); - ::close(out); - return true; -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void copy_symlink(const path& existing_symlink, const path& new_symlink) -{ - std::error_code ec; - copy_symlink(existing_symlink, new_symlink, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), existing_symlink, new_symlink, ec); - } -} -#endif - -GHC_INLINE void copy_symlink(const path& existing_symlink, const path& new_symlink, std::error_code& ec) noexcept -{ - ec.clear(); - auto to = read_symlink(existing_symlink, ec); - if (!ec) { - if (exists(to, ec) && is_directory(to, ec)) { - create_directory_symlink(to, new_symlink, ec); - } - else { - create_symlink(to, new_symlink, ec); - } - } -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool create_directories(const path& p) -{ - std::error_code ec; - auto result = create_directories(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE bool create_directories(const path& p, std::error_code& ec) noexcept -{ - path current; - ec.clear(); - bool didCreate = false; - for (path::string_type part : p) { - current /= part; - if (current != p.root_name() && current != p.root_path()) { - std::error_code tec; - auto fs = status(current, tec); - if (tec && fs.type() != file_type::not_found) { - ec = tec; - return false; - } - if (!exists(fs)) { - create_directory(current, ec); - if (ec) { - std::error_code tmp_ec; - if (is_directory(current, tmp_ec)) { - ec.clear(); - } else { - return false; - } - } - didCreate = true; - } -#ifndef LWG_2935_BEHAVIOUR - else if (!is_directory(fs)) { - ec = detail::make_error_code(detail::portable_error::exists); - return false; - } -#endif - } - } - return didCreate; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool create_directory(const path& p) -{ - std::error_code ec; - auto result = create_directory(p, path(), ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE bool create_directory(const path& p, std::error_code& ec) noexcept -{ - return create_directory(p, path(), ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool create_directory(const path& p, const path& attributes) -{ - std::error_code ec; - auto result = create_directory(p, attributes, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE bool create_directory(const path& p, const path& attributes, std::error_code& ec) noexcept -{ - std::error_code tec; - ec.clear(); - auto fs = status(p, tec); -#ifdef LWG_2935_BEHAVIOUR - if (status_known(fs) && exists(fs)) { - return false; - } -#else - if (status_known(fs) && exists(fs) && is_directory(fs)) { - return false; - } -#endif -#ifdef GHC_OS_WINDOWS - if (!attributes.empty()) { - if (!::CreateDirectoryExW(detail::fromUtf8(attributes.u8string()).c_str(), detail::fromUtf8(p.u8string()).c_str(), NULL)) { - ec = detail::make_system_error(); - return false; - } - } - else if (!::CreateDirectoryW(detail::fromUtf8(p.u8string()).c_str(), NULL)) { - ec = detail::make_system_error(); - return false; - } -#else - ::mode_t attribs = static_cast(perms::all); - if (!attributes.empty()) { - struct ::stat fileStat; - if (::stat(attributes.c_str(), &fileStat) != 0) { - ec = detail::make_system_error(); - return false; - } - attribs = fileStat.st_mode; - } - if (::mkdir(p.c_str(), attribs) != 0) { - ec = detail::make_system_error(); - return false; - } -#endif - return true; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void create_directory_symlink(const path& to, const path& new_symlink) -{ - std::error_code ec; - create_directory_symlink(to, new_symlink, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), to, new_symlink, ec); - } -} -#endif - -GHC_INLINE void create_directory_symlink(const path& to, const path& new_symlink, std::error_code& ec) noexcept -{ - detail::create_symlink(to, new_symlink, true, ec); -} - -#ifndef GHC_OS_WEB -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void create_hard_link(const path& to, const path& new_hard_link) -{ - std::error_code ec; - create_hard_link(to, new_hard_link, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), to, new_hard_link, ec); - } -} -#endif - -GHC_INLINE void create_hard_link(const path& to, const path& new_hard_link, std::error_code& ec) noexcept -{ - detail::create_hardlink(to, new_hard_link, ec); -} -#endif - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void create_symlink(const path& to, const path& new_symlink) -{ - std::error_code ec; - create_symlink(to, new_symlink, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), to, new_symlink, ec); - } -} -#endif - -GHC_INLINE void create_symlink(const path& to, const path& new_symlink, std::error_code& ec) noexcept -{ - detail::create_symlink(to, new_symlink, false, ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path current_path() -{ - std::error_code ec; - auto result = current_path(ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), ec); - } - return result; -} -#endif - -GHC_INLINE path current_path(std::error_code& ec) -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - DWORD pathlen = ::GetCurrentDirectoryW(0, 0); - std::unique_ptr buffer(new wchar_t[size_t(pathlen) + 1]); - if (::GetCurrentDirectoryW(pathlen, buffer.get()) == 0) { - ec = detail::make_system_error(); - return path(); - } - return path(std::wstring(buffer.get()), path::native_format); -#else - size_t pathlen = static_cast(std::max(int(::pathconf(".", _PC_PATH_MAX)), int(PATH_MAX))); - std::unique_ptr buffer(new char[pathlen + 1]); - if (::getcwd(buffer.get(), pathlen) == nullptr) { - ec = detail::make_system_error(); - return path(); - } - return path(buffer.get()); -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void current_path(const path& p) -{ - std::error_code ec; - current_path(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } -} -#endif - -GHC_INLINE void current_path(const path& p, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - if (!::SetCurrentDirectoryW(detail::fromUtf8(p.u8string()).c_str())) { - ec = detail::make_system_error(); - } -#else - if (::chdir(p.string().c_str()) == -1) { - ec = detail::make_system_error(); - } -#endif -} - -GHC_INLINE bool exists(file_status s) noexcept -{ - return status_known(s) && s.type() != file_type::not_found; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool exists(const path& p) -{ - return exists(status(p)); -} -#endif - -GHC_INLINE bool exists(const path& p, std::error_code& ec) noexcept -{ - file_status s = status(p, ec); - if (status_known(s)) { - ec.clear(); - } - return exists(s); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool equivalent(const path& p1, const path& p2) -{ - std::error_code ec; - bool result = equivalent(p1, p2, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p1, p2, ec); - } - return result; -} -#endif - -GHC_INLINE bool equivalent(const path& p1, const path& p2, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - std::shared_ptr file1(::CreateFileW(p1.wstring().c_str(), 0, FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE, 0, OPEN_EXISTING, FILE_FLAG_BACKUP_SEMANTICS, 0), CloseHandle); - auto e1 = ::GetLastError(); - std::shared_ptr file2(::CreateFileW(p2.wstring().c_str(), 0, FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE, 0, OPEN_EXISTING, FILE_FLAG_BACKUP_SEMANTICS, 0), CloseHandle); - if (file1.get() == INVALID_HANDLE_VALUE || file2.get() == INVALID_HANDLE_VALUE) { -#ifdef LWG_2937_BEHAVIOUR - ec = detail::make_system_error(e1 ? e1 : ::GetLastError()); -#else - if (file1 == file2) { - ec = detail::make_system_error(e1 ? e1 : ::GetLastError()); - } -#endif - return false; - } - BY_HANDLE_FILE_INFORMATION inf1, inf2; - if (!::GetFileInformationByHandle(file1.get(), &inf1)) { - ec = detail::make_system_error(); - return false; - } - if (!::GetFileInformationByHandle(file2.get(), &inf2)) { - ec = detail::make_system_error(); - return false; - } - return inf1.ftLastWriteTime.dwLowDateTime == inf2.ftLastWriteTime.dwLowDateTime && inf1.ftLastWriteTime.dwHighDateTime == inf2.ftLastWriteTime.dwHighDateTime && inf1.nFileIndexHigh == inf2.nFileIndexHigh && inf1.nFileIndexLow == inf2.nFileIndexLow && - inf1.nFileSizeHigh == inf2.nFileSizeHigh && inf1.nFileSizeLow == inf2.nFileSizeLow && inf1.dwVolumeSerialNumber == inf2.dwVolumeSerialNumber; -#else - struct ::stat s1, s2; - auto rc1 = ::stat(p1.c_str(), &s1); - auto e1 = errno; - auto rc2 = ::stat(p2.c_str(), &s2); - if (rc1 || rc2) { -#ifdef LWG_2937_BEHAVIOUR - ec = detail::make_system_error(e1 ? e1 : errno); -#else - if (rc1 && rc2) { - ec = detail::make_system_error(e1 ? e1 : errno); - } -#endif - return false; - } - return s1.st_dev == s2.st_dev && s1.st_ino == s2.st_ino && s1.st_size == s2.st_size && s1.st_mtime == s2.st_mtime; -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE uintmax_t file_size(const path& p) -{ - std::error_code ec; - auto result = file_size(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE uintmax_t file_size(const path& p, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - WIN32_FILE_ATTRIBUTE_DATA attr; - if (!GetFileAttributesExW(detail::fromUtf8(p.u8string()).c_str(), GetFileExInfoStandard, &attr)) { - ec = detail::make_system_error(); - return static_cast(-1); - } - return static_cast(attr.nFileSizeHigh) << (sizeof(attr.nFileSizeHigh) * 8) | attr.nFileSizeLow; -#else - struct ::stat fileStat; - if (::stat(p.c_str(), &fileStat) == -1) { - ec = detail::make_system_error(); - return static_cast(-1); - } - return static_cast(fileStat.st_size); -#endif -} - -#ifndef GHC_OS_WEB -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE uintmax_t hard_link_count(const path& p) -{ - std::error_code ec; - auto result = hard_link_count(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE uintmax_t hard_link_count(const path& p, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - uintmax_t result = static_cast(-1); - std::shared_ptr file(::CreateFileW(p.wstring().c_str(), 0, FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE, 0, OPEN_EXISTING, FILE_FLAG_BACKUP_SEMANTICS, 0), CloseHandle); - BY_HANDLE_FILE_INFORMATION inf; - if (file.get() == INVALID_HANDLE_VALUE) { - ec = detail::make_system_error(); - } - else { - if (!::GetFileInformationByHandle(file.get(), &inf)) { - ec = detail::make_system_error(); - } - else { - result = inf.nNumberOfLinks; - } - } - return result; -#else - uintmax_t result = 0; - file_status fs = detail::status_ex(p, ec, nullptr, nullptr, &result, nullptr); - if (fs.type() == file_type::not_found) { - ec = detail::make_error_code(detail::portable_error::not_found); - } - return ec ? static_cast(-1) : result; -#endif -} -#endif - -GHC_INLINE bool is_block_file(file_status s) noexcept -{ - return s.type() == file_type::block; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_block_file(const path& p) -{ - return is_block_file(status(p)); -} -#endif - -GHC_INLINE bool is_block_file(const path& p, std::error_code& ec) noexcept -{ - return is_block_file(status(p, ec)); -} - -GHC_INLINE bool is_character_file(file_status s) noexcept -{ - return s.type() == file_type::character; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_character_file(const path& p) -{ - return is_character_file(status(p)); -} -#endif - -GHC_INLINE bool is_character_file(const path& p, std::error_code& ec) noexcept -{ - return is_character_file(status(p, ec)); -} - -GHC_INLINE bool is_directory(file_status s) noexcept -{ - return s.type() == file_type::directory; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_directory(const path& p) -{ - return is_directory(status(p)); -} -#endif - -GHC_INLINE bool is_directory(const path& p, std::error_code& ec) noexcept -{ - return is_directory(status(p, ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_empty(const path& p) -{ - if (is_directory(p)) { - return directory_iterator(p) == directory_iterator(); - } - else { - return file_size(p) == 0; - } -} -#endif - -GHC_INLINE bool is_empty(const path& p, std::error_code& ec) noexcept -{ - auto fs = status(p, ec); - if (ec) { - return false; - } - if (is_directory(fs)) { - directory_iterator iter(p, ec); - if (ec) { - return false; - } - return iter == directory_iterator(); - } - else { - auto sz = file_size(p, ec); - if (ec) { - return false; - } - return sz == 0; - } -} - -GHC_INLINE bool is_fifo(file_status s) noexcept -{ - return s.type() == file_type::fifo; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_fifo(const path& p) -{ - return is_fifo(status(p)); -} -#endif - -GHC_INLINE bool is_fifo(const path& p, std::error_code& ec) noexcept -{ - return is_fifo(status(p, ec)); -} - -GHC_INLINE bool is_other(file_status s) noexcept -{ - return exists(s) && !is_regular_file(s) && !is_directory(s) && !is_symlink(s); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_other(const path& p) -{ - return is_other(status(p)); -} -#endif - -GHC_INLINE bool is_other(const path& p, std::error_code& ec) noexcept -{ - return is_other(status(p, ec)); -} - -GHC_INLINE bool is_regular_file(file_status s) noexcept -{ - return s.type() == file_type::regular; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_regular_file(const path& p) -{ - return is_regular_file(status(p)); -} -#endif - -GHC_INLINE bool is_regular_file(const path& p, std::error_code& ec) noexcept -{ - return is_regular_file(status(p, ec)); -} - -GHC_INLINE bool is_socket(file_status s) noexcept -{ - return s.type() == file_type::socket; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_socket(const path& p) -{ - return is_socket(status(p)); -} -#endif - -GHC_INLINE bool is_socket(const path& p, std::error_code& ec) noexcept -{ - return is_socket(status(p, ec)); -} - -GHC_INLINE bool is_symlink(file_status s) noexcept -{ - return s.type() == file_type::symlink; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool is_symlink(const path& p) -{ - return is_symlink(symlink_status(p)); -} -#endif - -GHC_INLINE bool is_symlink(const path& p, std::error_code& ec) noexcept -{ - return is_symlink(symlink_status(p, ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE file_time_type last_write_time(const path& p) -{ - std::error_code ec; - auto result = last_write_time(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE file_time_type last_write_time(const path& p, std::error_code& ec) noexcept -{ - time_t result = 0; - ec.clear(); - file_status fs = detail::status_ex(p, ec, nullptr, nullptr, nullptr, &result); - return ec ? (file_time_type::min)() : std::chrono::system_clock::from_time_t(result); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void last_write_time(const path& p, file_time_type new_time) -{ - std::error_code ec; - last_write_time(p, new_time, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } -} -#endif - -GHC_INLINE void last_write_time(const path& p, file_time_type new_time, std::error_code& ec) noexcept -{ - ec.clear(); - auto d = new_time.time_since_epoch(); -#ifdef GHC_OS_WINDOWS - std::shared_ptr file(::CreateFileW(p.wstring().c_str(), FILE_WRITE_ATTRIBUTES, FILE_SHARE_DELETE | FILE_SHARE_READ | FILE_SHARE_WRITE, NULL, OPEN_EXISTING, FILE_FLAG_BACKUP_SEMANTICS, NULL), ::CloseHandle); - FILETIME ft; - auto tt = std::chrono::duration_cast(d).count() * 10 + 116444736000000000; - ft.dwLowDateTime = static_cast(tt); - ft.dwHighDateTime = static_cast(tt >> 32); - if (!::SetFileTime(file.get(), 0, 0, &ft)) { - ec = detail::make_system_error(); - } -#elif defined(GHC_OS_MACOS) -#ifdef __MAC_OS_X_VERSION_MIN_REQUIRED -#if __MAC_OS_X_VERSION_MIN_REQUIRED < 101300 - struct ::stat fs; - if (::stat(p.c_str(), &fs) == 0) { - struct ::timeval tv[2]; - tv[0].tv_sec = fs.st_atimespec.tv_sec; - tv[0].tv_usec = static_cast(fs.st_atimespec.tv_nsec / 1000); - tv[1].tv_sec = std::chrono::duration_cast(d).count(); - tv[1].tv_usec = static_cast(std::chrono::duration_cast(d).count() % 1000000); - if (::utimes(p.c_str(), tv) == 0) { - return; - } - } - ec = detail::make_system_error(); - return; -#else - struct ::timespec times[2]; - times[0].tv_sec = 0; - times[0].tv_nsec = UTIME_OMIT; - times[1].tv_sec = std::chrono::duration_cast(d).count(); - times[1].tv_nsec = 0; //std::chrono::duration_cast(d).count() % 1000000000; - if (::utimensat(AT_FDCWD, p.c_str(), times, AT_SYMLINK_NOFOLLOW) != 0) { - ec = detail::make_system_error(); - } - return; -#endif -#endif -#else -#ifndef UTIME_OMIT -#define UTIME_OMIT ((1l << 30) - 2l) -#endif - struct ::timespec times[2]; - times[0].tv_sec = 0; - times[0].tv_nsec = UTIME_OMIT; - times[1].tv_sec = static_cast(std::chrono::duration_cast(d).count()); - times[1].tv_nsec = static_cast(std::chrono::duration_cast(d).count() % 1000000000); -#if defined(__ANDROID_API__) && __ANDROID_API__ < 12 - if (syscall(__NR_utimensat, AT_FDCWD, p.c_str(), times, AT_SYMLINK_NOFOLLOW) != 0) { -#else - if (::utimensat(AT_FDCWD, p.c_str(), times, AT_SYMLINK_NOFOLLOW) != 0) { -#endif - ec = detail::make_system_error(); - } - return; -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void permissions(const path& p, perms prms, perm_options opts) -{ - std::error_code ec; - permissions(p, prms, opts, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } -} -#endif - -GHC_INLINE void permissions(const path& p, perms prms, std::error_code& ec) noexcept -{ - permissions(p, prms, perm_options::replace, ec); -} - -GHC_INLINE void permissions(const path& p, perms prms, perm_options opts, std::error_code& ec) -{ - if (static_cast(opts & (perm_options::replace | perm_options::add | perm_options::remove)) == 0) { - ec = detail::make_error_code(detail::portable_error::invalid_argument); - return; - } - auto fs = symlink_status(p, ec); - if ((opts & perm_options::replace) != perm_options::replace) { - if ((opts & perm_options::add) == perm_options::add) { - prms = fs.permissions() | prms; - } - else { - prms = fs.permissions() & ~prms; - } - } -#ifdef GHC_OS_WINDOWS -#ifdef __GNUC__ - auto oldAttr = GetFileAttributesW(p.wstring().c_str()); - if (oldAttr != INVALID_FILE_ATTRIBUTES) { - DWORD newAttr = ((prms & perms::owner_write) == perms::owner_write) ? oldAttr & ~(static_cast(FILE_ATTRIBUTE_READONLY)) : oldAttr | FILE_ATTRIBUTE_READONLY; - if (oldAttr == newAttr || SetFileAttributesW(p.wstring().c_str(), newAttr)) { - return; - } - } - ec = detail::make_system_error(); -#else - int mode = 0; - if ((prms & perms::owner_read) == perms::owner_read) { - mode |= _S_IREAD; - } - if ((prms & perms::owner_write) == perms::owner_write) { - mode |= _S_IWRITE; - } - if (::_wchmod(p.wstring().c_str(), mode) != 0) { - ec = detail::make_system_error(); - } -#endif -#else - if ((opts & perm_options::nofollow) != perm_options::nofollow) { - if (::chmod(p.c_str(), static_cast(prms)) != 0) { - ec = detail::make_system_error(); - } - } -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path proximate(const path& p, std::error_code& ec) -{ - return proximate(p, current_path(), ec); -} -#endif - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path proximate(const path& p, const path& base) -{ - return weakly_canonical(p).lexically_proximate(weakly_canonical(base)); -} -#endif - -GHC_INLINE path proximate(const path& p, const path& base, std::error_code& ec) -{ - return weakly_canonical(p, ec).lexically_proximate(weakly_canonical(base, ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path read_symlink(const path& p) -{ - std::error_code ec; - auto result = read_symlink(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE path read_symlink(const path& p, std::error_code& ec) -{ - file_status fs = symlink_status(p, ec); - if (fs.type() != file_type::symlink) { - ec = detail::make_error_code(detail::portable_error::invalid_argument); - return path(); - } - auto result = detail::resolveSymlink(p, ec); - return ec ? path() : result; -} - -GHC_INLINE path relative(const path& p, std::error_code& ec) -{ - return relative(p, current_path(ec), ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path relative(const path& p, const path& base) -{ - return weakly_canonical(p).lexically_relative(weakly_canonical(base)); -} -#endif - -GHC_INLINE path relative(const path& p, const path& base, std::error_code& ec) -{ - return weakly_canonical(p, ec).lexically_relative(weakly_canonical(base, ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool remove(const path& p) -{ - std::error_code ec; - auto result = remove(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE bool remove(const path& p, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - std::wstring np = detail::fromUtf8(p.u8string()); - DWORD attr = GetFileAttributesW(np.c_str()); - if (attr == INVALID_FILE_ATTRIBUTES) { - auto error = ::GetLastError(); - if (error == ERROR_FILE_NOT_FOUND || error == ERROR_PATH_NOT_FOUND) { - return false; - } - ec = detail::make_system_error(error); - } - if (!ec) { - if (attr & FILE_ATTRIBUTE_DIRECTORY) { - if (!RemoveDirectoryW(np.c_str())) { - ec = detail::make_system_error(); - } - } - else { - if (!DeleteFileW(np.c_str())) { - ec = detail::make_system_error(); - } - } - } -#else - if (::remove(p.c_str()) == -1) { - auto error = errno; - if (error == ENOENT) { - return false; - } - ec = detail::make_system_error(); - } -#endif - return ec ? false : true; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE uintmax_t remove_all(const path& p) -{ - std::error_code ec; - auto result = remove_all(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE uintmax_t remove_all(const path& p, std::error_code& ec) noexcept -{ - ec.clear(); - uintmax_t count = 0; - if (p == "/") { - ec = detail::make_error_code(detail::portable_error::not_supported); - return static_cast(-1); - } - std::error_code tec; - auto fs = status(p, tec); - if (exists(fs) && is_directory(fs)) { - for (auto iter = directory_iterator(p, ec); iter != directory_iterator(); iter.increment(ec)) { - if (ec) { - break; - } - bool is_symlink_result = iter->is_symlink(ec); - if (ec) return static_cast(-1); - bool is_directory_result = iter->is_directory(ec); - if (ec) return static_cast(-1); - if (!is_symlink_result && is_directory_result) { - count += remove_all(iter->path(), ec); - if (ec) { - return static_cast(-1); - } - } - else { - remove(iter->path(), ec); - if (ec) { - return static_cast(-1); - } - ++count; - } - } - } - if (!ec) { - if (remove(p, ec)) { - ++count; - } - } - if (ec) { - return static_cast(-1); - } - return count; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void rename(const path& from, const path& to) -{ - std::error_code ec; - rename(from, to, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), from, to, ec); - } -} -#endif - -GHC_INLINE void rename(const path& from, const path& to, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - if (from != to) { - if (!MoveFileExW(detail::fromUtf8(from.u8string()).c_str(), detail::fromUtf8(to.u8string()).c_str(), (DWORD)MOVEFILE_REPLACE_EXISTING)) { - ec = detail::make_system_error(); - } - } -#else - if (from != to) { - if (::rename(from.c_str(), to.c_str()) != 0) { - ec = detail::make_system_error(); - } - } -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void resize_file(const path& p, uintmax_t size) -{ - std::error_code ec; - resize_file(p, size, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } -} -#endif - -GHC_INLINE void resize_file(const path& p, uintmax_t size, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - LARGE_INTEGER lisize; - lisize.QuadPart = static_cast(size); - if(lisize.QuadPart < 0) { -#ifdef ERROR_FILE_TOO_LARGE - ec = detail::make_system_error(ERROR_FILE_TOO_LARGE); -#else - ec = detail::make_system_error(223); -#endif - return; - } - std::shared_ptr file(CreateFileW(detail::fromUtf8(p.u8string()).c_str(), GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL), CloseHandle); - if (file.get() == INVALID_HANDLE_VALUE) { - ec = detail::make_system_error(); - } - else if (SetFilePointerEx(file.get(), lisize, NULL, FILE_BEGIN) == 0 || SetEndOfFile(file.get()) == 0) { - ec = detail::make_system_error(); - } -#else - if (::truncate(p.c_str(), static_cast(size)) != 0) { - ec = detail::make_system_error(); - } -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE space_info space(const path& p) -{ - std::error_code ec; - auto result = space(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE space_info space(const path& p, std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - ULARGE_INTEGER freeBytesAvailableToCaller = {{0, 0}}; - ULARGE_INTEGER totalNumberOfBytes = {{0, 0}}; - ULARGE_INTEGER totalNumberOfFreeBytes = {{0, 0}}; - if (!GetDiskFreeSpaceExW(detail::fromUtf8(p.u8string()).c_str(), &freeBytesAvailableToCaller, &totalNumberOfBytes, &totalNumberOfFreeBytes)) { - ec = detail::make_system_error(); - return {static_cast(-1), static_cast(-1), static_cast(-1)}; - } - return {static_cast(totalNumberOfBytes.QuadPart), static_cast(totalNumberOfFreeBytes.QuadPart), static_cast(freeBytesAvailableToCaller.QuadPart)}; -#else - struct ::statvfs sfs; - if (::statvfs(p.c_str(), &sfs) != 0) { - ec = detail::make_system_error(); - return {static_cast(-1), static_cast(-1), static_cast(-1)}; - } - return {static_cast(sfs.f_blocks * sfs.f_frsize), static_cast(sfs.f_bfree * sfs.f_frsize), static_cast(sfs.f_bavail * sfs.f_frsize)}; -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE file_status status(const path& p) -{ - std::error_code ec; - auto result = status(p, ec); - if (result.type() == file_type::none) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE file_status status(const path& p, std::error_code& ec) noexcept -{ - return detail::status_ex(p, ec); -} - -GHC_INLINE bool status_known(file_status s) noexcept -{ - return s.type() != file_type::none; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE file_status symlink_status(const path& p) -{ - std::error_code ec; - auto result = symlink_status(p, ec); - if (result.type() == file_type::none) { - throw filesystem_error(detail::systemErrorText(ec.value()), ec); - } - return result; -} -#endif - -GHC_INLINE file_status symlink_status(const path& p, std::error_code& ec) noexcept -{ - return detail::symlink_status_ex(p, ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path temp_directory_path() -{ - std::error_code ec; - path result = temp_directory_path(ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), ec); - } - return result; -} -#endif - -GHC_INLINE path temp_directory_path(std::error_code& ec) noexcept -{ - ec.clear(); -#ifdef GHC_OS_WINDOWS - wchar_t buffer[512]; - auto rc = GetTempPathW(511, buffer); - if (!rc || rc > 511) { - ec = detail::make_system_error(); - return path(); - } - return path(std::wstring(buffer)); -#else - static const char* temp_vars[] = {"TMPDIR", "TMP", "TEMP", "TEMPDIR", nullptr}; - const char* temp_path = nullptr; - for (auto temp_name = temp_vars; *temp_name != nullptr; ++temp_name) { - temp_path = std::getenv(*temp_name); - if (temp_path) { - return path(temp_path); - } - } - return path("/tmp"); -#endif -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE path weakly_canonical(const path& p) -{ - std::error_code ec; - auto result = weakly_canonical(p, ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), p, ec); - } - return result; -} -#endif - -GHC_INLINE path weakly_canonical(const path& p, std::error_code& ec) noexcept -{ - path result; - ec.clear(); - bool scan = true; - for (auto pe : p) { - if (scan) { - std::error_code tec; - if (exists(result / pe, tec)) { - result /= pe; - } - else { - if (ec) { - return path(); - } - scan = false; - if (!result.empty()) { - result = canonical(result, ec) / pe; - if (ec) { - break; - } - } - else { - result /= pe; - } - } - } - else { - result /= pe; - } - } - if (scan) { - if (!result.empty()) { - result = canonical(result, ec); - } - } - return ec ? path() : result.lexically_normal(); -} - -//----------------------------------------------------------------------------- -// 30.10.11 class file_status -// 30.10.11.1 constructors and destructor -GHC_INLINE file_status::file_status() noexcept - : file_status(file_type::none) -{ -} - -GHC_INLINE file_status::file_status(file_type ft, perms prms) noexcept - : _type(ft) - , _perms(prms) -{ -} - -GHC_INLINE file_status::file_status(const file_status& other) noexcept - : _type(other._type) - , _perms(other._perms) -{ -} - -GHC_INLINE file_status::file_status(file_status&& other) noexcept - : _type(other._type) - , _perms(other._perms) -{ -} - -GHC_INLINE file_status::~file_status() {} - -// assignments: -GHC_INLINE file_status& file_status::operator=(const file_status& rhs) noexcept -{ - _type = rhs._type; - _perms = rhs._perms; - return *this; -} - -GHC_INLINE file_status& file_status::operator=(file_status&& rhs) noexcept -{ - _type = rhs._type; - _perms = rhs._perms; - return *this; -} - -// 30.10.11.3 modifiers -GHC_INLINE void file_status::type(file_type ft) noexcept -{ - _type = ft; -} - -GHC_INLINE void file_status::permissions(perms prms) noexcept -{ - _perms = prms; -} - -// 30.10.11.2 observers -GHC_INLINE file_type file_status::type() const noexcept -{ - return _type; -} - -GHC_INLINE perms file_status::permissions() const noexcept -{ - return _perms; -} - -//----------------------------------------------------------------------------- -// 30.10.12 class directory_entry -// 30.10.12.1 constructors and destructor -// directory_entry::directory_entry() noexcept = default; -// directory_entry::directory_entry(const directory_entry&) = default; -// directory_entry::directory_entry(directory_entry&&) noexcept = default; -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE directory_entry::directory_entry(const filesystem::path& p) - : _path(p) - , _file_size(0) -#ifndef GHC_OS_WINDOWS - , _hard_link_count(0) -#endif - , _last_write_time(0) -{ - refresh(); -} -#endif - -GHC_INLINE directory_entry::directory_entry(const filesystem::path& p, std::error_code& ec) - : _path(p) - , _file_size(0) -#ifndef GHC_OS_WINDOWS - , _hard_link_count(0) -#endif - , _last_write_time(0) -{ - refresh(ec); -} - -GHC_INLINE directory_entry::~directory_entry() {} - -// assignments: -// directory_entry& directory_entry::operator=(const directory_entry&) = default; -// directory_entry& directory_entry::operator=(directory_entry&&) noexcept = default; - -// 30.10.12.2 directory_entry modifiers -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void directory_entry::assign(const filesystem::path& p) -{ - _path = p; - refresh(); -} -#endif - -GHC_INLINE void directory_entry::assign(const filesystem::path& p, std::error_code& ec) -{ - _path = p; - refresh(ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void directory_entry::replace_filename(const filesystem::path& p) -{ - _path.replace_filename(p); - refresh(); -} -#endif - -GHC_INLINE void directory_entry::replace_filename(const filesystem::path& p, std::error_code& ec) -{ - _path.replace_filename(p); - refresh(ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void directory_entry::refresh() -{ - std::error_code ec; - refresh(ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), _path, ec); - } -} -#endif - -GHC_INLINE void directory_entry::refresh(std::error_code& ec) noexcept -{ -#ifdef GHC_OS_WINDOWS - _status = detail::status_ex(_path, ec, &_symlink_status, &_file_size, nullptr, &_last_write_time); -#else - _status = detail::status_ex(_path, ec, &_symlink_status, &_file_size, &_hard_link_count, &_last_write_time); -#endif -} - -// 30.10.12.3 directory_entry observers -GHC_INLINE const filesystem::path& directory_entry::path() const noexcept -{ - return _path; -} - -GHC_INLINE directory_entry::operator const filesystem::path&() const noexcept -{ - return _path; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::exists() const -{ - return filesystem::exists(status()); -} -#endif - -GHC_INLINE bool directory_entry::exists(std::error_code& ec) const noexcept -{ - return filesystem::exists(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_block_file() const -{ - return filesystem::is_block_file(status()); -} -#endif -GHC_INLINE bool directory_entry::is_block_file(std::error_code& ec) const noexcept -{ - return filesystem::is_block_file(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_character_file() const -{ - return filesystem::is_character_file(status()); -} -#endif - -GHC_INLINE bool directory_entry::is_character_file(std::error_code& ec) const noexcept -{ - return filesystem::is_character_file(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_directory() const -{ - return filesystem::is_directory(status()); -} -#endif - -GHC_INLINE bool directory_entry::is_directory(std::error_code& ec) const noexcept -{ - return filesystem::is_directory(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_fifo() const -{ - return filesystem::is_fifo(status()); -} -#endif - -GHC_INLINE bool directory_entry::is_fifo(std::error_code& ec) const noexcept -{ - return filesystem::is_fifo(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_other() const -{ - return filesystem::is_other(status()); -} -#endif - -GHC_INLINE bool directory_entry::is_other(std::error_code& ec) const noexcept -{ - return filesystem::is_other(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_regular_file() const -{ - return filesystem::is_regular_file(status()); -} -#endif - -GHC_INLINE bool directory_entry::is_regular_file(std::error_code& ec) const noexcept -{ - return filesystem::is_regular_file(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_socket() const -{ - return filesystem::is_socket(status()); -} -#endif - -GHC_INLINE bool directory_entry::is_socket(std::error_code& ec) const noexcept -{ - return filesystem::is_socket(status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE bool directory_entry::is_symlink() const -{ - return filesystem::is_symlink(symlink_status()); -} -#endif - -GHC_INLINE bool directory_entry::is_symlink(std::error_code& ec) const noexcept -{ - return filesystem::is_symlink(symlink_status(ec)); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE uintmax_t directory_entry::file_size() const -{ - if (_status.type() != file_type::none) { - return _file_size; - } - return filesystem::file_size(path()); -} -#endif - -GHC_INLINE uintmax_t directory_entry::file_size(std::error_code& ec) const noexcept -{ - if (_status.type() != file_type::none) { - ec.clear(); - return _file_size; - } - return filesystem::file_size(path(), ec); -} - -#ifndef GHC_OS_WEB -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE uintmax_t directory_entry::hard_link_count() const -{ -#ifndef GHC_OS_WINDOWS - if (_status.type() != file_type::none) { - return _hard_link_count; - } -#endif - return filesystem::hard_link_count(path()); -} -#endif - -GHC_INLINE uintmax_t directory_entry::hard_link_count(std::error_code& ec) const noexcept -{ -#ifndef GHC_OS_WINDOWS - if (_status.type() != file_type::none) { - ec.clear(); - return _hard_link_count; - } -#endif - return filesystem::hard_link_count(path(), ec); -} -#endif - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE file_time_type directory_entry::last_write_time() const -{ - if (_status.type() != file_type::none) { - return std::chrono::system_clock::from_time_t(_last_write_time); - } - return filesystem::last_write_time(path()); -} -#endif - -GHC_INLINE file_time_type directory_entry::last_write_time(std::error_code& ec) const noexcept -{ - if (_status.type() != file_type::none) { - ec.clear(); - return std::chrono::system_clock::from_time_t(_last_write_time); - } - return filesystem::last_write_time(path(), ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE file_status directory_entry::status() const -{ - if (_status.type() != file_type::none) { - return _status; - } - return filesystem::status(path()); -} -#endif - -GHC_INLINE file_status directory_entry::status(std::error_code& ec) const noexcept -{ - if (_status.type() != file_type::none) { - ec.clear(); - return _status; - } - return filesystem::status(path(), ec); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE file_status directory_entry::symlink_status() const -{ - if (_symlink_status.type() != file_type::none) { - return _symlink_status; - } - return filesystem::symlink_status(path()); -} -#endif - -GHC_INLINE file_status directory_entry::symlink_status(std::error_code& ec) const noexcept -{ - if (_symlink_status.type() != file_type::none) { - ec.clear(); - return _symlink_status; - } - return filesystem::symlink_status(path(), ec); -} - -GHC_INLINE bool directory_entry::operator<(const directory_entry& rhs) const noexcept -{ - return _path < rhs._path; -} - -GHC_INLINE bool directory_entry::operator==(const directory_entry& rhs) const noexcept -{ - return _path == rhs._path; -} - -GHC_INLINE bool directory_entry::operator!=(const directory_entry& rhs) const noexcept -{ - return _path != rhs._path; -} - -GHC_INLINE bool directory_entry::operator<=(const directory_entry& rhs) const noexcept -{ - return _path <= rhs._path; -} - -GHC_INLINE bool directory_entry::operator>(const directory_entry& rhs) const noexcept -{ - return _path > rhs._path; -} - -GHC_INLINE bool directory_entry::operator>=(const directory_entry& rhs) const noexcept -{ - return _path >= rhs._path; -} - -//----------------------------------------------------------------------------- -// 30.10.13 class directory_iterator - -#ifdef GHC_OS_WINDOWS -class directory_iterator::impl -{ -public: - impl(const path& p, directory_options options) - : _base(p) - , _options(options) - , _dirHandle(INVALID_HANDLE_VALUE) - { - if (!_base.empty()) { - ZeroMemory(&_findData, sizeof(WIN32_FIND_DATAW)); - if ((_dirHandle = FindFirstFileW(detail::fromUtf8((_base / "*").u8string()).c_str(), &_findData)) != INVALID_HANDLE_VALUE) { - if (std::wstring(_findData.cFileName) == L"." || std::wstring(_findData.cFileName) == L"..") { - increment(_ec); - } - else { - _current = _base / std::wstring(_findData.cFileName); - copyToDirEntry(_ec); - } - } - else { - auto error = ::GetLastError(); - _base = filesystem::path(); - if (error != ERROR_ACCESS_DENIED || (options & directory_options::skip_permission_denied) == directory_options::none) { - _ec = detail::make_system_error(); - } - } - } - } - impl(const impl& other) = delete; - ~impl() - { - if (_dirHandle != INVALID_HANDLE_VALUE) { - FindClose(_dirHandle); - _dirHandle = INVALID_HANDLE_VALUE; - } - } - void increment(std::error_code& ec) - { - if (_dirHandle != INVALID_HANDLE_VALUE) { - do { - if (FindNextFileW(_dirHandle, &_findData)) { - _current = _base; -#ifdef GHC_RAISE_UNICODE_ERRORS - try { - _current.append_name(detail::toUtf8(_findData.cFileName).c_str()); - } - catch(filesystem_error& fe) { - ec = fe.code(); - return; - } -#else - _current.append_name(detail::toUtf8(_findData.cFileName).c_str()); -#endif - copyToDirEntry(ec); - } - else { - auto err = ::GetLastError(); - if(err != ERROR_NO_MORE_FILES) { - _ec = ec = detail::make_system_error(err); - } - FindClose(_dirHandle); - _dirHandle = INVALID_HANDLE_VALUE; - _current = filesystem::path(); - break; - } - } while (std::wstring(_findData.cFileName) == L"." || std::wstring(_findData.cFileName) == L".."); - } - else { - ec = _ec; - } - } - void copyToDirEntry(std::error_code& ec) - { - _dir_entry._path = _current; - if (_findData.dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT) { - _dir_entry._status = detail::status_ex(_current, ec, &_dir_entry._symlink_status, &_dir_entry._file_size, nullptr, &_dir_entry._last_write_time); - } - else { - _dir_entry._status = detail::status_from_INFO(_current, &_findData, ec, &_dir_entry._file_size, &_dir_entry._last_write_time); - _dir_entry._symlink_status = _dir_entry._status; - } - if (ec) { - if (_dir_entry._status.type() != file_type::none && _dir_entry._symlink_status.type() != file_type::none) { - ec.clear(); - } - else { - _dir_entry._file_size = static_cast(-1); - _dir_entry._last_write_time = 0; - } - } - } - path _base; - directory_options _options; - WIN32_FIND_DATAW _findData; - HANDLE _dirHandle; - path _current; - directory_entry _dir_entry; - std::error_code _ec; -}; -#else -// POSIX implementation -class directory_iterator::impl -{ -public: - impl(const path& path, directory_options options) - : _base(path) - , _options(options) - , _dir(nullptr) - , _entry(nullptr) - { - if (!path.empty()) { - _dir = ::opendir(path.native().c_str()); - } - if (!path.empty()) { - if (!_dir) { - auto error = errno; - _base = filesystem::path(); - if (error != EACCES || (options & directory_options::skip_permission_denied) == directory_options::none) { - _ec = detail::make_system_error(); - } - } - else { - increment(_ec); - } - } - } - impl(const impl& other) = delete; - ~impl() - { - if (_dir) { - ::closedir(_dir); - } - } - void increment(std::error_code& ec) - { - if (_dir) { - bool skip; - do { - skip = false; - errno = 0; - _entry = ::readdir(_dir); - if (_entry) { - _current = _base; - _current.append_name(_entry->d_name); - _dir_entry = directory_entry(_current, ec); - if(ec && (ec.value() == EACCES || ec.value() == EPERM) && (_options & directory_options::skip_permission_denied) == directory_options::skip_permission_denied) { - ec.clear(); - skip = true; - } - } - else { - ::closedir(_dir); - _dir = nullptr; - _current = path(); - if (errno) { - ec = detail::make_system_error(); - } - break; - } - } while (skip || std::strcmp(_entry->d_name, ".") == 0 || std::strcmp(_entry->d_name, "..") == 0); - } - } - path _base; - directory_options _options; - path _current; - DIR* _dir; - struct ::dirent* _entry; - directory_entry _dir_entry; - std::error_code _ec; -}; -#endif - -// 30.10.13.1 member functions -GHC_INLINE directory_iterator::directory_iterator() noexcept - : _impl(new impl(path(), directory_options::none)) -{ -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE directory_iterator::directory_iterator(const path& p) - : _impl(new impl(p, directory_options::none)) -{ - if (_impl->_ec) { - throw filesystem_error(detail::systemErrorText(_impl->_ec.value()), p, _impl->_ec); - } - _impl->_ec.clear(); -} - -GHC_INLINE directory_iterator::directory_iterator(const path& p, directory_options options) - : _impl(new impl(p, options)) -{ - if (_impl->_ec) { - throw filesystem_error(detail::systemErrorText(_impl->_ec.value()), p, _impl->_ec); - } -} -#endif - -GHC_INLINE directory_iterator::directory_iterator(const path& p, std::error_code& ec) noexcept - : _impl(new impl(p, directory_options::none)) -{ - if (_impl->_ec) { - ec = _impl->_ec; - } -} - -GHC_INLINE directory_iterator::directory_iterator(const path& p, directory_options options, std::error_code& ec) noexcept - : _impl(new impl(p, options)) -{ - if (_impl->_ec) { - ec = _impl->_ec; - } -} - -GHC_INLINE directory_iterator::directory_iterator(const directory_iterator& rhs) - : _impl(rhs._impl) -{ -} - -GHC_INLINE directory_iterator::directory_iterator(directory_iterator&& rhs) noexcept - : _impl(std::move(rhs._impl)) -{ -} - -GHC_INLINE directory_iterator::~directory_iterator() {} - -GHC_INLINE directory_iterator& directory_iterator::operator=(const directory_iterator& rhs) -{ - _impl = rhs._impl; - return *this; -} - -GHC_INLINE directory_iterator& directory_iterator::operator=(directory_iterator&& rhs) noexcept -{ - _impl = std::move(rhs._impl); - return *this; -} - -GHC_INLINE const directory_entry& directory_iterator::operator*() const -{ - return _impl->_dir_entry; -} - -GHC_INLINE const directory_entry* directory_iterator::operator->() const -{ - return &_impl->_dir_entry; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE directory_iterator& directory_iterator::operator++() -{ - std::error_code ec; - _impl->increment(ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), _impl->_current, ec); - } - return *this; -} -#endif - -GHC_INLINE directory_iterator& directory_iterator::increment(std::error_code& ec) noexcept -{ - _impl->increment(ec); - return *this; -} - -GHC_INLINE bool directory_iterator::operator==(const directory_iterator& rhs) const -{ - return _impl->_current == rhs._impl->_current; -} - -GHC_INLINE bool directory_iterator::operator!=(const directory_iterator& rhs) const -{ - return _impl->_current != rhs._impl->_current; -} - -// 30.10.13.2 directory_iterator non-member functions - -GHC_INLINE directory_iterator begin(directory_iterator iter) noexcept -{ - return iter; -} - -GHC_INLINE directory_iterator end(const directory_iterator&) noexcept -{ - return directory_iterator(); -} - -//----------------------------------------------------------------------------- -// 30.10.14 class recursive_directory_iterator - -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator() noexcept - : _impl(new recursive_directory_iterator_impl(directory_options::none, true)) -{ - _impl->_dir_iter_stack.push(directory_iterator()); -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator(const path& p) - : _impl(new recursive_directory_iterator_impl(directory_options::none, true)) -{ - _impl->_dir_iter_stack.push(directory_iterator(p)); -} - -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator(const path& p, directory_options options) - : _impl(new recursive_directory_iterator_impl(options, true)) -{ - _impl->_dir_iter_stack.push(directory_iterator(p, options)); -} -#endif - -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator(const path& p, directory_options options, std::error_code& ec) noexcept - : _impl(new recursive_directory_iterator_impl(options, true)) -{ - _impl->_dir_iter_stack.push(directory_iterator(p, options, ec)); -} - -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator(const path& p, std::error_code& ec) noexcept - : _impl(new recursive_directory_iterator_impl(directory_options::none, true)) -{ - _impl->_dir_iter_stack.push(directory_iterator(p, ec)); -} - -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator(const recursive_directory_iterator& rhs) - : _impl(rhs._impl) -{ -} - -GHC_INLINE recursive_directory_iterator::recursive_directory_iterator(recursive_directory_iterator&& rhs) noexcept - : _impl(std::move(rhs._impl)) -{ -} - -GHC_INLINE recursive_directory_iterator::~recursive_directory_iterator() {} - -// 30.10.14.1 observers -GHC_INLINE directory_options recursive_directory_iterator::options() const -{ - return _impl->_options; -} - -GHC_INLINE int recursive_directory_iterator::depth() const -{ - return static_cast(_impl->_dir_iter_stack.size() - 1); -} - -GHC_INLINE bool recursive_directory_iterator::recursion_pending() const -{ - return _impl->_recursion_pending; -} - -GHC_INLINE const directory_entry& recursive_directory_iterator::operator*() const -{ - return *(_impl->_dir_iter_stack.top()); -} - -GHC_INLINE const directory_entry* recursive_directory_iterator::operator->() const -{ - return &(*(_impl->_dir_iter_stack.top())); -} - -// 30.10.14.1 modifiers recursive_directory_iterator& -GHC_INLINE recursive_directory_iterator& recursive_directory_iterator::operator=(const recursive_directory_iterator& rhs) -{ - _impl = rhs._impl; - return *this; -} - -GHC_INLINE recursive_directory_iterator& recursive_directory_iterator::operator=(recursive_directory_iterator&& rhs) noexcept -{ - _impl = std::move(rhs._impl); - return *this; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE recursive_directory_iterator& recursive_directory_iterator::operator++() -{ - std::error_code ec; - increment(ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), _impl->_dir_iter_stack.empty() ? path() : _impl->_dir_iter_stack.top()->path(), ec); - } - return *this; -} -#endif - -GHC_INLINE recursive_directory_iterator& recursive_directory_iterator::increment(std::error_code& ec) noexcept -{ - auto status = (*this)->status(ec); - if (ec) return *this; - auto symlink_status = (*this)->symlink_status(ec); - if (ec) return *this; - if (recursion_pending() && is_directory(status) && (!is_symlink(symlink_status) || (options() & directory_options::follow_directory_symlink) != directory_options::none)) { - _impl->_dir_iter_stack.push(directory_iterator((*this)->path(), _impl->_options, ec)); - } - else { - _impl->_dir_iter_stack.top().increment(ec); - } - if (!ec) { - while (depth() && _impl->_dir_iter_stack.top() == directory_iterator()) { - _impl->_dir_iter_stack.pop(); - _impl->_dir_iter_stack.top().increment(ec); - } - } - else if (!_impl->_dir_iter_stack.empty()) { - _impl->_dir_iter_stack.pop(); - } - _impl->_recursion_pending = true; - return *this; -} - -#ifdef GHC_WITH_EXCEPTIONS -GHC_INLINE void recursive_directory_iterator::pop() -{ - std::error_code ec; - pop(ec); - if (ec) { - throw filesystem_error(detail::systemErrorText(ec.value()), _impl->_dir_iter_stack.empty() ? path() : _impl->_dir_iter_stack.top()->path(), ec); - } -} -#endif - -GHC_INLINE void recursive_directory_iterator::pop(std::error_code& ec) -{ - if (depth() == 0) { - *this = recursive_directory_iterator(); - } - else { - do { - _impl->_dir_iter_stack.pop(); - _impl->_dir_iter_stack.top().increment(ec); - } while (depth() && _impl->_dir_iter_stack.top() == directory_iterator()); - } -} - -GHC_INLINE void recursive_directory_iterator::disable_recursion_pending() -{ - _impl->_recursion_pending = false; -} - -// other members as required by 27.2.3, input iterators -GHC_INLINE bool recursive_directory_iterator::operator==(const recursive_directory_iterator& rhs) const -{ - return _impl->_dir_iter_stack.top() == rhs._impl->_dir_iter_stack.top(); -} - -GHC_INLINE bool recursive_directory_iterator::operator!=(const recursive_directory_iterator& rhs) const -{ - return _impl->_dir_iter_stack.top() != rhs._impl->_dir_iter_stack.top(); -} - -// 30.10.14.2 directory_iterator non-member functions -GHC_INLINE recursive_directory_iterator begin(recursive_directory_iterator iter) noexcept -{ - return iter; -} - -GHC_INLINE recursive_directory_iterator end(const recursive_directory_iterator&) noexcept -{ - return recursive_directory_iterator(); -} - -#endif // GHC_EXPAND_IMPL - -} // namespace filesystem -} // namespace ghc - -// cleanup some macros -#undef GHC_INLINE -#undef GHC_EXPAND_IMPL - -#endif // GHC_FILESYSTEM_H From b10dc10a903f8e82f5bfaed294692be822754a2d Mon Sep 17 00:00:00 2001 From: Shinnosuke Hirakawa <8327162+0x126@users.noreply.github.com> Date: Fri, 25 Feb 2022 16:21:37 +0900 Subject: [PATCH 36/37] fix: change empty pointcloud processing (#444) Signed-off-by: Shinnosuke Hirakawa --- .../src/concatenate_data/concatenate_data_nodelet.cpp | 4 ---- .../outlier_filter/dual_return_outlier_filter_nodelet.cpp | 5 ----- .../src/outlier_filter/ring_outlier_filter_nodelet.cpp | 4 ---- 3 files changed, 13 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp index 60eacb9b09ba7..8808cf3db0d83 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp @@ -354,10 +354,6 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name) { std::lock_guard lock(mutex_); - if (input_ptr->data.empty()) { - RCLCPP_WARN(get_logger(), "input pointcloud is empty."); - return; - } sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2()); convertToXYZICloud(input_ptr, xyzi_input_ptr); 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 d506031d12d22..7858322713063 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 @@ -87,11 +87,6 @@ void DualReturnOutlierFilterComponent::filter( PointCloud2 & output) { boost::mutex::scoped_lock lock(mutex_); - if (input->data.empty()) { - output.header = input->header; - RCLCPP_WARN(get_logger(), "input pointcloud is empty."); - return; - } pcl::PointCloud::Ptr pcl_input( new pcl::PointCloud); pcl::fromROSMsg(*input, *pcl_input); 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 5667accdfdbf0..7a842665e5f14 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 @@ -39,10 +39,6 @@ void RingOutlierFilterComponent::filter( PointCloud2 & output) { boost::mutex::scoped_lock lock(mutex_); - output.header = input->header; - if (input->row_step < 1) { - return; - } std::unordered_map> input_ring_map; input_ring_map.reserve(128); sensor_msgs::msg::PointCloud2::SharedPtr input_ptr = From 264909eb94c4350e5e37c7abaea19603b512250b Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 25 Feb 2022 17:14:30 +0900 Subject: [PATCH 37/37] ci: check include guard (#438) * ci: check include guard * apply pre-commit * Update .pre-commit-config.yaml Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * fix: pre-commit Signed-off-by: Takagi, Isamu Co-authored-by: Kenji Miyake Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- .pre-commit-config.yaml | 3 ++- .../include/autoware_point_types/types.hpp | 6 +++--- common/polar_grid/src/polar_grid_display.hpp | 2 +- .../tier4_autoware_utils/trajectory/tmp_conversion.hpp | 6 +++--- .../src/simulated_clock_panel.hpp | 6 +++--- .../include/trajectory_follower/interpolate.hpp | 2 +- localization/ndt/include/ndt/base.hpp | 6 +++--- localization/ndt/include/ndt/impl/base.hpp | 6 +++--- localization/ndt/include/ndt/impl/omp.hpp | 6 +++--- localization/ndt/include/ndt/impl/pcl_generic.hpp | 6 +++--- localization/ndt/include/ndt/impl/pcl_modified.hpp | 6 +++--- localization/ndt/include/ndt/omp.hpp | 6 +++--- localization/ndt/include/ndt/pcl_generic.hpp | 6 +++--- localization/ndt/include/ndt/pcl_modified.hpp | 6 +++--- .../ndt_pcl_modified/include/ndt_pcl_modified/impl/ndt.hpp | 6 +++--- .../ndt_pcl_modified/include/ndt_pcl_modified/ndt.hpp | 6 +++--- .../include/ndt_scan_matcher/matrix_type.hpp | 6 +++--- .../ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp | 2 +- .../vehicle_velocity_converter.hpp | 6 +++--- .../distance_based_compare_map_filter_nodelet.hpp | 2 +- .../voxel_based_approximate_compare_map_filter_nodelet.hpp | 2 +- .../voxel_distance_based_compare_map_filter_nodelet.hpp | 2 +- .../elevation_map_loader/elevation_map_loader_node.hpp | 6 +++--- .../lidar_apollo_instance_segmentation/disjoint_set.hpp | 6 +++--- .../include/lidar_apollo_instance_segmentation/util.hpp | 6 +++--- .../lib/include/TrtNet.hpp | 6 +++--- .../lib/include/Utils.hpp | 6 +++--- perception/traffic_light_classifier/utils/trt_common.hpp | 6 +++--- .../analytical_jerk_constrained_smoother.hpp | 4 +++- .../velocity_planning_utils.hpp | 4 +++- .../include/fault_injection/diagnostic_storage.hpp | 6 +++--- .../include/fault_injection/fault_injection_node.hpp | 6 +++--- .../dummy_infrastructure/dummy_infrastructure_node.hpp | 6 +++--- 33 files changed, 86 insertions(+), 81 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index f3c030c55ed41..0663aaf1d2b45 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -35,10 +35,11 @@ repos: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.4.0 + rev: v0.5.1 hooks: - id: prettier-package-xml - id: sort-package-xml + - id: ros-include-guard - repo: https://github.com/shellcheck-py/shellcheck-py rev: v0.8.0.3 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 2c3d061930576..922327128082f 100644 --- a/common/autoware_point_types/include/autoware_point_types/types.hpp +++ b/common/autoware_point_types/include/autoware_point_types/types.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_POINT_TYPES__AUTOWARE_POINT_TYPES_HPP_ -#define AUTOWARE_POINT_TYPES__AUTOWARE_POINT_TYPES_HPP_ +#ifndef AUTOWARE_POINT_TYPES__TYPES_HPP_ +#define AUTOWARE_POINT_TYPES__TYPES_HPP_ #include @@ -77,4 +77,4 @@ using PointXYZIRADRTGenerator = std::tuple< } // namespace autoware_point_types -#endif // AUTOWARE_POINT_TYPES__AUTOWARE_POINT_TYPES_HPP_ +#endif // AUTOWARE_POINT_TYPES__TYPES_HPP_ diff --git a/common/polar_grid/src/polar_grid_display.hpp b/common/polar_grid/src/polar_grid_display.hpp index b42cc42a810e3..322c57cc9933b 100644 --- a/common/polar_grid/src/polar_grid_display.hpp +++ b/common/polar_grid/src/polar_grid_display.hpp @@ -100,4 +100,4 @@ private Q_SLOTS: } // namespace rviz_plugins -#endif // POLAR_GRID_DISPLAY_HPP_ +#endif // POLAR_GRID_DISPLAY_HPP_ diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/trajectory/tmp_conversion.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/trajectory/tmp_conversion.hpp index 51f865a6f8867..b699a579c3a63 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/trajectory/tmp_conversion.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/trajectory/tmp_conversion.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TIER4_AUTOWARE_UTILS__TRAJECTORY__CONVERT_HPP_ -#define TIER4_AUTOWARE_UTILS__TRAJECTORY__CONVERT_HPP_ +#ifndef TIER4_AUTOWARE_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_ +#define TIER4_AUTOWARE_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_ #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/geometry/pose_deviation.hpp" @@ -66,4 +66,4 @@ std::vector convertToTrajecto } // namespace tier4_autoware_utils -#endif // TIER4_AUTOWARE_UTILS__TRAJECTORY__CONVERT_HPP_ +#endif // TIER4_AUTOWARE_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_ diff --git a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp index 137aafb30c88a..b2ac332107202 100644 --- a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp +++ b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp @@ -14,8 +14,8 @@ // limitations under the License. // -#ifndef AUTOWARE_STATE_PANEL_HPP_ -#define AUTOWARE_STATE_PANEL_HPP_ +#ifndef SIMULATED_CLOCK_PANEL_HPP_ +#define SIMULATED_CLOCK_PANEL_HPP_ #include #include @@ -73,4 +73,4 @@ protected Q_SLOTS: } // namespace rviz_plugins -#endif // AUTOWARE_STATE_PANEL_HPP_ +#endif // SIMULATED_CLOCK_PANEL_HPP_ diff --git a/control/trajectory_follower/include/trajectory_follower/interpolate.hpp b/control/trajectory_follower/include/trajectory_follower/interpolate.hpp index 99fc437d57f48..c01177cbe7581 100644 --- a/control/trajectory_follower/include/trajectory_follower/interpolate.hpp +++ b/control/trajectory_follower/include/trajectory_follower/interpolate.hpp @@ -56,4 +56,4 @@ TRAJECTORY_FOLLOWER_PUBLIC bool8_t linearInterpolate( } // namespace control } // namespace motion } // namespace autoware -#endif // TRAJECTORY_FOLLOWER__INTERPOLATE_HPP__ +#endif // TRAJECTORY_FOLLOWER__INTERPOLATE_HPP_ diff --git a/localization/ndt/include/ndt/base.hpp b/localization/ndt/include/ndt/base.hpp index 25cab0edca180..3f955ee98afc1 100644 --- a/localization/ndt/include/ndt/base.hpp +++ b/localization/ndt/include/ndt/base.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_BASE_H -#define NORMAL_DISTRIBUTIONS_TRANSFORM_BASE_H +#ifndef NDT__BASE_HPP_ +#define NDT__BASE_HPP_ #include #include @@ -58,4 +58,4 @@ class NormalDistributionsTransformBase #include "ndt/impl/base.hpp" -#endif +#endif // NDT__BASE_HPP_ diff --git a/localization/ndt/include/ndt/impl/base.hpp b/localization/ndt/include/ndt/impl/base.hpp index 897712bfcd038..1c2381d8842a6 100644 --- a/localization/ndt/include/ndt/impl/base.hpp +++ b/localization/ndt/include/ndt/impl/base.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_BASE_HPP -#define NORMAL_DISTRIBUTIONS_TRANSFORM_BASE_HPP +#ifndef NDT__IMPL__BASE_HPP_ +#define NDT__IMPL__BASE_HPP_ #include "ndt/base.hpp" @@ -22,4 +22,4 @@ NormalDistributionsTransformBase::NormalDistributionsT { } -#endif // NORMAL_DISTRIBUTIONS_TRANSFORM_BASE_HPP +#endif // NDT__IMPL__BASE_HPP_ diff --git a/localization/ndt/include/ndt/impl/omp.hpp b/localization/ndt/include/ndt/impl/omp.hpp index f00dbff7bea55..e0cd88a9574af 100644 --- a/localization/ndt/include/ndt/impl/omp.hpp +++ b/localization/ndt/include/ndt/impl/omp.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_HPP -#define NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_HPP +#ifndef NDT__IMPL__OMP_HPP_ +#define NDT__IMPL__OMP_HPP_ #include "ndt/omp.hpp" @@ -183,4 +183,4 @@ NormalDistributionsTransformOMP::getNeighborhoodSearch return ndt_ptr_->getNeighborhoodSearchMethod(); } -#endif // NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_HPP +#endif // NDT__IMPL__OMP_HPP_ diff --git a/localization/ndt/include/ndt/impl/pcl_generic.hpp b/localization/ndt/include/ndt/impl/pcl_generic.hpp index 8528859c8fa01..b817d2de35a5a 100644 --- a/localization/ndt/include/ndt/impl/pcl_generic.hpp +++ b/localization/ndt/include/ndt/impl/pcl_generic.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_GENERIC_HPP -#define NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_GENERIC_HPP +#ifndef NDT__IMPL__PCL_GENERIC_HPP_ +#define NDT__IMPL__PCL_GENERIC_HPP_ #include "ndt/pcl_generic.hpp" @@ -160,4 +160,4 @@ NormalDistributionsTransformPCLGeneric::getSearchMetho return ndt_ptr_->getSearchMethodTarget(); } -#endif // NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_GENERIC_HPP +#endif // NDT__IMPL__PCL_GENERIC_HPP_ diff --git a/localization/ndt/include/ndt/impl/pcl_modified.hpp b/localization/ndt/include/ndt/impl/pcl_modified.hpp index e0983ecd50516..1b208da132d3e 100644 --- a/localization/ndt/include/ndt/impl/pcl_modified.hpp +++ b/localization/ndt/include/ndt/impl/pcl_modified.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_MODIFIED_HPP -#define NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_MODIFIED_HPP +#ifndef NDT__IMPL__PCL_MODIFIED_HPP_ +#define NDT__IMPL__PCL_MODIFIED_HPP_ #include "ndt/pcl_modified.hpp" @@ -160,4 +160,4 @@ NormalDistributionsTransformPCLModified::getSearchMeth return ndt_ptr_->getSearchMethodTarget(); } -#endif // NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_MODIFIED_HPP +#endif // NDT__IMPL__PCL_MODIFIED_HPP_ diff --git a/localization/ndt/include/ndt/omp.hpp b/localization/ndt/include/ndt/omp.hpp index 20c68db1a32e1..803190d22d4ce 100644 --- a/localization/ndt/include/ndt/omp.hpp +++ b/localization/ndt/include/ndt/omp.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_H -#define NORMAL_DISTRIBUTIONS_TRANSFORM_OMP_H +#ifndef NDT__OMP_HPP_ +#define NDT__OMP_HPP_ #include "ndt/base.hpp" @@ -71,4 +71,4 @@ class NormalDistributionsTransformOMP #include "ndt/impl/omp.hpp" -#endif +#endif // NDT__OMP_HPP_ diff --git a/localization/ndt/include/ndt/pcl_generic.hpp b/localization/ndt/include/ndt/pcl_generic.hpp index b6d7500b75871..ae1255b2dece7 100644 --- a/localization/ndt/include/ndt/pcl_generic.hpp +++ b/localization/ndt/include/ndt/pcl_generic.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_GENERIC_H -#define NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_GENERIC_H +#ifndef NDT__PCL_GENERIC_HPP_ +#define NDT__PCL_GENERIC_HPP_ #include "ndt/base.hpp" @@ -64,4 +64,4 @@ class NormalDistributionsTransformPCLGeneric #include "ndt/impl/pcl_generic.hpp" -#endif +#endif // NDT__PCL_GENERIC_HPP_ diff --git a/localization/ndt/include/ndt/pcl_modified.hpp b/localization/ndt/include/ndt/pcl_modified.hpp index f7f16f532d690..f9fa99bd782e3 100644 --- a/localization/ndt/include/ndt/pcl_modified.hpp +++ b/localization/ndt/include/ndt/pcl_modified.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_MODIFIED_H -#define NORMAL_DISTRIBUTIONS_TRANSFORM_PCL_MODIFIED_H +#ifndef NDT__PCL_MODIFIED_HPP_ +#define NDT__PCL_MODIFIED_HPP_ #include "ndt/base.hpp" @@ -65,4 +65,4 @@ class NormalDistributionsTransformPCLModified #include "ndt/impl/pcl_modified.hpp" -#endif +#endif // NDT__PCL_MODIFIED_HPP_ diff --git a/localization/ndt_pcl_modified/include/ndt_pcl_modified/impl/ndt.hpp b/localization/ndt_pcl_modified/include/ndt_pcl_modified/impl/ndt.hpp index 492bc57d84075..0feb97a19d839 100644 --- a/localization/ndt_pcl_modified/include/ndt_pcl_modified/impl/ndt.hpp +++ b/localization/ndt_pcl_modified/include/ndt_pcl_modified/impl/ndt.hpp @@ -51,8 +51,8 @@ * */ -#ifndef PCL_REGISTRATION_NDT_MODIFIED_IMPL_H_ -#define PCL_REGISTRATION_NDT_MODIFIED_IMPL_H_ +#ifndef NDT_PCL_MODIFIED__IMPL__NDT_HPP_ +#define NDT_PCL_MODIFIED__IMPL__NDT_HPP_ #include #include @@ -373,4 +373,4 @@ double pcl::NormalDistributionsTransformModified::comp return a_t; } -#endif // PCL_REGISTRATION_NDT_IMPL_MODIFIED_H_ +#endif // NDT_PCL_MODIFIED__IMPL__NDT_HPP_ diff --git a/localization/ndt_pcl_modified/include/ndt_pcl_modified/ndt.hpp b/localization/ndt_pcl_modified/include/ndt_pcl_modified/ndt.hpp index 73771b0b53e9c..81a2e219f2b81 100644 --- a/localization/ndt_pcl_modified/include/ndt_pcl_modified/ndt.hpp +++ b/localization/ndt_pcl_modified/include/ndt_pcl_modified/ndt.hpp @@ -51,8 +51,8 @@ * */ -#ifndef PCL_REGISTRATION_NDT_MODIFIED_H_ -#define PCL_REGISTRATION_NDT_MODIFIED_H_ +#ifndef NDT_PCL_MODIFIED__NDT_HPP_ +#define NDT_PCL_MODIFIED__NDT_HPP_ #include @@ -117,4 +117,4 @@ class NormalDistributionsTransformModified #include "ndt_pcl_modified/impl/ndt.hpp" -#endif // PCL_REGISTRATION_NDT_MODIFIED_H_ +#endif // NDT_PCL_MODIFIED__NDT_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp index 61084bcf0d4cb..a83e8db02f521 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/matrix_type.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NDT_SCAN_MATCHER__MATRIX_TYPE_HPP__ -#define NDT_SCAN_MATCHER__MATRIX_TYPE_HPP__ +#ifndef NDT_SCAN_MATCHER__MATRIX_TYPE_HPP_ +#define NDT_SCAN_MATCHER__MATRIX_TYPE_HPP_ #include using Matrix6d = Eigen::Matrix; using RowMatrixXd = Eigen::Matrix; -#endif // NDT_SCAN_MATCHER__MATRIX_TYPE_HPP__ +#endif // NDT_SCAN_MATCHER__MATRIX_TYPE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp index f9dc42f76a3d6..740acf335099c 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/particle.hpp @@ -31,4 +31,4 @@ struct Particle int iteration; }; -#endif // NDT_SCAN_MATCHER__DEBUG_HPP_ +#endif // NDT_SCAN_MATCHER__PARTICLE_HPP_ diff --git a/localization/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp b/localization/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp index 2dfac343b0a86..043087a3afdf2 100644 --- a/localization/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp +++ b/localization/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef _VEHICLE_VELOCITY_CONVERTER_HPP_ -#define _VEHICLE_VELOCITY_CONVERTER_HPP_ +#ifndef VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_ +#define VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_ #include @@ -44,4 +44,4 @@ class VehicleVelocityConverter : public rclcpp::Node std::array twist_covariance_; }; -#endif +#endif // VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_ diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp index e8ff385b76ed5..42ac59f4e62b8 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp @@ -51,5 +51,5 @@ class DistanceBasedCompareMapFilterComponent : public pointcloud_preprocessor::F } // namespace compare_map_segmentation // clang-format off -#endif // COMPARE_MAP_SEGMENTATION__DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#endif // COMPARE_MAP_SEGMENTATION__DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT // clang-format on diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp index 23e191317e2d0..67c7b9cd28ea2 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp @@ -53,5 +53,5 @@ class VoxelBasedApproximateCompareMapFilterComponent : public pointcloud_preproc } // namespace compare_map_segmentation // clang-format off -#endif // COMPARE_MAP_SEGMENTATION__VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#endif // COMPARE_MAP_SEGMENTATION__VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT // clang-format on diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp index cb6f99251efd7..a86a07cd73958 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp @@ -55,5 +55,5 @@ class VoxelDistanceBasedCompareMapFilterComponent : public pointcloud_preprocess } // namespace compare_map_segmentation // clang-format off -#endif // COMPARE_MAP_SEGMENTATION__VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#endif // COMPARE_MAP_SEGMENTATION__VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT // clang-format on diff --git a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp index 81bfca84441ec..308e18ddce374 100644 --- a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp +++ b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAP_LOADER__ELEVATION_MAP_LOADER_NODE_HPP_ -#define MAP_LOADER__ELEVATION_MAP_LOADER_NODE_HPP_ +#ifndef ELEVATION_MAP_LOADER__ELEVATION_MAP_LOADER_NODE_HPP_ +#define ELEVATION_MAP_LOADER__ELEVATION_MAP_LOADER_NODE_HPP_ #include #include @@ -113,4 +113,4 @@ class ElevationMapLoaderNode : public rclcpp::Node LaneFilter lane_filter_; }; -#endif // MAP_LOADER__ELEVATION_MAP_LOADER_NODE_HPP_ +#endif // ELEVATION_MAP_LOADER__ELEVATION_MAP_LOADER_NODE_HPP_ diff --git a/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/disjoint_set.hpp b/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/disjoint_set.hpp index fc3cc6b18a5ab..9c1c0405b36d1 100644 --- a/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/disjoint_set.hpp +++ b/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/disjoint_set.hpp @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef MODULES_PERCEPTION_OBSTACLE_COMMON_DISJOINT_SET_H_ -#define MODULES_PERCEPTION_OBSTACLE_COMMON_DISJOINT_SET_H_ +#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_ +#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_ template void DisjointSetMakeSet(T * x) @@ -72,4 +72,4 @@ void DisjointSetUnion(T * x, T * y) } } -#endif // MODULES_PERCEPTION_OBSTACLE_COMMON_DISJOINT_SET_H_ +#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__DISJOINT_SET_HPP_ diff --git a/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/util.hpp b/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/util.hpp index 50318e633039b..9ae382bd51cec 100644 --- a/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/util.hpp +++ b/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/util.hpp @@ -28,8 +28,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef MODULES_PERCEPTION_OBSTACLE_LIDAR_SEGMENTATION_CNNSEG_UTIL_H_ -#define MODULES_PERCEPTION_OBSTACLE_LIDAR_SEGMENTATION_CNNSEG_UTIL_H_ +#ifndef LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_ +#define LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_ #include #include @@ -56,4 +56,4 @@ inline float Pixel2Pc(int in_pixel, float in_size, float out_range) return out_range - (static_cast(in_pixel) + 0.5f) * res; } -#endif // MODULES_PERCEPTION_OBSTACLE_LIDAR_SEGMENTATION_CNNSEG_UTIL_H_ +#endif // LIDAR_APOLLO_INSTANCE_SEGMENTATION__UTIL_HPP_ diff --git a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp index c4194a3f5c1e8..30d560135cb4f 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp +++ b/perception/lidar_apollo_instance_segmentation/lib/include/TrtNet.hpp @@ -21,8 +21,8 @@ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE * SOFTWARE. */ -#ifndef __TRT_NET_H_ -#define __TRT_NET_H_ +#ifndef TRTNET_HPP_ +#define TRTNET_HPP_ #include "Utils.hpp" @@ -112,4 +112,4 @@ class trtNet }; } // namespace Tn -#endif // __TRT_NET_H_ +#endif // TRTNET_HPP_ diff --git a/perception/lidar_apollo_instance_segmentation/lib/include/Utils.hpp b/perception/lidar_apollo_instance_segmentation/lib/include/Utils.hpp index 8813206b965b3..93c90740934b9 100644 --- a/perception/lidar_apollo_instance_segmentation/lib/include/Utils.hpp +++ b/perception/lidar_apollo_instance_segmentation/lib/include/Utils.hpp @@ -22,8 +22,8 @@ * SOFTWARE. */ -#ifndef __TRT_UTILS_H_ -#define __TRT_UTILS_H_ +#ifndef UTILS_HPP_ +#define UTILS_HPP_ #include #include @@ -131,4 +131,4 @@ void read(const char *& buffer, T & val) } } // namespace Tn -#endif +#endif // UTILS_HPP_ diff --git a/perception/traffic_light_classifier/utils/trt_common.hpp b/perception/traffic_light_classifier/utils/trt_common.hpp index 269f7b11c6716..fb3f495fcdcf7 100644 --- a/perception/traffic_light_classifier/utils/trt_common.hpp +++ b/perception/traffic_light_classifier/utils/trt_common.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION__TRAFFIC_LIGHT_RECOGNITION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ -#define PERCEPTION__TRAFFIC_LIGHT_RECOGNITION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ +#ifndef PERCEPTION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ +#define PERCEPTION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ #include #include @@ -143,4 +143,4 @@ class TrtCommon } // namespace Tn -#endif // PERCEPTION__TRAFFIC_LIGHT_RECOGNITION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ +#endif // PERCEPTION__TRAFFIC_LIGHT_CLASSIFIER__UTILS__TRT_COMMON_HPP_ diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp index a02d0508ac977..cf583639bfc6c 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp @@ -109,4 +109,6 @@ class AnalyticalJerkConstrainedSmoother : public SmootherBase }; } // namespace motion_velocity_smoother -#endif +// clang-format off +#endif // MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT +// clang-format on diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp index 3f1aea85d94df..cea252f991f75 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp @@ -54,4 +54,6 @@ double integ_a(double a0, double j0, double t); } // namespace analytical_velocity_planning_utils } // namespace motion_velocity_smoother -#endif +// clang-format off +#endif // MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__VELOCITY_PLANNING_UTILS_HPP_ // NOLINT +// clang-format on diff --git a/simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp b/simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp index a8c71277b0a63..eb9e1ede3a099 100644 --- a/simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp +++ b/simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP__ -#define FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP__ +#ifndef FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ +#define FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ #include @@ -67,4 +67,4 @@ class DiagnosticStorage } // namespace fault_injection -#endif // FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP__ +#endif // FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp index 510130b67e04f..0f578ff343a17 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp +++ b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FAULT_INJECTION__FAULT_INJECTION_NODE_HPP__ -#define FAULT_INJECTION__FAULT_INJECTION_NODE_HPP__ +#ifndef FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ +#define FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ #include "fault_injection/diagnostic_storage.hpp" @@ -59,4 +59,4 @@ class FaultInjectionNode : public rclcpp::Node } // namespace fault_injection -#endif // FAULT_INJECTION__FAULT_INJECTION_NODE_HPP__ +#endif // FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ diff --git a/system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp b/system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp index 09309541fb964..69ec02134d1ab 100644 --- a/system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp +++ b/system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP__ -#define DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP__ +#ifndef DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ +#define DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ #include @@ -76,4 +76,4 @@ class DummyInfrastructureNode : public rclcpp::Node } // namespace dummy_infrastructure -#endif // DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP__ +#endif // DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_