From 8501e377fab6bea25c460f1cf371dea9645bda1a Mon Sep 17 00:00:00 2001 From: Takeshi Ishita Date: Wed, 9 Feb 2022 14:19:18 +0900 Subject: [PATCH 01/14] docs(vehicle_velocity_converter): sentence correction in README (#367) --- localization/vehicle_velocity_converter/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/vehicle_velocity_converter/README.md b/localization/vehicle_velocity_converter/README.md index 561e052439771..e25c46dfd7c0d 100644 --- a/localization/vehicle_velocity_converter/README.md +++ b/localization/vehicle_velocity_converter/README.md @@ -2,7 +2,7 @@ ## Purpose -This package is converted autoware_auto_vehicle_msgs::msg::VehicleReport message to geometry_msgs::msg::TwistWithCovarianceStamped for gyro odometer node. +This package converts autoware_auto_vehicle_msgs::msg::VehicleReport message to geometry_msgs::msg::TwistWithCovarianceStamped for gyro odometer node. ## Inputs / Outputs From 4edcdd769f69fa81523a0da9d743f306828e8662 Mon Sep 17 00:00:00 2001 From: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Date: Wed, 9 Feb 2022 18:05:17 +0900 Subject: [PATCH 02/14] feat(behavior_velocity): add jerk limit for occlusion spot deceleration (#344) * fix(behavior_velocity): use general naming Signed-off-by: taikitanaka3 * feat(behavior_velocity): safe velocity consider jerk limit Signed-off-by: taikitanaka * feat(behavior_velocity): apply safe velocity and offset Signed-off-by: taikitanaka * feat(behavior_velocity): consider delay response Signed-off-by: taikitanaka * feat(behavior_velocity): update gtest of caliculation of velocity Signed-off-by: tanaka3 * feat(behavior_velocity): add margin for debug viz Signed-off-by: tanaka3 * fix(behavior_velocity): fix stop dist Signed-off-by: tanaka3 * feat(behavior_velocity): consider safety margin Signed-off-by: tanaka3 * doc(behavior_velocity): update doc Signed-off-by: tanaka3 * chore(behavior_velocity): revert lateral distance threshold param Signed-off-by: tanaka3 * feat(behavior_velocity): use same velocity after passing safe margin point Signed-off-by: tanaka3 * doc(behavior_velocity): update doc Signed-off-by: tanaka3 * chore(behavior_velocity): rename collision point to collision point with margin Signed-off-by: tanaka3 * chore(behavior_velocity): add collision marker Signed-off-by: tanaka3 * ci(pre-commit): autofix * chore(behavior_velocity): better expression of safe motion Signed-off-by: tanaka3 * chore(behavior_velocity): fix better naming and change ego min slow down method Signed-off-by: tanaka3 * doc(behavior_velocity): update doc * doc(behavior_velocity): update figure Signed-off-by: tanaka3 Co-authored-by: taikitanaka3 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/occlusion_spot.param.yaml | 16 ++--- .../behavior_after_safe_margin.svg | 4 ++ .../docs/occlusion_spot/safe_motion.svg | 4 ++ .../occlusion_spot/occlusion_spot_utils.hpp | 55 +++++++------- .../risk_predictive_braking.hpp | 72 ++++++++++++------- .../occlusion-spot-design.md | 62 ++++++++++++---- .../src/scene_module/occlusion_spot/debug.cpp | 25 ++++--- .../scene_module/occlusion_spot/manager.cpp | 21 +++--- .../occlusion_spot/occlusion_spot_utils.cpp | 34 +++++---- .../risk_predictive_braking.cpp | 57 ++++++--------- .../scene_occlusion_spot_in_private_road.cpp | 14 ++-- .../scene_occlusion_spot_in_public_road.cpp | 14 ++-- .../test/src/test_occlusion_spot_utils.cpp | 8 +-- .../test/src/test_risk_predictive_braking.cpp | 67 ++++++++++------- .../test/src/utils.hpp | 8 +-- 15 files changed, 271 insertions(+), 190 deletions(-) create mode 100644 planning/behavior_velocity_planner/docs/occlusion_spot/behavior_after_safe_margin.svg create mode 100644 planning/behavior_velocity_planner/docs/occlusion_spot/safe_motion.svg diff --git a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml index 0ae1c7b705c03..3397c6479a5be 100644 --- a/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml +++ b/planning/behavior_velocity_planner/config/occlusion_spot.param.yaml @@ -2,20 +2,16 @@ ros__parameters: occlusion_spot: pedestrian_vel: 1.0 # [m/s] assume pedestrian is dashing from occlusion at this velocity - safety_time_buffer: 0.1 # [s] delay for the system response threshold: detection_area_length: 100.0 # [m] the length of path to consider perception range stuck_vehicle_vel: 1.0 # [m/s] velocity below this value is assumed to stop lateral_distance: 1.5 # [m] maximum lateral distance to consider hidden collision - # road type parameters - public_road: - min_velocity: 1.5 # [m/s] minimum velocity to ignore occlusion spot - ebs_decel: -2.5 # [m/s^2] maximum deceleration to assume for emergency stops. - pbs_decel: -1.0 # [m/s^2] deceleration to assume for predictive braking stops - private_road: - min_velocity: 1.5 # [m/s] minimum velocity to ignore occlusion spot - ebs_decel: -2.0 # [m/s^2] maximum deceleration to assume for emergency stops. - pbs_decel: -1.0 # [m/s^2] deceleration to assume for predictive braking stops. + 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 + delay_time: 0.1 # [s] safety time buffer for delay system response + safe_margin: 1.0 # [m] maximum safety distance for any error sidewalk: 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. diff --git a/planning/behavior_velocity_planner/docs/occlusion_spot/behavior_after_safe_margin.svg b/planning/behavior_velocity_planner/docs/occlusion_spot/behavior_after_safe_margin.svg new file mode 100644 index 0000000000000..c26c0d1db18a0 --- /dev/null +++ b/planning/behavior_velocity_planner/docs/occlusion_spot/behavior_after_safe_margin.svg @@ -0,0 +1,4 @@ + + + +
pedestrian
pedestrian
pedestrian
pedestrian
pedestrian
pedestrian
pedestrian
pedestrian
pedestrian
pedestrian
ego
ego
safe margin
safe margin
ego
ego
collision point
collision point
ego
ego
ego
ego
ego
ego
t_{0}
t_{n}
Text is not SVG - cannot display
\ No newline at end of file diff --git a/planning/behavior_velocity_planner/docs/occlusion_spot/safe_motion.svg b/planning/behavior_velocity_planner/docs/occlusion_spot/safe_motion.svg new file mode 100644 index 0000000000000..c82d0df41e5cb --- /dev/null +++ b/planning/behavior_velocity_planner/docs/occlusion_spot/safe_motion.svg @@ -0,0 +1,4 @@ + + + +
S_{safe}("TTC")
pedestrian
pedes...
Obstacle
Obstacle
s
s
ego
ego
V_{safe}("TTC")
TTC
TTC

is calculated by emergency stop jerk and acceleration which ego vehicle can stop within TTC.
is the distance to stop when the car is running at .
TTC: TTC means Time To Collision of the approaching pedestrian with the own vehicle.
V_{safe} is calculated by emergency stop jerk and acceleration which ego vehicle can stop within TTC....
ego
ego
collision point with margin
collision point with ma...
collision point
collision point
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 d5acadfcf2311..e03ec0d154597 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 @@ -71,24 +71,22 @@ struct Sidewalk double slice_size; // [m] size of each slice double min_occlusion_spot_size; // [m] minumum size to care about the occlusion spot }; - -struct VehicleInfo +struct Velocity { - double vehicle_width; // [m] vehicle_width from parameter server - double baselink_to_front; // [m] wheel_base + front_overhang -}; - -struct EgoVelocity -{ - double ebs_decel; // [m/s^2] emergency braking system deceleration - double pbs_decel; // [m/s^2] predictive braking system deceleration - double min_velocity; // [m/s] minimum allowed velocity not to stop + 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_accel; // [m/s^2] maximum allowed deceleration + 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 + double delay_time; // [s] safety time buffer for delay response + double safe_margin; // [m] maximum safety distance for any error }; struct PlannerParam { // parameters in yaml - double safety_time_buffer; // [s] double detection_area_length; // [m] double stuck_vehicle_vel; // [m/s] double lateral_distance_thr; // [m] lateral distance threshold to consider @@ -98,17 +96,27 @@ struct PlannerParam double angle_thr; // [rad] bool show_debug_grid; // [-] - VehicleInfo vehicle_info; - EgoVelocity private_road; - EgoVelocity public_road; + // 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; grid_utils::GridParam grid; }; +struct SafeMotion +{ + double stop_dist; + double safe_velocity; +}; + struct ObstacleInfo { + SafeMotion safe_motion; // safe motion of velocity and stop point geometry_msgs::msg::Point position; double max_velocity; // [m/s] Maximum velocity of the possible obstacle + double ttc; // [s] time to collision with ego }; /** @@ -123,19 +131,17 @@ struct ObstacleInfo */ struct PossibleCollisionInfo { - ObstacleInfo obstacle_info; // For hidden obstacle - autoware_auto_planning_msgs::msg::PathPoint - collision_path_point; // For baselink at collision point - geometry_msgs::msg::Pose intersection_pose; // For egp path and hidden obstacle + ObstacleInfo obstacle_info; // For hidden obstacle + PathPoint collision_with_margin; // For baselink at collision point + Pose collision_pose; // only use this for debugging + Pose intersection_pose; // For egp path and hidden obstacle lanelet::ArcCoordinates arc_lane_dist_at_collision; // For ego distance to obstacle in s-d PossibleCollisionInfo() = default; PossibleCollisionInfo( - const ObstacleInfo & obstacle_info, - const autoware_auto_planning_msgs::msg::PathPoint & collision_path_point, - const geometry_msgs::msg::Pose & intersection_pose, - const lanelet::ArcCoordinates & arc_lane_dist_to_occlusion) + const ObstacleInfo & obstacle_info, const PathPoint & collision_with_margin, + const Pose & intersection_pose, const lanelet::ArcCoordinates & arc_lane_dist_to_occlusion) : obstacle_info(obstacle_info), - collision_path_point(collision_path_point), + collision_with_margin(collision_with_margin), intersection_pose(intersection_pose), arc_lane_dist_at_collision(arc_lane_dist_to_occlusion) { @@ -143,7 +149,6 @@ struct PossibleCollisionInfo }; lanelet::ConstLanelet toPathLanelet(const PathWithLaneId & path); - // Note : consider offset_from_start_to_ego and safety margin for collision here inline void handleCollisionOffset( std::vector & possible_collisions, double offset, double margin) 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 00e1d5c1ba79e..10e79f71930cb 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 @@ -26,51 +26,69 @@ namespace behavior_velocity_planner { namespace occlusion_spot_utils { -void applySafeVelocityConsideringPossibleCollison( - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path, - std::vector & possible_collisions, const double current_vel, - const EgoVelocity & ego, const PlannerParam & param); +void applySafeVelocityConsideringPossibleCollision( + PathWithLaneId * inout_path, std::vector & possible_collisions, + const PlannerParam & param); int insertSafeVelocityToPath( const geometry_msgs::msg::Pose & in_pose, const double safe_vel, const PlannerParam & param, - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path); + PathWithLaneId * inout_path); // @brief calculates the maximum velocity allowing to decelerate within the given distance -inline double calculatePredictiveBrakingVelocity( - const double ego_vel, const double dist2col, const double pbs_decel) +inline double calculateMinSlowDownVelocity( + const double v0, const double len, const double a_max, const double safe_vel) { - return std::sqrt(std::max(std::pow(ego_vel, 2.0) - 2.0 * std::abs(pbs_decel) * dist2col, 0.0)); + // if target velocity is inserted backward return current velocity as limit + if (len < 0) return safe_vel; + return std::sqrt(std::max(std::pow(v0, 2.0) - 2.0 * std::abs(a_max) * len, 0.0)); } /** - * @param: safety_time: safety time buffer for reaction - * @param: dist_to_obj: distance to virtual darting object - * @param: v_obs: relative velocity for virtual darting object - * @param: ebs_decel: emergency brake - * @return safe velocity considering rpb + * @param: sv: ego velocity config + * @param: ttc: time to collision + * @return safe motion **/ -inline double calculateSafeRPBVelocity( - const double safety_time, const double dist_to_obj, const double v_obs, const double ebs_decel) +inline SafeMotion calculateSafeMotion(const Velocity & v, const double ttc) { - const double t_vir = dist_to_obj / v_obs; - // min safety time buffer is at least more than 0 - const double ttc_virtual = std::max(t_vir - safety_time, 0.0); - // safe velocity consider emergency brake - const double v_safe = std::abs(ebs_decel) * ttc_virtual; - return v_safe; + SafeMotion sm; + const double j_max = v.safety_ratio * v.max_stop_jerk; + const double a_max = v.safety_ratio * v.max_stop_accel; + const double t1 = v.delay_time; + double t2 = a_max / j_max; + double & v_safe = sm.safe_velocity; + double & stop_dist = sm.stop_dist; + if (ttc <= t1) { + // delay + v_safe = 0; + stop_dist = 0; + } else if (ttc <= t2 + t1) { + // delay + const jerk + t2 = ttc - t1; + v_safe = -0.5 * j_max * t2 * t2; + stop_dist = v_safe * t1 - j_max * t2 * t2 * t2 / 6; + } else { + const double t3 = ttc - t2 - t1; + // delay + const jerk + const accel + const double v2 = -0.5 * j_max * t2 * t2; + v_safe = v2 - a_max * t3; + stop_dist = v_safe * t1 - j_max * t2 * t2 * t2 / 6 + v2 * t3 - 0.5 * a_max * t3 * t3; + } + stop_dist += v.safe_margin; + return sm; } -inline double getPBSLimitedRPBVelocity( - const double pbs_vel, const double rpb_vel, const double min_vel, const double original_vel) +inline double calculateInsertVelocity( + const double min_allowed_vel, const double safe_vel, const double min_vel, + const double original_vel) { const double max_vel_noise = 0.05; // ensure safe velocity doesn't exceed maximum allowed pbs deceleration - double rpb_pbs_limited_vel = std::max(pbs_vel + max_vel_noise, rpb_vel); + double cmp_safe_vel = std::max(min_allowed_vel + max_vel_noise, safe_vel); // ensure safe path velocity is also above ego min velocity - rpb_pbs_limited_vel = std::max(rpb_pbs_limited_vel, min_vel); + cmp_safe_vel = std::max(cmp_safe_vel, min_vel); // ensure we only lower the original velocity (and do not increase it) - rpb_pbs_limited_vel = std::min(rpb_pbs_limited_vel, original_vel); - return rpb_pbs_limited_vel; + cmp_safe_vel = std::min(cmp_safe_vel, original_vel); + return cmp_safe_vel; } } // namespace occlusion_spot_utils diff --git a/planning/behavior_velocity_planner/occlusion-spot-design.md b/planning/behavior_velocity_planner/occlusion-spot-design.md index b936ac55a7d31..2cbc0d2368fd0 100644 --- a/planning/behavior_velocity_planner/occlusion-spot-design.md +++ b/planning/behavior_velocity_planner/occlusion-spot-design.md @@ -53,12 +53,31 @@ Occlusion spot computation: searching occlusion spots for all cells in the occup 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. + +- jerk limit[m/s^3] +- deceleration limit[m/s2] +- delay response time[s] +- time to collision of pedestrian[s] + with these parameters we can briefly define safe motion before occlusion spot for ideal environment. + ![occupancy_grid](./docs/occlusion_spot/safe_motion.svg) + +##### 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. + +![brief](./docs/occlusion_spot/behavior_after_safe_margin.svg) + #### Module Parameters -| Parameter | Type | Description | -| -------------------- | ------ | ------------------------------------------------------------------------- | -| `pedestrian_vel` | double | [m/s] maximum velocity assumed pedestrian coming out from occlusion point | -| `safety_time_buffer` | double | [m/s] time buffer for the system delay | +| Parameter | Type | Description | +| ---------------- | ------ | ------------------------------------------------------------------------- | +| `pedestrian_vel` | double | [m/s] maximum velocity assumed pedestrian coming out from occlusion point | | Parameter /threshold | Type | Description | | ----------------------- | ------ | --------------------------------------------------------- | @@ -66,15 +85,18 @@ Note that the accuracy and performance of this search method is limited due to t | `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 /(public or private)\_road | Type | Description | -| ------------------------------------ | ------ | -------------------------------------------------------------------- | -| `min_velocity` | double | [m/s] minimum velocity to ignore occlusion spot | -| `ebs_decel` | double | [m/s^2] maximum deceleration to assume for emergency braking system. | -| `pbs_decel` | double | [m/s^2] deceleration to assume for predictive braking system | +| 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 /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 /grid | Type | Description | @@ -121,8 +143,12 @@ note right - occlusion spot is calculated by longitudinally closest point of unknown cells. - intersection point is where ego front bumper and darting object will crash. - collision path point is calculated by arc coordinate consider ego vehicle's geometry. + - safe velocity and safe margin is calculated from performance of ego emergency braking system. +end note +:calculate safe velocity and safe margin for possible collision; +note right + - safe velocity and safe margin is calculated from performance of ego emergency braking system. end note - } partition process_possible_collision { :filter possible collision by road type; @@ -137,10 +163,10 @@ end note note right consider offset from path start to ego vehicle for possible collision end note -:apply safe velocity consider possible collision; +:apply safe velocity comparing with allowed velocity; note right calculated by -- ebs deceleration [m/s] emergency braking system consider lateral distance to the occlusion spot. +- safe velocity calculated from emergency brake performance. - maximum allowed deceleration [m/s^2] - min velocity [m/s] the velocity that is allowed on the road. - original_velocity [m/s] @@ -186,12 +212,16 @@ note right - intersection point is where ego front bumper and darting object will crash. - collision path point is calculated by arc coordinate consider ego vehicle's geometry. end note +:calculate safe velocity and safe margin for possible collision; +note right + - safe velocity and safe margin is calculated from performance of ego emergency braking system. +end note } partition process_possible_collision { :filter collision by road type; :calculate slow down points for possible collision; :handle collision offset; -:calculate safe velocity consider lateral distance and safe velocity; +:apply safe velocity comparing with allowed velocity; :insert safe velocity to path; } stop @@ -236,12 +266,16 @@ note right - consider occlusion which is nearer than `lateral_distance_threshold`. end note :calculate collision path point and intersection point; +:calculate safe velocity and safe margin for possible collision; +note right + - safe velocity and safe margin is calculated from performance of ego emergency braking system. +end note } partition handle_possible_collision { :filter collision by road type; :calculate slow down points for possible collision; :handle collision offset; -:calculate safe velocity consider lateral distance and safe velocity; +:apply safe velocity comparing with allowed velocity; :insert safe velocity to path; } stop 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 9dea5b7784ec3..4af5a95ce4413 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 @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -97,14 +98,18 @@ std::vector makeCollisionMarkers( debug_marker.header.frame_id = "map"; debug_marker.ns = "collision_point"; debug_marker.id = id; - // cylinder at collision_point point + // cylinder at collision with margin point debug_marker.type = visualization_msgs::msg::Marker::CYLINDER; - debug_marker.pose = possible_collision.collision_path_point.pose; - debug_marker.scale = tier4_autoware_utils::createMarkerScale(1.0, 1.0, 0.5); + debug_marker.pose = possible_collision.collision_with_margin.pose; + debug_marker.scale = tier4_autoware_utils::createMarkerScale(0.5, 0.5, 0.5); debug_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.5); - debug_marker.lifetime = rclcpp::Duration::from_seconds(0.5); debug_markers.push_back(debug_marker); + debug_marker.id++; + // cylinder at collision_point point + debug_marker.pose = possible_collision.collision_pose; + debug_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.5, 0.0, 0.5); + debug_markers.push_back(debug_marker); // cylinder at obstacle point debug_marker.ns = "obstacle"; debug_marker.type = visualization_msgs::msg::Marker::CYLINDER; @@ -116,13 +121,17 @@ std::vector makeCollisionMarkers( // info text at obstacle point debug_marker.ns = "info_obstacle"; debug_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - debug_marker.pose = possible_collision.collision_path_point.pose; + debug_marker.pose = possible_collision.collision_with_margin.pose; debug_marker.scale.z = 1.0; debug_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 1.0, 0.0, 1.0); std::ostringstream string_stream; - string_stream << "(s,d,v)=(" << possible_collision.arc_lane_dist_at_collision.length << " , " - << possible_collision.arc_lane_dist_at_collision.distance << " , " - << possible_collision.collision_path_point.longitudinal_velocity_mps << ")"; + auto r = [](const double v) { return std::round(v * 100.0) / 100.0; }; + const double len = r(possible_collision.arc_lane_dist_at_collision.length); + const double dist = r(possible_collision.arc_lane_dist_at_collision.distance); + const double vel = r(possible_collision.obstacle_info.safe_motion.safe_velocity); + const double margin = r(possible_collision.obstacle_info.safe_motion.stop_dist); + string_stream << "(s,d,v,m)=(" << len << " , " << dist << " , " << vel << " , " << margin + << " )"; debug_marker.text = string_stream.str(); debug_markers.push_back(debug_marker); } 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 28eb0f9ddd660..316873d80d751 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 @@ -81,7 +81,6 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) auto & pp = planner_param_; // assume pedestrian coming out from occlusion spot with this velocity pp.pedestrian_vel = node.declare_parameter(ns + ".pedestrian_vel", 1.0); - pp.safety_time_buffer = node.declare_parameter(ns + ".safety_time_buffer", 0.1); 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); pp.lateral_distance_thr = node.declare_parameter(ns + ".threshold.lateral_distance", 10.0); @@ -90,16 +89,12 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) 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); - // public road ego param - pp.public_road.min_velocity = node.declare_parameter(ns + ".public_road.min_velocity", 2.7); - pp.public_road.ebs_decel = node.declare_parameter(ns + ".public_road.ebs_decel", -5.0); - pp.public_road.pbs_decel = node.declare_parameter(ns + ".public_road.pbs_decel", -1.5); - - // private road - pp.private_road.min_velocity = node.declare_parameter(ns + ".private_road.min_velocity", 1.5); - pp.private_road.ebs_decel = node.declare_parameter(ns + ".private_road.ebs_decel", -4.0); - pp.private_road.pbs_decel = node.declare_parameter(ns + ".private_road.pbs_decel", -2.5); - + // 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.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); @@ -108,6 +103,10 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) // 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); + + const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + pp.baselink_to_front = vehicle_info.max_longitudinal_offset_m; + pp.half_vehicle_width = 0.5 * vehicle_info.vehicle_width_m; } void OcclusionSpotModuleManager::launchNewModules( 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 dbad637972216..4922d994bc8e0 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 @@ -15,6 +15,7 @@ #include #include #include +#include #include #include #include @@ -206,8 +207,9 @@ void calcSlowDownPointsForPossibleCollision( const double z = getInterpolatedValue(d0, p0.z, dist_to_col, d1, p1.z); // height is used to visualize marker correctly auto & col = possible_collisions.at(collision_index); - col.collision_path_point.longitudinal_velocity_mps = v; - col.collision_path_point.pose.position.z = z; + col.collision_with_margin.longitudinal_velocity_mps = v; + col.collision_with_margin.pose.position.z = z; + col.collision_pose.position.z = z; col.intersection_pose.position.z = z; col.obstacle_info.position.z = z; const double current_dist2col = col.arc_lane_dist_at_collision.length + offset; @@ -317,11 +319,19 @@ PossibleCollisionInfo calculateCollisionPathPointFromOcclusionSpot( * ------------------ */ PossibleCollisionInfo pc; - pc.arc_lane_dist_at_collision = arc_coord_occlusion_with_offset; + const double ttc = std::abs(arc_coord_occlusion_with_offset.distance / param.pedestrian_vel); + SafeMotion sm = calculateSafeMotion(param.v, ttc); + double distance_to_stop = arc_coord_occlusion_with_offset.length - sm.stop_dist; + const double eps = 0.1; + // avoid inserting path point behind original path + if (distance_to_stop < eps) distance_to_stop = eps; + pc.arc_lane_dist_at_collision = {distance_to_stop, arc_coord_occlusion_with_offset.distance}; + pc.obstacle_info.safe_motion = sm; + pc.obstacle_info.ttc = ttc; pc.obstacle_info.position = setPose(path_lanelet, arc_coord_occlusion).position; pc.obstacle_info.max_velocity = param.pedestrian_vel; - pc.collision_path_point.pose = - setPose(path_lanelet, {arc_coord_occlusion_with_offset.length, 0.0}); + pc.collision_pose = setPose(path_lanelet, {arc_coord_occlusion_with_offset.length, 0.0}); + pc.collision_with_margin.pose = setPose(path_lanelet, {distance_to_stop, 0.0}); pc.intersection_pose = setPose(path_lanelet, {arc_coord_occlusion.length, 0.0}); return pc; } @@ -332,14 +342,12 @@ std::vector generatePossibleCollisionBehindParkedVehicle( { lanelet::ConstLanelet path_lanelet = toPathLanelet(path); std::vector possible_collisions; - const double half_vehicle_width = 0.5 * param.vehicle_info.vehicle_width; - const double baselink_to_front = param.vehicle_info.baselink_to_front; auto ll = path_lanelet.centerline2d(); for (const auto & dyn : dyn_objects) { ArcCoordinates arc_coord_occlusion = getOcclusionPoint(dyn, ll); ArcCoordinates arc_coord_occlusion_with_offset = { - arc_coord_occlusion.length - baselink_to_front, - calcSignedLateralDistanceWithOffset(arc_coord_occlusion.distance, half_vehicle_width)}; + arc_coord_occlusion.length - param.baselink_to_front, + calcSignedLateralDistanceWithOffset(arc_coord_occlusion.distance, param.half_vehicle_width)}; // ignore if collision is not avoidable by velocity control. if ( arc_coord_occlusion_with_offset.length < offset_from_start_to_ego || @@ -418,8 +426,8 @@ void generateSidewalkPossibleCollisions( } std::vector sidewalk_slices; geometry::buildSidewalkSlices( - sidewalk_slices, path_lanelet, 0.0, param.vehicle_info.vehicle_width * 0.5, - param.sidewalk.slice_size, param.sidewalk.focus_range); + 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 @@ -463,8 +471,8 @@ void generateSidewalkPossibleCollisionFromOcclusionSpot( const double offset_from_start_to_ego, const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param) { - const double baselink_to_front = param.vehicle_info.baselink_to_front; - const double half_vehicle_width = param.vehicle_info.vehicle_width * 0.5; + const double baselink_to_front = param.baselink_to_front; + const double half_vehicle_width = param.half_vehicle_width; double distance_lower_bound = std::numeric_limits::max(); PossibleCollisionInfo candidate; bool has_collision = false; 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 21c78e5345592..ce6df41e80338 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 @@ -23,10 +23,9 @@ namespace behavior_velocity_planner { namespace occlusion_spot_utils { -void applySafeVelocityConsideringPossibleCollison( - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path, - std::vector & possible_collisions, const double current_vel, - const EgoVelocity & ego, const PlannerParam & param) +void applySafeVelocityConsideringPossibleCollision( + PathWithLaneId * inout_path, std::vector & possible_collisions, + const PlannerParam & param) { const auto logger{rclcpp::get_logger("behavior_velocity_planner").get_child("occlusion_spot")}; rclcpp::Clock clock{RCL_ROS_TIME}; @@ -34,37 +33,24 @@ void applySafeVelocityConsideringPossibleCollison( if (!inout_path || inout_path->points.size() < 2) { return; } + const double v0 = param.v.v_ego; + 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) { - const double dist_to_collision = possible_collision.arc_lane_dist_at_collision.length; - const double original_vel = possible_collision.collision_path_point.longitudinal_velocity_mps; - const double d_obs = std::abs(possible_collision.arc_lane_dist_at_collision.distance); - const double v_obs = possible_collision.obstacle_info.max_velocity; - // skip if obstacle velocity is below zero - if (v_obs < 0) { - RCLCPP_WARN_THROTTLE( - logger, clock, 3000, "velocity for virtual darting object is not set correctly"); - continue; - // skip if distance to object is below zero - } else if (d_obs < 0) { - RCLCPP_WARN_THROTTLE( - logger, clock, 3000, "distance for virtual darting object is not set correctly"); - continue; - } - // RPB : risk predictive braking system velocity consider ego emergency braking deceleration - const double risk_predictive_braking_velocity = - calculateSafeRPBVelocity(param.safety_time_buffer, d_obs, v_obs, ego.ebs_decel); + const double l_obs = possible_collision.arc_lane_dist_at_collision.length; + const double original_vel = possible_collision.collision_with_margin.longitudinal_velocity_mps; + + // safe velocity : Consider ego emergency braking deceleration + const double v_safe = possible_collision.obstacle_info.safe_motion.safe_velocity; - // PBS : predictive braking system velocity consider ego predictive braking deceleration - const double predictive_braking_system_velocity = - calculatePredictiveBrakingVelocity(current_vel, dist_to_collision, ego.pbs_decel); + // min allowed velocity : min allowed velocity consider maximum allowed braking + const double v_slow_down = calculateMinSlowDownVelocity(v0, l_obs, a_min, v_safe); - // get RPB velocity consider PBS limiter and minimum allowed velocity according to the road type - const double pbs_limited_rpb_vel = getPBSLimitedRPBVelocity( - predictive_braking_system_velocity, risk_predictive_braking_velocity, ego.min_velocity, - original_vel); - possible_collision.collision_path_point.longitudinal_velocity_mps = pbs_limited_rpb_vel; - insertSafeVelocityToPath( - possible_collision.collision_path_point.pose, pbs_limited_rpb_vel, param, inout_path); + // coompare 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; + insertSafeVelocityToPath(pose, safe_velocity, param, inout_path); } } @@ -75,8 +61,7 @@ bool isAheadOf(const geometry_msgs::msg::Pose & target, const geometry_msgs::msg return is_target_ahead; } -bool setVelocityFrom( - const size_t idx, const double vel, autoware_auto_planning_msgs::msg::PathWithLaneId * input) +bool setVelocityFrom(const size_t idx, const double vel, PathWithLaneId * input) { for (size_t i = idx; i < input->points.size(); ++i) { input->points.at(i).point.longitudinal_velocity_mps = @@ -87,14 +72,14 @@ bool setVelocityFrom( int insertSafeVelocityToPath( const geometry_msgs::msg::Pose & in_pose, const double safe_vel, const PlannerParam & param, - autoware_auto_planning_msgs::msg::PathWithLaneId * inout_path) + PathWithLaneId * inout_path) { int closest_idx = -1; if (!planning_utils::calcClosestIndex( *inout_path, in_pose, closest_idx, param.dist_thr, param.angle_thr)) { return -1; } - autoware_auto_planning_msgs::msg::PathPointWithLaneId inserted_point; + PathPointWithLaneId inserted_point; inserted_point = inout_path->points.at(closest_idx); int insert_idx = closest_idx; // insert velocity to path if distance is not too close else insert new collision point 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 ffc53f8efa586..2bd245a91f76b 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 @@ -48,11 +48,14 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( if (path->points.size() < 2) { return true; } - param_.vehicle_info.baselink_to_front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - param_.vehicle_info.vehicle_width = planner_data_->vehicle_info_.vehicle_width_m; - + // set planner data + { + param_.v.max_stop_jerk = planner_data_->max_stop_jerk_threshold; + 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(); + } const geometry_msgs::msg::Pose ego_pose = planner_data_->current_pose.pose; - const double ego_velocity = planner_data_->current_velocity->twist.linear.x; const auto & lanelet_map_ptr = planner_data_->lanelet_map; const auto & traffic_rules_ptr = planner_data_->traffic_rules; const auto & occ_grid_ptr = planner_data_->occupancy_grid; @@ -98,8 +101,7 @@ bool OcclusionSpotInPrivateModule::modifyPathVelocity( // 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 - applySafeVelocityConsideringPossibleCollison( - path, possible_collisions, ego_velocity, param_.private_road, param_); + utils::applySafeVelocityConsideringPossibleCollision(path, possible_collisions, param_); 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 4d29fdb0dd93e..ceff1798eb2bc 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 @@ -48,11 +48,14 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( if (path->points.size() < 2) { return true; } - param_.vehicle_info.baselink_to_front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - param_.vehicle_info.vehicle_width = planner_data_->vehicle_info_.vehicle_width_m; - + // set planner data + { + param_.v.max_stop_jerk = planner_data_->max_stop_jerk_threshold; + 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(); + } const geometry_msgs::msg::Pose ego_pose = planner_data_->current_pose.pose; - const double ego_velocity = planner_data_->current_velocity->twist.linear.x; const auto & lanelet_map_ptr = planner_data_->lanelet_map; const auto & routing_graph_ptr = planner_data_->routing_graph; const auto & traffic_rules_ptr = planner_data_->traffic_rules; @@ -87,8 +90,7 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity( // 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 - applySafeVelocityConsideringPossibleCollison( - path, possible_collisions, ego_velocity, param_.public_road, param_); + utils::applySafeVelocityConsideringPossibleCollision(path, possible_collisions, param_); debug_data_.possible_collisions = possible_collisions; return true; 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 fa5430e2329b5..004d192d90a3e 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 @@ -117,7 +117,7 @@ TEST(calcSlowDownPointsForPossibleCollision, ConsiderSignedOffset) * c : collision */ calcSlowDownPointsForPossibleCollision(0, path, -offset_from_start_to_ego, pcs); - if (pcs[0].collision_path_point.longitudinal_velocity_mps - 3.0 > 1e-3) { + if (pcs[0].collision_with_margin.longitudinal_velocity_mps - 3.0 > 1e-3) { for (size_t i = 0; i < path.points.size(); i++) { std::cout << "v : " << path.points[i].point.longitudinal_velocity_mps << "\t"; } @@ -127,9 +127,9 @@ TEST(calcSlowDownPointsForPossibleCollision, ConsiderSignedOffset) } std::cout << std::endl; } - EXPECT_DOUBLE_EQ(pcs[0].collision_path_point.longitudinal_velocity_mps, 3); - EXPECT_DOUBLE_EQ(pcs[1].collision_path_point.longitudinal_velocity_mps, 4.5); - EXPECT_DOUBLE_EQ(pcs[2].collision_path_point.longitudinal_velocity_mps, 6); + EXPECT_DOUBLE_EQ(pcs[0].collision_with_margin.longitudinal_velocity_mps, 3); + EXPECT_DOUBLE_EQ(pcs[1].collision_with_margin.longitudinal_velocity_mps, 4.5); + EXPECT_DOUBLE_EQ(pcs[2].collision_with_margin.longitudinal_velocity_mps, 6); } pcs.clear(); 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 5d19e30df0bf4..644790d44e50c 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 @@ -19,42 +19,57 @@ #include +#include #include -TEST(calculatePredictiveBrakingVelocity, min_max) +TEST(safeMotion, delay_jerk_acceleration) { - using behavior_velocity_planner::occlusion_spot_utils::calculatePredictiveBrakingVelocity; - const double inf = std::numeric_limits::max(); - std::cout << "PBS(v0,dist,pbs) of (10,2,-inf) --> 0[m/s] \n"; - // lower bound ego_vel - ASSERT_EQ(calculatePredictiveBrakingVelocity(0, 2, -inf), 0); - std::cout << "PBS(v0,dist,pbs) of (10,inf,0) --> 10[m/s] \n"; - // upper bound - ASSERT_EQ(calculatePredictiveBrakingVelocity(10, inf, 0), 10); -} - -TEST(calculateSafeRPBVelocity, min_max) -{ - using behavior_velocity_planner::occlusion_spot_utils::calculateSafeRPBVelocity; - // lower bound ttc_vir = 0 - const double t_buff = 0.5; - double d_obs = 0.5; - double v_obs = 1.0; - ASSERT_EQ(calculateSafeRPBVelocity(t_buff, d_obs, v_obs, -5.0), 0.0); - // lower bound ebs_decel = 0 - ASSERT_EQ(calculateSafeRPBVelocity(1.0, 0.5, 0.5, 0), 0.0); + namespace utils = behavior_velocity_planner::occlusion_spot_utils; + using utils::calculateSafeMotion; + /** + * @brief check if calculation is correct in below parameter + * delay = 0.5 [s] + * a_max = -4.5 [m/s^2] + * j_max = -3.0 [m/s^3] + * case1 delay + * 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}; + double ttc = 0.0; + // 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); + } + // 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); + } + // 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); + } } -TEST(getPBSLimitedRPBVelocity, min_max) +TEST(calculateInsertVelocity, min_max) { - using behavior_velocity_planner::occlusion_spot_utils::getPBSLimitedRPBVelocity; + using behavior_velocity_planner::occlusion_spot_utils::calculateInsertVelocity; const double inf = std::numeric_limits::max(); // upper bound rpb_vel - ASSERT_EQ(getPBSLimitedRPBVelocity(inf, inf, inf, inf), inf); + ASSERT_EQ(calculateInsertVelocity(inf, inf, inf, inf), inf); // lower bound org_vel = 0 - ASSERT_EQ(getPBSLimitedRPBVelocity(inf, inf, inf, 0), 0.0); + ASSERT_EQ(calculateInsertVelocity(inf, inf, inf, 0), 0.0); // lower bound min = 0 - ASSERT_EQ(getPBSLimitedRPBVelocity(inf, inf, 0, inf), inf); + ASSERT_EQ(calculateInsertVelocity(inf, inf, 0, inf), inf); } TEST(insertSafeVelocityToPath, replace_original_at_too_close_case) diff --git a/planning/behavior_velocity_planner/test/src/utils.hpp b/planning/behavior_velocity_planner/test/src/utils.hpp index bec213595f9b3..8054dfcadaca1 100644 --- a/planning/behavior_velocity_planner/test/src/utils.hpp +++ b/planning/behavior_velocity_planner/test/src/utils.hpp @@ -178,15 +178,15 @@ inline void generatePossibleCollisions( intersection_pose.position.x = y0 + y_step * i; // collision path point - autoware_auto_planning_msgs::msg::PathPoint collision_path_point{}; - collision_path_point.pose.position.x = x0 + x_step * i + lon; - collision_path_point.pose.position.y = y0 + y_step * i; + autoware_auto_planning_msgs::msg::PathPoint collision_with_margin{}; + collision_with_margin.pose.position.x = x0 + x_step * i + lon; + collision_with_margin.pose.position.y = y0 + y_step * i; lanelet::ArcCoordinates arc; arc.length = obstacle_info.position.x; arc.distance = obstacle_info.position.y; - PossibleCollisionInfo col(obstacle_info, collision_path_point, intersection_pose, arc); + PossibleCollisionInfo col(obstacle_info, collision_with_margin, intersection_pose, arc); possible_collisions.emplace_back(col); } } From 12ef731c20400cd2ceecb9258b72c65b94e8dbaa Mon Sep 17 00:00:00 2001 From: ito-san <57388357+ito-san@users.noreply.github.com> Date: Wed, 9 Feb 2022 22:36:03 +0900 Subject: [PATCH 03/14] feat(system_monitor): handle parameter as mount point (#259) Signed-off-by: ito-san --- .../config/hdd_monitor.param.yaml | 2 +- .../hdd_monitor/hdd_monitor.hpp | 16 ++++-- .../src/hdd_monitor/hdd_monitor.cpp | 56 +++++++++++++++---- 3 files changed, 58 insertions(+), 16 deletions(-) diff --git a/system/system_monitor/config/hdd_monitor.param.yaml b/system/system_monitor/config/hdd_monitor.param.yaml index 32d3a425b1898..817ff68814a56 100644 --- a/system/system_monitor/config/hdd_monitor.param.yaml +++ b/system/system_monitor/config/hdd_monitor.param.yaml @@ -4,7 +4,7 @@ num_disks: 1 disks: # Until multi type lists are allowed, name N the disks as disk0...disk{N-1} disk0: - name: /dev/sda3 + name: / temp_warn: 55.0 temp_error: 70.0 free_warn: 5120 # MB(8hour) diff --git a/system/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp b/system/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp index 0dcee7de54aad..204c52fc23705 100644 --- a/system/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp +++ b/system/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp @@ -32,10 +32,11 @@ */ struct HDDParam { - float temp_warn_; //!< @brief HDD temperature(DegC) to generate warning - float temp_error_; //!< @brief HDD temperature(DegC) to generate error - int free_warn_; //!< @brief HDD free space(MB) to generate warning - int free_error_; //!< @brief HDD free space(MB) to generate error + std::string device_; //!< @brief device + float temp_warn_; //!< @brief HDD temperature(DegC) to generate warning + float temp_error_; //!< @brief HDD temperature(DegC) to generate error + int free_warn_; //!< @brief HDD free space(MB) to generate warning + int free_error_; //!< @brief HDD free space(MB) to generate error HDDParam() : temp_warn_(55.0), temp_error_(70.0), free_warn_(5120), free_error_(100) {} }; @@ -86,6 +87,13 @@ class HDDMonitor : public rclcpp::Node */ void getHDDParams(); + /** + * @brief get device name from mount point + * @param [in] mount_point mount point + * @return device name + */ + std::string getDeviceFromMountPoint(const std::string & mount_point); + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics char hostname_[HOST_NAME_MAX + 1]; //!< @brief host name diff --git a/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp b/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp index 20be9d3010d1d..b863a19547b39 100644 --- a/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp +++ b/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp @@ -156,8 +156,8 @@ void HDDMonitor::checkTemp(diagnostic_updater::DiagnosticStatusWrapper & stat) for (auto itr = hdd_params_.begin(); itr != hdd_params_.end(); ++itr, ++index) { // Retrieve HDD information - auto itrh = list.find(itr->first); - if (itrh == list.end()) { + auto hdd_itr = list.find(itr->second.device_); + if (hdd_itr == list.end()) { stat.add(fmt::format("HDD {}: status", index), "hdd_reader error"); stat.add(fmt::format("HDD {}: name", index), itr->first.c_str()); stat.add(fmt::format("HDD {}: hdd_reader", index), strerror(ENOENT)); @@ -165,15 +165,15 @@ void HDDMonitor::checkTemp(diagnostic_updater::DiagnosticStatusWrapper & stat) continue; } - if (itrh->second.error_code_ != 0) { + if (hdd_itr->second.error_code_ != 0) { stat.add(fmt::format("HDD {}: status", index), "hdd_reader error"); stat.add(fmt::format("HDD {}: name", index), itr->first.c_str()); - stat.add(fmt::format("HDD {}: hdd_reader", index), strerror(itrh->second.error_code_)); + stat.add(fmt::format("HDD {}: hdd_reader", index), strerror(hdd_itr->second.error_code_)); error_str = "hdd_reader error"; continue; } - float temp = static_cast(itrh->second.temp_); + float temp = static_cast(hdd_itr->second.temp_); level = DiagStatus::OK; if (temp >= itr->second.temp_error_) { @@ -183,9 +183,9 @@ void HDDMonitor::checkTemp(diagnostic_updater::DiagnosticStatusWrapper & stat) } stat.add(fmt::format("HDD {}: status", index), temp_dict_.at(level)); - stat.add(fmt::format("HDD {}: name", index), itr->first.c_str()); - stat.add(fmt::format("HDD {}: model", index), itrh->second.model_.c_str()); - stat.add(fmt::format("HDD {}: serial", index), itrh->second.serial_.c_str()); + stat.add(fmt::format("HDD {}: name", index), itr->second.device_.c_str()); + stat.add(fmt::format("HDD {}: model", index), hdd_itr->second.model_.c_str()); + stat.add(fmt::format("HDD {}: serial", index), hdd_itr->second.serial_.c_str()); stat.addf(fmt::format("HDD {}: temperature", index), "%.1f DegC", temp); whole_level = std::max(whole_level, level); @@ -301,18 +301,52 @@ void HDDMonitor::getHDDParams() const auto num_disks = this->declare_parameter("num_disks", 0); for (auto i = 0; i < num_disks; ++i) { const auto prefix = "disks.disk" + std::to_string(i); + const auto name = declare_parameter(prefix + ".name"); + + // Get device name from mount point + const auto device_name = getDeviceFromMountPoint(name); + if (device_name.empty()) { + continue; + } + HDDParam param; param.temp_warn_ = declare_parameter(prefix + ".temp_warn"); param.temp_error_ = declare_parameter(prefix + ".temp_error"); param.free_warn_ = declare_parameter(prefix + ".free_warn"); param.free_error_ = declare_parameter(prefix + ".free_error"); - const auto name = declare_parameter(prefix + ".name"); - hdd_params_[name] = param; + // Remove index number for passing device name to hdd-reader + const std::regex pattern("\\d+$"); + param.device_ = std::regex_replace(device_name, pattern, ""); + hdd_params_[device_name] = param; - hdd_devices_.push_back(name); + hdd_devices_.push_back(param.device_); } } +std::string HDDMonitor::getDeviceFromMountPoint(const std::string & mount_point) +{ + std::string ret; + bp::ipstream is_out; + bp::ipstream is_err; + + bp::child c( + "/bin/sh", "-c", fmt::format("findmnt -n -o SOURCE {}", mount_point.c_str()), + bp::std_out > is_out, bp::std_err > is_err); + c.wait(); + + if (c.exit_code() != 0) { + RCLCPP_ERROR(get_logger(), "Failed to execute findmnt. %s", mount_point.c_str()); + return ""; + } + + if (!std::getline(is_out, ret)) { + RCLCPP_ERROR(get_logger(), "Failed to find device name. %s", mount_point.c_str()); + return ""; + } + + return ret; +} + #include RCLCPP_COMPONENTS_REGISTER_NODE(HDDMonitor) From eb599aec607084113cf0994888031ebe6065468a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 10 Feb 2022 10:37:27 +0900 Subject: [PATCH 04/14] fix(behavior_path_planner): crash when drivable area expanding (#365) This is to fix the behavior path planner crash when the drivable area is expanding towards opposite direction lane Signed-off-by: Muhammad Zulfaqar Azmi --- .../avoidance/avoidance_module.cpp | 22 +++++++++++-------- 1 file changed, 13 insertions(+), 9 deletions(-) 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 5649c7e2a4025..1922cb97b1286 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 @@ -1682,11 +1682,13 @@ void AvoidanceModule::generateExtendedDrivableArea(ShiftedPath * shifted_path) c extended_lanelets.push_back(lanelet_at_left.get()); lanelet_at_left = route_handler->getLeftLanelet(lanelet_at_left.get()); } - auto lanelet_at_right = - planner_data_->route_handler->getRightLanelet(lanelet_at_left.get()); - while (lanelet_at_right) { - extended_lanelets.push_back(lanelet_at_right.get()); - lanelet_at_right = route_handler->getRightLanelet(lanelet_at_right.get()); + if (lanelet_at_left) { + auto lanelet_at_right = + planner_data_->route_handler->getRightLanelet(lanelet_at_left.get()); + while (lanelet_at_right) { + extended_lanelets.push_back(lanelet_at_right.get()); + lanelet_at_right = route_handler->getRightLanelet(lanelet_at_right.get()); + } } } else { auto lanelet_at_right = route_handler->getRightLanelet(object_lanelet); @@ -1694,10 +1696,12 @@ void AvoidanceModule::generateExtendedDrivableArea(ShiftedPath * shifted_path) c extended_lanelets.push_back(lanelet_at_right.get()); lanelet_at_right = route_handler->getRightLanelet(lanelet_at_right.get()); } - auto lanelet_at_left = route_handler->getLeftLanelet(lanelet_at_right.get()); - while (lanelet_at_left) { - extended_lanelets.push_back(lanelet_at_left.get()); - lanelet_at_left = route_handler->getLeftLanelet(lanelet_at_left.get()); + if (lanelet_at_right) { + auto lanelet_at_left = route_handler->getLeftLanelet(lanelet_at_right.get()); + while (lanelet_at_left) { + extended_lanelets.push_back(lanelet_at_left.get()); + lanelet_at_left = route_handler->getLeftLanelet(lanelet_at_left.get()); + } } } } From 0638c3f7015035c23633ddeaf6242cd1fce3f1ec Mon Sep 17 00:00:00 2001 From: Kenji Miyake Date: Sat, 12 Feb 2022 03:45:10 +0900 Subject: [PATCH 05/14] chore: sync pre-commit.yaml Signed-off-by: Kenji Miyake --- .github/sync-files.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index ebd79a1dd6d92..e4055a49f688e 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -5,6 +5,7 @@ - source: DISCLAIMER.md - source: LICENSE - source: .github/dependabot.yaml + - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check-differential.yaml @@ -25,7 +26,6 @@ - source: .github/workflows/build-and-test-differential-self-hosted.yaml - source: .github/workflows/build-and-test-self-hosted.yaml - source: .github/workflows/check-build-depends.yaml - - source: .github/workflows/pre-commit.yaml - repository: autowarefoundation/autoware-documentation files: From 7274a31693314bcacd077a717d90aae8d4efe2c8 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 12 Feb 2022 04:13:41 +0900 Subject: [PATCH 06/14] chore: sync files (#374) Signed-off-by: GitHub Co-authored-by: kenji-miyake --- .github/workflows/build-and-test-self-hosted.yaml | 1 + .github/workflows/build-and-test.yaml | 1 + .github/workflows/spell-check-differential.yaml | 2 +- 3 files changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-self-hosted.yaml b/.github/workflows/build-and-test-self-hosted.yaml index 3d28151b1d691..95ee077432cef 100644 --- a/.github/workflows/build-and-test-self-hosted.yaml +++ b/.github/workflows/build-and-test-self-hosted.yaml @@ -26,6 +26,7 @@ jobs: uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - name: Build and test + if: ${{ steps.get-self-packages.outputs.self-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal with: rosdistro: galactic diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index a9ee40cb8e09f..338ead5c47d5b 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -28,6 +28,7 @@ jobs: uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - name: Build and test + if: ${{ steps.get-self-packages.outputs.self-packages != '' }} uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal with: rosdistro: galactic diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index 484c3690241ed..1b5c52cb40ec4 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -13,4 +13,4 @@ jobs: - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@tier4/proposal with: - cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/cspell/.cspell.json + cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/.cspell.json From 1278fe93ae6b91fde28fc2ca91f3071e4a647bfa Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Sat, 12 Feb 2022 13:42:23 +0900 Subject: [PATCH 07/14] feat: add rviz plugin to publish and control the simulated clock (#349) * Add tier4_clock_rviz_plugin to publish&control the sim clock in rviz Signed-off-by: Maxime CLEMENT * Add step control Signed-off-by: Maxime CLEMENT * Fix precommit Signed-off-by: Maxime CLEMENT * Update documentation Signed-off-by: Maxime CLEMENT * Fix spellcheck Signed-off-by: Maxime CLEMENT * Update plugin description and icon Signed-off-by: Maxime CLEMENT * Rename package Signed-off-by: Maxime CLEMENT * Fix bug with long duration jumps (high speed + low rate) Signed-off-by: Maxime CLEMENT --- .../CMakeLists.txt | 42 +++++ .../README.md | 27 ++++ .../icons/classes/SimulatedClockPanel.png | Bin 0 -> 561 bytes .../images/select_clock_plugin.png | Bin 0 -> 25813 bytes .../images/select_panels.png | Bin 0 -> 67237 bytes .../images/use_clock_plugin.png | Bin 0 -> 8608 bytes .../package.xml | 27 ++++ .../plugins/plugin_description.xml | 9 ++ .../src/simulated_clock_panel.cpp | 153 ++++++++++++++++++ .../src/simulated_clock_panel.hpp | 76 +++++++++ 10 files changed, 334 insertions(+) create mode 100644 common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt create mode 100644 common/tier4_simulated_clock_rviz_plugin/README.md create mode 100644 common/tier4_simulated_clock_rviz_plugin/icons/classes/SimulatedClockPanel.png create mode 100644 common/tier4_simulated_clock_rviz_plugin/images/select_clock_plugin.png create mode 100644 common/tier4_simulated_clock_rviz_plugin/images/select_panels.png create mode 100644 common/tier4_simulated_clock_rviz_plugin/images/use_clock_plugin.png create mode 100644 common/tier4_simulated_clock_rviz_plugin/package.xml create mode 100644 common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml create mode 100644 common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp create mode 100644 common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp diff --git a/common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt b/common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..6418b77a661a4 --- /dev/null +++ b/common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 3.5) +project(tier4_simulated_clock_rviz_plugin) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) + 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 -Werror) +endif() + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) +set(CMAKE_AUTOMOC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) +add_definitions(-DQT_NO_KEYWORDS) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/simulated_clock_panel.cpp +) + +target_link_libraries(${PROJECT_NAME} + ${QT_LIBRARIES} +) + +# Export the plugin to be imported by rviz2 +pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + icons + plugins +) diff --git a/common/tier4_simulated_clock_rviz_plugin/README.md b/common/tier4_simulated_clock_rviz_plugin/README.md new file mode 100644 index 0000000000000..73e53b69279ff --- /dev/null +++ b/common/tier4_simulated_clock_rviz_plugin/README.md @@ -0,0 +1,27 @@ +# tier4_simulated_clock_rviz_plugin + +## Purpose + +This plugin allows publishing and controlling the simulated ROS time. + +## Output + +| Name | Type | Description | +| -------- | --------------------------- | -------------------------- | +| `/clock` | `rosgraph_msgs::msg::Clock` | the current simulated time | + +## HowToUse + +1. Start rviz and select panels/Add new panel. + ![select_panel](./images/select_panels.png) +2. Select tier4_clock_rviz_plugin/SimulatedClock and press OK. + ![select_clock_plugin](./images/select_clock_plugin.png) +3. Use the added panel to control how the simulated clock is published. + ![use_clock_plugin](./images/use_clock_plugin.png) + + - Pause button: pause/resume the clock. + - Speed: speed of the clock relative to the system clock. + - Rate: publishing rate of the clock. + - Step button: advance the clock by the specified time step. + - Time step: value used to advance the clock when pressing the step button d). + - Time unit: time unit associated with the value from e). diff --git a/common/tier4_simulated_clock_rviz_plugin/icons/classes/SimulatedClockPanel.png b/common/tier4_simulated_clock_rviz_plugin/icons/classes/SimulatedClockPanel.png new file mode 100644 index 0000000000000000000000000000000000000000..9431c2d4223632e7cf0c3d2c6a6203d8ffbf0af1 GIT binary patch literal 561 zcmV-10?z%3P)Q!bb9uh;93Knc(e6K`;VPnKo9Hw@!?n_y%9 z3Y_}=ezMst>2#V%Bm%&6I;Gd^VVWkkZ3FzUEbFyl7}tJ)P32Qv*D06FM5EEYvawi< zSS&^+lc83tu~;l#>biagyi=Q=e+B{ptx~D%nUzwA$X>F^WJ0xC#kOq+c&2Rzre(9) zqsliCjYi32G5|iHpaD66R4R3=*(04!dpFE!z(Zg=u)E-CMdXp+3m*3Bp_JM?ALv8_ z#sKsA{KzaKM+;y!n|aB{8gL2F?RM|nf~OUcOU-rN3&1f=lgVUqt9d*g({8r`9H8Or z_xpd6$>amqb)OFg0}_b@;c)oB=31@BYPAA5uh;8ed;sxy{3;j>zF4o>8&!LJrLNbsIqDYOmn z2HsXe(*XdGoWL(R2=qY@SpXmbB)u=6qiZb6qe!D1=<7o%Cy1b+L70gJdroh91sBN;lESOmLj)sn+ z>S1+HpmE4$bQGoZb@w=Bf!jz*x$s2taf_Ma(d zIEJl6mD)Z$s+BsGbM^0Jg~1?Q~*G-H8b}~Q&$7@ z;$D|$*KWs8Nu3n5qH>`17=C2xZ2xeZrt?Q&>oGY)6Wqdi0}-3rY~Iw7xCRk=g#!60 z{1gRNozRuS{WF4uxg()K?dnUp#aIhu(Z<_|!XDSk7RG`j9(T*?$TJ}CWGGQ`1!C`Q(()kPkKbx`t$R?)p^Hf>R7W$~fK}hjmNr z;keoMo?Og>_Qy+tPZhi_wgZ_<=@Dz^8xb}*$AzB@W3uKV^_nT^rurSm8<>_mRXwbe zZo5omgCdz83ya1kZRY#2X$^)@6X#R=dTs6{+K1l_-7W6|0K-dQlw~4X-DbbCAj8~f4isGkR+D*xevtb)IRQmPWna19W`D_s+a_hZw%4z z>$h)Yr;3mC*weUy5WwW@zyUg??4q-|)mT9qmt=(0Jhlj24jl!j_{09|3cflyMHCHm zHqsb+_X=(mpMX|012Fk?%twGhpjjq=^w?h{FpDC2ZlzLUy4br z!FyDU2O`2Ln#8#Tf1-(~2B^@1K5@SDl@YB|E5+i(A^q`OQ@@Grk0z2J^TGpKdU%*E z-zsbVDu(8N-zU$k6XJP)AJRY%?2{4MVn%^m;SW_qtnk!Z?&{X|v&g)-I~~rIzPDrC zJ-<-qt8|&*1|%-KS|z#>{i1V+3jo$)8LFgG)kc37dvbCB801}C;&;0hq2i=FDUtC< zE1@glU92}dI8yn84(L&|v|ysA+_Oq97u&<_-~OOk3o~CB#;19?>bFzOU}s}{50w+* zQsWmZ)Aek#JV#t>v$eOxz{sdN8v8r9jnC_p>`!%s&f)dhQnTC$-T-a!V7d;$Q*KGV z_X-c;5~$7L%tmo#bhbc0D>H+)?#gObrF4d>h2iAMq(6JQT-Rcpnpiii(e0wLf4+g2 zZ_Hkm!{GaD;wk1lA}g%?FB^h^82B9I90g|`OG#cDW+HEP~&9fJthH<*RJJZ$FAf`>y@@rrBYF^ z=#7huOFqxz>2lsXM?oseLJ3Ms2b;?KKAZbh)}d-Z!BZ`-);$D{^e5~!v@c=vE!G<^ z?PQx1{mRe78NzzYwTFjs;R>c3i1pQ zbmFK^XDqlfc)SV>dD{h1iJhD)Ku&$50{kzPJ!JWf{i-6I}6*rhp*Sp`IC^#R4~0WP*N zLq@_`D4}gc__$uJ5^J&OB9GU{dLxq<0C?N>Hb!3QrdX_^RcURtvK7d5BS6ga{phx8 zEC>Y>SosOw;aKi;#3fA;`)h7K9_>OXSR|)Ndud^Met$TnhB;12uTAE7X)m`>J~J=h zG|$vXk|H*#QmL$r!Dp#eo+_!`WDM=GQ1Sc57Rb2obj|t9!LbVUcy4bvU>+3@Bj z3l&=3+hoIG%4)Q2Z2I|vjvPtn>Qk3AK-QMd< zaM3=eiI&mzO)5L#&p?#LTB|~)ogG%q@o{0vfq|HbxwU&o5s5Xul@lwgIZGsHUuFU1 zK7MnpQv`m$Yw%>KL z$T-(c4i68Hj>_c>LjZCl>J`s3rKVBuU{QyRSVbhBILg73YGnnlSI`S4?;M2w=%R=Q zo}8W^h*5zMX8lXPv+p*A{iDuR^{sbzYZb^kGzu$g&WXlPcPF5|C_(nr7H(V*-X&ja zV#@{eK>c^mmBpv~g54Fzp!Y9w35TiXNk0O(PR4g@%EDWE3}EMtSqfDo`*Zu z$%azBGst{KE{lJyd!$hT&5X3edSTB`4>^E`X)1e$ zWqG-iEZ-P0w_DTx08sa%*bEzMnJ-i)?6cVmSU^g@+!bCS5BJnG%l9#hfuVt2Q{ zDLgZ!lG}BJ_8l?5_lGwMesaVsLRGpt4i32)LYwYgQBQMot&Skw5>3ra9uEQSVutVK z;IL(}wrk*ViwFq~;2)W1Arnt?zT&!`J0Ztudc@244j+HZ?X9KNS9!~clI!sdaRqBWw+q5 zS|L&^HIdal`Xe4iUU`rK|J8$?wKYvLOpK3|Vq<5h-(td?u~2E}k;5i2H8C?b@q&&! z!9W9umY_&JF0!w#0TnA!Y_e-veNJ-k?d>fb)uUPDaqOT5zn8`1G(X)!2CQDRc;*~0 zuWir9>zsn>%H8x_FUw?z=VJ`|2bEf^+Kv>YY`S}Ux_c8ou0aT)`C~Y=)HcZ_icGW= z;{eN{%~KT-`kl|sRQC7p^=FH95rJC*IC)uV=EpCWR!?|KHWrUC-g>oKLhEj@ zylL^%j-e@$Xsim1o~ho;yk8fWiMx>#2B?W|ELW-n8nn9e+kf2#5MyFd`aF*)N=frV zp$AGz$-)9O`R_#FRGl8wGgJ=am)`aaq|DOP+BRVTpy675`^Qg8ow(1($H!2@`)vDc zir}_6g9XAb?z%j6mHL%(opWVG0`8ud#}DA~jNt+e03q-5<)w*x$iWLL->IOh>s#mN zVi^--0~7#P6TvE`^eHT^2mlB^Zla46m5dk7NDde`^})nJ0_RFPe_@H64IE{3k^ZkA zD;v{cNc|NO0&`vc(O5OQdwan+K>Q-AhY^m{zk~~h?gjb{{B9Nb=R+i#NFc%<_=x>q zH?Y{@NR6ug#s@Hn|Crjl7ef+NHLMd_N)Ow*dcyj`q7rd&@qi;jC_b79 z+{;#MoHBTp)~A)0HVEr$wm;?#4|IBp!{tbIjgE4N7h|f2x&0v_2KQtpz$NtycpVH- zpC<8-?xZ`?0iQI74))&{{?{j5hL8qdh5TO;TH_X*@F5^v+v#75W51``E^EB@#xhe8 z9UxKa_-l(w2>_s49vW2>BOk&^EmrB9g;iG-2$oUv#_YvqRX`*GS&Xmbnt~{ov+~$R zob6Yl7rTd3+)K?OUPyBbe$A-E>poI;gx2{*otU=I!+dJ62Z>5g!p%}S+{@Aj`ZJD9 zBMU!2gn^*l;gy#!L#BJFPRSowM=MirMb5{6&X(Udq`@;QXAhhc?_QVF=WBA-Ge7V2 zBN7!!P8qOKJ6Djd=6%4a|JILs3BA-_HU^CF2sm~8Mrj|}Z724c>EUOjJ2g)2{kYz| zUg=dH676ohf?CR)rvw~1=bA=Yn*9`qRiWJwjVlU8v(HTD@f?}_^Cy)>PS><-6%Vh; zaBthaur5m~A0TN7^*-frnn_&qeghqafp~L4*&z#6G}RAxIXT*O%ttZzLxXHKZ8;^~ zBklMOhx58bzI03(EhjUrZ#$w<`Ac=yh%Y%k zplIX?t&2po5(3*_Fskl4$BXD$mek>*FDSX6+iVR<_cl@@(&YIj`}4S?suLom5U>HI zJ7+5^T%f?@Pg9p}0102SJ3HyC`+0vZkgY0FrZlzI!UU;Y-`w8gZ)m6AG}GpJXg!tb zzyJpu-dL#r{yo6rbhf;>zt;eTjPG<}yj(Lt?gHV<6IUD;`?(XN@1h8U?kIx_{c%o$ zPt00lVU0;pz)C@8xi&8$z}Dxakn~|?+dkzK0s<0~W=ydewXmFMDS6}!BDD`1 zRl0L}e^>wI$dEIrDa(6&GdHmSND+b-9)EeC1BnH|?YI`*4Yb^RPCxHvDA_)*q$x4? zAN~}OAP07}%nNy`TxP8E+!@n;F1*%U<9nKp~@ zGnNH8{#~!0SiWp@e_Dhl+WnS1xxhm}0-EMa2Q=bi+l41RfHrgsft)BGby7X4?P5k* z#WA`_9v4(DF`~eGKZbN0gFfjt*+NYkCh+uSq`JG?bbCy>X>sE_ysDVd`FbZeH+NdS zC06}@GdAJMWPLzGXfy;yW9vB8xy% z5b2jKzXa%oXxwVOnliUyh^WG%sG|K9pkDqJr)d5TO=5pf`tZLa+=q+5A{WcQzFsW< zk1+Ok+p@b>WX;r2d^^cJ@@z5vH7QWd7xJ>!baHU4}% zrvJFMGmj?FCu8opCZD(0W|uSUa*6!Ojt(Je>cU^5e_ca?2$=vi=Un%^h7KbY6VvG0 znm!toFq)&O7dU0PJzHCAcCpcgm7@K_A}1$@^fQYCO=Q13!KZs~dpGjgeL4^ReM@U= zx78z8R^O6SufB_qZdc%t3SsgT1{4?l*@_OiUFO71q|)qobphdaW3OHE3`9 z*D0`kfbU~hI+3y*O*f&GXblrA>?i!{lK>KHS}}jB^XK4Hv*Lb;Cyk=2NM-oUDcZ^l+#7SVD&njo(tb`%iQDg-rQvC=)yUz!ej4zn9JXcfb@Ml zYwhebK%M?Fjt9zYx&PVl&}_XD8;;6zfZbrLwl{4Rw@WOu3qk;W&T5nnoC{^DMx}4N zk>!28N{^U80LR5KGY7#N);V5=@!>9hv&Ffs$_8wMQo-NkBz#Mc2T5bSmR1-%49@d8 znndW*eHHCF(EVO+d%x%Wqy?Q5k8F&tgZl$zmB_6r3yMqc(%Wn;>5rbpPI?wrTpj}} zkIfLWTM3p8)8;Z&y@qQH>tv8oJb)R3<;7_?=b8<9i=Yq0Y5ad5ozVd${FSvtF)rM~ z9tK!QE-fVw+G3nhbr3zO7gf2hTpe9=8}=1hI~%^B2+6k1}XJKj+>wH!V(@YPWr8 z+&v^_!-Mp>>$s>ma?WyOH}nl#<37tC+Sb?ZuTQ+5(K{Vo9g%#+?+WB%_0wYP-)S>! zI@Z@bN^<&vf&^%w-rF7RiD4)Zywr`|hJE&atm+qlW4;?+6B4st+_5N#)aCf(+Pqew zi2UW}Qy2e)PRi3oL0sh{49_HWU!JG#H|Z$ECBRF#Wo&^?1LcZK_@L z%ja0oXRLM9aAo!BJ-kQ}Yf(oq4y`wCzV&McS{JLoahSL(5hJz2k5~-WwlB*W?Y}S# zvt-~FA%GI30_*Bn4k(see6Eg}a0rF96-@g9n?+U^a#s>>CIFDodG{DwoZHv_f#ti9 zd^?Xl4UfJo+nIkQ3V%|^5G8JXg4hW=W~dHNUPwek>b=WtG6|%R13TTB5kxn-egn1G zh~VLe>T9FTj*fKlK6c{KtLUz+F6&Q6las_}w;HtrApfV&EZD17{IU=o)43MfZW5M| zZ>hmJO4d5+bp$ijcn~aBm%?d>^Y^z;_;1HfV8sXNxx_*bvy8>T0rY%BPq}N!e;ZK-oP>}KDv$gEx@G0clS^G zLj&uZC;@#vwC$H`NFBz7MzLcsd9MVwR#Rj){=fImZ=O6>xn7@oKfe3ZXQ?+|UM1;d zc96$kCtc6v!Z{%Zb+@cF4`z(x_cSWeOVzJEM`(Ze@k2zr-yX)co_8B&9miFlO6zF! zGwqAAjWWL;NM_|v>E=O$$cjj|S3rIUDri3EwD%!X-yr}R;75xKIIY3B@Q^gRd`3m^ zk3VmOAyrXToz5#|TGMAkM|CUI2Kl2U1eyZAkbR0EwSLtrDXgTJ@{z%b5)dDtYT+L% ze(}YGVMu0(22UEJUTu{b<;DB6FodsqUfzMeG1*0m z7aJ_VmxG`33VCj!3faT6KT8Y8eU*-+qp`mur62=E^VWVnz4Jzj8%ntcVcDdcw5 z4L!P2D%Kf?i%4J7Z3@o^6rFzQrK151_cln|-C3#9Ad86gLR~KcTfyi%T#0P^C7yDP z)P^aO`b%tjzMO<|abqmAetZ=Lx3cQDuAkG*@;=Gv*8{}fxk>di3Bjs!W?`G{S)4^l zfyN!R5A*sa&h!E)FL+&Hf(5cD($UEh#Vwt44rx-FlU`qM2G%@1SC48$rv#Co9WIJu zg37`P(mpxG0sAL^4sl=h#^jRuAL7>B;QwfNu^7)#2r6IPhJ8D_-XFcyG2lJ&iA2Io zx7xL_(e|dn%^bn=h7y{*uc3?+EGl?As;L99!&1XA$x5p8UL)v@i@+>CW8b~%H_4^& zP}D`ng`|j{q#^-Tr~0EOAB|T#RwvD!Z}8^l)u-(UNmUl2g@3}(CJc^SE%h)yR)~t% zUt`G^yc6oM+eumF5T!SMJ5*LsPC^-7cR+g$LKmwZAr z--axYPnxAzbIO0b48O1P{H8fr0F%TYNu{{+QDD&iCmxU;-&=^_-!T#t0)`V(`6YHI z=9}i+2D-2TWdsxziHP53HkNh>yJzYt%pPYhRYeg$T?tJP5Bd6F2w08ASQf{ti$oBy z`Op-Se-J6EE{zUm&ZSx%aasEan?06A6|!`#sr@11a7sz%rIIYsYnI@QyrM0#b|Kjc zwlBC8oEP5Nh&^}P+ZgOzW*cA*0YCi+e!Q}UUCAa@X zkXSb}g`0@JnDzf1O8Z6D#<01$`TX(%EsO^BLkR)E#l?NPJ3CuxuCI8PA8+shjOap} zVR6Bep~{DC)5)TqikkY0uTt7A&;X7!2!(KxQUEYAHgtOqyEpE$`1(*#8y(H)XL&-#E{0)pW*MB3hYFlnJNB~m>a0`*5efPD6 zgLQad)bs3)|FU^Ux$pGhrb>NDj)|dPJ5u}1_ib~&i#CjzX4ujKWKP!@%WHdAhFw1! zrE^;Az16WS`)60cMs>?=JJ%m7KzA%xvJ8q=wR5XRSX-JH)B^Be~YuQ_WRi5AmRo!)6+H&resO~ z&eWe$=J}i4dhYY|4g?%Wr&KrliS&In{9BZAa>XwU&z6@w^{s0X9CB+=YyLzB-$%gh zx@3Xu5?BKV)0O=?*Wcc4N8icsbRKQDUeC;j*ib2vxjZE&8q*qYcVnhZUg>q`9l;_h z!SkNwC2Xp_On zC|KS{b^7GoA-wd%{bW&_GvLhG(us4BhyP~F2^O~Yxt0gz6rB|+Tni1;%tphpI2@c; z7072akx)=j?FLpTIc8X|VKX|u(eGEL`B3{;AsJ|PRr?#m4WWs>`Dn>yLsC*2d4@Fb z`iN5YTBo3WI-X)SAsqZ#9h-m&gulR`*s>b}(=MC=I+tl2T`LmL!+g(i{U4^}`1yw6 z0Rzea+>w=t2F+4wbyHg4qYd`B)_bf6KH5ifwbD$hvW2cT6}z268xFN6XM;EQYQH_~ zPA*5H4+=|gz8cQ^D-5^i0Wu{a-1e(&;=VPj7ecO1t{b7tV|$)THTMRP8q{mEH`_p- z*3s#RlHpdh6ptF#`l;wz#S}=J5EnSQ?}R1V{0wunJ(m;n5%_2^UKGf>b%XyIPL&Wt z7_FL>wR^`!HTn{qu0i{5{(Su9nmK0<5~BSa9M4GF$(>mOf@D?*q_yaHr;r)+_zv6Z zrNuTv<$u6z6F*q<yW6_R zFWB-;UnN&h*E00k@A<0rs=mKHb2hiOCdacY;p$Em_;fP)+v0ZhbQfAaQA-OBer$>s zQ2ipl0=7s{Ah)h;j%7-(L-^MY;aKlf;(%#yTMXcvfiWdhJF$&TWi&LRBWkyms4bWi z;3JLQW^fWol^RL#loINS-Ih@efk#z36L>KY8>jZUkI-9HQzui?Eo2OR^Ipx?!%Kvi z+BNh^SzxpY))MQr>V322H?3b z&-ej@@2rMM5Kdxu?psb$0%7`e>(bYy^I zv6QBf)}Y}42$j8~k`2w|*vwtQo}J;(km3^dMPrr7b7_B7$#~y%!f6-QW-&3r=q24i zE&Ml%Ytrzr5Ed3bS*l-iooP@{DyU>dWKPF4!2M>y#B0C1+qm=6WA!HcyoH=4Kbiq@ zC_CacVwYXxH0j95CTG*aOsf=zQw`3`qww(XumcVA1QZgTs@YEHGZ7p@omT9FnoBpevU#@%0icJ zzeYz+T}wFMT<>}aLTJ;av?IKJ@kdds#GOgXn-_!eG-GNixt1*=yJ(!PNCZLEGRtK) z?JajU{#peOe`6){s@Hck`4`2Iq_$TZ_)G_ibgB^+>hINu;E#A{jCM%uK%Oje{HA56 zv=wdn-|#nxZRRz$`&hF>i?Ft4`z~02DWWYScS`lHct-n$Y0 zB{=*OlfCWgcq&#l_E#&rmNbB=GS$8cwar0681a9weg6V?C5!0H1FGgxucQO2e`^b> z2f<0(bPi(~&tz57r;TyRmtdAoM>XQ!&(kL}RnR?CYiocu6QjK z72j&ZUS;l9dWC#jUMcr3`-9o2{PAFZ`SCnRjkif>_EJm+s1Ek?aXRT0x^8Jv;F)b*E(%MfsXr-N!bDwZ)Jh@Y%%7eX9v5 z_2@TEOl-*#J`A;4SaHxW8hSM{PKBYBK$a+V<7|7lJEIJ-K*6CY6xRxME`PB$FiDTg zh4#&Jpq5>9noiXU%|ZpBC?H3$0AQL<7+J`uTGEQ5Jxgu1noV0-x1(&%mVq&a<{ ze}eVRLp04_5u98C2R>V~66A$l!MZpCkNBrOL?%t2b8FL)Wu7#U)X@Etme)}p!G*e9 z$rq0NT)Uv4McdZM9=PSKi4+f4px9DQJa_kEp?z)2bANE`MLI#Gb9&;KUil^-G1c+w zQ#}W9YV2<%%C|bw1uucEa6I$5dJSV_Kw&C&L}E;q$!%J`1uw-(%_OR=w^(Dqw0xv( zcu*&{3(4FZ$)!fXhf)C&DL@PW6bd63C@e;vOApoK8+HWOmX%(AP~s4ZL#*Gv>zVgZ zAsH4gXK+_lE>{37n0~j!aUW16Xs1=&vXo>c$L)V5TinA6eYOH89+86>7x^pMFaXIL z5j)ihkM*M4WmpGOamoT@!0@mRW1lIl{fO-L!UA0)T8PRc89V<$4}C65hTDtPHu`&W zBoG4!K4M&7ai&Mk+@@#L%nAyy$K_)uvu~_bYkCaD1J*TTZzW~H+%F(C>H>7Rs^OzXQjih?ID*uR}`-8hiAP0S(OZ@1hyORQDrzaaes0rCANWSsBTr-WlCfYB<%$9TWQJ@%-y_z4KQQ8%(c`5RdC(yt zOw)dV001lmA3NQ-%_kY72XG#(Dvs4G;>X4@lkZtW1&YYSXjF-fD>s2-=>QW!`S!hP zoZTkDxgU+p2V45t#U1j(bD@BaMJ*+5K^;cpbEVEb$bQDWQ&zB_Oj%Bf0RYy8LuV%j zihg4PzA>z74Bx98_GXOQz~94a7qdYC{qDtW-_7~jD!N5noRFo%5%dBO)RiTM@G!`M zuM2XK6ifkoDmnzzCtp9q0W4p@V|7!%grj>qZ}#I;t=7deEWnb8&Xndu3B*WwO6gO# z+zXKVm;5UE6go#M@xTn(%;y?fY5r+)p5Qgrti~9)1kKf(1+MP?A)Nhgf z#=Nu5-yEzCUos>>CHROS71^FO$Q!zJWkeZ#_u%QK@92;A2#e8yC`c*Keuftd) zw^1C_oPcKiHxK36t?Ffr->oJ9ZRqAf4Lj@tUe6V=(!!Xfk}kpjV@mB&@LxWI9@QDe z78FxUx|7!!wZ9AtPzw2fE#>}tsQ)q>{B!MBU3atynOh+T!}OT=cnYQ$<^Ro>@Xw}L zPE8<&JCdb#pSP7}moT+FC9|(zv*Y5FC&<7i0T*Rb^sKlvi*J?;71-}_aQ4p5nBn|L z;Nq2l{{H^?b|0U!)mA4$ntY@`T-@9rk-Qg$;BxBKUjO z?a~DP7sEr)X9m(rkTNzjRBm;5!ok5&S6AocW}AuP-TY}&7E0ty16 zj_@&xwfD~$TTjmZR@>-Yb_7FV0Wi8hP%dPGgHI7~I<)A$v4+(Yx$h!W%cbIaYf@=Z1Z(M7HBPI) zR_qWWIS+W4ubT@lw5dk~lZP#^%!33RlETkf2hNHcTQu%|ApvpD7keL>8Ntj+DvY znpJvy5oq9$RbO(!cd01i*Hy7MY`pdSg}!ETxJ$pvOh2l9Q_H{nwL8-H-14YUUjV-b zB)MNTZxCeS_Jx74`85!mT2nl)%OqLM=nmF z{INREkM<)of+nA!UQd5)>CT-99GLe4IPDIr!bt<|bf<*;beSzKD$2h`bMguGmo`zhPahL$7Nf7~|$K!;#R_{Wp$pF!LZ zfLa&iNXz>+o@*UQ<|LzKH9XK3V*-5GlOr@gZo7y+L+apw`!GE!jG)jP zVe3L}J$ra52qvGBIT62?KX6|{pFowx=?97R0$*pd6_Jg_umcV^O|f77{zs8eRZU~K zPs6qT<`Xoa993bpL;4&3*@8?@qR~!w!Cqy^9IB&s0M@Ex4a129dxZBv3k}$UiAYc2 zWQ7L6j*eGNtPd9-KXPLG`|k&yZ-UDy*4^|i~^;&Mue?bb3eNr?eGHHOMT>5#~01qfDpTR1P8zD$#ixkywGWD@KJHTNdm|1 zX1)r9uZQ!grwDoFqdWO528T#^czz0Qiu+RBC+n%>o`LuBAV3A(>$$&@FOd*{d4ZGfI z3I!#*YC;-4Q+rnRHt+UG&y~MKY|S*h86CU&8Fj{1 z78WRSNII#p70&xuE!hD`mvcSFD^ETLJjRF7^E`4?CfFbgR-mKFhr7Nn-tC=-bm_v3 z#aBaS0e)XJ_ty7gGdLLRO?^$UucKn_{Hyr5JdQ<5#mlvBVGW{dp#A;Cw#@-Y0FJ8y zb7idcSl=vYHc z`~B?c{`$mlgZukhI?F|((FeuFYo+^U?hd5>)cvNRfJ_ z-`m~^CB8=O{F?siMQq$C3{GsNwv?eo)_4DW0VA+{rI`k2b~{jdRmD#cH53eWdN#?a z%EU?xoHe!I5#z(}M12_Ey-MEKa*J2zE9t?ryAMC-*b{$1e`GHC-_^)AgBf}Y#9T!$ ztE*e-1)9z#s;ytE>6=`QJf8UT1}Z?PVi_K8}{(Ecwj3{Gmxn z!GZYS_A*8=DLi&GYo}VQ!ok5YQ>yM_XJ_Z+@(lwc%3#PZKN5+i(o)~6*rmBnj-hHa>$xg;vGt^NhF)$U zO!I)g`prEGU1T3wO0MrtJu!ZdOD=c9sPy31Z(S!v^#+oF*F{Xc$Wbk?lJBBHCWQYs zLJ1_9+#=Rn|5*!l%S=Yf)PMWbuFr4p@Y25{chpv|b#=5LPFpX&TsiUTBh4%Ra@L%# zX|Sb}5wo&QEXeY7wD?^He&g_cmf?pP%Um6s z(RjIAU0<()H7ENXp(U@!{u?AY*rV#;!=EGtVaXGo#@Rbor;*NPhT}t2!}utw6)D;b zPa4-egT^#^+BU`MX)Lb{ob0RQ}H$Sts7(Blc?*{bJ0D0_9 zk!fso<@_#n_fI5EA-rHY`A6wPWN$q)zuZ79`-}a?aT}98oi}It{!JE4ITlaya+G`e zy^=DgZD*8lWmd9nUvqxIzu0J<_#4MX1CkR$b z(Wu`pKEJitTg(S?Gv;>)jxNEI)LFIZE=}|&Z=97QrK7(VEve^Mn05+=s>&iGrWuxm zYqGiy(yg82TJK?xgjj7cybd0uQLb4()kIL`NM0;%6 z-MpmzG4B{^-3l6Bo3mH`ihR-hv4lxz6x2L(TZRZ`+#bEIJCOGtncvQhzn>GcgH@B9 z92q+U>o-x@#j=+#EmnWg_CL^>m7ZCpR-SoD|56_l@izVzA8iI*i^YR(of&|m< z-XqzXKdGik^<@HRNh5=ed$gh0QV43BOb;Ir&+0M@fUk!WpmIJ64q;ic{{Vh$G}+84 zJnqk75I837BPH+J8>BMr5(S>)>)ZR4}}Y2=crL zW=@ERH~-#Tpu%`Vl|7M~$D#;5wh#97df#!p-35e=aRaYAA@5!A z*{!-0PgcGjdulD}t$N)DU;{;Tl%k587wy@e7+%T)DTP9Ft;nKR)>Kt%&Na59+6x!xQ|MCQK+yhm;`3?^YH+n>i=|Q ziAfZm?FzzWva;w%gTx|Wneon;(21TuTG?y(b$^lCL2k=jQZb>-sH1s(a{K9SrU4_9 z7WHDh8zlDY9i4VP$g8_no-^NQN2@lat*Qpv;Qzo|PFXLC~RnGsytK4mR{z=BO2qOTkEO{eFnVx{ig|j4m4Z?!bhk| z{8fo%SW=ag=$y|%U@x_7TK#|VZ1kBju)e-qgKVuyl9j=xyUpMPQ#o189@oX*TJ5$O-GeBjj4M&1rEiJo`5kF9{Zs1W! z^O$LA2mYeupp%JWC`%Z=n~|0PLWSqke^z9ARDJ(TUu?T1?g5ihmAW-e44f=qKZv10 zi3DrWC-+OQycdy(415X#qcL55PP-S-vjKzQjQ6vPSia2ncEVS^`S6{+sVl)E2`@2* zm&rY1E^|zem287-&VVR1*01?6M^7};ZSR2mPXekWP}Tx6nDqzB|JD)d{qhdfht#nc z|HfCIre#Oj(Fs4hXF}DFof?k>u^!+_jmGIHHiwErT&`AJh9UN^3MIh?vRQ1g+{ao> z^*8kH>ao-$w1b7dgEWVg%mv z;y>_)9qkl77kYy$lTw&Wko%&b}an`AMmN zS6cm((fseu{!jPX?2~8^bbB4S3bm^Tq|D!jD*~5f*<0jLYh- z>%-i_k`w}v-S+8iE2XfyhacQQh?X~gbD_hb6(fVE-U6s?MzKmuBXg=#KkzZK3CIM94b=qKnYip?ZsH^;8NjLUm%8V^g+_Zmp#W6ml zZ4>nszv47GHHBR6US{JSrJZD49`vJj&CNc$iTZfJe8O>Tot{%0<38r|S?cQTE%7*N z%X};yicDdIsI4~)fKQui9;g97T4LF8I}ZCt-N+NFOOZtcm_L7%r$2iD#vfV9^15}@Yxh?NQz1yozHpNNalb~m zuErP{W!cU2mX!fIrdu5>a+~eo{k(a>_gKDimBnnXXXXPCj^{aFtmU{(P6W*3F)p!x zf+R6vLN29etD)&Xay(wDsFP`d02dWX?C^w+H9EZ*FwQ+HZ9t5AN99uDN zRT4Z}U7W9JF>5TPDUp2fp?v@Co4Jmq)q6TP$Pte((7xXYFBNnPTl&JSr@qjQNjpG7 zgr>Dn&qXn>i`Dog>;iBdtLM~glsY7# zh&G1;%Hgb!uI(hG-PK!p#=?tExk;kt;SnFctvC(u-6|b1`@u3I;a*%Q0g_X8rG<6q zHk_yyTV?#LZu6njNT8o@!(WMUqaRlux#hAjT_+6BQEMz6TaEO{+s_CumB+s#pUaf{ zHnM4@#B+VeQTpXv(Kz2TSDE;^k#GqdEGEgoi5l1&n#N&+{(l!?X?1?z&Dsj;MPA{Y zQKz#8kLS0B{}u5E1(O-gK7nPIA|yH=umkr0D(^bOn%cT_yr^73kVx;+rArIaRYDc% zyP3nfYu5s((7cLLJ8^j@TwK#g;hmPUx6o$WQ^xj;=h?_brQbN4McEE;GhdODwDG$A-CE%{qF z4giSh~V>R2mhxTbstiQKHde1Id9+>{% zOtUJ+O^BR7O7+-vU-em)2^I0W4f^@4jR1tC`txsJP6jk&N!ObJqr0V>U_EbS8)Sfs z@N~B}2WF&{efRge%=@0BihCL!Qh3xuintF*<%3g96r70vYBTkGp)&2gerLf4>y{T&;PKYWs^L5j6l;Bkk%(Q#3VAF6p@k*#@W$DxTLh0+e zmEJkH&|=VwF`oKT-(|ElH%5P6dobOnn{Q9Gpszk(;|kB!I^ljAGbg-6M1FkxT%p}D{6$iw zgYFXu^l&?;3(=8r66xqVKn@mk#ptT*n)=?1^OJFCUPP!UNN>#G`x52yoe_~l_wNPW zR50(+7PiM5XZX?wHLll~f=wFftio zSijDOe+@j{x}%=+VB+H%CfCUV1ggl4qjs>_&B(5LEO{K0 zzQAJ45hOylgZ&&KXRUsXN{!#nF(LUwzlUbQ^pZkw3^v$~0MF z?=TV`>cFZkhtzPGtW41xV-pBBTA`lBxMI_AQQM>?axy1L2WOe;lfquS5mTNQ>!mt` zzxj@?A(4ib!@EW|CK}=dwkMX`{mm}72huXUk})Yq$Ytlw!s(iq6IVF#z|&V-s4X5= zZLW6N9a_4YgFg<_AwpXxT)Es;!xHg3#Gr4Lqx*cQ%>MJxUEHgK!z)Hh`N~N|h0v+l zS(su%?@S7vTbo#Ug@~8K@K4ic$@Revv8+<@(am8lv8BnUY+LC80h#0RFswe!Dg1B*U&x}NJS>#p-iDIp-p3;~gmT}<{2FcdriN}H;zjZj zp37Z-V(ItR&as#+vs6;!L<_3;eR3=sA_Ko%T$pMOViSJl_Fdm}@Mo?&Z;FVAKOBf> zD$*<2P)KFi6|70H#n(FsLBo`?eFU$eLJ(Yj{tfQB(MyJ!gkre8=@=AM z>Kg+8xytg;`=REo{_hd|o`Zl!<=d;JeZ#8}hJ*-t zav7_dQfe22stfIQ2?Ee)?Q}|e**g<0a(VS^$3qeucSjAZk1Umctcu~Cm&4Y5ot^R> z;g@MOd6sPCox@YIVDQ+MtiST%cfk&3=Rf{fnI14wh2F?2ywN(i2n{T0eA>F2!eG1w2E#jMFUB=2m{xIR8?=HkU35qL zSm6SlZkEHD7etI?6q2tr!S?LqxKO@zKCS^-18JI6TegO9Q+zC% zVGZJ^Y&WkNE|vGQj9oYF8#6b<-q*hY`WAPAiziN*sUp|^AYlFx?&U$Q&zrvz46xr^ zslUJ}7)b~sf~dJ>B5A8=xmADm%ti z9=epj_kuv*@ZQ!4+GwaDAd8y~t@uwCd#f7)a-`@VeE$mL|6}vTBE0Vm%Bc5}{kbs^ zY4sOt9B8IdZOaAMeY+*!GeuKVtIs9Cqz>V0XUEQ_L3%}FqKjGD_FPqv79K$Bcmpka zO$d4;N&0uUs64{ECR$pAO~>#S=*{&rm|{q@sX(EA`i?>jKO+M@GIxEnunN1oGYhD28fDqmw(Ix8@A%n8tw1$4n0-}@ z^oKHc7_mP+dfs*>e#Uc4$uU=m)hsi;$$hYx<}!@iKe}26u87vGy7#Ou1;IOFtU|88 zIy94*;u^I4LDQ0#t2J`M{YpSk|-u#p!ThEI$y zSnG88TCs0hT&vvd6ndMV#*Pa?CIn$`Z-A?A1IkQ}olgH%x22&dmB0(5`A3qXb|no= zexBBT>pe@{4p#e~85cPxPORKjQg5yqV0)VJ_9zZ$sZ=* zUMIo7v9gX`7EIyzCTU7vV&9FInvl-v>C6ol=x5hgUDS2q(w|LthB!CwTfNO@(C;%2 z|2lTEkVq*f%iVOFJ2VXh&i_*k%_nv1RU8OAI$z*nJ z!xnZBIT>iC(mnwZY+NpV#KU8S|9HZLHuc~{V+KH*pgv&Hd1R}WWA5pT*k|aQTMz~u z-X3&cjB=UY>$R?E6kStq42ZV^u%pz(>mGSz*U((4(Od*W1dkvmL~J+8Xz7GZON-Ps zCSh&xU#u?LB z6&hL`xgogn7^oN&mYz?>hfsPXZc(P7b`Zxtg6h~O*JsZ`ozJs|KQn)@hN=}=ts+(n zlQ2ZRBAQB;9XBMOCR~>1elYWp&{~-Nx}{Ozm#RDc9g(Eec@NWP4bALE?3XJ~W=IcI zx3+EU2o%jGWpc8{U5hHgoUw*chP$z0RRyLCdCJ4}h?&J}DYu0WAxP0Pjqem<)%%3= zsc(#=*KcMF$P+S~N!adxIKQng;B4Fzw8K$-Tju3Wncq#Mtu&*dE#0#nf+@2F+v0C| z+(>HGQLFGd+zs%aenaT%0}B~=qK^!lU2 zzFd@?;&Vlrvm_RA8Whx)-JfV|Wcas1ZJm)t9D8-SI~Bxkjnaa)XPKL#%M0`-5E&b5 zYi^Dz$rrOX_Vu-V`nCi}-PLM1jORxG#=8LmS?P}a1(jugc_EH||NWbee=<7uit>^l z#sFqM{F_x*3CIZ>l!b`xlhiq&7Y2&J-)mNT z|QF#Cu0gB^m90 z4erdTsoEOP@nRMnY?Oy7n)zk7pXr9KFeJ`X9wuoU5`w&MiCw;OjQ#H!-cCjyGm}Y` zN#iynHJkdRZcz(;0astmxRjHhrk_Uw=k;EOzsDUJisSR7!&G|xH(kS|)KnUG^QL!i?&ND*|dJ=KTMl2?L zqBUZ|z=-eeiw!N#rn*BXmS-@Gp>mq?@Wva;vi_Hq$Q`emfZQzZ=Z9p^s3klQ~UJhK0D}qPZZq=zj&JiFMgI*ZpF0}RHu18ufyeG5W=q4>`5&aMS4g{&OWv#< z$Z8@qQR3(Y)!cCo8|f@gx=&vfnmOS-&`fF0;iJ)pV!D@b`8*U^aRcHT%;k?qv9PkL zYgja85_AgX? zPZs3U;}Jqvb_4{x6P^Rwte+=OF01zn1qo5kBCOI*^U3Yq#P4M{Ech0>yR7$BuVo>r zH^URxo}tnRnj!9i}w1PZ$oMC zKPt182FTeweJKGKSfWDIKCo-^TYw6mY?!P{2P%DW9UU2zTh+O?-PIC#UK#M#74!1T z+V+Yyrx6Xkm>0ZC9qj2H={RKKJz$=7;17C}xD-M{pRM_@(j|_&*enMEl(g%NQmELiV)UjZBY;d)voW(LbqTq_=^gINLXVN}b%D`{I3FKhFfbSw7xzlAyLm3HM=9ejl>_LNo{KpuD~nRd_l1i-RovOFTVwqr zltk@YF*vA=y?sKe#ZHFSZDKKyWLWHlUqro4b-2*+XPD5iRlRoMFlfEFDd1!47D<^m zXtv$FDID$jV+?|fhsZ0o5v=p*A7dStRx%JfR1W2Dc!9~NIQLc>Le7fYKM92q4%r4? zGK5ahu`)gJDxDBqDqs}EOIt(lF-Jx=df}MBQ&UrChdA8QQU)(E{d72$!6;}w zKahVOC=tNy%s9`KgCQ4N4)FSfgoGOhtCSR!h^wh}ef1*I%nwmb2eZdJTpB4v#??c8 zeQMQjU0Re)i7ImLZ#t0P4pspQ@@(2xXbWf5{!zDNZiM+A}Fe(3dV08yli;K&9WP z7cji7@Zl8@NZj1wjaF`HrP6cZ(7tYTTs62Z`&!O%zFeBY%+Mby-qlc^ zqD8~aQv$pQzKav{gOY02Tkrl6e?Zv8?*?sQZy^YWpF^I6U*KA)!r%%s5 zI;VHs3(bh~hn$xkGckp|d%t#m#!p0g{OgzZTpJuyl9uWchFM)&(t)$FreiET86fAc zwz@ncygO)K+D%P!91JLC?>6OdN-kkcfvXM)CHznj@+7%niRQZt`adVp)OzMH#EExg! z$`ux~;1`G=8jDd*@#pt@);4X_5j0hn0G=c!sQMv)HFH;j)Likk4-(sB5#5=W%Zwndk}{SS$EEAsKcOVw}Q#J zG=#*&NQlkap0meFHC5AAmXuX9$LI1D3&A>{;$Z5USR+EzZoci#k{q+t?s$<&3}>Ld%ebAE+ozy4-jhPNC6jZ1 zy8wrkj<0HzLLK|NOop{fM%T?LB(y@TR?zyRZ*RJ@{nng6@D|pe@nWuc)+&}S1FmtN zyF+&7rgxVXcER@yetMDSNXp`dx;Ijnt6c7rDpeq=V6)ZnY;h)Ab~x0@U% z;m5KDsfwMOY-^LWYMdR7UUwUFxVqwEa@5h-63dp;J^zjG;h}X(ZbQ$o8zRO{Q`0ju zb&FIS)xNG877+Ms&%7meWncS4x#bCML3aJ+-Vbs|n3|le)gM#&uX{J2#ft2R?G*S~ zUa^tpJswzW_~9yhw1?k>PhLbTiE2lRY(QR5LA@3rf;s)4Y6fNTeB$C>OWFM`fNE-H zAXN_A;0FW-u;R9kO6Q4UzN5{=)IiypbcL{vhyug1tBtkPx>vh=h5CXbA|3&Md^2th zAz@rxUT)j-_xHc3be_3;_b%1V+na4lsR1%x#aS8Fu~CY&rlNPg^?rqj)HF5s_ebO& zd*NMAlh&MIu;ZQ0F{ShI+;TjC!Et1=}&(n0GWko@*dI2l1<-D;3{kFe547z!HaI&tTO2s5 z({Dd9ka+x<6G(Kja}v=*^UY8v2>(Dg6_> zFU`i%z$`*Sa5uNE-d=J5$L(Ye5VfERBls6&gN{qgRf0PgHR8~^|S literal 0 HcmV?d00001 diff --git a/common/tier4_simulated_clock_rviz_plugin/images/select_panels.png b/common/tier4_simulated_clock_rviz_plugin/images/select_panels.png new file mode 100644 index 0000000000000000000000000000000000000000..a691602c42c3c688f636b57aa7449486df296094 GIT binary patch literal 67237 zcmYg&2RN2*`@fbHA(T;x%qSuKNBqVzjE}T;%A=&CrLb4@{j1*tF z=3KCh|7^FHRnQ>A|2)WyAL8GP4(G2rs9T#lINz`{A-QQ~ecR-?y^)=XiIu&XwZr7L zaw!rL77~SXG8!&1V?E9;8beV_>yvYDS{lrRMoL+Bouhqd`r*!@13tFo??adDO8AD0 zmAxh>qK_}%&Z#xcRfw74w0$n}M8v8}nc`ITu)!A6Es2V+Sa;3;lxtmGeIQuFO>^~o z3WId~Xn&5x$)TvB7_mXAMfE4?FJH1hVj;Un{Lwk%mBIUefA>BY%>Cb&m5$syCqum* ze{Rt1W#9epN6A9DlP(Kbo&Wb`naB&qG&}zN2%jup1Y3l+L?y>yUgn*Duk~@Bhm~~; z$%9H67V3ged4)y)d*P4rKYggAJ`_1R2S-Mdoe@1~YH1l@Kh!k+pkzSlLoF|6BJ(tDkPSPFv-#KFVATpP6om|MwYe&R$MyXP_XJVCHvp zoPU>>cSDHj+Ivez{mqrli?+4`ipfuliri!qPMkk~{$)yv5_hHLsgpOGERTecIXXHn zc}U?>7?_xDnIWUcVNzlCROf&Te>m#L1h_f}cLUrhx1ZETcDR#U&?$PiSs?Ss0?I$5$>#jjsqILbws0{f?3hKGmyo?W-9u*%Q1Xy?(^ z*8V#-c8)VtH?VzE)t}`uahH4#-0v7o&dQ2!X}MgYhmY(?M^7ITY;Zn7^_PRVxw$## z>C=zr<{ZYHPLGd|M>bB=?ce`v)>X`HE>Z(G>Ss`e!S8S_z4OUxIhLJ*c6N509;r10 ze;P&dTUuLvT8EEF{q&VfVwL)Nj+@TV*f`AKgiD@C^-j*`(f=x=pzl??1r05&!lg?b zOo3n9+b?m`9bpQz`=hkS({tU}#N_F-XQX$k4U=EJio_Kv$4MLwSJ%}1^pxXq_SIvb z2kpWXIV|#+VwL6Py3e1y|%D{GL6V^_68MSy^2j{`=QpqFe0c%a_4XQ3{%x`zs8BQE@sBcOF&tedx1! z(J`uU@nW?_-q+5~itE;;9HsfUI;_;x)nC8*u5#(p9%12|)2r*gm3?W2j8b$*F3=Hs zw(q{}#+vKGxchkE7$2l!6`r%>oW7-H^((^8i@uaEE%x{JF*1b|kXBj9TU=_FfR0LVxA^X3NK-$*TRUaq0O7@^K{aWt* z^z>tNyZz?8@Tw@)s+#C1vE1#2I?C9_97D2g7I|S25xFSRPoF-Cy1(Bau6W7LPSDoY zR?8?aljnaO%%*bMMM6ke__DhF{>F3EPA{=Xd-RC0#pPS^OSp;?7XB}qw1 zmYp-=Ugh!oc%K>Na{2G5%@U49> zQI9f_&w?z2xwWDn^16{2wQS=SO1Y&QYrbo>#-@F9uU5T2S+QHDqvO9HrRE!9qi27U z?icxpxhgn+V_U@F=xM3pybn`_3O;IW&lo=oe=6V5eWhEP;x)qj_pTApW_PUEW zPiC|j#h?Z4NJe*7?7ym7 z^(y{G_3AA)=Iu7x{iiejY<%I2;jsL9~XEC2om2dLq6M@a9$7P3i zi87|SGv4euoE4qk=TO_u+5hP92aUDY7fByyrexq97q0x@wH6y|XDk%$rXinP+r036 z_SgB|N%5KMKd9Co23ybZd>g4uZF^p;v#}Zc{%^nM@l|E(MBC9&t!&Nz5W#@)&8C<_ zt9w-uDx9kAH)3W=>D2EOUzGo>GNn7Ht$Xd#S?%{4*Z(rAt1NHaqo9v}F5(b=i-Uj| zA8TSQjg5a7kjG?bT2_U8Z(OU_4D$ol_o!!W{^-2CVYM7sy76CW z>i_O2+DbCCv(W6$QgVC90jV?Fm+FpRmMT6bIOyKh^!cx|-r(+C#LrG;JLzus-*o@g zzooyiTB}g7<4aNDz^FvH{zRPHfqy^3qO%|sdWDQ zjs#URZId%dWh*?l zZ{I$g&hl@^S-I2=d;ImI*L#tg`oKo?Sm}G4K3UVo=hff8GnAH=k^o2W@bG+YYBHVf zujUS))Ln~CeGxp>+_*$y9> zH)&~|h4x%QQY(KSXfLb}s$M=^O&iG|A)SBgPAaoP*hcTr?DVGt*1@5nl`&%Ws%fdr zYc#Dte>VLrb+4_fJHpF5dNw2Xzb5|7e1|`O+0u~&)raVLN2!52&U1zexG#)R(b*id zj*V&X_?^N{+UU-I{qp4synup=3YU}=bAHz)b#>Z4o5;cXi1JBs-CLxW!sM;)=}*Km zu)i-3z2h96^f+RJq@FS~f%qYzvh0QQ}N`|9*dYZ;%e(O-oCPLY*f) zR$To2RD~WAF5|<)2^krCQd|9%Q`xw_jl$_XY z@5)!dcCGfy7iz3a)XAGURz2d17cUMUjy~vX%&D_+!4w|@mwfv4f!xjjOrBu}yM?i9 zdTzrUn0>*u##PnT(}VopQBR-J2r=#9FPYkk(gfJ*a}dY)Gd4Ay@#FW{Qrz>TvhNqb zUEf$|F0M5}GwoWA@vi)CJMyDPkJ64{D7h{VMu<6%(A_;lQmE7Pl;h&}w>K(RcheYk zC3>3mpBgz_>=G<0C@5=U!qN5qwvmeqLzI%7q2ZDE)$SqgW5;6VmTz~x&-Pq(GHr_S zZyu_gTr?7lT3Q>DR?*b_7IruJUjZJbYGp3yw-Nn2F_Ds+8yXkK+-Vb6Cpk21(sHU8Juc!9o%07dZ#Pe%QHPU}tnX06k?Y3{8ZaCR&(=54Y zkf+UW?f28@y2iJ_md;Lvn>V?7dU|Mc3b>SG46rIMQ&VRj>#yCj_FnBemvq@{HoBLZ zYYY<+8h@MnLUn2@|)yu;w-io%i*C_xHSe_wLucTk>FiU0vj9XFi_rM^#nla&mLcEi8^ulTFp}X1#S9 z*G5URdVaG!)!Nh3`1$i^UpH(B3es)!^Yac44%Czn6ciQRdaqSIb{$TRxSDTuX!Kjg zz}=n9FW$USbelv`i5{f1DqnXpXKDTvc%U=eXlI3iP2CJ$wF0H2$`k(G@)YrXr|}=c z<1NGg`g?a|N>BIN(m;^?P^>e};ltRsHO7K_{gotB^_9H6rRAR-yn(lQrNLw1F%r3h zeE%;SQEr8cK1Q?==EV(MUyfhP@s&U98HNRN5RaXc)XRzhmYyPR0D%71yCeYD`0%^7 z1nXtVr?qb#xHN(mo7Hhqh$%TO?eUv8JbLcq!mo$h2d3Xz^%N;YX+$@E3i6s`^I9L( zpKXob2pb!-WOg4DuqqxuMMFcwXPwNKeY|YBJ&^AEDUyN4<;^*j&Fuj}@14YB$GY-^ za&I;(ddelWaHG3kV3!pVFFdNB+ParsDTk0tWFfGSe$wym-I^GjY3r6 zRqyKM*`a}Xx6TsRlUd~(;+kpUUDoBEKSu2nrf&aL$n} zg*tre(M_K_uB2&RzJC28t`$usP_7ar3(e`Xan57P4=%+Mb{4|SU#d5%m)5;N&#;TH zW@!Gl6SFQ~U*M28)W49dW=qTsv=k;Lrr`QP6vB@mKmLx7$4=>nT=31#7N9&VMFB<` zQZ~D8`kU|lo~Hx+8wcq2?b}OF57u^?%un{OgE**gUS3}4is~mJAt9SzAGUzi|NZ;- zSEER;@nBte>+=D%|EOEXzQFBu_4UJ(lc{LY8Q1e^{Lj6;dJItgd1B%blDZtW&_9YE z6E6b%3I}F)lZy2PX;pOBEff12Y}aN80Rwv_6rI60ld+he9-VHp@1S!w*i zKx;pLW?^I77G=41*}nIupjbkolT%pvb+6$!?HwJoWZOSCHpU8_VP~Ka6cxQ-Z=c)N z@x@qB0HXo(n$+j+k007#@=;My;K1EhBD%V|VDU#Eg2yFiWL$bKj~@;J`Nilsbm$Pa zgu0&IlaA5Bx#3pP*nv>#Pbt6AYl_D1j4tjpwmf}OOntS}b?93DT#tXfPX!B?N?es` zE?&T2Ho*XL();(PNJ&XS8}V*mzkVfPmYLbZi3zKmoE+RdiS@Zwa6DpL9UZ`sl)Z5y zA(HE#Tq5-+Wgokqd2cs`V^8R|YW|ETIvvf{Wi&rCeSm99jz3aoTdR>gJmD;f*T5o9 zwP$&S2LuFA<=gy&Hd0^tI=jbgM3?Y&;X!xY@f&>~{SGT~Fkhq8-yHbeQR9$9ue(sWCix${=VN4-JF@rS zlh@lqsqAwG4|ciC&S+dpFYo3ZvUCpP&vF&%V{~8Zu2yokshj^jEGft{l4|u+Sd6OQ z{+<2nJU8j`8Z=}ew|F7J|JY<-k(t$#bMe2Hl<^7P+mKa-cvvI(Oc8|L09~K z2I;*0yX$jj$15WhpZ(TT{jC~&bqmv<4Tt_elHygqSwv2=#VeQV^EX;`6_P_nUp^#y zh{YEwoPRpJ5|^25eXQ>BPM?G3kA5xaujD#6X-zE)ze!UU_z!a){p=yt>&VEyHD>tX zRKri|jBS&;)z^jvt&U!KE2_VIm$Pr)9g`@sF2JO&^(cD~;IKIX5?VLP*HBesD!~NHHc;DkyHC z^k^F;hu5#1uYsXM+V4gs&BAF{Wfxo>md*|&1@9~&UF)OT_&oa5cT3$<_X}U$IZIR9 zEd-bXzmG2{G(Y@DJ!J}*_;@djO-z{D*iie)-h~hvx9EP{#b-BVOwhouWfu?DYT>k+ z!7n_O-C+X;GWW^T_#9fAYX|KxRqYC6peSP=W*Q#QMG-eel~yL2gP=UKq@sesvMzamHW#* z0euc4*Dxhxl{)VyVkkJ8`*v0R{Ug z3XFvo(ioh085cZ6uc^lJ$UYalP$Z`GOjzkThY&0G+KZ2UCtA$rigthg_eqyrmVU9F z$TV_u^krNiqjrB6tL2tuq~XssHSw_jDvPTC<2N$#c9%ObH#YuC?^pe&t*X+1z+tGKsA>t)VIcXB`3 z?LIP?5ln%9w6)}^tr)Ou&`vQfnF8fT;*XQvvq^fo!cIv=1x@^dib~Ds{MVkIOVGCa zrjq01DF(KfUb(WbckPde00RZ;!ux}1E^CCoK3kylo0Kjt0UG}k5)w*)vFO`?mbQC~ z@8T-@rd_@aJ8*|9f|S}79!zTa3@S^4+3zC3j0F*oePSc3#6o>0SuH`8durK(ozrVd zOkSE&PF}vV*qQ(A*|Y3GG61r3ZtHoO&sfMJsCUTbP|L{vP5J>PDCpqP&`3z%I(%GA zfrdg%NBQ{T=K3D*;6-mY#@t>5pQ#v_o&s^XI~4ED>{DSgXt5z+E4HQo*Dn_NAm+iT zzDjluj%>UGaP0XPElVm+NI1* z`JM3v<4&ZcD`Kww+oAe@rwM)a%H=_XzSr`P%+K;?gqS#J{8>V4x%v51%gW*i6vuR) zlUC&-jqm8CFmBe51yf(n?ObnRwKCadQ8i%A|A3Aih;P@m%3)(_Bityr(m0@Nj6I9I zmCB6dsW^z%ow+x$j4`QkZjU~FlGF2;J}))@S|ubj)IKAPOJ~c0QVchx_2fxf_%op0$;rtP`;L7o zi8t|Gv^Frf6MNd(Fu$vC{CyW779Abk6v27GccwnG1wo`fD)>kwa@$Ty>MUt_t8a$E z9CsTwI-HGJ9+&^JuHWHZBiQOSLw?fbFY9c3#+>{YDB|ty?J?5cacylH5JAp6JBxU4 z%*I1=PcA69`tCW|N5_wkgU;r(N~C$j(h3ESs`QC%Y&$oZzj%H(&A3x>o2B6i2C(Qz zCsz7X)py8fve<)aD)Yc1F}!)0Z!u zpD3ACo^z8Fj0*Vk$Mjpq^%{`MtoaeL!)IVe&{3XbUaS4I$?Fzm?l>E#eoyp> zR&?FN7IJxJoB7)HB>|eSXN!DiBA*J`z;Hng0h543Y4C&#Ma>RAtsj(_uA+tTKSi*0 zm{{2AH6!h5XaObj->(1u{d)>bNagCpf!-xjl!O7Gcf=SqGud{R*+!9T#ZJf31Kup` z8W|qGVQjqpakZ?XV%?SHrts8X&GBqI_)!aB4WA^H_V$9>7LgZr)r|G5^qVciT>vKT$WYmbeIv zc4Tp#JURO&J*#;rsi^2VK(QUX2Do472HmzbhX9V5!WHL^Zi$rkmU7G6W850=cZMeL z*J2@zhPb!hhs5lBk6(ZPrMFi_^x!9$S2rq2t%`DnO2$}-NtKTV-viv;DkwWDmrj|b#Y*Ebr-1*^dAF=EZCg@v$(&4Cr|nZ1;uML zfm&=%QEig2n9SPS+q?d{yE9VE{?8TN)Yk`b1tLFPd@?inNS;1@N~~1neUwwo$RDEBCbL6PMNX$DI;!d7G7oH$H$sT+KGz0V{GlnqXE({X|dkGHzZi zTad)Z@%&z?!7_HG{TzyZYogKntnC$TpLlgr$Gv)d?~J(qjJ0uD5d&k+t|2k};^ECD zdA!FJ+2xXWb`DBS79TU^ADTzL&a-5c~~=|5f;_MV=j`iMJN*Z;nPl@*(yf`WCP_ z3BK&w@>$`uA`=S6S?6KR>^#$M##E>hkqU+O}<*#+565v&*m2(n9%kyqD|s&CJXQf|B3m zdF2~F-R^ArA!W!VXSKDN;+Gq4s&dnz^hZWV3zz>yXDLdi(73NO&I?+Uqhv&TT>ms2 z+j6aY@c6OT;HRg2+S6*hN56kwieDeQc}%w`ESy(MvCC7OKJD(^E!x+wM+x8hwt8(J z30%Y1>FHG#d3v)ffKs4&cRNO_4YR-e`0=RG6lTv^Cb784$P2o|@ zine|0-CKn}I(iBx)bujkedy&kWN*vRSF~|oJ|9M*PZPh;)3m#Nt58m@dIcnDz&2j3 zOm-=$I1DtjV@!^8{qnfJz8e-67A}~@aALnw@Rct&TDxE?UWMnbI9S}OBoA6cxl>qJ zcn!K>jll_YRn8ZL7&v0gM*`3bY6A~)UB zd*?DVd1E*G?)~|5^$*{(^Fq;$5fW#5T?Y0v#Y;DrxXxZsR(^Jm62hdK8V!0ERG*n4 z>CLGAenUHZdqOVzXVz)jjC~i_z$NIvThr3_+y`}AR(7k8kB^xU(|&$EB}K*E#ZKe> z-G%mR8;j-gsjX;q&cV;0E1o^Ojld|-KH*Z!$ZV;P;E$MKg69oI1nR{8V^_~yyhx6k z2WmrCCge8q{l{2f;Lk1-n-;8yMA-kQrZeyPTO=gwM?1mZyM>4#r zNqJ$iR|Rt$8x{iCDa-FH!gp&>)3$SeFOy6ZPfD48xit1f{^@|IleCG-@*|Dm22W@IjzKO0UAdJA8~#UfP-Dk?&0A8t)WasHim zn<(G(!aU#%{|SHuQ5#Ap#x?F`A;kF$7cQ`%u{claDaT6%c8qfH@jby9Eh;K<83+_P z!4x<*KQCbYQ{vgNYcpHke;K@GW)}QM_TZsI)uy?9Hlq04oWjE4HlhKjVFrr+f9VTW zF)>C|CVUk1Wke+qY*=1irmfS%-83;Vp|$z~e*hx^{(zczie`p(bpYc@5^PozU}6di z3TppzL_rM>4#uGIe*30LNRtL@oSOt@eercH*T;3eVobAw1-mmqpOSY z&><7xjc~>Dm?);XQI8(&#@(9z(`W=~`NPr<^NvhiLSdd=zHsrPQD=^c+O3*Nuf@~P zj$fBkQK156!VS#DJq8fo^`H_~jnDbV`$NLR9XXuu?gE=gP`#6Q&sh6M65T%blR|G; z_-iNx=})EIH{g~%!NB_SrEKPuTJVA9hi4V01EyteSdYJn68e1fn`GbjY$Ic1V**)V z&Tw#We68+;@{foC(}4ppblADLE^fKgI!stcF;bq-aWm9j8;}3U1IC4(-C6D}4WtS< zsl-W3PS5wUpdeDxeZk;V^fe59h~$81(6m0nQJcb06?fbXc!(DCWD=;vY3%#m`oXOR zF!a=D{<^7}yh?5Q;+N}8mn?TtEhe_Oq`vTMDNU&1Nc7DN&H76sJ-#hwRR$*v^1C1| z4q>pOTQWx}-PcSrnICEYup}&U`gHW+wO>04u#%phuF&!2yCAP-It#2fpNbFVo2%um z?d|8e>H49PX=rK^!W+;jNuIV0x7OE!~?fa{C0dsKfcz>%S zlLHZhIssB3DPY}QHEy6e3=}gn_57_cG1zG;%!KT^Zs)_%AkrQF823Z7peL1y=O2qY zjWJM3ubog#p6SVqaVy2;fFy9ZUZ*Mj;1L1Lo?!scUTW|;n?9J0AoJRP}6{GWt zNBhz6fWD`fJq}8^1RK>nN$40wdIAm7LHrN|(C_0;;HcOiN%{F&MYGZvq^7xy#XZVc z9b}0zG#^(Od@vTgk$n|}mR|P(FY7_d)-PXJbYHr=yW>?Ol{m2?+&nx-PM!?y?$&wq z_;GUVJQ_dZNN60fv9Uz#g}cKr`^2qp#|R8pGtl=rgbjs<_V)5u>YF!2q3op~Rk&~g zQh1P-p6hvwpFiK3(_);!0wU(pYxPu!*2!>(0k#Ovf~*R5QYe>--O|*JHLp!yH+0uN zyF$<&VsAn|PoB7V@nZ6}O2h2nn3w<{jD&={l@F*OzP?<4iT8v6gLNewfX$6{tVVzw z8x|pSAp?dappZ|k@eyj&Z0fsZ;mYS0Nth%y5C*v5jZdR%=EmypzA zAjBjPr38qn7b@k|*w~1c+UHaZ?H7(UIew_eNz`vdPyWCBm{yPQjkV@+Q_<9n+YYVy?(2m0ak^N)QK?vPLQ%vRjUK)i9Aek? z`3^DL{_Urt_n_gXT#9}v=HiSXSls%P$81NB`agL>NqI=T3b8;>PtTH#mC?C{g{Q!i z9v&qc5#MdS5D*v^E&uV`j`94m?dL(koRbuP9e00KcevVMVX3)C!C$+7pv^dC_>0-^ z-=@0a+oGeRAERngQtnq&5CMXtJUq{XV~8$){P=MsA~E>jArAbi@WCzwSH(mM+;_^(H@#_b?S8FuK4+$Xw){=I#qjs= zT4R7b%#~Box9ghI0Dm4ou5E5k#U!7Ym{?5LA0xdExY5>D1#bFxWaP-vqq_hT!S2m5 zY0=8oW}A~*%z*wl1q3d;y;6YX1f7UON=on1tvK%uSGde!86_~EP^M9-@m|k~|I_Qa z+yyH{meOT)Jl`Lc#lf)yg{Pe%m)d&c1OvuA`b+=70Hz82J(UqF?s)|`jUQaRMUXOR z9cC90m`-eL%&v6_lw)%%^^)ihtH;Y2)js8bEsynp>JhGN1%(rdJ@Z92B?W~W_#Pk^ z_Gl&ch09!v{IvobR`4!>AFO6b{ovS-yvMLF!N=hkBBDZcklIi#;JpyR7{ajU3{`mE z^l@mmZ*i4KPh@9@0E82H6QH;Arly=!5>q7Nv6SV#{5!6qYQKI}8|E8OES?epO8-4L zXgivbPm~sx2>CYvA*AW%Dr-2EG}GF#1^4=&Bj7quxMERp$y*)Z?Z7)yhy`4KZ+T;V zWu6Gnd~mUG18@hR43b=6KqELPYIBEJP)x@C$F-{#%N8ZUoe*RkfKV6NXo|ZDv)Qn> z%oFPgDFQ5&f|7Cu$rt25PbGNEryu2aiV$z#pfCQ6#)}sQ4EiuSp99Ki;L+PqTiX{R z&s>37Lm1V~ag8hUqb+7aYaQO}^nh*1)%p_66o5r)HmVs8)@5$Gv7X|H2h47S5z9_< z13qcD>rgD*K%^$1SbkOa$6tso@3PeQAj|FWkz_T0wPmT*n{{E4$B%}Ev0t!X=iuU+ z{c@Jd7T_7QM$~=b7^c=S{W3xjMIC~LzIgd^JHupg4&nyD#bvwBi-?F|fhJGD3u?yS02QgvL2-wNu&R-U2eNm_cTm>-zB~jB4hfoj^5)hW)-$ zbppHnwn9}xvsF%|1rP+_#uf_Cam6(zUyR5>>KJo?Q#i|WAvc~FW)KbuEePDDmN%SapI*IXLv;|{XxEk#$ayjxsYu>1XaFUC)Etn<%Wyc{4rkeiHE;M6=9-tV(T;6~~uBN9)84xcInFISR!6E4sbW~68v0lG< zCViD1K&jnOSbQsQfN0hsby5M==!yvoF|eoDSzT52jJf%+aFmkNxk#z|E|FlPJ53+@{!WP*=V*Z+YoU3W6yyO@SdXa{xNA z8r|NT>mOW1Qph`Wf7JU_Oy8uhAs^7rC01=Sa&e$KN^a;@SW$0}$ zud=X}m?s$YKzIOnsHm-XKb(&k9~t>L?9gvlXm;xs8;yT(M1;JXThY60?C<21xSv1u zV9qyy%fVTIV}W^!Zi9OUqxpM*ZBpCNwDn|F*1kOLMp_jK8NfC4Krk$@1oPXs2a!;Q z{Qy}26BOzXLA3~IR($DB@kG(Bx?@&j`R>!z^yvPk*xE4?u4*fd_*D!e7Jvr;D3iP3 zYTU<LkMaIQo&G00U;BZQ{vEXGjwIjmEtN6sB|G>wlr63(19}ln7M>+=m zH=>@yB+XI$5Mt-xYCqjZj{`+81(L=$%Y$1deCd@UU#q)iX<21yX=+|L?|JOFe3Gz1 zUYWZ_Q}!cM!DU}lb0~=9*c%(ZN zdcC3F@bL0tTK<>s(95EKP-)wK@0_3P6UF4ds^Nu2-TR8kQ90K7nwrnTWaeEYh}1q} z6WcC`Xl66=qV+<+Hokc?sbiFpk?{r;VbrF1FK~MG=)9o&f+fbT3ZyZB)=G;!LELgc zrr=sm%3lvnwi#t{u(Jn0d&VhQ@fs;MGoiX)zh2O}5O0Bez%9ENw<+6aoIjr){=K99 zlyTFE!3o1S)oyu3nIrz%yr$!G*58bV?6IGbKv4p#mWsEoYyOmZ(XP-#O@g|MI1_-0 zju4`l875SSswUn1V`mM+y{aYVOJN9r~I zLxdcW)kHslM$H@~KjJKgRI0+E5B%R4C856fk<$}|H5cRL*#3Io@x$b8HJ?5Kq5&d7 zz_PU+SeGIKW?snAg+xX^tQlaHl+?8tsY7`5+jZ-~Khf4Os4p^xluLd$q_4V~8{Z=( zwWyCI3_vEbu*3!hzaSR1wzgIR4j6Qli>qgk@$REt-7McD3bOk6yZN-OJLIKiLL1!#-#;p{*H%u|P?G5d2Kgi{3_hIBx2g)UTy~{qfH^6$6-)s6YA^3rI zAeJc$O%q0#ny%4ML81MS9X8+Y-Mb<8pyCi5-L-wIT1vB3{w$J6g5u(eT3Q{x$ILA? z1HP|RS z*64i2`ZGrR4!`pn9p#%XjrfbY(?vyq;1zp*{W1^P#odq$@Up{Sle?XJJtLJ;$`^tT z_EMo;x{l{{dmdVLwrL0!-_|fe#Rc6_tZ*Ps?hHV8zHfmVP+5 zvX6zv|3Zc;B$*5B9|^Q!t~z#+9}whUU={R106j-)v9K9gHZBw1K)Hc;I~}VRlD#*E zyi;IJ18e1&w{jW_MmY?4y>^i+Dynj#gLnd$ZFF8atvpscdN5atrP3*Fshd1erR;Q@}}fG7WpQ3}1L zI*Y-9$QG9Rmedu(N=EnjYF34th7AaAh4F}DdrZ&o)qHm!6tsKywwA55XQ^GiDte>% zb-M*LZJhcuU7YA4XvoT(`ER?zIkFnafz!G1>j52l?twEib|5|>wZO&JI_i1OU(rmziWD}%J`v?4&H*O2TVPP3A)b_wXh5a@)QUfo z+o^<*8}5t|-uElXO9&*InL1*_vmqDG)jfBYUIwtuQay;dsfaP7pGLs|1tv==vC(-Xmz418 z)kF9@mqb$#3V>NBi*!bdnJ7FD=;jc@aL^FBx!~YC;2?lkcsujA^Z`M34x$G!Siq`a zPV52JKf`i@6(*sO2aL8qI0C@|c>)~e1$g?{SeVsYKpNaz@S39HVtl>9B#VnBRy~MW z@=>QHC%{)ky`OeQ+21pCvC1NSqSh7`MI$0c{{BwT+bek0oGj0TD5pjX-PW*t@dx)3 zy$yQog=W*{&!2-$3m=-4P(hE0-RAD*_HxT}d<;YQ2e@bE7O!=SofPc7zjbuz&lP2~ zTR_r)29pc#Z$F>TLwtTv5=2-K8_)dg6!nOlYSpA>Im(W9$gH~mtNpExts9c#hfi?N zw^BwLqFxEVjZmc!+k-G4m6F1##2MNq4BbXeU!T8+V)92Gd1|Y|wQHRwRB<@J@pNVP ztvv0cN%=6a(Wx=u&_hwtFO7PQ1r>bq@gtD$f(0AsqjxurJK_9=GR(je%tP>dF6!zU zUaNynxMe_OE7CKFy+42cJY{Sr-@HOVW5ly(&+gX`CKeY*Lpgn{N5VhmoTQn?)p%ge ztLphYpvwNoCbGdOZou2%=czLNyw)NZ-W_3{kW9{{9KDcoTk6d15o;d%Bpa1|36x$p}{V!fMcrm9lFlh=w}=A z`kPmZa$O;e97PC3l|NanR@b@bJUTId=^PD+Q9Lj&bh#;HsvNNK~AMc_ACc{Mu) z=PW=F?9I&0`&N55r4V1mn;`$|z^6VxN2OY8>4!!d3|CV&X6Y-uo#q60v7^j8E3?~&Gjwm?I==YxNBm;f;QROQ^B3QLyOlO? zaZC5ZtsTy1s5|LpSQ*HC-`->+S1=V^U0L;M3Sl^NhGlzibB)h~$S8ZMcrmVqlA-l$ zKjmQWb(VRa2G5{4B(4$5Gp&Gm6cclBUUKI5kdF8IJOjmjz0DM6k13g_p(;wOOSLLq zAJtVPtG^~+^shE-h!G1VI-EZ(7xHY4MnRHtdV0(NW)@RlaIy(RnI1$EyB;lD5N3hY zEDidSNVm;4IHANq>3__>mFvC?l-P@CoJ@iD5wW&`hJaI_TDp$m;v;nW0SwJN(Mp_f z{MxkZ7S;{9i)*>2A<@xk%0Hx+S3CxJ_4|fX<4s|CVb%eZ zpS@2ZHn>)M7eZjj1$La}#<}84J-cfs7t_ckf#8UJMwBi5C7eour1^j4d?3UMF|aSph#{n5Q^DdORyYD*V7YxEtm za-{8iyEBE#`bz!z2Yb_{yfVwFrunO|^NBMlC4fs94N#~*tuOWl;edkWsoC{OZ~am& zm=}L=;=^F>Z;R*8$$_M;z*i$BzeBHRXh3Qq6z*$OC`md3AuPCRg%i4xHYRkrDK^8#BLa!LJFq z>uG2xf9KW%w&s$^Okr^25JV?7C*)im`$plCsgL9z{HX?^B5y(T44x5TDPk_*lmYw? zsx#0UCXq$+E(@sF19B>Mp8Ny79r#`y-o&GQyg0!B^4+_z#Kc6es1N*AL)Es)(cas& zrZk&*yfO=ecKI8v6km)#U=i$cN|}jogD5LkSJ{W;{EA_!$COU&{}`}0_RrS| zg;m!SyHioU>)GyWW`vhHMgf+14MQ@pymdPt*;tIV3v_uF?o z3oX0Ys=`?|nDcRlqsP~|=Skh~t}CxU~| zKy1^lyh6NbznU7vF7`vXD7>CqNPFYIYe}T)fnd8*O!epGiU;%9vSo_C)5 zRk1PQgSVJ909$Nso}9EIW6e|*Pi^h&^~4X^B3$~)@;s++fmxF|`9ZwTP!=E-RGW^` zD6-cFHve0_9?qxe)po*(7JJ zs(!gm6rdN1{gOx7tT{#Vee^W=ZXRHj)Z)^sb|)Yph3JEUco=$rJN7q0~UFPxt(nb^!$3rP#8rD znbSBGub1e5@2h-(A+-kp1#?hr$defbr)roTxiaLz{mAaFJG(D+YAUHeQ=|Wx6U-Dm zZimEum`mgIq&vKiT#%Ulp1RW?QLf*}Gr~th7#pS&%J}xesbJQ##E~o5ApLl!6r`SZ9`>My-5?`#mnlpx=`tb#IE{PtSc<9m9@1^uS1IC~ zQ>FO#KL&+q>#)gLind^(R@I{8d2~-NYqI@GA~%NAe5An%vO9WNTr~cmP!Mjp_+pfu zj~INruzZWPs&hF#s;d493$^IbaZg|B2x;M>){T=N)K2<~A95?DjO9xq)x)J8Vv1!R zd^y(NNg+~MQ`yNG>JOBH&aa@P^joBSc@L^J;Go!3X@utk4v0K~6G!{Fnuu8tC%n?q z$f1cMu!y6{RA9qvV>hLfN=jlN+v1Qaqm+jzq|lcyUc6B0!r?^1B7>VioS*_0zJI{# zMS6Mwl1e|lH$5Tj>96(EZ$Yq`i0#;jHXP6ImIWh23gks$AtSK&ONGz^IKw~(MQ8F+ zOUcD*xeo~-izuj@xAR#t+qt15aB-3E^tA@aR&@1F7NH(}@~7mlbT zwWwab`gxB?_nj6qW8{A?mwHxCG9lR z+;l2*NnyIL2ak1u^xc-wU7*VC+cnNfO@^bmIJ|DMG}SjU0ErzyQPAuQ3&aD^1{P{E zBnuOyZZihTr6@%a#0IHMrC4#87m5fAApwA38{{QCA_ubX!g$xtGx!XoK3m|fp}XZ` z#R~!dV>(9n%X&z~N_2aac@uqhIL~G<)SgCVyKlB0W98DveS`6L6NxZ`*ycWG6m3>V zTGI}RYslcC=l##f1xh)}%d7q%6aWLCRd*1V9h;PFxE9 z!XRL{oe&0auX6BQqx)2cn{ba9PCFe#!^L6)&Z6=31BW6z>yJC7uC49%b4w0&|Lm}0 z16p3Dk_D%LRJX?)CByh*{nDFh|5TBo(&J}wlo}aWxujkj68F^@~I00@%)YsE$u%pDKMRo+(3wgz!)tG4N;{ zY&RHbdp&Zn4qN0T4x(}@Mc$E1>chdrmzkLpC3^X|K!u!#vJdb6o+H@7B|msR zmCcE{;>NN4>f25u<_~j#NV?-FC`17$pYD>q!w!k9!wiycLOA*2IQos?h|pQw$`CLN zMi8UI;1{9@IA91u>K4oOFWqyeW7OoM?=BEw_3PKWcq0R>Yl%IJSl6RORSXv>A%k{s zONf<*uF3uABNiC#Npy&u&v(fq)IfzyK=m&Pp5L>&FgY~bo~B|TM168d{m$BngW=#s>l z5*jU0a@I@<@jEyrjqSNpHz*>!=p-N_Kzv#QZ!DA1E&!69Fsbr+cj<~_at4y z=q$o6D3)zFEe*E-T@ex@L|>@YS8|_XOA}f>w5V!BnY4C1tLQbUEzsZ<@~+W&H~bhP z8VD#{*3oG|NDmSZLOyC58t33G<9rN)s!%^{#A9*SuwSDjTm>OeTXaDR1^+?4A=YNm zdx?|QtyJ%L+MtangRli1euDlFA3%c3^kPP{xPyn(X+<*Ds^u>g{vRy63v5TID*H|V zKR~&_Gd&tml=xTy3szX6q>AJ)9QQ|9ojYiYi^M4blW#_()#sXyn06-o7gQY+yfgZUP%qJkdhT?xe0|1Xn&T)ZG>!m6;yG$Z= zf8t2Q?N#SP6Nbz0O-T-FZtE?`oV?%p@BI=tb)K?JUv;N1ezIVbep<;i@yR!3s>u$= z6GD}B3o8Q++*u}*xV`mb8`q18 zqrO%vw>5#=by$JMf@2#7aBdS_J!aQ2OtrsK*OLK zMmiJ!2`7ABy~G#~O%pjc$G(R~szrVq@1&J1?a=+ZetqT{@j=NyvcF%SKlPNg$@9Jv z?rE^H7jW?)!waYNQ==!q%1_|JLd2QtR@06-)GI_U3#`2W{T=WcKujPba?7TPNJ!Jk z>ABI+FAV~fLNopbh9?Wq6F7j-V}wUVIc_uwAZspH&*K*EJFM6(T%iL|8=%hml0iAlbZY z#l^)0G8SRk2`CBHITR%+{;Rk&hm8Fwj#oT7)W-N^foUK93qM)akKcZOap%E<+ants zPgPKot;Fg)PZa>WKj^*~T-ng6xgESH5f536Im8-xiAnmDp`snt%fGlH7$#}8Kehg) zW1yLT#Cp+O`FV2kh68gy9|bKwqjEU;-X?pd(0#yUq=M~YXtP3Z=|Qe7UMmYfh#P`n zYdFn+Ul`}vbPo!Qc6+45?Em2&2}egXx}nIpxOxcaXaB`kJYFA&>H&`?hWyzfp31(4 z$hkNB%d1fI4*mY!1NrC$Xr;j2p{mS!^yue(Kd#@*Rw?Qzm_W5b)9Zt$-EMs2`}H-% zcM1-gs5PNO5)u&su(ygf{+wBWP7o(0ae){bvJqn&G(FH95QQ}C9woRjWB>>UvFz!A zj0sr_PqA!a{$EMNK8LUwr|0DoWOl$0dl4=W^a1qXZ94yEynKl>wO-rvA0x6={L%zT zdKED%;j+V3f*`-Mt2qcmS@r zHcJy^gDejxuXghwDHZC<@B&1Pp83O2QAjLp@P#1UrFLJl{1L2Tc%;C8LPG{$Pk(=` z=|$+2$wx+&a9@yyQ9$D-(l7QAoO_GcEG2Qn*-6|F`GI)rB-ha!^)Lz};wy7T1QMI910S*cA)5(rWgOB0duV?1 z@d^ogh!1^H!kH>~uNxl)c z3=45PU|8Y7edf2^#yf}C{89MbH>ZD0=A-NH9X;A8`gQ#jd)NMjLa+%qqR`&G0}v6K zgFf-Ndj|3_6ek)f^6`ir&CpKO!rJOAwmt3Ffkt^{K5qpEvBn<=sCxOO?tM&zZ(5=6XhlyS6^s=nEm(K6DDqq?~`-y-5O6Gs(w4LuG zxHMWhNQkuA)}+3J@ed+>oL!`!QvsEVikbYH(0W2`f{{4h-rILZB?l2qCBC&p3&sXIDSQ?eXnIB~XpyIL$4 zdlgp?SfoM-PC&0Zy_F3>H;x_x%1Tg~0P7*`fVdkaQ<@+Rs#&yu@L!^yj*hNH9fOSv zS>os1vyGtOYk;Vr`^7^7k_C#v@=u{jUY&Ij@MN5wLyUqij76UrJ(2s-40S%-kqBmD z34*N-wnm&F?$%+fG(JQVw`b4h#P=EHF*sZyHLx!=#F>q+n&eJja>omu#kK=cGO7Uk@X)2G5zicI-KRsQYm>g6kk=blj5$ zBA*9jkh<19aI)~aX9YJhD$y2QEpCMYQ;Zd78q`)NnAWX|Tq@6rJ$0G5NY+0p7Ggfb zNqeKq#cwl*w7Yd`Z)Y1&GU8W)p6Rgy3ylvd-3_4mzQ2Hv1RAc5Nd|X%oL<821?=sa z(O@klUq1B3b-*kYxudddqCD;mMIAHh+>Td89D-pm3MJNoKcQj$e_~U&j)P zV9r04+`80v7S=muLRJ>9=%oPM1}vJ%IZ#8eiNfIoW3=As2~S;jnd?Nr0of9IOlaoG zNdUdROuk)zR%Xg;BrBlB%hu1qEex%^A4-1E$hc@S0pjDvhWXCpl*i}cDbjU7LK;r? zrdeCIJ}`T1rn!mK6%A-V(cDDE#87;Imi=qdWm((@NDw2@cC=jbaafjMl}_a_=e6V9 zA8CzgFi(R53|Kh{e8c5UoT6y{_`z6Xm3mowoiQ@9LXH>iaHs>sY3ZgFlWbMLT$~zkMAQA#&$NfF&3p83vxa*( zRmWlTCSH9JfC>=wF1kq=H6F25pdO6@QK3+$2@nO471=5fVWR>gr~uTNQU@$0;<3Zz zCqEnk(}LsWWQN9$ojY%%+r#QNeBmerY6ROAT{Wup)UTE*IrI3o1 zrP0cO=w`y=p?a$8wp;Tk{v86on1ITl1}$G0Iq7$Ax3I7?;=*Q$5xXXU5x4c=br1Ao zbH!c@`=zgbgY>va&it&tJ_%d{P$GB1>#XRu6-a>boDQeAz^GQ=*f?Bx=;-S1iaE}} zcXxXXOfg}JDTjQ|*0nt6VzHHb({x+wPTmTXjr z5waGLZhVx$JFpLd&_i7TY!jJ-2r)YkMR(7(3RO+bkQc1!PoIY2?U2A(zbyjGzw7Mg*U-fX8DieD^Zf&ZymxhV(c;1hJFTUEDo>5;fm#)gw2b5LA9^3{boV< zYC`9XhY0N>`e!ypPkFG_*1x2Y^@P$J);bl`viMhk-B5>nGj0k5x(I&nx7`AsSliE! zFy6xO5Q#5@0Uw6}jtUf^D6k=}JTDRdiFp|R5;UCWWI8v_0kOpQ8gXJbu{hD37JE*F?KT>JshM~x98;gv%f`YsbP+_gdY%};%rRx1yM`X zvke|4}oa1+D#tNY=tTWKT}bCAO_Rz2}Kak=zuB^u{TtKTiHVsm}ld%$B0 zqZO$nJuu{GTj~$j;U|RW>>C)!k&4^v3knPzjLdh1zAXx~JTMlP-KxiRo&ve@@h3LC z_`%fnvK(PbW_%3Y$V5N)@qwB~f@A0zk&b5i9~r%kOpNgj3n2fa3dl^ z6cz^0thSQ)mxjhh#AT9*34jBv07YT1%6$Gj247tWyAC{%xFsy0;zg5Smd^@7I$(P# zqSXZChxoNmm6MKGBeSo!m6I#~Q@KzeL8nQ#1FZp^$c(AYb9?+M4 zn?7P5bd=z(2Dym(j|qzy2Nxp81yQ?yyWW15XtD7jdg1Q}Hx4rzP)*|PNjd07Tsg$w z1DJEKd-o>5@6hGBwv4{-AA~}larKylv}QY&BrJ9jxXKar0qpQR3Lhfp2Um`F0yj&% zYbt^w;!yy@CPEwvFglVD2O#Q%kV5MOV26}eU?ZX^v2w)kZ64GXN2KVf9Q_p(ELisk zZj2CXwzX3(ta#+8!YS9~KB1|wICcd005%MIYXX($o_(pRriNqlsq2(=m)q#UHAHBL z$`Td8fB1VdjA_j|w&-^Mgq?xFNDwp-WDw6A$1gM} zs)(??e`2ubdsO3>1gXm;<^wMW5FNSSP`+0KiGX_;4vMF!>q$Z`3WC2*$PEON2T-*Y zpBmEhFG%_UeDCMA*vtJ2Nek$k@sQ^R(?dzb29BGhMQc*@HD5er$8d}$jV-5{g zyo^0BRFS`X(N99$-~i>%I6CDRBErSux%z7SD3nZybtT%D7cb=SVw%8Er~(imtrH|^ z{hLf@DQwH<1W=@t!aaEVff#5&N!p&5^$(DqMt6m8NheFqK#xEMQhMlM*-E{o%JaJCIV zNC96e=_JV#fkN6JRXieJ&|Z=u1*musgD8#uNM{tqFJbZ_ctAbpf^Y?wm8BVckJE+q z6DZ z(5dmz^RNVw01a$<)L0jxen26@ifxL`At)q-E;T9NmgE+Y>b1BNXpuf;5DF5)4m!SI zj5XC^!o_x`_$ojoh=GAnw84g@2ohGn1(Ou*KFeFKItViW;)4ee-MD7Pha zGyvZTfq=5cj#uWO;~>3O=EOA)zPoJud~qwGMg(qw!XCK*%CNTKc!Ng-F_+4axpv!O z|0tuRLN$s`7(E<<7k@S?N zz_>j)fdE1XhQ5~bfKxEm+v$U_F@^&S*AQrxHSXVid~vxdKxpm7!qWCdUBbE3{e^;p zU>Uej(Z^sLfN=x^@@ZgqVA`@mRlowm0u-i>uUm8E5G~l30S01>YODHj-qIrk_XQ1Iq|b0sJy3P5}DP zW!;RaHQRv%m$Tp93ubv^N`Ut0KnG9aVRQi0p;>qC3qPjNdYw?AVChVk5Iw_5hqZ>5 z1IKICIhoOGUMb`wzyV9d!ldLUFv5?OR)0Z$8Y*M&vZ*Ap*)Fk z{>hVvrKRyjm)pU$jcn>_hs_C}4vh)&Q%Cj{!RuRvZYC=)&k{zW-(eE~V2E(nvtor} zdhzYUHfsn8z+>PYlgwLgk4c@p0laE*GaztG4XYD45D}Pe-FbBKWFGnGn=VvdWVj;D zvHo^<)WW6&4FUL&@CHLT_B%lG#f5Ky+xW-Q$c;Hj91SWw528o>{jHLqdk02eMIspp zd?s<%{d_T;3k1VwSBmp3>}$}_IOF5q|7x9n53ztGyLQL^GLyU})1a3)o=Jo_G4g|- z-N+~aVPn?wt=zc^vXqZtFu(#AD@1@PN#9k5rvfocW004{)p5B66IvSW8U#M1^COD4 ziXeqbLy;Jh85pC^L#eaFO-1KF!#|TsH-L*i_#h6Fp9L)*4#J}$>}|tcAclT5B{!1H zQ*0|_n+#kwU0_G;I~3ba;9+Ay^*@dlM?_&=phdl3b?#7J`wUG<&jd9{)R+dZF@&Nt{%RO`n0I!MqXZ*N) z*ry@K(~G~p|G(8A)6Q%rrP( z8q5#pw3&>z8%*Y5m(p>{KpCdyb;GBQ+bgLyXxj{7Ew+8}e#a*q=Sk*%QgXIV~MBLY`~4#iR+Au{?Lzb=PTXpk03?@12?aJ^8sLOV_ih z$5Ov38)vpo896#+yLn_RFd+G{?cH-yd_F8m8vr?sC+$D6k7r-NVPiUoO`Rc~Mf$<- z=x|am=TiM^5U6pHh}S@EnniedycZ^kZ~v*B{(mKO_4}S{mVl?QIa6B2N#%$#bX(Rj zav${{yH#@%3RiNmLe38?-TV7!69Oq<&&AdPmi4soY%Rvp~wYs5-~CudjVJ z5j#fn3*RE7!2*GmyAU=wvw#j_(;ECGYmWhfhI7giHwxAWNKxEsfSo+1KP*Zvbs(7G zK6Wy>2p8P%vWlm*D@2iBNrX~DmDaBsX7ygDmp4OasNW$H|KP!;eWRz_TUx3Rjdd14 z;c_TQfzAGv1A5SH5Ir&0&?1myd5h>c2s>McP|W&3k8_>zAEXEx?O*Bhl%}JJsYZ+pIZxTouiviCAOPhcN zZupre^ZxdKJPNlm?nR=*1P2G>3iNWpxI&4cmmIYeDu6&JQ2MtZ^?xeQD;ZA(JvF`! zdI?f0ZNKqN>HPWgUN`b%opll$_v}Og0!yU@cxH0W;!JZ$&|WL?Jt!>US#c^f`3CYq_CNc=bSj!V~He#h}#^nF#v#?MKYbLGYNt5dJw z4BMkbJvnsxm0~8sbBLIA6|f)BngjSpk!<&*J^I{%)^ zb9-fc4&?z84awbKSVH4O=+kMhdjSIJJeNK z?FbbkBo+xJ>VgV+-}8Kj{b(#1}Twm>ZdE;d=q z55*&N87SF_xoHjD>g22jA#6_IiUg@3=G~{jPqg(GLqUgce+-8ce6Zy8LyP%R`v56p zpLbsEC15;?B~C@pB(k!hs?jwvdW#WP@1guBLB~EnM#)X+K9ytIPY!TXbc7`0i$H$l zn;cV|-%7COzWQ)NO586jj5H7-AyNN>-gG)W`lCpkp{Q`?wwhGn4o4`}Av~0dh3}&%QmeY{#2ormJptiM zT>GT~mJba$u{r~3lki-0CXNX#WQVU4<)r9A+YX>Z92%8nEYIw!zYyaRg$em?1Oz8E zEI>i|_A_3F{$S*9+?XJ$YE1qLf=I$7bQ=?snER|9t}!sO=`in+-Hf^v=PB+JI0PjC zh#d`PwSOZ`+-#F)IDn%Cb1RZ$P%w5%5CbEdEEA6gZ}d0|aEaU#lya)U6LapUIuP8D z=ULeSHXX7ql3xh~tcKX$@dm7HZ1~tibWvihEHD+ zQP&Vw2U*I7Wm;&-(O8j51BT`9vSeHWeun{Q#F61z;5=?dG`~d6Pd+iMW0)?{aH;tQ z@@-%$1wEs9C1e0ZizoaW82>;*v}PMkmv7;uN3z2Zv)wA4M8dki0azg?4mfdIl>CwLD;z(cdyi9oyrYT_V<;zof`y2;Pl*6kr0h3DL z;^N}keOsWettn*-yT;JFIuQWi38W2U3rogse~UoKu%Z2KXxJeo#f;F9G(i%6xau2~ zl!TYM5tSnDd6GNGa^zzP8h>x=83~IU#;jdGbtD(9G{ONS&cCKY zj|hKt9~AZX;1Ywai4+_Nv?Hi0fRdct7r%pdJCvF11^E#d=loXoW?&jY_hBT9ldzyc zjuv18Bxt!Hb(Cb;08c5qO9ZC)6O@Hw5ZR%^Q9~065^4Zv23+Rni;PN#b6*0*;(EG? z3ltib<_a1YHHAvdNWjW0>8%gHNe$KnO5LQL=E=7Fpj zC-76mhmh_X$rtDo@F)PFqp$->26(oO`PHGkEr3Gne=JY$_oZcf-FDg(ngMCFfPnUq zMT6fQy^2<n;I7#qj#!hWkW&cCiEv>jl(jS1!S#0NbNwQtvj@S@1W()xH*8&HIZ- zGF!6-K)nO+fw?Le4g9WM``l;8T2r+1+QG^<#WmPqD+AcVn@8;l$N}FUWj|y+P$S@u zhG`N+5e?oe=p*6^g0}!ffprClI@m!dovH${cLjGV?;pn&4+pOYsJuDO=Rj!)IVY?n6Fe^w@(_-4GCl}AA$kF#1|zpT zIuZ$>f2-Q=)rSp87|TZ(ED`~oL6%_NP7F}%e5}svSBI<;A7 za)}2CSK3)n2FD@ZXBS-i+l*F42gF**_Yo6-n`PyvW8R$;y9cGOw+L5~%Ie5Jh)m8h zF>a&raos$$D*8Q5xm!gCT4YFsQxtJ;heDBsmvky;Dk@JL({ZrDuqM0hN}7d#q0sNJ zfkt%F=maia%uUGrrn_r-(RmH|e^eAGuJNcL8E+k0zexYE!MrCsC%1<*EhyMkbci8~ zjOjtT6`)E;a{|)@v1Sm8jm`-19E2;wD@GrFrjhuR$d-C`rKZAW@)*jnjbQ5W*Diqo z#1IyAwFErfD?&<9d2+}fO~3?Bo_v9 zspAp38U(SO`yo2Y0RKb23|Y$mDUlP0aTMoyb&Up&z#|i zj*cb^5)~#;>(_9JHv;**AZ4}k`*g)ym>MBNB03`gg+S4qJDzVvsRg7L{Kz7{0>T;m z3sOGdAhs+MDkazfshfx{0qQ5fI5-~A+zFk`c(hg*5D@Wd0a|KlY1#eqG)ATl?E1qVBoC=b2Fq|fH;On{uTt*fbWpa_YwXyB7y*1h1fB~QoLEB+C)P` zpeP(oJ^6K9M|79~1=W+7Bq@%4aOfaT@c#OjNZUC$d|p1MO&ygD%5Y*Z!p3d+{5fO& z#Y~ieRXF{DtCK<*8yToUU>c?i;h{oc?v2k+k~E2P>bhGh1ifhS0k|E{yQT%o4$t~2 zifV<~pOm;pz)@M^!*07?QG0w(O4~t~s^&Wz8SP{^Q4XZH4uQ3@0H2Q6LGn*lGkOEC z$kmfWUErWYJ70?jx3^OoOA%RbH86-_v=Rb(K_C%!=GLuSyMLFX)tvp}?S7*ju258* zIA9)CKO5ij29gZ`uf)Cp|0NDOGl_Us33FH6kJ$1_ez1}CknJIN z1It2JU*8ATg`y>RQHg4ua32u&2A~Thv@KpaL@|eSn8;0pdfP+IQ@g1KElgLJ=c(p{ zZNeib=gd6_X^PuupXro2fL{KcJ9~qhheoA;DrdOPPY!9MDl9#2Lep;c^Q4*O*DHoe zy6&x)v7SU&$f5ER>FDc-brhZi`M*vQJs%;XM94*I!SgW`eu%xSl})w<1q7sf^stkT ze={btMI-th62Ff>&UTO2aa$tra_ReKsBn*_kEe?JqJAqKtQA~uE|6b=Egp;~oWqQJ zz#70hCUkC@UB{NX0k!Bh{O9z4f3Y*0Hy=Z;lSc}P zqgnH+OAj@as&+FHh=QPwfwBO1oX7L51E+}*2_Jm2aB`9sC&&pVg4kwcyeTwF`q<%; zgba~)7dO%QQTpv9WdN!aT;aGnIA~hAU!8b zQ1_JU*n$VpS&+9RjOSgPy`vLXW`2J6tAfD){cvMmqbDT93A6-vxvxkqrlRmH zavv)VtTn^6RK##rj1|Eq$oGLXF5OP~_xbNdGga8861c__MfkDbu zm|ypCaU+2iX^f;;#aYI{mjVO5GH6m@y^wj6a~D@1ytL>hKSCT#M4qTki6|d}L{glQ zxD;SkQ#WRSDbw;0{D+DI=VZvy6t(T%oJEpO%JG zo}wt_A9}+2_e(1sZli*wZx>)KZ+w^BRXmz~eD|mDJ637b^gNa4YeKp?s3i$PwL2fEstKT!IBy%vaU zfc^P*-Ilh5Jc!_-os2a0oa?XYwI})6@F_!`Kss0We$lZWgJ9xCZY$!f<1JGfpc-Yx zlw=4JFMx(7w-@#XDST02)RRsI&kA4grgvQI#)xr~!h+39m7gySz&e1ReBC>KLWBju z=bqIFHmkyy1FRy6o&*mi#E1oMUc$XB)_E;%AORORxl4?5Bg?2b@K55&q?y1YnmL#k z@n(~W*KE&N*`w@0h)0b@7nccBeNODor3B|Pg}_?g4x9Bd?^V+H)ana@MJft|9ZKIJ z;9al-hM=gk+k}Z;D7NuD>w0oUhO3TcX?p~s!y)q)31J^2dRD#2h#!A| zoCa}8No7Q&LQYF!r3^niA51%n@Yp7F<8Cmfgjuk)N+RT}p9DF86x=XnGLmzfFOV0J zfvAeJv!||1AOxQL4J5y{Sx2LIC6z67F<{C-5zz;Wr6#&MIfu9)rf?|%$It7}V#8>vBBgP*yoVuOL;6`-2{qNC z3@0Hz1Jf`cT`+ccX0fU}I9gQXvr9!LzEDb3V#Me$0udvxHOcys7;{4w{8lK20s(&_ z)WW4FV3#u@D2Ry#q|u=(2MQn$z)-zpbBPAPO0#4gkl`hmsnATGHhJpk$xv$%5ijA* zSGBv4Qj%hT$WV;k$7^u}BwUbO^M6_Zd9LQQ(v}izFnnv~8<-;z1w@-YBn41StN}vx z&8~VgjJG0u>Bo+Af7Lu5<1qCB+Q~w(1F6^o&ash+JS@e~Sl&jFM>Vfie{&GnCh3 z&k^D*U56NPph+;$RxcS$3!6JjG=b6C0%-584=ljq8_WCUZG?>^`7p8^RF zpJ+JnAaPtF%*GEXx4KzO2n)n@;)eq+cXhkzW+?+nAhb3Hvu$7wK;#L*f?mz`1Th7v zIG!DV2NMS&rIc+uBI;n!KiVour9^_?Nve#9fnBA0#w7xp(N|ZLO-oS_m7Cay_#07~g1sx(W7HzhoT_M%ok7Ajh;*vvhib{TYkl}HPfHXlZ z!=)}14XlVxo=f}S&NfL+ z?7!LZP_K6YQ-z|fRfLPNlpe;K7;RgF^?8WrMCuQ?+UWd-J3Hw7(oMV`>1NS~)^(ta zCRicut4N1j!M8hnI&iv`;Io$YMI0w#XJmfp7jP^Hb^;dH@+* zzQ~4ozccOE@e6~OpXw7_J>EihN!bq~+7+HCVD_k}*$oHhwCS)0Nf# zj3oeL8j#Prq~3*@8Qx2G!n3mpCQQ=p7bi0nNiWA2sYcK|?!vD#bM6|6(ji3qO&luM zca%2kyOr2jE71ckz|53uh&CTj=U(y$T!tS@&|P9~#g-sx69DHYfJ7Et&E!*?@(hk4 zgL82JVB@5ABcL`DLxYv*e>clA7rfA3C(?Mh^_i>uqe}@^2?*WcN!9}G2hh3~U0u3v z7CLC;&OOi-A^{UM@2>s#8w)JRU-tC!1~ureptz>PCdT>I$~}*0MPYXlraKmf*F#UB zSSS!7Gnbx%O1qG94L(XJiN`)3-%Ezjrd?vs&MrXmEy6-Wg;m=y0T`tR>d4mszSIRG zkuyw0-|%i=5+*h`iT+q4b(1wf`M28cg_57QHbJ)BjTVhRS?i=|EUaj`p@muN1~E@M zom@nq-ihLs1m_W(3YiZn$VBj8GF`HUQ9DdSfIPFUR5$lE$yAH(H^(-b5J!N#xQFYm z*34!Ik`QVRpUW^rOv|d9lx5x@3^*19cnYarBDj54{~IkfnczC*8tS42gA=+RKYWGh z%9Lp-`Y^Zwfrk8>0bGkRmb(p!-9dyF!#EZI$qeL_z|m+rhC8zkXbG5};o1~tmGek{ z!^z}>lNo(j2{1^4--lbo6T1fKum)df!M>P^5yb{C9EZg7#?$Wz1`=J7Wr~Y0T71{| zdwE_lgn;ufFU z16?&JTe42=&a`;dozH8K*=?=a3QrVOMa3z4UIEAW`@$7KRU6FX`#miUqrFO!FAs z@u*B2!*Yil+0T-3#o)}0MPtjZ*j{@pj)*@n7^qz2Ix_5tcnjo6s?9zd8wIff5k|UW z{zotPr>UZ?Z{GYtA!cK6=EGe&Ohg5<#Z@DM@9_N(o}n9WdGo2^J#sl{<+Z;|wZxwT zCYyHCdgAl`K+jdvf_E*hdCYc+d|h_fEk_( za$moE`QlF7(SBN%m39X;1tJ066^aiPr$JH-ZwpQl^3Si^c;;2-{NWz2>s8SY zLR_j&R+QrB9y{*ms?Syr>HIl^t+c+lPw?nyt82u9$4~58SKR3X@HR3a^2#r@I+g(G z|Ni0LL~)Y`G#*N79%`IW|K{XhNQPS(vh;^1 zN3EAOdn7CJB<9=>Rfe?I5X;x`C10BkMI|3gdH3IEeDjN%`j&TNKi6LOJ>Vd>s%+HX z6VW^%#Po0Q1s(D@AMMITLHD{F*F~5*e?z}kD2rQN;uaOYQy;7Ke4j^l{^RTK+E1Ue z?n6<6Dign*pq@ZVh}&D2*^9>BoHhlutM@hPBJmx8yg;Tx>wE_K(;Mh6$Yv-dx?rI%2ex~Vr zvuX8oY*bGjHRhAiXGNzU?GBA*Yzl89Tup;RbZPyL}p!l{E*IkIy}C&<(5*pnmp*kes- z;UT-jOdS!2u6eU6hb7+|u(x7+9kRo?ispjt;@(?43SqEU&!kkg$y3TYf7fwg)GQ0u*>mnU zvqgfWArIw^t_}e7jDU`|XywIbB%pY|wr2H}k)0jxW>o+mjZyCEmUCJt4t- zxVl(usK=Im_|-4(-WUtB-^`N^ERBzD@$mRdM6~+#jh%~U_s!t-r!%kh(i@PRqVYYY zO#fhuN?d}kug)HCi=MGpt?ea7!M88*ygcIX@T4mppTmmZyw=p~za{wVHZL_VDvy~3 zaO*P3G?)x}^QMBH{=wV<1OwuAc%ouQ$;?5Qp!<;~+ScvHY=n`g>kaLx(F z1OB510lOr8KC5^+=}oX4-7o%p>V{ysfLzm35aTPFN9GG`UC!KXhm)Evdj|7R8^ko+ zjW$&}c~YZnQj22yz*_nr^VALBz3%;e+__QHo%;&Ko}A@rXWJR@UTDEWv6y(MDR5l) z`W}S@FK~?CaCg%{_Jw~D{hVdTEx83@5ruGeC!w8 z#^(6>PEvU+rWvxFdgvYhWo_+N5vkIZdj$bKGbdF4WF!n8OjFgkp?K^^j$&oId}3DP zXbofX&HK^ybgzzjn(w^1aUj)-`%kghY+poRZwZi)JL~rL-zPbkKkw@WY zcNpK4mN=MGC2=UMrSVd5wz}-WV3Ve`EEy&lx~%I(;x_^4t&@_v3hE8bJKl3 zEgP-=x$~o^0aMUA_*HPW!A6Zp-NUHbQ9QH087f`3ClJ@sonOCLFf-vMuRSJE5qcZO z%87f7q^AJw07%-YCX&sE(;?E|pZeEJ6PYK$`mEK@G#>xq(NpI+pu|)~A9j{^eoU#M)4v3lC-#sZs!J=jRq%FmyN#aHSe!k}i{RZvC=BG!; zijx~2Y${iBohiih=i?9Qk2$$o$@DTxCXEa6W%|udA7krWlu6@@{4y@NJni#r?=o*$ z-r}Z~OQ-3R^C@&3BDhD)949E1GxK=l=gerTIas@9cNb6&S4!IX9Efvl**`A*E-mTr zuFe_ZZlTyTs%ft>i_`Qstb~0tbc1cH+a+UPpV&4srd)Y=H$UEtl%6gKcjDl6|D?kNnUVCZD*86-JzYSt(k`_{K5x66Ab`}@ zt}ZTf!;I2ZQ4U5!u(Gp1(9KF>dfBxXJn;!Z4Ux~@NLopJ49c?52Tn)66wI9YC_l4OwLLyiuzg;5ld8Yp_}l*VUFV!z^Tum3S_^(^3*Egc(7Lid z=F&&WQSHit4>`>Lb|%I>Urha=&gR=SzhdWnLGs-zx;3Y*c>h{@ZOtscshgb`uDPY> zU(pA#;a0yQ!zgCXl=W0P=A&O<`fFCu*j8)s@%!_r*Ix~&?>jD@Ej)5=!{$Q8+kKO3 zd4$%=HO-`@+A|yoj6%7tgL**HJ;2iT~0gw z;S*oRslz83&F4+ud}@4G@^68<;FgXM&+fH{?j?;_I8NA(NhaBQt15?u9o!mqXy06S z@tD+m{sSd+H_T}YcHPRjd!Lz6&*2EG(MHp14SHo|!yR8dS*`@xs?bv%mF{Z(FmEc> z{jH*sG4ZC(o-poj-n-?)0|r)@>9lFfqB4@$@NC!_W0$4U`p%tuuU$V`e&^5K9vZGx zs$HvR*U2p?D^H%>2WPfsD|kWRVD~P473$4zy}tcyJLZL$J32-|k@G35RVem2nmJUG zTF(PE)DG!^8VAnBNw;gx{cd?Vm*d$?qbFQ~46yuynIQ4aYp&lffzpFWSfIt%8qkT! z*s3COq`E-(UQB*A|D(^YI}&`DGWc$vT35Y>Qsjt_16wuQdNqonv6tOO=V==y?VLHb zZkM_l*Hsvp|D@u`$wwTj~%j~R!Kj5&HQXNL+soaX$@)L8Igx67nD7h;G4njX~#@_O_1Tuy0@IzC#n zJ>Kc31l3x@jXifY1d4BL-?ORw&{eC0dnQ(>@&35|!QjcXB_Y)mi^Mm$hkvCqJqCM`$?yc6hbfl1Ej`U9&K&&+o&h zl06JppcPOsD>1$bTmZUh!$q%$*n$%Qb8OcFk9M`|W4j<_-;y9P!?Q(-w*}jHhJE%a=5$Q5VAq>C!snzIa!O+ji%<7^XO4^Ktm|T`_=OY}_XIs+>HTwd z=9+Sc%Dp*_w0(I>?0dIOj=bxqtXr`6+qJJ?dM_7BtIh>~# zv-jCWS)?&AnKB?0e5Fbvo7FX5*P8z1-q1~YcFw$l6tP-3GH06b}+i2RX*J-v2M(fFQ?FDxU z)v|Qr!AoW>{SH9Zftmmb&Cc$dz|fVCN{pU#L)q8ll1Xq?PF}9X2JJYpwSK)z{HIDX zlT;qAY>^3(pljsZc9X|>(Lb{3NQ$e_MTaea7z4b!^&cfjG`(Sy;oa_MYGcI^(Rw@K zt51c+4mw-f8|K35PbsNzYHk?jVQyQe^IAev(3$0k$XwsgZgOFsElw|7A)nc zjd=Q=sFS6RU`#jS5mE@X_+4a2btsIph&^HS{walHk4%p=N?hK*VYTkblq%|JSE5*} zm?o$z94*MQ36lp}1#(Bv0iG0&mVoJOY925#jy}jqQ1Lp-UGG!7OSzDn_ha-(#DnqS zGYQP&{s^u@opAoti;m8e%!PLz82I~c^!3qKyZ`3c!V%Z-dt?kNI|K`l+Pxaaz+vt?!SIto?kv-T(5p%yvNg~lh z^IHAp>-RI9(y6`*^4~}oc&T&i36!oZ8M%>PrzBh0PNxqGmxfQtyeW2Uo0Ue1!y6g9 zHPK}cwnc4UZu$#>jQjVQ>jW)b$7|$J9Ey|$X2ou$+Ncy}ZD#fAQL#ll^(}vshKM1L zYxI%_mVenw+Br^&O!NoHmTVlI8ag}!w=*T?V8JGdkt|I~Y{T1+}`*)D8z=yeAs zAm;`1j;kw`+Q%1P`~t)7R6!p>6b@Qq!jE5lzSfCJvDQWN`U^4Ozc?ACN`Ia9dDk? z-{C7g5&2R)wTL;zdhyaW$t7xhk;h=v^%?HHm+$Is@*<#PplxI=5AfM`Tp9;s~Ss_ zUldl+?75#fqZ<3O-99Vpr0EJpHuj%r>$zlVIc5h;R3e@yGMw7yHAFE$>H*?8lqxHv zDvFNBMDP)G#jje1v&r5*4l~Ru^5(RiM}O5vG@l3@efac-R7}({9V%rtW%e6PYyt)m zsPq$X!Zu*`75rAQ*hLs{1Z|isRP%4cm57^U`TYeR*d=)!8hN-@8$xkxycZ zf#UA~@9wp)LJC_x@x|Y4ZwS3|RF|SAWYlWS3P!frmnex7|RA6uiO zVCI6DuqF2d4%!`~){xmIRhGDDx2=Go617nM~X^wASS(BHD5n_$R#7Ie=^QmmFBbG2^Wd|-;QSt+kZ;l>&;TfuWxT8M|gOGrdi5j0DUlbaQIRq1y=f{(G7zyJWr6HUO;SUFje7P12QQQFE2{5cw}q9f>n|WOUSQdB`ySLdzPKrfU+DpSY5?(!&UE66i)ysMV^!npvHE&! z*U7nRoU!>Aj?tlEaC6%L*&9YRN8P;X3H=Gw@7Z5 z(A+T5xPXyR%{+&`mWtNYa_B-4(sME!iVTkCoJ{{U8@RZ-p@RlY!xMqm}{{LHPA zP$|}da+j2JHriILz>Hr=a(^*Bt?vo_=-k{X5afi(?E(BAXO{1LxXHsPsOHnJf%;qz z>V2h~^ExX#cI;61d|D|f;`k(V^7x8c#;{sK-n?9s)rMPw$u@RY$&8g)IXHG*3opqUmM-M;VZ;($V#>bc$ zo*CvERJO%E^0T%V$LUtbJGY%?|053bWtq4_i%puf+e7TTGj+4{=mbB!f@FcIHsA+0 z87uBk%F4k}c)W{q-OWQ`tKfE(m6}Xa| ztQ!hMCe_39Gd;bJY0&#q*{Rdr$@Za7yeV^jBhNXy$46K@eff5)dL}y-B<5Rs9q!B= zRi0J}om)Iwr0Osb>8;Y6)XY_U{cp9zb>IEpf~uJXP!cE)Elo8(mz9Dt;v!N{h;|?L zk$=a$CXYe<$LaKrMC(8mfV}h_XeejHL=G;Indl&h$g~2$O360Y(CGXFVULDIG?t_K zL*0S&M^TOZwAC_$ak^?xHr1QuBYhe|p8)HkQ=j=$70Yqr5uk3>h4V&I)1lPpNsTT* zli2C+e}*@o9p3U6J|GYV8`mF!0N~@$vpRG5UT@NPSF7{} z!W3SBWIM@Yx&saXDvTHrjqQa#;v#@HSOK~{nhmq`Nb+74f2{Fq1eHOg^;mJ{-~VX= z))37Av5DYsLX%5Z7hbyzkqMDYl60>$RXzP^cqURHY)8t?Z24c$3Ni|l%zanoD;aq) zjM?N0+4fNRlDL0km;UHuOby2xzkFdOsR1BX2_GV>#Q8X{Ae#k+)+6ijFo;n84A+7H zdNV+BQ^)5P!6f~g`?k@fAxm4#V7U9wlq(K6vwYS2C+-=Da9(eZ_9(l5oS(Tukw8eS zw9s|vwDHDk{ECY>qjezMDr(|^X<6urpe=qpJM}c5R-yxWa>tNW=@8XYvZI^Q29Sn%%&jh z`qOh&w|WH_LU+YjoQG)U%KrPyC6^L5$U8}1``fz|T$nG5S@4`Fii}0~!{A;rrGHAF zSzjNC5LCB!e7kz1OeHltoBKe%U?49#$Kp;x4ALv>6{(8GrsH{DTltk>5WKTdqT7xN zr?m`cRlkFdaGUE9?kAOgtta@*23apuJI6X6YPsVvdb;tB!}@*YlvG=fYu>(pTW~Ff zp60h5TZTr8#on&F+tSO~=J@-d z0h$ZHEk3%X)G;Oo?EZ3>M>ea^7hOqOw61@|t=;l$fYk2Tj~lYOB|5y=(E6x{#_62i zUCzR-iT3;<*OsX}wsRG0D$^^!9Wp^%kJ8rqJgZ2M)qs@w!s&G8I(%dV z)^X6?6RfL#eWyQzk&utc+n-~~8=vjHpEU9?YGkd5e7@GV@GSp=O|6e~-*46lwyk=^ zM8Ey2`yR`lNvYJ2XZoO8AVE4H@wq>q*^jADaNRVROW-mfHe86B$DF4t@-dBu97o2Y zbtG3)I?)1h8}mX#Vj?Rtf*s9dN4$muf)%*!QULUmiD$ymY0&XhRaMQ4>+54?yCvc@ z(95R@k`)B;6s{+tIK=2Ud{bMmg)^Wp;}9+dq8@S)iFn#HK_c6Op8{HfIuT=Vys*ny zVpJ7!UBsA+h5)$>lp}#@VlbuQ8pHSI=L(&`6i7@FBd!b}1H=@C zpo)(lP7HUHAt4q&gyb9`ma4O}5i&fW4G?fZ-SNBbuCJrqdqj4#Zr`pF!G};b!fZqH zfT6qa3z0C9+qa9}HKM4xOF|J5LzHj8m-t=+Y9AtT!y%1d7lK4&B@wlBq<|*HIXISj zZ;Tf0{QeKa!ll$cjI7JGMNQi~Y!*u{HpMhryzK{~ zxMB0=5Xg_hn+LGsQH2E7z82rq(z;eH0vZr-nxK_{Pc;wV%|Vx=F)_IATla_S$(Rj5sgjMReNY4!WB(_a7j7M!YnFB##pO9^yT?In`pP^#Jv^{zR7c*`RLP6 zob`9dxp&bSrm=HZehkg{`M{f}o;u=!VoUnzz~Cz$tc?Y6-((VXU-;e6T~XR=>HmJ7 zsbjf~_VJw1_JMCVTRXk)3#k2djrewATZYcWRpBb>go{7Ci|wV`zR};d{eIg-eW$7x zlh>x`KlEL`P1T9J)Ttxfy?Gk9l&P%@D+O^1kHFqw8<`(4{N&-s~Ce4v~MDZzC=({RS`Cpul|N&B_Cv6EPN;`%C0!#VPfigVHRK^M3!?)+?AK0Mp=r;yXPwF+SzD_TJp4*%Ab_1> z3424nhhgprr0$?A|uA1eq2S{a-S1ihM{Ncazo03zV zcv}i8B{bg5#O2dc(o*I`)v0gs{zIkqM*VN?+x|mLRS$Ve4*r}t&oS)z@jaz&<;Gu}2)gI{5BiWIyc;0Cy>BtmfLrXDL2^Xd=EW%XC!j572nw zZ#B>srR&BDR&{6Mh~?XY18RRcOUp zfIgan;jD@WUQ^omE3sB*oOhR&U1sfEmYM6G60CA^aBB}6afxr(=CR4E(=719nU3lD zzq5(IddHN*YmV3sq-p?mz!W?SlvrfRUd}De@O&q!39|D&kzbatER7c0bVv{x<`&N} zNbd5XMQyZzYXZ~k-mqEPAzY9g{YaH0HWp$gL(mx+7CU#JTkA`>oO_=5?SHH+c*#OawiY5zxj(YWT9zJv zaY-VeE0SzRl!2V$r&=X7=NA^{h?o#blW(TlO|_*H`~4IbcQh-m$V1sfVNHQtpYoZq z(ZAdFCa6CoA-aU{Yq_3`eA-YFuS%5cn?y^z@g2toFm8$H!}0&ucw>?&8Cz+OdlfP* zY>Zuz4Pw&L)8%=^A@BXF%Kr(0rLdC;#?D|}Uut|;Pk8SBl>X=I$t^A6u2#qR7_y4v zjtejX%4_Y)K|xd?0vL27m37xEhf)m*m&L|5%(CUx;@yg|A0NLNZ(32q7Z(~jo;~o$ zavY^SxO*ACcM*XnvJR=$3ZJeNyKnqPudbI}xcBWBNu@pKV;TpQ_D9rh>Isj%!mjW8 zV_s^!n0uX4%}|i|T+hnw19Bb}1G4hsyeIQ`zE4PWaxbtKG#;B+Z0;R<^He10+lNF| zt-UF}fKCD*%#KMlnUxHCOI!E0s!-Y}I5b*&0id>_XI( zJ$shy#=h@MAwmctdyx@B$i9`ONtQ{{Bx&s1Sd)fq-+Ac&UDw-ny@@gNJiq6h``qU~ z_nDufu{eL#{cqokKlRSn*58ZDD!Hz+L9`F&R$lKnIr~-rgw)Mv52l{nI)45-zv|7$ zhu&mGKTibm2_B+WuU9Y9*^2QR?eo-I6E)T6ZeLtEJlxLwJXx4ZB57n%bjVIT!Ghvu zV;g+a@v)h!3?;cn92wZyg$9hw(Wu5J2`1 zTj*QC(2}8NzopclZ|2DK@jX!UC3kms|Fsi#8M!uJJsLyneiSNys>@E*u<7tDDh7P4 zKy?M9xmmBxIVp{mqLkD%H@6~^n}Wi*^~(CAEn;)6+3a6DS^Z@Mhnz={}6lZQoX#tEWpH zoO}?pCpcv0g6!KLrK~T{RHDw-?kWCr@}VjvPVJoJv=~LyEQ1KD9x4qb&;1wQY|7q9 zvgD}S8=7Z$tzi9V>ICWD?BTt8lQi01PGBgnIIb*ONgwDDxopuEYk3MFh3bN&i~ljT zv6oaj9nFNEPd@x*7qkYrbT(GZgJ)mi`Sw0lO1Xb!D?xetl>6lemML1Uy!E9g^+r#A z&K`R^>}&mqr^dOug?cpDfbNW5QUrG9Y3fb!OIM4VqMCW zPc&zQh0aKYdhFzNpgJIcjUa9k07VsgMRr7zPi7Sc^5Zu7nqGgX=6G)R|tB>`Hzz~8Nys-cDEt7(% zx3(1@VH5LAN-(q;U~kpiRcA57AQccUhna#TjJ$9V6A$L0X7KQ=2!8g8g_Z^5ajHGx zEpj{zxYAPWMxEm$X+KXkx8T+YGk8Ga;*Mwcu)x45@E%|GcQ(?c-cAWHhTS&ciCk2s z2!P7l`=RUF7hbN+o98jP@vEDAz$5`A!bwRw^bukqA%38K>J?FwjpM2Hry^{kr&pS? z#j~&0()>MsErL@sT9IcQ?Z2GF;S*yupmJ45UTl;9;b+O8VU);g=mbEv4R-S!-+eB& zIBms$dvjq)v|IiOBWIf$IVCICV~H6UX3A+>ts`QaM{UL#lJwV~&5WaPfn!WcWg~d# zj1S8!(w?Cnl?64~QdQ8c+DS$n|28+&TxMEFX8lJ9__?5MHnE=Jw$mA5+`@_N9a~!g zv9gR}U{LrC24$OoyqM{K2a5mCpPRwsgHo4pGgtE|4kN@OHD!p8r~3@9ZE9+S!0hYV z+J_%}KVt{v7HFDFI9b!)bNf~w)S{aR@(94xoRmsSx6Tl{L$YF(UPptGG779#A zu2(v-fdz#%2#=wz`2`4a&*fOV8p8?1j?e3d%R!hgy>|9~LBT=B$c32EP=hGm7NI}u zWrB$}U)nlE+2Lc(tQQ$EC^oJXIh{%T#HbhtLwnuQ6vIZa0TK53HMTEv`FF1xo3Pv3 zVC=!Ydo1+1;$99Kb(B3aWkCulmpN~;R7Q%AS z3xUlJpFiJ(Nv?C}&Or>xu12f7#DcpNlm%;pTbO>B`U@zB+uzzX%MM+p`s| z<8HJ<;v9Wb7=5;8LqwqAcm=!WwfC+a?0t>Tx-zSHWmhdf(*6jmvHsC={;*!)gR(KX z3lUV4#aDlY#-vGumIXi>o+O&Z+p(4T;dfMj-MlqO8~&pjNK%Iu){jk2U-6LqWZpc# z4|7H#>=F;Vs^iDH^YWSSuh9wagd%H!7#rbx5RqM%;a_2%op zUjYr;X5q`qIr4$t(z(hD8WBGdU~iHoOtK+HvEUrD_oYuVGGKy?z`{(@)w6L!z(x%r zyT3|Hm!1Wio1nTD7Z=xmeKqo(&P8VWz)-jEQhZ%)?aWyXq6bY2vP_6N_$|b8*rp&q zm^QuQOZIwMV^}N$y#nwygcek`X8z(jX*;m#TQ#Jvr4Q#~QQGxC8c)R|Sq=#)h@aHX zADD01aV|wFbrF@(6IrWN2;f4pBNRo?pL4)a7*BEs6d!QFz{aMCF!1$j7>p$S`2)-@ zVz2_Wz)I1WR|y;#B_$(xIkl-Vk%c8tLr?UUO6&p0wAWnd>KbV=BJ39+XdfK0ZD&g1Or9pr};GNf=DLn{O z6O>Tb@7!5$7qye+#DG(APruIre*PkuP5@&%khgx|<)HnT9ad-YfkmqsBcBAr`+bi4g^Yv^K85pDx3A!^Yh&B*jysAw zrd0Jcv!wiF))iebb{~E>bZ0WpU-R6r5zO`~ykhJ(eX2W0 zn9kk1b87v|BVHi8(0v_UsaTcmO{@GxtdCAH4veLoVIYdQEfkgg0p@~M!6l{(hMsq} zCNLN8-m??e*TPs_1iEWC!h?A4G|9kF!CG%`v^0bFxu$P+B~Ui=&~QCB?M24 z+Ow3zGX5mYBR-7)ilHPYPf9Sr*P)w+3^hQV8}A!@Jy-J`n4`gaM;3u0OE(c09mKtN z3+jUX;HnE_40vQgJVMRvXEuB*yV)zd1eRqBh@XeT0p78Z(zLna4U zbPOgNXB8YT?hc-HK`3AQy-oO;v3VmY(<^X0^TcGUzL|LG^)VgohJ=RrY)s@?X(~+g z)Nz{rdjbdE-`LmrUrx=5AxY9-+Qq~}ENujJLFX z-oP~~KzjXDCf5c@4GVZ=`ez)X2vGgt z94-#K($~DU=SeQ)ul&eFa6IQB#5cy2+ zZsq9%1r;5(x#{=c?EE|jf63=Nkrm^v7^Yg(M$k6%7HP}wjrTpr8)Mpsw8Lm3ym?Pp zi`T1jB;I_p^-eZtV@8(K+92z@p~NluAMXe~A0=NtmPTSmk*c>TrO9feac3+ZqCW+TB}Ik zss8)0@Aw4%Yi%d}k1c}w5tT3UWOIJ!vtBo5kM$H19^a1clYDO(dFAhUeR}qGafYt5 z$8bEpj18_KB8GG|3h;Lm`%*)z*7?WZvYzQW#@#+zCUW-apn{IOyIrhh65aak<~9!f z**)|%{>R~m3>)2t`JF){zPkDp=$tN>NyHtlpa8reV7{e8IIM*O8OMgW~EEs*KtFPW|@|YZ*{ro2|cS!0u@8{>ob|FUWB5SO;j0{)I zXxH&qIIO*c1N>Oa@MFiSTQXVKwfnjnvNJNyKx&X;b#r%bH7k8vhR*bvIN2;T2G#bM zYt2gT^x2qE=h62^K{A5)zRJ-#LoQG|YBaj^)VKs5HB;-!&5v8?4p5x1ZBAWB2FieO z{JSZ$8OTPWfLa!6^{$v<*gzW;lr`?!4rX-Ns)5c)w_~)ln0Slj3UaM#UawrQ2*p*WJk4$;s)2jT5O6h}1U&b1L^JQn7(evEXj+DVcS!r0pr3?L$P#c#s)P9IFcAMn% zfTTB@N8DfbZKZC`@`#x4i;4E+6iy5|GltL4@5+a92Bs)+Y$`ZDQiErWlb3HQP9t9n z1Z(Kzj+HT%G@ie!G~`0%-ZzCO>D9b@Wrp9WO>eD|=)8i$Mrbt7#-69g{AA~?{7_+H zxj@`H9ZA^KrDddhKpqa{(4Z?mah(1^pGUF;3_GdxJ{+aOm%5-PPfYTe9BeZ?q^Kdf zKWKR^{oP&XVmV0pA1&=RCp6De`%4ivzZi$;_9sd@Zn2ktfB$MrA!*zp`<+A5JT-RE z+&O>d?icmb1a+S+`|n9G3`5|YAA;+;gSxP8(;5_`-Zoi;Fdm+z{y4J z52wb?E=q_dg)nLTo%)B+qpntZjDb;&ixD%4A~5@M9aHm}W9i!5*9*?%#3M>&A)&6lIDI{m`0pz@%b|=!qy6$NLa$#P z4l{j5KJ`F;4~fEBODIBjOx51Urara053{c2{eb4NSt)3+6n-p0sqQhmaZHe&_jsF@oF$QXl^J*SAHxzZyF!> z;?|S&(72|cpeA~$b3suu?-EWM@>E>Bo${tm<}o1?%M%3$__pCee4WUCPC~I+mPi zr1;yzg@dD~(gAGr9FSr`vxK-dxxJB9URUSG!BHwnyQaGxm=(0#%h9x{l(4<#Wm3O@ z-xMS@wSX7h$N+pdTVq+*k&NaO#`(?$59EhWaO=M4k2g6(u+gRYXvM0ZB&w1Kr=~j< zn>sr;_)If@Z=ueGg9q0;txg=LBSegfF+>Se7#!8sPU*s-ncR-ku?^jq-7~o?9<+QV zs0Heuu1o6{*wkNF;O`qtY}*%edLHgL=;O_|7HPL1BV_hQZ_r;g;J;&kY^?ryJHEZP z^mu#YXZooALn?Q4wCU68ej0{5|VhJ;z6H9}UfGajj`RYPOZP zJt{kV;L!H^_A0;U%t-V-c4})v86TvA!w=3DlNaafnqZOlSqwc~7uaxeB-He3)j%7i zAthR6;<8}FS93Nc>Z8dKW}g&lEGq^&v9 z#2wOKrVQ1|=f)ISQsz=qgU?$*Som?Z=$YmhSDLwp+pAH$mPS5zZzz|aPYiCBU5j=I zq})2=uB|-bZ6Ge!8MNAed;z7pmSGYU7F>K*fPp&LSqDBJ_`JE+JmPHk&cqMaRq3Pc z%h2aLg#SBs?AW)TKXJxRFi{~UBST+j7>m)?=1b&T@!f}sf2#Z*Jd5Hvf4(V8f&ZPn z1hht%Rg`C4myO5^BH3thMlk$f7;N8xPS`MEYnA}o7Q~C5lEL;D3n?e)Z=Pe~(HsBM z0t9_TtgvQQBoL408m|Rb()v#dSd&1$3S10fL%g|`VOD)nH)ur{xmNzxU{>hiu>O`S1Ctjjx({HtlJU;2@MjG&D9 zk|XJS$p`vYx|D}J}Pe$R0jKUsWmhiUUcwU~cK`j?U$ zpJ)66?87&fg8Z3JMr?0gAZUC^JW{g-A$vs=o%FJA2KGU$)UWP|8I9*`518c3!^*=W z2tqP_CO9+KG+Mo-z>c}Ek`|~&bNxh*J&#-6CE8q=u4()(m7LH|inBZk08NPIB2CE6 z+>h2W%ficRkBm#!zf?BeSF1^QYIzb)e$cwpHvfOfoI4K#>m2nwxLb}OTzA&yto0hQ zP35`z5V!2wAz5%GU7h!8isHn8qkZ54B{0^iyd7q&KeBE1uq`En1MlqIT!7gPf2X0P z?$RhW+{VO(%UeB@2D4w?Eih;A2t*{D*GMfjY;IOt9jJ5rY~Q~1A6@jo%n_1jbu-wwHdZ91|GH)AI(_k8u{tvl z>q8#gBinRkm|U{3*x$fst2)bfBzV!A6O*mQhoowzTQ9K9-csKmb*;Zy57S_vSLAR( znGT48lG&j z7Hq6#ZHpsE5Ls{lqrJ$y82Cd)lmti}T^j9U+B|Ycu@W6UurIc0b^Xx7Q7O*5bp^|U zjips+=NU1HK+hP;NxX#P7Oed4kln&>KSj)4 zcKmN)VLhkd?PBQ2%JINlw03ydrY;0Fy|Q6!A{gB>ew&@pJlZqfqlVfdjSQKd4J zy?d%#;b(2bGsz>Xot{ey92$fU|K-F3PP2*dJmyS?hh#D1HVPIvZqb*_C9eK*W3p9+ zY}x);Qo-f^YC%V#@D+nXQL&&E)nsN0U+3UM6IRu=&ruG6bNx6QCr;|-bAWImwLe$q z%pxRkUM%ltAh;b09{Pe$ZIvSgG0`i7T18hxd-EM0_uj>8t8zIz&-T!_7pIazFd zK{oJlM;Q%XKYEEwIj`J%jp*@x?pQGyN~gtu?N^PDZq1!g$Oa$OdY=T+Mi*%e%qc)( zDEo^WsFfYVU_h-%7}{8Yv41Oc_rV1-m~{9)CyJ1_$c7Z&WH!S%f3p&t>4e*jw**=T zneyAu9IzW9gfDulhX&b#{3i*W7xZw!1^$0svI|}{2ct2CSN|@WR61kEEmBPU8r#(z zY1e3FrAK17HqKaJJFa*UF2B{scoODqjoC zLQX|XH6@2n%Y2O6gU&;Qdd{^X21a{Rkub2w}O$7gKXS| z!Fy-1F(flJElV~jG#Cd>F^OF{&6U-pZ&v+qHOfRe&N6~9h)%HTI5>ZxJ&XR2GCzLV zA>m4p=*U8>(bm>Cj;>e!&WLWWbPO;z zh{(|u|JNe)Ve+#3pdQgw1L_C#Kn1>}rxFd;oBd7JBrU^CXE9k-caTrl_CP zBNA}tV^^2UmW6P0<(V?{=5J>42W@7sy#*K%he$J+j`uJMev4l&p2UpqOE3Y>71?x} zwY@P(m`%tp_z3*gd#Ie&!2b0k^yecA3O2xFT?Xj3_va4w)Sq3hGnt`lJsITZ^p5hA zb#a1#e`*`U-u2m%U=_O_w{bGi$PoC7kw11#vbOMCO+WA_|Nxq zHLchk^ZI+lRxz5iHNqbm_LP98ZVova7J(bj*D82vn<=8=j0#`#S7HfMbLZzy{M<3_ zY7}?pxuJmhK-5Y`E!o9MHObA!fVD*kq`WrY`B29W0BaXGLN0YUJy3a3CBe5rwZWL1 zrbWf$x5tcKe!)zLg4uI*vEF;Da^T2N5-?|noap^x+Hr3S>&|bDU!knNBj7hy-&)z@ zUy4UecK8_Er1_6O;G4t7o6mu$CeQ#4fP&9x9F*c=`|VlD{8<2 zQMHaTD}D3xT`CNAKFsDmeN5J-#?UcUw#vW(5N#@sqeC2p=ZZL&%fVjHzQ zk15pu+Gcj&wgRkX;AyoHY4*s7GX5EmUvM+8yrO3B-2u_?@bzmw1+){|5&F;uSA>`5 z`$9fihOT?s-xa+0BC*2~aZe8jKZ^bj^R*uiI+T zt8tkJzs)nOnIlOPOA$?53i?V@?drKvWpy0Q|%84$fa(UQ-UeHaxxKbh%U{b>7VW*|+rSFtj-ntrE(7&|De4$No;L$`?zQ&x3@ZxGHA0Hl%rC2`KrEl2 z_*nQkc+2J022WDQqmYn*W5@o$@6H{Ze}+939&Y&k*-NqnAW7Q_B?d(lE2~gi11aQo z=ryGD%=Z-5?H4(++DOQdtXh(yd_?ugJS0oNeJc6n5dzrrw3B~kyG7^l@Vne^+MVOB zT7256T}(Kv*}##l`Gr6wx=`Ie0^_iPrNde5nL$x$UEQrz$BU?A0AZOM-bB0hn?Y&q zZw!8b!l+|1f20NFv!Q%m)Z$D02*#Yhe2$VR0EL?=y3tQd6i%lAX@c6S5m^$Jg&sTM11L?k{CIj?m&c3~aXQ`ilL{>_QEU}R_! z+6x7|2Dm9fyQ_3=e@@TTkH&*X9-K|Q33G!`1NGQEob(AbUCh_zgZi2Z!aKhau@vDD z*fGKw`b${^XQN5w2|g3WV)Cn|K(<~q$SjI<{LZ8^TYt4xB1W%>)zO1-EEUJ{+E6}= zHH96U3K={in?*kfIZ^67|IuSpU+aB?ATUD!&FKUAIL&;pXM2H-bP!yu?;~xt9MIfh zHA3yqXA!{o>66DkBO(xC*EAkE2s)$E*sC+Ir^SBsFft^ziKxI)O1ybgyDNuBJeb{o z_S{{FxnM;TbzVyw99w{Xs^s6AH}x=aDScWpu=T27=E#F)s~@A@QfDJs1$n^x+4Lz; zbRsI&HHIU#0+kJKDVx^=Z*%UPF=zg<xWG5K0Jbsi`*8y7CI#wvWZ=4I*{oof=w3o?#P9S7F%YHnJBgWk1gW-7L z2TFiH={oT!6l6H8W?>(IEuP3lsfETm^)fUJL%@ut{`p5Oh@;}DCpc_7l{ zzu}AgFs^ec>R`ybilQWGC%GXYMjvML0HU9r|M}MA3^1G6R651u`biGW&rP4|>FnxVHFqkq!XpY@V^z)yHjS zE>`5@KOyi z{vvu#3^e<|u{H5#B2VPhN-f)|b6n{eE7$9$A1ew9X19 zf^&0cJU#zF(}5;DB+7WE;t9bH(vNM01hBeboW%@@2uLZBQ!0P{a6+Gh@TzM3`Yr=# zC^0ZF0I4qN)>Fdd>;kEcve^~-5IPfjI*cu!`UmRXK`6i7&$3?svfyKPH<0m(oEZ2; zkMQQ%JQg*E!mP3S0+82wr|mhQEC2ABw+@_n9Xs{HzQ>j+)9&&m#Pce*L3cGZ_1L)N zRyjiV-D!1EE+Imk&YG6kjXMJA=#D2hEtTE0`7d+`!xptm5(_zQi6QLln6Q^fmTrT3 zT;G1cN@z;f^PJfpnidFbFoCNlkW3T44-T3s3mq`vqh;tjvA^7|Y_9Poem{|Q-T#cf z&I7A*j7*8ce5jJf#`C6a5fx1DlVRt#a8wNidZ*pNzn%OuD$gls-)^X9zM-K7UR8ZF z1)8EA!iL1b&=#J^`8owqfk%vbH-vmPs%qvfZ)hlYJnJty+Lg%!AGh&qrKld8xh}EWR`!a?-33Q@fGwd zz~qXkoQ%Ehof$rwKL4v>(g!X*zzoF%i&}Y>h3eyRaLq=2a*7(yaDqcO_WzMz!rFdJsh378w)TM2-N-GP81Et^PfR z&i8v_N1;(mU+Ag*B+6I9JMr=}O$j3roDoE~H%G>nXUx0KH9G1He|o0Q1KL~=4T7f+ zn#ntJ{kdONUL1}W4n?`2_pcvrHK>I4vF9P#yQ#RQN91UW5V6kh6eb?P3{zBF&Cip+ zrIO!0Q$yh)ej+&IXz<&hnPxK>v{2WZE7sxDb`{@Ga61_t_N{XBTb)jpl}r}oREUG{ z>DtUrYHMF1Y+)tBy2o8@QdLX!Aaa4VRm>12BQ}U||pLX!F zgh3AgE-Hf}oC;j8K+I@*e{o-)c)z{~%|2~yScVd6`oUeohtHEy`*Q3Km7bc!O``zu zG(YMlYa1|UQmhV<=E~*wCVkQ}1`j?^+|6B=I67eHJ)U3(S*OczeAwCfIXty*^GFN( zo?($nU^6ht=uE)&%yc0%fgI+kL{F)J!5K85<~#}Yu|Hc3&^mpeA?yKpTVViR_DVU& zG4X~SH{Fr_3^0u;52RB~C#>#L6F~)jahEWa$WSlR$tRxHOKS6%F&9lM%4!Ms^4g8Y zs)|W!@|XzEy6EE5)x`=`ex3d@byMSe=oC4C@CI(avdYVQI#)X_DJSP#@Y^OPIgKPY z__A#UU$oK*MGZiG0Cz{k{wNC4{)cyQMjce?1p;=sjoAc%S??Tc0&cp(CIxT|oEpzM zc*h5ml=E(LB`oFkzcXIZOoxbMQ&shncp8!{Br|Mk9IkMZefRA0RTw0~+Pw(Cwxv%Y zvxYhd3i#?%5^=on-o8~fV6RG@I_ff5e&Lk&X8^QGmVkANbWQ`$tIGWdpL5G^TbM=x zRs^UBRHa_u04DZ0l}vc}LES&p2JxIb@cy%XC74tK_=e~AMUtvoyhDir>&dWoK#JfP zeE`_Y&CP(jyt{8lVy!-GVf{ygALZklRPhvx((>|-WkSYwYP)3fCy%>R|N$<Vx?*GOdW-}NB;66RsL1(6K;i$EJ0tQq!Qxk)LvjX3eIS@-(8 zBJ_C5a5(8c;ebChhn89TZ4Ll(lP!IvZ&}J5B zS{KQd?si7;IFzHSjcRnO%w?I}a=UMM^`7?V!XXTO4jJ)>grUe$u}-UAZdal*(F5G` zaM-gLVGRZu#^J?~W+6@*1w*3#70W9xwF)3%8xq0CPAYD6rH`dW7&^0BmaiIB>-&d>RKgOPo zF$bMQWf7nUn+l1ixOUe=a&&Z5TQv-1pc?Yu9L|g99IY*!9D?3yzJUz?zlP`@@CBC0 zV8;}iJ&=D6j+U#9v1AGBvO;bQJs?k>SIwpZc>r9YkRo~%_Ze07>M@o+!t_4!H*P6I zLq7$G{xyG3t{}BCbPl;tBMhex3gjIuK3dzISg7~^zvu+`LcAZ<&UGu&$?Lb*Msn6Oj8S=!Lm$&xi8PS zcY%eRH9JKE3b2fH$Jz&crtv#aC4k%C$6wdg{}GbeW(Q+S=$Pr zr+aLEmmapk#J7)Iz}@b%1>dM8spOWHkPDaIFP2Fjnr~$LH0=)MFWGKyj!Mh#6NQs; zuonw3HPj{0&F4+aGZFcBml<@tzTUOA4!={CX(}WHc$l;i2$N%dw%`d}-v0>3#fR3D z{botp6?&cUd;)6m^rArgHWiu*n)QJy0md)vMa{)f4=0!Y+eJ6cyy7ukC4noqL{!Y- zd56Ac6u=wA1ijN$lup}k(;NQV`x*JIJ&>S6~ zefh#0riqia0s{k*z#jakl*5t9J>Qf8v)#&dgIrmJ(RG;+xori)s0HgEXoQ-wfRy3d zo}PWXD1th6%A(Tsx%z*c{-l;=DSr}o3@NL5WL*Zhrh?QwJ@n^k`=Y%3&esm>BaQd$ zVD8aWpV8fjI|k~iLvlkwJWtjefp7>ly#X6Z!~J~D@aT3`KcM`JRkYI~M_->m)GP$_ zu0P4|?(&58jira#k8LYJ3JIm-RjRg2;D!$6gl0a~jq2hScZs#uoUw#6?-P#uulQz& z6bZ4$>Y=X@KA!k@tMbHBitJgq3JUCF1k`YTQZytArgxa@=@;9}V5v`*17D_m=dO#C8@eq3eW}u8OWcHOp}XLPYFI|q>cZ(T49qKL5g(2w z^nd(g-lY?h{g5Y;y5+G!QDsVhdI#@nBj_e37ZVNH;yL38c4^K}33i;APMbHWr5l(N zI;>-y=!skzr;ty%!H=EO$B-pFvn>la+YRa zHV>2OanQ5x`1bO(nMFV+i{>vp(L?rLt3ZjBK1Jy4OZk8zAVeEIVUX1})z~dY^0_dd zxgKg2u5?Mi1G@;+D3Rd+ z1Y?iQjS`|Hh0tIqATA*>26Z45weV!ZINY%Fy-~3j*uPr;Zb>MFcNn?=xd?1I1uD6+ z;cn2jKrz|)Ln=rP+shv56t;c+ddwNRO2H$&^h~-0MVxU-kE7RP&XgTSvHI}}ijB?9 z-(R`B-^^*@094S9RUO_^wSVBY?-H06`tZK^;V}Y&8cfS>^>CK}x`6)%=NCZ$6>rIl z$6tShAB{5pexhgE9>Q4rII^-QtmR#^^-nq%m70DgEU|j^|JmAhX|M&hf+>!F1MH-&q!}OCN z2LSs7!49a6InT5uZ-gG18qYX{iHG>Blyg7(B{Z1=o367Q;KaC2XWmM(w9tn**yb^) za&BJN7z;rG*pOr`BmFo3(*ihl#TIJuMeVW@CeW<9kjPh10Pm65mDCdM7#t7>QXQ2O z@fItE&;?25f+aZbhRo)tG9DNTgj?!s6<&tI2VV-5qiMCTK(e%rr9NDZR+nq3T=oug zU}q7>39js3`JS?D(1Zcu4hR|)HU3eMFwh1vrX)*X${QDed0VVM7)z+@{4CN|$xL-W zwwMfT1-dZUVE|xa*{p3Sy>^$mKFkIm4tqYjUKkixm?WDebAG(6y^LnS^G0s~gJP~h z5pqOFYmc=IFDkgz3rZ?#K+W^T)}z^3yPba*5IcaqH&B0i$n5Z;mU~cAE%-6(l=|!F z)ae#xh+^V}X!f-TO}SSBYm+%?JaY!!A_Pbu0&hI0l^AMd{bwQ@rrOXdZ2?4AkhWWd zzV-LNqXbMW_vi9F^rchOfawzQ;Gd1ZHLu>&NA6x*AMOM(z*uYbHyJV>5$+7FZz&2c zC>PDQ7R_rFM>-q8!wRHk@ATN`xetto6(NO!vP)3|Qs}h%-)p|=GFad+E1BWk08iLv z2DOv35!grz_H}1xzl0x#s8CzHk3OOOY0uPVq{BbL5fje|9F01Ura-br--ZNA6@o^x zFJ%G^=my>{j+lc@eOVB^ur3zkHthCn*(Vy9PR)EM^Po)hmTIol^^z~SG+<1JKc0%a zjb_4%-r1=i-!0ci8MA^M4{Q!aGDK8fBmJ*K!L&`!|8a1dGGcg&g}-t9tNB@@3ctJ7 zrhV_Nfhc`GI1h&cOw18X+pn$Fx4~7 z3M6e^BD=td$|KzLR4uegt`jchWl zPgV1X1uGv$Q@gCt$?7FUppaqG%j_a|WVRcvb>U(T;*_0;1{w&P`YN`~dUC75B_(6_ z^T{wd2rG7WM~EKKu7J38tr=R>P#A!IM>GG?WDV_QPtDyhqxErI`$9syg?wse01Iq7 z0bHd5qbo{~Yg7{K23uEMivG$Lr%G21I6&%v`vZ@Ifc9WKClCN|P4l&g1TIUVsd7DZ zv2x!^!qB?R`Z@&~udr0G%2E0j>N-$$l2y;3wg)ExOMOVFdJqWUgV9!u3hW+eKK&%K zRIW1gr3}>@y}y+U?9XGkk`qAV0eBHKM=q#dvWKjDjq$43fbsq}I)%|#CYvhBG#zp4 zib7CSg_YWJIp{Nf78!?#jiBR_AR|SM8&!TZuRH^)s=Od(T+>ia%~aXvf{BNB23ZvR+o8fg&d&oz8Tjqn&_(;M7utqz3>?rM&6EHL>Y1r)ZPxERjG(fO zE+#`GFo6&-zYL&f{%3<5*Ewqb4!Gc_ReHN;Q)Kx^#H^qKg)33*v&>Xd{|h#CriX-V zUgEXy5rGAhjxgz^w$k~J3~+!lds6jUVIQ0>a9g^5Jv?^B00OaRokFP|ppw9qLNCBJ z`Au%C)zDVy&KS^w4ZMHhWt`pJH@@wcS@8`~%?l}*0L}~g?1BP=Kgfj^Ams(&BJelR zoj+^J@`=2{YIj|y*WI?_6aWAb6$H`&Az&`c_KzVMUWYP$9Y7;2nuju6{10UTdQUQ! zhsIsSq4emog6S*>lrZo_2{rZRwO%#8?1H*<>L{Er(1tI;&M_vu%amsV0syd9#fP{z!*c{l`AK%{qCorA)}Z6GELY)dMX(ZJ737=IZM6w_%VVy zk}Z^~2B2dGBqi|r?<*acqSp4U^CjK1goKoegU<&E6N*aIb+dy@G`ZN1&SJop+~#A% zil#xRhDrwF*ZrXGGCnA6859TKC`4vYDL2>sdp94;`kt1xv;;tFucPeS;9$-GXo?ne zT~a3srsRl6L61FjH;d=6pknzj8BMdVS%^Ibxs=gL31+3xxBK?!LxN?BW`4b6Xc3SD zA#z#JoI4Be9G($KI1CS}i^H+0vkh1_rN$q$EsQEsSYUu_3Cuu4kSjkyA(urQLkxczCqWYMBX ze#n-!3f9s%%z-)=$TafG>$$$w_T^e;zTIaZRy7DCjIcmNHZZOC`$~WNh>)0AqfJ?! zT7gproHzF4`1V?&v2keYt)Um#HJI~I>xqCW?bq5y%Ajoh|4uJd(2!P)OjJhH85l_v z78)JKbkJJ*HpCPZ&>YwdFMiF~-EG_Y9M~3U&jquCczytMU~p{)=Rvm|A8I4#zGtUf z4@;V$gt*tbv;;C4?_SOUA(~%n+HyVZ0X^ma8gMXefL-k4_|9_yJ1PvE975c+PI=~{r#`J5$kxKM2Bx_rIGC!X`S zuMrS(eYWKl6=1{+vCMveNp30qrETCPYkdvZZ0kir5QBZhsj~uJvfHL&Cjv5uGR-rDE|xJP+3Aq4(YeQ?Dy3r{rcZ!)9TtIc?EoejjJaC z!b67+j{0$VRSZ!V-v;MGL}l6&fGjT7zsb4uX}Mk}Km#Zc;w-1RS|3{fUWL3J&k0cv z=vELME5A>xRF54QI|(EuqzD*flYn~(BWsbR{z&(`O|NSq;2^qxC zgBmIb0l~w=_ouQ}pF)cbqz>>nHj(^h^}n-;{ErfW7y)nS-LooeGryD+CLY@JFa!eJ zEewJ5*m%!KK4@HUaehsJya8_#!Y1sSWWB(%3(V3%&PZvvv{DVD8X)@KX|H*TgYLjX zjrnR8*G?9R1_K|i6ON=nO6LNdYToUuaK~MiCoa((kUkLdE+sIAtPCUTRbH?c8CsK& z>IiQVRanA)G;XrOmTb@_gRJWvw4ny117F|<{@wF3Ljl4Y>6@uskT6hqoI#Px=zA3a zHX^5_e;xnP+bVJd8IEzgjB^k}AwrRrpTncDv8~^}Hsz~k$rVxU8Bl?w1T~W7H9#_P zxWeF!q6X+Ctb|Wyti5>xY6*lZZidPYwujq``pnlbF9yJP2t{4;_wGALR!zl0FpsCX z;#CPeBrMm=A_(~UB!jC@woYLV_LK|C#os@4vIdfWQichmYbx#q_9p5&IvMFOz8N_4 zpKn9)RN?9#(B}x;0cii4Pt*mKCiLh={IbKkyXN!{^2(Gur*iq#!am3)hQzg2$G!i4 zwGQe!w3O`q?qiu=zY>n8D(~+-!*Cw+UF$RiPhc-tV?{3|Wm#OrBw3=Fj*N)G=nQ;D z80myT9U)ZaR?MKbE->&S22-^$WC=2B_;5{lOYGqmXgpq*DFF%#D{>01N>|MC=D&`s zEw>~G@ND^7P$)wQg~I#1Wa1!3fKT9IMF^p(xHwDR#OBo3DJQ1l@mkVLf0ZBD$R5TZzZ$stjF-L z5uMEgN_Gy6aFV6Ngq$oto&Z&UVIL1etsYxg9GUIs-DO4EuO zfQp-4X5DyMC61V~2qO)OguO2$*h>usO6PVtspdWyponTi;a#AlN{e#=_9&`tP_kns zMwcD}1V7(AeEmE|zRFLzgc~XTZA5m#WN|S(I`CEaudol-XD}F)rkYn>?3Np-2UJH1 zpBjH**`e_A{#k?BTJabVChXvYk@wMepyLnlK9SEpjuWPoz^$jF4DK|U>5>-|HgCsk z*#3&itp4w|8L-g&eH*V+r~uY?qy+%(0-G_}=#Dh54#1*2LVhcW3_848rOL+y$gT~> z$q<>KBnUJ8ME1DSl_gl7F!Kv8%8r7dr-!4mp?WGeCXshx=XehRT zyf~=IfV4F7%J;v8ybM|G=G;A*7$F+iZYGN8TRlL}27vXrVzQTRsd33plb;^$Fx1i6 z$?nDfD)z)a&O^yJb8qJLn%dcg4?ACNBGpahIzV9riA^a7Ba>w<#ai0bL~uy503ISk4g!NqzEFDifwS8L4pU8*Kxh^2T_iJ?-pO*#N^?fa279gN!WHhbOwMA#u{86g)F^7{7VA4+75gZ4dx~h9+By3@7ZL={=$c(XF5)NKA@j_kBC${*%PVzW~uLz`J%E z5eslFfW^^$o!BVwrB1a~ie(k^Q=?FN1TYC57vBbuV7LSW4PXu}288scc zoS~Y$8F)RFYs^PU!rdN5_5)lhy$3TS%u|^%Cwm;Lcq0J|d|2M- zm(KJ#OivFRYU{-@W%AnEQciHt@_N*%gNF(i4i*&Lgn=L-*c628w~yz%pi{``liARo z^D*3+C|O#-ck1YVl}mtmKu(gB`-(^|DgKR34Ff=oQ!MP0=xhlrD$i{S3%v&We4R8I z9z3y(a2SAw!CfIvf?H(vYBnF>_+}ShphUz93O!5~(-0myuXpAu^2HM;j^i8gG9I}b%Qt}87hQ5dIHR7re&x4nX3F^ zyIrZ+ySv~nY}!-gb@YHOFisynQc#;HHNek*c>VyY?CIPNN!^IVAKkt25{PpeC- zW0iRmiEZyD{AA@E9hFRSGBf=#*@T^IGI9=lp92EArl)zqOO51YeK@O!yuv~ghKxf( z@XjQyR#(~VC?}Tc_W(cy=`ct}3bjE)gkL@|>nSPYzshXN^5I;zAUksULRX`+Klp5K zNoP(jfw#vp3x_un3)+c%>_j=FlZ_v}kFu=FUz#6`U_Tyou z@wh`x8^5-{El|=k8==2jq!oLgonkap{->4^p(!V1$aVr3Ljt%AS%E&q^OqU zp6_9ff6N0rz5lCp81>l)IhyBdebDw1?F#WX&Em4Mpdf^XAD}pnjxvQ3#U+s)&3vs< zbQwB@U=0&HR^_lc^OscK;59cLK7fnp*&%(%O!;1@Jikl=2Aix8>poICXGl~a9!=_~5itwg+cHc|SmudbnLDzaUiRZPi6rv1n4DTr z@XfKR)9N-%S5(e9`~Hm)i^0TSn@N4A36yMh3K%$Lea~S4;Ai|R*0tO9($Qg& z#bkJ3Ec<6Ee*QsnD7=YC`~q&I5Sk}IjrZ7e`ZjQ>ocJZRJ=PRt_b&(nZ9Z5Galj@O zO4=uuJ}+4VF`riTl5%G~?-&wWTzvJC_J48R*tnY7HDO9}<&tjVVU8g93^gL+eN4Iei`zi^(ggYyPVG zN!7(sWZ##z2~q?Lu0?6!!%+Blm1ltb$EMON4(o=ukO1bi$(z=BV5=kn;Q;DD6J4nS zZtdJp-TZ$0&yHTeNCWB;(F(rX?!UEoDXD7UFv)}-5B2qNQqZ<^$2dKS!W(I5P~yKw zTN_*P{rCEn@=~w5Gr*b&(Xeh<1Ja4-gcxVx+Ui9LxXz#mVwMzK$j+57QO@ak)^E?M zR3_JDR(iL_Q0gz?r(>0&iOC+|yg;;}oJSnimv>gT8`}dCkOyi+8BMU0vPu^z>igl%kn* zo|&2XmCjN^@pKK;2I-lZ!l$BvGb=BrRrBS3UBK7fEd%2FN(VPr*XF*y@wECpo}Kp} zmCJLu!8ogZj9Od!(B3RsHvf;V%l0u|CB*_e@2#OfM+-z0L}r0ZKXV z*49ooHf{8>CX#L%5vlI0u^fP3`3rVz-)0a`PEK|zV8iWPd_mRn{#F-Xn(%X{qTkQu z#62ze?(ZR)hSwxshOn2E`+Hpggd8Zgtk-&-P3_X{lQ8`SA>PG^_9a9FP{?}T*)&y{ z%~K~{_Aqku@o9%a$K?a?{pt*B4wqI&@{?Dmc8|XXP0JV*zU~r6@fK};ec&TpIv`E* zsrN7{A9RGdHpQBgyjN0`|NE(>E~1jK!54ae9HE30Bws9 zWRXzQ)h``>TDw`Ay0#e7Tq>^IxWsAT$&*(^!MyD9fjLJLGLube;L{EIusztnzOfhU z1_d@7qfA*C6yLelNOd*`@eQ)%nP?o^@wZaicy8 zGpCw`yuad0vh2j_4>frN^o9!&$`wvOOD-SW)T{eW_i6oZhEJH+x6evrI*zjJ2h%$%@mlIGlXboP5%f%T=(i8zewfhB*I zeV`=sJ$KR;G0E2huf@GYu=1F22sI8n7$P@PsacKZ!x?J^*)_Uz_gGJ%4#s?odd4I} zEWoj3G?;zEuiL_q;fb_t*jhj80@U01ijw$IklIFRk3kq%^vpVA246bR_Nd=k!CuFg z>c=u*gj{fjJt8V}WNLpXKXrhPYX?FKjT>D}_k0b(x`d{XE3_IB_r?Dm1;uoiqu4xp zPhCp%iW@QlF-JW*-=E(n@i;aWr`^$hRj%;IO7yq6uHIdLO(|59a#^br*$^HnC~;(i zN<~uMLBDWUbKM4zhFFHV(b>MJ$Z?0yZ)`4&=G-DM;hbPv?4H65r*!z;{p@)&p!lNB zdbBoHEQTeyJR_e*6F&|AnQWt}+g>SO-Wn}zxAQ9F3>U1w23SHR!41jGDGGgmgw|7~ z=xUiG6$~@;2JkrM+GwY8R|Mrxcg&);o9AwX%NM{k7c9B=vorif8^#{x!Rzlw>SOy$ z$u!zKP2ZUS(jp2r6QYbYb}ytwxa9l7MCe;B9V8#KSwh%O&^8ke_CvKFkotZOv? zUm>=x=9s(p#5Xo}q~7a!LsP}o@@h0Sf(85K3sBSDxp~&p8Hb2#xZPiAb*7L3HhpYQvzs4+lA6(+VbzLz=ItwaBDz+Kp zec37gq)%%YjoTMBttsL9_;$TR<#Z8vSJl>z_Y*lgxH&s)j&~0z@^$}%_W)(fVDq;Z zRu|J6VmK5k$u~KC;?aKkgQrht>)I)5Z&YmTC-0U1C}D=_`yNEK;7?$1_1T(9Q#xOX zWjkrC00jBptLn8@$8Mt?sM}NzBRRk-n7deQNZebV;Yp}`b**rAp{)@XOSoHLy^B{F zgcX1ObQ=*Q=P1jEtA)1nfOLVhfs2Se+N~CF^T~{-Y&TKOK?k`!U%m0S-FrwB9~$j& ze}{6jXd3LWuoxH?f(Ie42Cs&PmDH(_P*-#Hc&~OVjkc>ehakd~$Qx)rx0pLXsUS@C z$ZEvm+d-7d^JNaml{IwFM8A8({!-iM<#X#MV7bQ*_* zb*myQcQRy{$>SKFDZUaD@4B>_FR@1jYYxMW4_gXPKV{kf+p(2iTCX;C)s+&XW8aoHC5 z=RuTa*ye>td9|2cI{yiAO!O>@!^t=ls0UH)2~jH8{&H){mz{cg`ZBLA8-JL#am{av zM9jt2`>m!gK)c}kX@C>yc!KG4&SLTX!Gc4ZrmY3ap%jOa0^6vJr3Y(DScT=Mo1-(` zQQ2CJ&DXq7Pks~Rj_ekdstw}N5$x)<7E!WQ)ODRLC6M-oD9#1 zo|S{_|dl zG4rlHSokFP^>||;EFd%*EcMkalqTc%X({sAr7uSIk|!d@DqE84&#X^07|A^nmbvj&oGvx>k8I$tV9`~QeMkmlG-A?tJ;pEakq$!i2?QB zQ5cY(k;Tjb4ipnveJ46r+IX3Yz8_hHiia+)pt0Iw^JHN-0_-ow_|VBU+De`BVxRcxd1{PE0Zsu&EyS1at2js z36^xL)u%gFPSGBg61gu}O}MqK(H^Y`G@|aqN81^w12GF7pNF^xJCXfJ`T+sil{Zv!+93zD7)B%4|Lt zfi2YIqj1XqI$)HV+YvhUSjvI#)ux(-8K{Dt{(>cqs=}QA3DHx$>Gp+|;KpFd5-E$j zYV=wE)k6q~swQ6csKEAeh5O_SDk6Yy;rn*ycCtogHBpsvjNzcD2xC!HcNMpUmM?9U zw2EB1e$(~n-A{-aU39 zRWUV;VGe>JrX;JAB2neWT3?3Dx_P*G#`FBDnrQQ;d1AtaY}n?i$xJKye3a~fxy|oS zLyiy8kvhRQY=}Lu_h?qDs@VG)DFP^nZS$ok|>C074YJJyo{M1+VZtCI3 Ni{i6IylL;T{{zK3R#E@} literal 0 HcmV?d00001 diff --git a/common/tier4_simulated_clock_rviz_plugin/images/use_clock_plugin.png b/common/tier4_simulated_clock_rviz_plugin/images/use_clock_plugin.png new file mode 100644 index 0000000000000000000000000000000000000000..39c3669c2ea316827912ee5fd865f39b6e87b2d5 GIT binary patch literal 8608 zcmaKyWl$YKn63wR34vfCIDudRf&_OBZb5>(>mj&=AP0AMKLocNJh;2NyXWAxXQ!soxLl|r!ph>WOe~QI>&j<-&Il+U z7C*FWrxT=0h&xc6D38}iYUq^KtJzwY%|xgn5@=~SQpONa;8vgb_)_4q_~Uh=o_V)< zwFK@$n{+eZU-vtYlA$S6Fd+uwik^ZK(o;oP#ZW2LP?j4($iSNxBFaFeZ-6J6Nwy3?h50&QZV?MKO1qGb{##l>-A zD2$APEx99z@PFDAvy|}n{z78ob7}!m)H)OP67e)lBtS5WHEBS$+h|+#ZNy8ZufVx` z5~}{Z+DeXc{$`x?n?sk-Hj_tTDQxo z4dZuJqN+_@=`m?J4)42(0eZuW`3l9AKKy?CK;_*SI1Ch$<)xba{pd@MM)v)|r}yp~ zPqecF4L&nEQF;i%+XBs+dvnYFa%o5EBIqL$M{h=NoJ2k8qC2G8G9J!PoUO_)_{u4<&1qkF65JcVGQaIhzdV&J#()~fBKBbBH8sE1c2z{D)<1o0 z{Y=(qSs!*MD1thTP-ngk0Ql-x*Ya9M>_DYJlcUfchWIxeGtOWe(;&0fe)Ae4L|kG2 z)=WK=qR8izd@yXz{&fDqzS9VWg_gOGfRqijFlp7uO>CH>7KHw%OrOOOzLC#ipOZ6A zQ1Er#v*V~=G<2kp3BtsxX*A%+4J-K61d%`RJ`MT#j+ z)EmbrC_`s-v7>K!Grl4MJ(;h~qg**D^I2KQd0{$qrUoXK_Ei4$fRe{)$7*wowG>|( z9w6+%%mf84z*5<=e zHoNDYX%vjz7R@TI${~TJMe@e9A^=6}AcahbCLxxc&6LmP=|O}mwv>;nsMZ@r!&!*dj}O78R9VD4+hq4_UCou?dPxQ(WJ-#&L=%i;z!h8yq6ow-{1$)P8HJVx?X zmg=NXs>6q#%Y9oo`~Y*-2;TeD5>Gd{=)%X^=QlzQw%G_$skhEs<>ZS$eK#I<9{%VX zE~QE<8jI#oq@3Xc^z)^1!L3iTd+8r)JkkSX3uvFHhCM2QgS zF1!WZo})}I!rgw5|HNj~&4gficRog)qz_9rNckR6KRUU{aEc>Z{8S>N1OU;rvxF||?{;PRs{0Vo zu`&S<Wtr|CpT zZv~l$dnzu#WUYvkro#?oTiJ*K5+Ez&*}tlu*uY-h>1F2m$X1e5T9GB~vLuv*1MurN z34jM=z?q2j=$o?^yuq`P^v|Axgd+kU z_YUT#{eZQ(`M-ng;_biFyd@aQGmb`Dq&UfyzL1qk`9jWVn5wnId{lT9~rjnS5h<~Wsi8Pi6 zJp`XNNyy#3p#Szd z71S}9uU!h?`7Q7p!K=%Bv}Wns6w5DOZtdfsB9K>JbasrK7|xXytNr z-?OsB)>T;#B1N};k5?9l16~G3yqlH=__)~Q(ht3y-Bdvb`cw?7@aL`~XB1Bb=?ejT z_kNrjX@COL6Z7PJCyCmZ{}sc_;Dvq_)!>J(DYMqRedHUZ0VurPclBcOYOn_LYpAcs zGw@#_0q7~=@IcVF(VW*i3T!PdYrF4b!3m`?_@Q5Cju$HZKFE8=Yds!kgHydFQ8_<( zJgKk2P6tocSp+>Z@!lwRP@T{JJ-S}{{CGc>gaEjb=I9$$f0|@foOsz$%U1>rK8ADz zs340}qDrdl3@&is12l@PM?83%!u$JGJQ~aIM`3K#Q$<*0e?0AP+I4!lC06RWHi$^) z)cJa6-N<>jX8MO0?T8(j-tsPT!1-A&n)`L1WLU@YVqrbhK8N2{vj1_Uqa?D#jNZv7NzaOuMtI5-s`&;SCn&+oA6$( z0(h;G$TUAzXMGbH2}2^OcYR&97Aq50;VRSVekE)9gob`}AGP1fJ4-%o`jvVII{py& z^E%`NMZqqVYumBxxasTeI3c|h(N+Gb^Qd+aC$8wF=%WLEyTdJf|McR;eH7rgebTYN zng-8_pja1j*zlZ_#PH2pR@%#Mab{|y$7bH}148lbUkn;@GY34;-E{cPB)}4^b^K%L|ERa0f}?<6cGpJZlWPGw5)j<4_5?C* z|5x9KJN|dfh;_lvFLE%SAXoV7cW%m@qz1wk1M#glX7 zLq>Ot3W~zSsg|S0YinJaK%f~74H&wbZ*>h4Ly6_GZu&k!M1jPW6G9zig8YXH{xp!) z75r)J%Ywd|%0x#b3z>=Su%f(TQ4&|~oB2VkDaa-N?-#{6Q}{tLtyj2MqLW3q_%q}R zP4T-*lv19|moM;uq9Tq5(u8PSEo4GQz|119lf{A)?{!>&W;v!FwECe^>N2-Pn?T4O zKc^=#Ik}dNo!x0u5||?*hO+bgj*(JiR(V}-bqQ4lclgTR;PmE}iQJCs`9ynqc>Kb| zULhi$@5?JnEV9(8TS)Lgf9Bj5n%ZC>Ki;N|@EvO4mtTSK`gF!^jYdC_hZAvwmXeh> zcYl38&qnPme49e(X0RVW-r5<2MJj089i=FJ2Y(vq<>+!%>urhd;r@-m$^JBDlY{=K zK3s#+_vx^ap*2r3f`rfdZ-NaT;P*jcj{GBNt~g3cK^t_WY`L8qe>Nbi-}WQwMUkql zCvY0?`aExBT%!v6*bnZ_ucF11N~d4UUTVI;j>HbPv-yel_4{8bDpfomc(pH0Y95lK zz>zEjVF`oQG-0beN00uk>0cB0m$ z4hz;@H8PrnGhvrOZG7c|=ZE%f-*{>mEuu59o5^Ceswn;M<@k7thZtD{z{X_D(HpSz>jH04m|Hu39cXu#wYUL7q zn;r zp=Q{#aN(nHjE?~*{!fqhr29Ea2hI``AgVAQj)6r!sdsnEs*^XupNNOwGEDp7Z_hwXRtlJ|u7Q@xOLcjbdos04CpRG^_b{B9RmQ zv_!828p>{}#9ecp8O(+1EZ?YuxD)J)CP-JaqxR zTJeM(B~0zdjjs6ma9yp}5F*XIrp^;Owv!Iw@L9n1VV4(G^7vL*rX{cvBerNqHti%m ztD?>klvCrzy~AA*CSzdw7H7qUQj_JiOqpaEIQ`30<-Xbl^$h!STcd(DIe+pi&6d^S zY6WIkn;?(bB9FEF$`5sqln)_ov`1t&nXll+3~!_~{+1U?58FXp?24>(N@x`MiSS)p z5QP)tGOe1nu9HJ;SJwIXtSuY0AqO!7eIimZ-TS*NW-jO2eaHsC?<9JLHre~qRYl;6 z$nRL3i&(LQ307{_aSq#GD+^o-(d1QYIvsR5vKhka0 zqrI4h>i_h_d7keK?-L{-61yQ6+_$B7uUuw@ea(u4%UFczxEKJMSvk^+9In%>ih}5S zU%g#}j?XCC=5%m`LbYbYu)sq%VD#=yn)3_tD4&w+Pi8y4G1s6c7mGUO6GaRuemdh-3+QF*C!3OpbgKmpU#QQM*xkY^L2gs-RkU{4Z=9Z zrPQ~AoxWqNC`a`tnHJr^__k}UkN*0C^MO)}=OXq*upiG3 z3yc6rpoyG0Gg$QaejKVMt$O->-Ptyh8J>D++uPkV>z$8-NqsF?&i?`qT)$b}teq0$ ziG8{GZo3Je-opv2^zB9K#HWfgGB6MNM(^Jl`o2uv&Zoy#>^2#|Z@&IIxqg~l8DpE9 zO6?ID5ss$dQAW`DKK3jkWe0YuY!mhcsFADd4w0{Eqr?$L1p~BML^(OYKnvN zt8IyT%i6wkAR(2Q?AZbj3=dlE?(IO)z?7k{UfY;qwZEKeadr2s-ACme^5r-ePl#1X9)4_6N$efXo!H4 z)6anGr-@`G^5qm1BiFPBw^78NEJh)LG+JXo+U^uxaMJ9rrt%2C)(`$dwR;b(?AEnr2U6Y;h&WDltunJQ^ zSmxqFoP;*9JZ8tVf+;O)UMJi2fU0pYb8Hjv%d`r7lh3fcH`UGYY|kPkGjYz=gJn&`Fe zgpG#&r`ws~(v-Pf8qnh`)<+vO>aCmf5z9#M7%OA=*>MY5lOy1VCvfBb?3R&n$7kgbDnoF4agif1x{CvQ$8XcU zd#y1<+#)BL0(<1QN+yO|V>cfjQ@8HDON{x29Vbft?ZZ3ir_-tk!X{>cg8?`{Y*mf$ zGo8l2k`=CkJs&2`Fc(8fXUxhTjUJ-V-~2G-wdh_cSTWw=Ez{!=`Z>x0ayl|B7nE}M z?up_dVRJpIiV856oMfCf;vJrc-4)oA&Z zo}7$NKvs5ZY8rG|+#NT{yyVn+-Dnv%a(v^pZcnFsX!lOR1~35KSp-}T6sT4-$z$N$ zC$F6TC^%m|Z4>NjQsip|88ZYeZ>dkt{>tR#*ZosV(r9H(?oFY_*AS#rt@l{_w+q8? zw(r&v2nQL@1V@y8cC;P?${=k27u066lAbR1XQT9@NX9Qoxf`K84Yv0zHL+@jHqrXk ztNRA_3$!W7xNh%#grBeX3yQJT?C~o~aDj5&mYKmtIcPo`XP%zMqMsE;j-j^teuQ*Q z=;tY*_86X7QwmGrvclSmcR_iX)4kM+J5vhPQu;R8ek-p9$$CL!`h4+JhtO6#>mzX; z2ME6fe?R}iSn&I{ED*BvyJ|f0DzOYrNB#PgRH7K^0tTahmTu_bU(jhTw3@cMj?j1v zPelZYSWol?doYgEl!5iB0$w1qq_HayZDFet1J^3@OjckbIVVR1RPUz;K2QgN>T~?z zT54a__37DVYn1Vp?4HAr;QbTSIi8v$&E(H^B0{U!TGZZub~{dujZIC>RHzWX>>V2$ zn};&~zhZZcbU8}N=?}&E`GKvdR`@+VJ&}+j*B_&NwY0@+* z5QzwM4*Z;*;ultqDop!dAcyCstG{|3?jEqlR% zaoV<%yU~RA1MI%AV{-QNV5)nrD^SlLcfwYkEj8I?b!4Vz09>IKMiM1VAwAsZ0CIwC z65{r4U%VjlD<8K+?2jMUpgepWLt_1bI|3s2sIu=eG~FFqarzCl4`d}~-}EN5Cm4|Bt8xh#}O!%5LktUa?^- zxda#fNZ^HBC4f+K?t&5UGbR9UWzIC!=S4}94i<};N*z~OF&C-2ar#zss(cM2BRt@{ zhsPKrZtn1ZzJ7lN*)Lzv^`LkF6}O#N15G!a>|oG~6ERK4#%5`3VzSi}0aUWFJDECE z_Q-&VA*v+Vd=R7f0AzPS&28?kv5;SkG0)l5;f#-l0aU7B8FErA$PIbG5G^BR7K3Y_ zoZKXf!$+ZKPQ7bu8k0ADeri1TjT3su;n7tb`WLjyQt0_%BCfLaj28==GL#TRh94>T-6N1dRr!IJ5EBiu)>B12|0I~X1N)iA zaNOiK1jf>W#TAqyD0o;07ghKgJPT&F3bw$%bSSUz!)5KMh8knl?=SjUa;!)|ojTSS z+4PR2>)q53wZ5(P@m*Ye2{z2KGU4+ZSRpl9Q~@dc$vn=tdeAS4i|aJE=ga~Cyvs&S zW0Ad`_stob@y>B_BXgJF5IU^g)X|Xl&bySi;GK5XpVJ1DYbj($ITpH!(&!*7v;l31 zTFE;tHJ>H_GX!o7zi3siP0`NYT6+capS+SxEIQ35=K<})+}zyS(?3vfu8x*TTbQ*! z%N(xLtB!jiGh+@KI!iqg@b1>!oU78^Tpe0;9etu}zZOk2>0WV<{1Q!jGDosXy`hwh zMSUuI_VDQISyqL3-nly?LAQT63wB)# zEzb0yh#UCI{Kz?93A==1z$4@}*y}f2#5lzYem~1@jus@b1%``J(5OeDo{b^G=l1PsFtBS!ygO6w0huOYd=ig@W@gK1t22_yD(#@>5L|9p!gWOOMaV zW9wtCme5j4bvXi({dJmJUmus4#u2)UnFbT1FChFu8k|d?Egehc@=SbiwUXnOf6++& z3pwcR#XxwI1N*|W_-UoLbGoZ%eF?FHtLwK~`hRUngarTw_g7?LZ;+skjgZe9>Tcy8hfDDeQKT2g`5G3jcY6yGL<919gxccaf$p{jd-Hy{ zK5k7Ga~IIzl2_qJrOCKKYktp?0@;KEWyb$sU@>)h${+klD_zW$5HU0)?dafQ(#GG~ zf%v?IERZdf`rNm$P$Oy9m+_{4Fms&uFk>OF&^s70QW7Nh46@1OENVFg_gOw2zPDX` z^U)P2PGax#7j!H#wDwwV&wA(e=A!_k#I$E^{np4f%RLXmS~@4_!(9ZaU3vMNH*abo z&CSgyIOKP*!(OB5TW{zBY6#wH6xzaLRQMn*YK_R#Br_WNeXHJYSLbgv9mS`1qtGO+A&A9EjM|f|Q_dcjZw@x^KNXoz>t5BUGbm2*ou311$J+&#LAf)4R37Rh z3P#(;z}id1faJee01OO!)`|=AJy%rDqP7xytV#@*1PwTd(<;4{EY=v|@UEFfsjso|^iH zo^a1}6z8C#S2MTjz+KXmSp7LQKr7D;o?ATRVI{Qp&(j1)Ev!FJTFd z*#E + + + tier4_simulated_clock_rviz_plugin + 0.0.1 + Rviz plugin to publish and control the /clock topic + Maxime CLEMENT + Apache License 2.0 + + ament_cmake_auto + libqt5-core + libqt5-gui + libqt5-widgets + qtbase5-dev + rclcpp + rosgraph_msgs + rviz_common + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + + + diff --git a/common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml b/common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml new file mode 100644 index 0000000000000..00caf2e5d49e0 --- /dev/null +++ b/common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml @@ -0,0 +1,9 @@ + + + + Panel that publishes a simulated clock to the /clock topic and provides an interface to pause the clock and modify its speed. + + + diff --git a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp new file mode 100644 index 0000000000000..ad698d925fdff --- /dev/null +++ b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp @@ -0,0 +1,153 @@ +// +// Copyright 2022 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 "simulated_clock_panel.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace rviz_plugins +{ +SimulatedClockPanel::SimulatedClockPanel(QWidget * parent) : rviz_common::Panel(parent) +{ + pause_button_ = new QPushButton("Pause"); + pause_button_->setToolTip("Freeze ROS time."); + pause_button_->setCheckable(true); + + publishing_rate_input_ = new QSpinBox(); + publishing_rate_input_->setRange(1, 1000); + publishing_rate_input_->setSingleStep(1); + publishing_rate_input_->setValue(100); + publishing_rate_input_->setSuffix("Hz"); + + clock_speed_input_ = new QDoubleSpinBox(); + clock_speed_input_->setRange(0.0, 10.0); + clock_speed_input_->setSingleStep(0.1); + clock_speed_input_->setValue(1.0); + clock_speed_input_->setSuffix(" X real time"); + + step_button_ = new QPushButton("Step"); + step_button_->setToolTip("Pause and steps the simulation clock"); + step_time_input_ = new QSpinBox(); + step_time_input_->setRange(1, 999); + step_time_input_->setValue(1); + step_unit_combo_ = new QComboBox(); + step_unit_combo_->addItems({"s", "ms", "µs", "ns"}); + + auto * layout = new QGridLayout(this); + auto * step_layout = new QHBoxLayout(); + auto * clock_layout = new QHBoxLayout(); + auto * clock_box = new QWidget(); + auto * step_box = new QWidget(); + clock_box->setLayout(clock_layout); + step_box->setLayout(step_layout); + layout->addWidget(pause_button_, 0, 0); + layout->addWidget(step_button_, 1, 0); + clock_layout->addWidget(new QLabel("Speed:")); + clock_layout->addWidget(clock_speed_input_); + clock_layout->addWidget(new QLabel("Rate:")); + clock_layout->addWidget(publishing_rate_input_); + step_layout->addWidget(step_time_input_); + step_layout->addWidget(step_unit_combo_); + layout->addWidget(clock_box, 0, 1, 1, 2); + layout->addWidget(step_box, 1, 1, 1, 2); + layout->setContentsMargins(0, 0, 20, 0); + prev_published_time_ = std::chrono::system_clock::now(); + + connect(publishing_rate_input_, SIGNAL(valueChanged(int)), this, SLOT(onRateChanged(int))); + connect(step_button_, SIGNAL(clicked()), this, SLOT(onStepClicked())); +} + +void SimulatedClockPanel::onInitialize() +{ + raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + + clock_pub_ = raw_node_->create_publisher("/clock", rclcpp::QoS(1)); + createWallTimer(); +} + +void SimulatedClockPanel::onRateChanged(int new_rate) +{ + (void)new_rate; + pub_timer_->cancel(); + createWallTimer(); +} + +void SimulatedClockPanel::onStepClicked() +{ + using std::chrono::duration_cast, std::chrono::seconds, std::chrono::milliseconds, + std::chrono::microseconds, std::chrono::nanoseconds; + pause_button_->setChecked(true); + const auto step_time = step_time_input_->value(); + const auto unit = step_unit_combo_->currentText(); + nanoseconds step_duration_ns{}; + if (unit == "s") { + step_duration_ns += duration_cast(seconds(step_time)); + } else if (unit == "ms") { + step_duration_ns += duration_cast(milliseconds(step_time)); + } else if (unit == "µs") { + step_duration_ns += duration_cast(microseconds(step_time)); + } else if (unit == "ns") { + step_duration_ns += duration_cast(nanoseconds(step_time)); + } + addTimeToClock(step_duration_ns); +} + +void SimulatedClockPanel::createWallTimer() +{ + // convert rate from Hz to milliseconds + const auto period = + std::chrono::milliseconds(static_cast(1e3 / publishing_rate_input_->value())); + pub_timer_ = raw_node_->create_wall_timer(period, [&]() { onTimer(); }); +} + +void SimulatedClockPanel::onTimer() +{ + if (!pause_button_->isChecked()) { + const auto duration_since_prev_clock = std::chrono::system_clock::now() - prev_published_time_; + const auto speed_adjusted_duration = duration_since_prev_clock * clock_speed_input_->value(); + addTimeToClock(std::chrono::duration_cast(speed_adjusted_duration)); + } + clock_pub_->publish(clock_msg_); + prev_published_time_ = std::chrono::system_clock::now(); +} + +void SimulatedClockPanel::addTimeToClock(std::chrono::nanoseconds time_to_add_ns) +{ + constexpr auto one_sec = std::chrono::seconds(1); + constexpr auto one_sec_ns = std::chrono::nanoseconds(one_sec); + while (time_to_add_ns >= one_sec) { + time_to_add_ns -= one_sec; + clock_msg_.clock.sec += 1; + } + clock_msg_.clock.nanosec += time_to_add_ns.count(); + if (clock_msg_.clock.nanosec >= one_sec_ns.count()) { + clock_msg_.clock.sec += 1; + clock_msg_.clock.nanosec = clock_msg_.clock.nanosec - one_sec_ns.count(); + } +} + +} // namespace rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(rviz_plugins::SimulatedClockPanel, rviz_common::Panel) 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 new file mode 100644 index 0000000000000..137aafb30c88a --- /dev/null +++ b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp @@ -0,0 +1,76 @@ +// +// Copyright 2022 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. +// + +#ifndef AUTOWARE_STATE_PANEL_HPP_ +#define AUTOWARE_STATE_PANEL_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +namespace rviz_plugins +{ +class SimulatedClockPanel : public rviz_common::Panel +{ + Q_OBJECT + +public: + explicit SimulatedClockPanel(QWidget * parent = nullptr); + void onInitialize() override; + +protected Q_SLOTS: + /// @brief callback for when the publishing rate is changed + void onRateChanged(int new_rate); + /// @brief callback for when the step button is clicked + void onStepClicked(); + +protected: + /// @brief creates ROS wall timer to periodically call onTimer() + void createWallTimer(); + void onTimer(); + /// @brief add some time to the clock + /// @input ns time to add in nanoseconds + void addTimeToClock(std::chrono::nanoseconds ns); + + // ROS + rclcpp::Node::SharedPtr raw_node_; + rclcpp::Publisher::SharedPtr clock_pub_; + rclcpp::TimerBase::SharedPtr pub_timer_; + + // GUI + QPushButton * pause_button_; + QPushButton * step_button_; + QSpinBox * publishing_rate_input_; + QDoubleSpinBox * clock_speed_input_; + QSpinBox * step_time_input_; + QComboBox * step_unit_combo_; + + // Clocks + std::chrono::time_point prev_published_time_; + rosgraph_msgs::msg::Clock clock_msg_; +}; + +} // namespace rviz_plugins + +#endif // AUTOWARE_STATE_PANEL_HPP_ From 2af2183147226d76939c4941d06ad94380c3008e Mon Sep 17 00:00:00 2001 From: k-obitsu <56008637+k-obitsu@users.noreply.github.com> Date: Mon, 14 Feb 2022 10:11:56 +0900 Subject: [PATCH 08/14] fix(turn_signal_decider): fix getintersectionturnsignal of turn_signal_decider (#321) * fix getIntersectionTurnSignal of turn_signal_decider Signed-off-by: k-obitsu * fix(turn_signal_decider):fix getIntersectionTurnSignal of turn_signal_decider Signed-off-by: k-obitsu --- planning/behavior_path_planner/src/turn_signal_decider.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/turn_signal_decider.cpp b/planning/behavior_path_planner/src/turn_signal_decider.cpp index 9fca606455c2d..bc1b41a7e1abe 100644 --- a/planning/behavior_path_planner/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/src/turn_signal_decider.cpp @@ -87,9 +87,7 @@ std::pair TurnSignalDecider::getIntersectionTurnS if ( lane.attributeOr("turn_signal_distance", std::numeric_limits::max()) < distance_from_vehicle_front) { - if (1 < path_point.lane_ids.size() && lane.id() == path_point.lane_ids.back()) { - continue; - } + continue; } if (lane.attributeOr("turn_direction", std::string("none")) == "left") { turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; From fe9d05b4709b5783c1528f9028f1211b6db7db4d Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 14 Feb 2022 14:15:49 +0900 Subject: [PATCH 09/14] ci: add clang-tidy-pr-comments.yaml (#375) * ci: add clang-tidy-pr-comments.yaml Signed-off-by: Kenji Miyake * use gh run Signed-off-by: Kenji Miyake * copy fixes.yaml Signed-off-by: Kenji Miyake * replace paths Signed-off-by: Kenji Miyake --- .github/workflows/clang-tidy-pr-comments.yaml | 52 +++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 .github/workflows/clang-tidy-pr-comments.yaml diff --git a/.github/workflows/clang-tidy-pr-comments.yaml b/.github/workflows/clang-tidy-pr-comments.yaml new file mode 100644 index 0000000000000..ea035a25f3000 --- /dev/null +++ b/.github/workflows/clang-tidy-pr-comments.yaml @@ -0,0 +1,52 @@ +name: clang-tidy-pr-comments + +on: + workflow_run: + workflows: + - build-and-test-differential + types: + - completed + +jobs: + clang-tidy-pr-comments: + if: ${{ github.event.workflow_run.event == 'pull_request' && github.event.workflow_run.conclusion == 'success' }} + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v2 + + - name: Download analysis results + run: | + gh run download ${{ github.event.workflow_run.id }} -D /tmp + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + + - name: Set variables + id: set-variables + run: | + echo ::set-output name=pr-id::"$(cat /tmp/clang-tidy-result/pr-id.txt)" + echo ::set-output name=pr-head-repo::"$(cat /tmp/clang-tidy-result/pr-head-repo.txt)" + echo ::set-output name=pr-head-ref::"$(cat /tmp/clang-tidy-result/pr-head-ref.txt)" + + - name: Check out PR head + uses: actions/checkout@v2 + with: + repository: ${{ steps.set-variables.outputs.pr-head-repo }} + ref: ${{ steps.set-variables.outputs.pr-head-ref }} + persist-credentials: false + + - name: Replace paths in fixes.yaml + run: | + sed -i -e "s|/__w/|/home/runner/work/|g" /tmp/clang-tidy-result/fixes.yaml + cat /tmp/clang-tidy-result/fixes.yaml + + - name: Copy fixes.yaml to access from Docker Container Action + run: | + cp /tmp/clang-tidy-result/fixes.yaml fixes.yaml + + - name: Run clang-tidy-pr-comments action + uses: platisd/clang-tidy-pr-comments@1.1.6 + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + clang_tidy_fixes: fixes.yaml + pull_request_id: ${{ steps.set-variables.outputs.pr-id }} From 9fd7a59f7f97510310700c8677da3e59a321ae78 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Mon, 14 Feb 2022 18:49:37 +0900 Subject: [PATCH 10/14] ci: update build and test workflow (#358) Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --- ...ild-and-test-differential-self-hosted.yaml | 12 ++++++++-- .../build-and-test-differential.yaml | 22 +++++++++---------- .../workflows/build-and-test-self-hosted.yaml | 12 ++++++++-- .github/workflows/build-and-test.yaml | 22 +++++++++---------- .github/workflows/check-build-depends.yaml | 11 ++++++++-- 5 files changed, 51 insertions(+), 28 deletions(-) diff --git a/.github/workflows/build-and-test-differential-self-hosted.yaml b/.github/workflows/build-and-test-differential-self-hosted.yaml index 8d6abbaf5950a..6c2dcf960c10e 100644 --- a/.github/workflows/build-and-test-differential-self-hosted.yaml +++ b/.github/workflows/build-and-test-differential-self-hosted.yaml @@ -37,9 +37,17 @@ jobs: id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal - - name: Build and test + - name: Build if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos + + - name: Test + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal with: rosdistro: galactic target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 1ba8540a1860d..1eddcc9b06514 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -28,28 +28,28 @@ jobs: id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@tier4/proposal - - name: Build and test + - name: Build if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal with: rosdistro: galactic target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} build-depends-repos: build_depends.repos - - name: Check the existence of coverage files - id: check-file-existence - uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + - name: Test + id: test + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal with: - files: | - lcov/total_coverage.info - coveragepy/.coverage - condition: or + rosdistro: galactic + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos - name: Upload coverage to CodeCov - if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + if: ${{ steps.test.outputs.coverage-report-files != '' }} uses: codecov/codecov-action@v2 with: - files: lcov/total_coverage.info,coveragepy/.coverage + files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false verbose: true diff --git a/.github/workflows/build-and-test-self-hosted.yaml b/.github/workflows/build-and-test-self-hosted.yaml index 95ee077432cef..1f8bc542855d6 100644 --- a/.github/workflows/build-and-test-self-hosted.yaml +++ b/.github/workflows/build-and-test-self-hosted.yaml @@ -25,9 +25,17 @@ jobs: id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - - name: Build and test + - name: Build if: ${{ steps.get-self-packages.outputs.self-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal + with: + rosdistro: galactic + target-packages: ${{ steps.get-self-packages.outputs.self-packages }} + build-depends-repos: build_depends.repos + + - name: Test + if: ${{ steps.get-self-packages.outputs.self-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal with: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 338ead5c47d5b..880f47192b558 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -27,27 +27,27 @@ jobs: id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - - name: Build and test + - name: Build if: ${{ steps.get-self-packages.outputs.self-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal with: rosdistro: galactic target-packages: ${{ steps.get-self-packages.outputs.self-packages }} build-depends-repos: build_depends.repos - - name: Check the existence of coverage files - id: check-file-existence - uses: autowarefoundation/autoware-github-actions/check-file-existence@tier4/proposal + - name: Test + if: ${{ steps.get-self-packages.outputs.self-packages != '' }} + id: test + uses: autowarefoundation/autoware-github-actions/colcon-test@tier4/proposal with: - files: | - lcov/total_coverage.info - coveragepy/.coverage - condition: or + rosdistro: galactic + target-packages: ${{ steps.get-self-packages.outputs.self-packages }} + build-depends-repos: build_depends.repos - name: Upload coverage to CodeCov - if: ${{ steps.check-file-existence.outputs.exists == 'true' }} + if: ${{ steps.test.outputs.coverage-report-files != '' }} uses: codecov/codecov-action@v2 with: - files: lcov/total_coverage.info,coveragepy/.coverage + files: ${{ steps.test.outputs.coverage-report-files }} fail_ci_if_error: false verbose: true diff --git a/.github/workflows/check-build-depends.yaml b/.github/workflows/check-build-depends.yaml index 20848a436a7cd..2100b82172e10 100644 --- a/.github/workflows/check-build-depends.yaml +++ b/.github/workflows/check-build-depends.yaml @@ -28,8 +28,15 @@ jobs: id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@tier4/proposal - - name: Build and test - uses: autowarefoundation/autoware-github-actions/colcon-build-and-test@tier4/proposal + - name: Build + uses: autowarefoundation/autoware-github-actions/colcon-build@tier4/proposal + with: + 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 }} From 45816fca98f54328948eb15e7319f17d1460d02a Mon Sep 17 00:00:00 2001 From: Shinnosuke Hirakawa <8327162+0x126@users.noreply.github.com> Date: Tue, 15 Feb 2022 10:38:18 +0900 Subject: [PATCH 11/14] fix(pointcloud_preprocessor): empty pointcloud bug (#373) Signed-off-by: Shinnosuke Hirakawa --- .../src/concatenate_data/concatenate_data_nodelet.cpp | 5 ++++- .../outlier_filter/dual_return_outlier_filter_nodelet.cpp | 8 +++++--- 2 files changed, 9 insertions(+), 4 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 b59d52010f831..60eacb9b09ba7 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_data_nodelet.cpp @@ -354,7 +354,10 @@ 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 cc442ed081b5d..d506031d12d22 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,12 +87,14 @@ 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); - if (pcl_input->points.empty()) { - return; - } uint32_t vertical_bins = vertical_bins_; uint32_t horizontal_bins = 36; From 823e9e1d94b375b18455112dbac68c0aa73d2348 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Feb 2022 11:00:55 +0900 Subject: [PATCH 12/14] feat(longitudinal controller): add params explanation (#381) * feat(longitudinal controller): add params explanation Signed-off-by: Takayuki Murooka * fix typos Signed-off-by: Takayuki Murooka * update Signed-off-by: Takamasa Horibe * apply format Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe --- .../design/longitudinal_controller-design.md | 97 ++++++++++++++++++- 1 file changed, 94 insertions(+), 3 deletions(-) diff --git a/control/trajectory_follower_nodes/design/longitudinal_controller-design.md b/control/trajectory_follower_nodes/design/longitudinal_controller-design.md index c91a40ad959e3..76d4f19bca2e0 100644 --- a/control/trajectory_follower_nodes/design/longitudinal_controller-design.md +++ b/control/trajectory_follower_nodes/design/longitudinal_controller-design.md @@ -1,5 +1,4 @@ -Longitudinal Controller {#longitudinal-controller-design} -=========== +# Longitudinal Controller {#longitudinal-controller-design} # Purpose / Use cases @@ -142,10 +141,102 @@ Depending on the actuating principle of the vehicle, the mechanism that physical In this controller, the predicted ego-velocity and the target velocity after the delay time are calculated and used for the feedback to address the time delay problem. +## Parameter description + +The default parameters defined in `param/lateral_controller_defaults.yaml` are adjusted to the +AutonomouStuff Lexus RX 450h for under 40 km/h driving. + +| Name | Type | Description | Default value | +| :----------------------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| control_rate | double | control rate [Hz] | 30 | +| delay_compensation_time | double | delay for longitudinal control [s] | 0.17 | +| enable_smooth_stop | bool | flag to enable transition to STOPPING | true | +| enable_overshoot_emergency | bool | flag to enable transition to EMERGENCY when the ego is over the stop line with a certain distance. See `emergency_state_overshoot_stop_dist`. | true | +| enable_slope_compensation | bool | flag to modify output acceleration for slope compensation. The source of the slope angle can be selected from ego-pose or trajectory angle. See `use_trajectory_for_pitch_calculation`. | true | +| enable_brake_keeping_before_stop | bool | flag to keep a certain acceleration during DRIVE state before the ego stops. See [Brake keeping](#brake-keeping). | false | +| max_acc | double | max value of output acceleration [m/s^2] | 3.0 | +| min_acc | double | min value of output acceleration [m/s^2] | -5.0 | +| max_jerk | double | max value of jerk of output acceleration [m/s^3] | 2.0 | +| min_jerk | double | min value of jerk of output acceleration [m/s^3] | -5.0 | +| use_trajectory_for_pitch_calculation | bool | If true, the slope is estimated from trajectory z-level. Otherwise the pitch angle of the ego pose is used. | false | +| lpf_pitch_gain | double | gain of low-pass filter for pitch estimation | 0.95 | +| max_pitch_rad | double | max value of estimated pitch [rad] | 0.1 | +| min_pitch_rad | double | min value of estimated pitch [rad] | -0.1 | + +### State transition + +| Name | Type | Description | Default value | +| :---------------------------------- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| drive_state_stop_dist | double | The state will transit to DRIVE when the distance to the stop point is longer than `drive_state_stop_dist` + `drive_state_offset_stop_dist` [m] | 0.5 | +| drive_state_offset_stop_dist | double | The state will transit to DRIVE when the distance to the stop point is longer than `drive_state_stop_dist` + `drive_state_offset_stop_dist` [m] | 1.0 | +| stopping_state_stop_dist | double | The state will transit to STOPPING when the distance to the stop point is shorter than `stopping_state_stop_dist` [m] | 0.5 | +| stopped_state_entry_vel | double | threshold of the ego velocity in transition to the STOPPED state [m/s] | 0.01 | +| stopped_state_entry_acc | double | threshold of the ego acceleration in transition to the STOPPED state [m/s^2] | 0.1 | +| emergency_state_overshoot_stop_dist | double | If `enable_overshoot_emergency` is true and the ego is `emergency_state_overshoot_stop_dist`-meter ahead of the stop point, the state will transit to EMERGENCY. [m] | 1.5 | +| emergency_state_traj_trans_dev | double | If the ego's position is `emergency_state_traj_tran_dev` meter away from the nearest trajectory point, the state will transit to EMERGENCY. [m] | 3.0 | +| emergency_state_traj_rot_dev | double | If the ego's orientation is `emergency_state_traj_rot_dev` rad away from the nearest trajectory point orientation, the state will transit to EMERGENCY. [rad] | 0.784 | + +### DRIVE Parameter + +| Name | Type | Description | Default value | +| :------------------------------------ | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| kp | double | p gain for longitudinal control | 1.0 | +| ki | double | i gain for longitudinal control | 0.1 | +| kd | double | d gain for longitudinal control | 0.0 | +| max_out | double | max value of PID's output acceleration during DRIVE state [m/s^2] | 1.0 | +| min_out | double | min value of PID's output acceleration during DRIVE state [m/s^2] | -1.0 | +| max_p_effort | double | max value of acceleration with p gain | 1.0 | +| min_p_effort | double | min value of acceleration with p gain | -1.0 | +| max_i_effort | double | max value of acceleration with i gain | 0.3 | +| min_i_effort | double | min value of acceleration with i gain | -0.3 | +| max_d_effort | double | max value of acceleration with d gain | 0.0 | +| min_d_effort | double | min value of acceleration with d gain | 0.0 | +| lpf_vel_error_gain | double | gain of low-pass filter for velocity error | 0.9 | +| current_vel_threshold_pid_integration | double | Velocity error is integrated for I-term only when the absolute value of current velocity is larger than this parameter. [m/s] | 0.5 | +| brake_keeping_acc | double | If `enable_brake_keeping_before_stop` is true, a certain acceleration is kept during DRIVE state before the ego stops [m/s^2] See [Brake keeping](#brake-keeping). | 0.2 | + +### STOPPING Parameter (smooth stop) + +Smooth stop is enabled if `enable_smooth_stop` is true. +In smooth stop, strong acceleration (`strong_acc`) will be output first to decrease the ego velocity. +Then weak acceleration (`weak_acc`) will be output to stop smoothly by decreasing the ego jerk. +If the ego does not stop in a certain time or some-meter over the stop point, weak acceleration to stop right (`weak_stop_acc`) now will be output. +If the ego is still running, strong acceleration (`strong_stop_acc`) to stop right now will be output. + +| Name | Type | Description | Default value | +| :--------------------------- | :----- | :------------------------------------------------------------------------------------------------------------------- | :------------ | +| smooth_stop_max_strong_acc | double | max strong acceleration [m/s^2] | -0.5 | +| smooth_stop_min_strong_acc | double | min strong acceleration [m/s^2] | -0.8 | +| smooth_stop_weak_acc | double | weak acceleration [m/s^2] | -0.3 | +| smooth_stop_weak_stop_acc | double | weak acceleration to stop right now [m/s^2] | -0.8 | +| smooth_stop_strong_stop_acc | double | strong acceleration to be output when the ego is `smooth_stop_strong_stop_dist`-meter over the stop point. [m/s^2] | -3.4 | +| smooth_stop_max_fast_vel | double | max fast vel to judge the ego is running fast [m/s]. If the ego is running fast, strong acceleration will be output. | 0.5 | +| smooth_stop_min_running_vel | double | min ego velocity to judge if the ego is running or not [m/s] | 0.01 | +| smooth_stop_min_running_acc | double | min ego acceleration to judge if the ego is running or not [m/s^2] | 0.01 | +| smooth_stop_weak_stop_time | double | max time to output weak acceleration [s]. After this, strong acceleration will be output. | 0.8 | +| smooth_stop_weak_stop_dist | double | Weak acceleration will be output when the ego is `smooth_stop_weak_stop_dist`-meter before the stop point. [m] | -0.3 | +| smooth_stop_strong_stop_dist | double | Strong acceleration will be output when the ego is `smooth_stop_strong_stop_dist`-meter over the stop point. [m] | -0.5 | + +### STOPPED Parameter + +| Name | Type | Description | Default value | +| :----------- | :----- | :------------------------------------------- | :------------ | +| stopped_vel | double | target velocity in STOPPED state [m/s] | 0.0 | +| stopped_acc | double | target acceleration in STOPPED state [m/s^2] | -3.4 | +| stopped_jerk | double | target jerk in STOPPED state [m/s^3] | -5.0 | + +### EMERGENCY Parameter + +| Name | Type | Description | Default value | +| :------------- | :----- | :------------------------------------------------ | :------------ | +| emergency_vel | double | target velocity in EMERGENCY state [m/s] | 0.0 | +| emergency_acc | double | target acceleration in an EMERGENCY state [m/s^2] | -5.0 | +| emergency_jerk | double | target jerk in an EMERGENCY state [m/s^3] | -3.0 | + # References / External links # Future extensions / Unimplemented parts # Related issues -- https://gitlab.com/autowarefoundation/autoware.auto/AutowareAuto/-/issues/1058 +- From f45815bd65318e86efb2864690e4cf030537a712 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Feb 2022 11:44:49 +0900 Subject: [PATCH 13/14] feat(longitudinal controller): remove unnecessary params (#386) Signed-off-by: Takayuki Murooka --- .../param/longitudinal_controller_defaults.yaml | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.yaml b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.yaml index 0b3e262b065b3..caaa61a054782 100644 --- a/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.yaml +++ b/control/trajectory_follower_nodes/param/longitudinal_controller_defaults.yaml @@ -70,13 +70,3 @@ lpf_pitch_gain: 0.95 max_pitch_rad: 0.1 min_pitch_rad: -0.1 - - # vehicle parameters - vehicle: - mass_kg: 2400.0 - mass_fl: 600.0 - mass_fr: 600.0 - mass_rl: 600.0 - mass_rr: 600.0 - cf: 155494.663 - cr: 155494.663 From 942f81c93417e2d09746b6595e3166d661943c15 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 15 Feb 2022 11:48:11 +0900 Subject: [PATCH 14/14] feat(osqp_interface): add interface to give csc matrix directly to enable warm start for computation time improvement. (#378) * add osqp initialization with csc matrix Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka * remove unnecessary includes Signed-off-by: Takayuki Murooka * add test for new functions Signed-off-by: Takayuki Murooka * fix osqp dual variables output Signed-off-by: Takamasa Horibe * fix osqp test Signed-off-by: Takamasa Horibe * cosmetic change Signed-off-by: Takamasa Horibe Co-authored-by: Takamasa Horibe --- .../include/osqp_interface/osqp_interface.hpp | 14 +- common/osqp_interface/src/osqp_interface.cpp | 85 +++++++++--- .../test/test_osqp_interface.cpp | 124 ++++++++++++------ 3 files changed, 161 insertions(+), 62 deletions(-) diff --git a/common/osqp_interface/include/osqp_interface/osqp_interface.hpp b/common/osqp_interface/include/osqp_interface/osqp_interface.hpp index 46bbc79f2f8cd..950f699b912dd 100644 --- a/common/osqp_interface/include/osqp_interface/osqp_interface.hpp +++ b/common/osqp_interface/include/osqp_interface/osqp_interface.hpp @@ -57,7 +57,7 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface int64_t m_exitflag; // Runs the solver on the stored problem. - std::tuple, std::vector, int64_t, int64_t> solve(); + std::tuple, std::vector, int64_t, int64_t, int64_t> solve(); static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept; @@ -75,6 +75,9 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface OSQPInterface( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u, const c_float eps_abs); + OSQPInterface( + const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, + const std::vector & l, const std::vector & u, const c_float eps_abs); /**************** * OPTIMIZATION @@ -97,7 +100,7 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface /// \details std::vector param = std::get<0>(result); /// \details float64_t x_0 = param[0]; /// \details float64_t x_1 = param[1]; - std::tuple, std::vector, int64_t, int64_t> optimize(); + std::tuple, std::vector, int64_t, int64_t, int64_t> optimize(); /// \brief Solves convex quadratic programs (QPs) using the OSQP solver. /// \return The function returns a tuple containing the solution as two float vectors. @@ -115,7 +118,7 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface /// \details std::vector param = std::get<0>(result); /// \details float64_t x_0 = param[0]; /// \details float64_t x_1 = param[1]; - std::tuple, std::vector, int64_t, int64_t> optimize( + std::tuple, std::vector, int64_t, int64_t, int64_t> optimize( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u); @@ -128,6 +131,9 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface int64_t initializeProblem( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u); + int64_t initializeProblem( + CSC_Matrix P, CSC_Matrix A, const std::vector & q, + const std::vector & l, const std::vector & u); // Updates problem parameters while keeping solution in memory. // @@ -138,7 +144,9 @@ class OSQP_INTERFACE_PUBLIC OSQPInterface // l_new: (m) vector defining the lower bound problem constraint. // u_new: (m) vector defining the upper bound problem constraint. void updateP(const Eigen::MatrixXd & P_new); + void updateCscP(const CSC_Matrix & P_csc); void updateA(const Eigen::MatrixXd & A_new); + void updateCscA(const CSC_Matrix & A_csc); void updateQ(const std::vector & q_new); void updateL(const std::vector & l_new); void updateU(const std::vector & u_new); diff --git a/common/osqp_interface/src/osqp_interface.cpp b/common/osqp_interface/src/osqp_interface.cpp index 5b60dc55b4f96..3052844d6b6ea 100644 --- a/common/osqp_interface/src/osqp_interface.cpp +++ b/common/osqp_interface/src/osqp_interface.cpp @@ -60,6 +60,15 @@ OSQPInterface::OSQPInterface( initializeProblem(P, A, q, l, u); } +OSQPInterface::OSQPInterface( + const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, + const std::vector & l, const std::vector & u, + const c_float eps_abs) +: OSQPInterface(eps_abs) +{ + initializeProblem(P, A, q, l, u); +} + void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept { if (ptr != nullptr) { @@ -82,6 +91,11 @@ void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) osqp_update_P(m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); } +void OSQPInterface::updateCscP(const CSC_Matrix & P_csc) +{ + osqp_update_P(m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); +} + void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) { /* @@ -96,6 +110,11 @@ void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) return; } +void OSQPInterface::updateCscA(const CSC_Matrix & A_csc) +{ + osqp_update_A(m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); +} + void OSQPInterface::updateQ(const std::vector & q_new) { std::vector q_tmp(q_new.begin(), q_new.end()); @@ -184,11 +203,43 @@ int64_t OSQPInterface::initializeProblem( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u) { - /******************* - * SET UP MATRICES - *******************/ + // check if arguments are valid + std::stringstream ss; + if (P.rows() != P.cols()) { + ss << "P.rows() and P.cols() are not the same. P.rows() = " << P.rows() + << ", P.cols() = " << P.cols(); + throw std::invalid_argument(ss.str()); + } + if (P.rows() != static_cast(q.size())) { + ss << "P.rows() and q.size() are not the same. P.rows() = " << P.rows() + << ", q.size() = " << q.size(); + throw std::invalid_argument(ss.str()); + } + if (P.rows() != A.cols()) { + ss << "P.rows() and A.cols() are not the same. P.rows() = " << P.rows() + << ", A.cols() = " << A.cols(); + throw std::invalid_argument(ss.str()); + } + if (A.rows() != static_cast(l.size())) { + ss << "A.rows() and l.size() are not the same. A.rows() = " << A.rows() + << ", l.size() = " << l.size(); + throw std::invalid_argument(ss.str()); + } + if (A.rows() != static_cast(u.size())) { + ss << "A.rows() and u.size() are not the same. A.rows() = " << A.rows() + << ", u.size() = " << u.size(); + throw std::invalid_argument(ss.str()); + } + CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); CSC_Matrix A_csc = calCSCMatrix(A); + return initializeProblem(P_csc, A_csc, q, l, u); +} + +int64_t OSQPInterface::initializeProblem( + CSC_Matrix P_csc, CSC_Matrix A_csc, const std::vector & q, + const std::vector & l, const std::vector & u) +{ // Dynamic float arrays std::vector q_tmp(q.begin(), q.end()); std::vector l_tmp(l.begin(), l.end()); @@ -200,15 +251,12 @@ int64_t OSQPInterface::initializeProblem( /********************** * OBJECTIVE FUNCTION **********************/ - // Number of constraints - c_int constr_m = A.rows(); - // Number of parameters - m_param_n = P.rows(); + m_param_n = static_cast(q.size()); + m_data->m = static_cast(l.size()); /***************** * POPULATE DATA *****************/ - m_data->m = constr_m; m_data->n = m_param_n; m_data->P = csc_matrix( m_data->n, m_data->n, static_cast(P_csc.m_vals.size()), P_csc.m_vals.data(), @@ -229,7 +277,7 @@ int64_t OSQPInterface::initializeProblem( return m_exitflag; } -std::tuple, std::vector, int64_t, int64_t> OSQPInterface::solve() +std::tuple, std::vector, int64_t, int64_t, int64_t> OSQPInterface::solve() { // Solve Problem osqp_solve(m_work.get()); @@ -240,29 +288,30 @@ std::tuple, std::vector, int64_t, int64_t> OSQ float64_t * sol_x = m_work->solution->x; float64_t * sol_y = m_work->solution->y; std::vector sol_primal(sol_x, sol_x + m_param_n); - std::vector sol_lagrange_multiplier(sol_y, sol_y + m_param_n); - // Solver polish status + std::vector sol_lagrange_multiplier(sol_y, sol_y + m_data->m); + int64_t status_polish = m_work->info->status_polish; - // Solver solution status int64_t status_solution = m_work->info->status_val; + int64_t status_iteration = m_work->info->iter; + // Result tuple - std::tuple, std::vector, int64_t, int64_t> result = - std::make_tuple(sol_primal, sol_lagrange_multiplier, status_polish, status_solution); + std::tuple, std::vector, int64_t, int64_t, int64_t> result = + std::make_tuple(sol_primal, sol_lagrange_multiplier, status_polish, status_solution, status_iteration); m_latest_work_info = *(m_work->info); return result; } -std::tuple, std::vector, int64_t, int64_t> +std::tuple, std::vector, int64_t, int64_t, int64_t> OSQPInterface::optimize() { // Run the solver on the stored problem representation. - std::tuple, std::vector, int64_t, int64_t> result = solve(); + std::tuple, std::vector, int64_t, int64_t, int64_t> result = solve(); return result; } -std::tuple, std::vector, int64_t, int64_t> +std::tuple, std::vector, int64_t, int64_t, int64_t> OSQPInterface::optimize( const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, const std::vector & l, const std::vector & u) @@ -271,7 +320,7 @@ OSQPInterface::optimize( initializeProblem(P, A, q, l, u); // Run the solver on the stored problem representation. - std::tuple, std::vector, int64_t, int64_t> result = solve(); + std::tuple, std::vector, int64_t, int64_t, int64_t> result = solve(); m_work.reset(); m_work_initialized = false; diff --git a/common/osqp_interface/test/test_osqp_interface.cpp b/common/osqp_interface/test/test_osqp_interface.cpp index 5683023c7c3e3..e3cd601c9c6e4 100644 --- a/common/osqp_interface/test/test_osqp_interface.cpp +++ b/common/osqp_interface/test/test_osqp_interface.cpp @@ -23,67 +23,109 @@ namespace { using autoware::common::osqp::float64_t; -/// Problem taken from https://github.com/osqp/osqp/blob/master/tests/basic_qp/generate_problem.py +// Problem taken from https://github.com/osqp/osqp/blob/master/tests/basic_qp/generate_problem.py +// +// min 1/2 * x' * P * x + q' * x +// s.t. lb <= A * x <= ub +// +// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] +// [1, 2] [1] [1, 0] [ 0] [0.7] +// [0, 1] [ 0] [0.7] +// [0, 1] [-inf] [inf] +// +// The optimal solution is +// x = [0.3, 0.7]' +// y = [-2.9, 0.0, 0.2, 0.0]` +// obj = 1.88 + // cppcheck-suppress syntaxError TEST(TestOsqpInterface, BasicQp) { + using autoware::common::osqp::CSC_Matrix; + using autoware::common::osqp::calCSCMatrix; + using autoware::common::osqp::calCSCMatrixTrapezoidal; + auto check_result = - [](const std::tuple, std::vector, int, int> & result) { - EXPECT_EQ(std::get<2>(result), 1); - EXPECT_EQ(std::get<3>(result), 1); - ASSERT_EQ(std::get<0>(result).size(), size_t(2)); - ASSERT_EQ(std::get<1>(result).size(), size_t(2)); - EXPECT_DOUBLE_EQ(std::get<0>(result)[0], 0.3); - EXPECT_DOUBLE_EQ(std::get<0>(result)[1], 0.7); - EXPECT_DOUBLE_EQ(std::get<1>(result)[0], -2.9); - EXPECT_NEAR(std::get<1>(result)[1], 0.2, 1e-6); + [](const std::tuple, std::vector, int, int, int> & result) { + EXPECT_EQ(std::get<2>(result), 1); // polish succeeded + EXPECT_EQ(std::get<3>(result), 1); // solution succeeded + + static const auto ep = 1.0e-8; + + const auto prime_val = std::get<0>(result); + ASSERT_EQ(prime_val.size(), size_t(2)); + EXPECT_NEAR(prime_val[0], 0.3, ep); + EXPECT_NEAR(prime_val[1], 0.7, ep); + + const auto dual_val = std::get<1>(result); + ASSERT_EQ(dual_val.size(), size_t(4)); + EXPECT_NEAR(dual_val[0], -2.9, ep); + EXPECT_NEAR(dual_val[1], 0.0, ep); + EXPECT_NEAR(dual_val[2], 0.2, ep); + EXPECT_NEAR(dual_val[3], 0.0, ep); }; + const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); + const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); + const std::vector q = {1.0, 1.0}; + const std::vector l = {1.0, 0.0, 0.0, -autoware::common::osqp::INF}; + const std::vector u = {1.0, 0.7, 0.7, autoware::common::osqp::INF}; + { // Define problem during optimization autoware::common::osqp::OSQPInterface osqp; - Eigen::MatrixXd P(2, 2); - P << 4, 1, 1, 2; - Eigen::MatrixXd A(2, 4); - A << 1, 1, 1, 0, 0, 1, 0, 1; - std::vector q = {1.0, 1.0}; - std::vector l = {1.0, 0.0, 0.0, -autoware::common::osqp::INF}; - std::vector u = {1.0, 0.7, 0.7, autoware::common::osqp::INF}; - std::tuple, std::vector, int, int> result = osqp.optimize( + std::tuple, std::vector, int, int, int> result = osqp.optimize( P, A, q, l, u); check_result(result); } + { // Define problem during initialization - Eigen::MatrixXd P(2, 2); - P << 4, 1, 1, 2; - Eigen::MatrixXd A(2, 4); - A << 1, 1, 1, 0, 0, 1, 0, 1; - std::vector q = {1.0, 1.0}; - std::vector l = {1.0, 0.0, 0.0, -autoware::common::osqp::INF}; - std::vector u = {1.0, 0.7, 0.7, autoware::common::osqp::INF}; autoware::common::osqp::OSQPInterface osqp(P, A, q, l, u, 1e-6); - std::tuple, std::vector, int, int> result = osqp.optimize(); + std::tuple, std::vector, int, int, int> result = osqp.optimize(); check_result(result); } + { - std::tuple, std::vector, int, int> result; + std::tuple, std::vector, int, int, int> result; // Dummy initial problem - Eigen::MatrixXd P = Eigen::MatrixXd::Zero(2, 2); - Eigen::MatrixXd A = Eigen::MatrixXd::Zero(2, 4); - std::vector q(2, 0.0); - std::vector l(4, 0.0); - std::vector u(4, 0.0); - autoware::common::osqp::OSQPInterface osqp(P, A, q, l, u, 1e-6); + Eigen::MatrixXd P_ini = Eigen::MatrixXd::Zero(2, 2); + Eigen::MatrixXd A_ini = Eigen::MatrixXd::Zero(4, 2); + std::vector q_ini(2, 0.0); + std::vector l_ini(4, 0.0); + std::vector u_ini(4, 0.0); + autoware::common::osqp::OSQPInterface osqp(P_ini, A_ini, q_ini, l_ini, u_ini, 1e-6); osqp.optimize(); + + // Redefine problem before optimization + osqp.initializeProblem(P, A, q, l, u); + result = osqp.optimize(); + check_result(result); + } + + { + // Define problem during initialization with csc matrix + CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); + CSC_Matrix A_csc = calCSCMatrix(A); + autoware::common::osqp::OSQPInterface osqp(P_csc, A_csc, q, l, u, 1e-6); + std::tuple, std::vector, int, int, int> result = osqp.optimize(); + check_result(result); + } + + { + std::tuple, std::vector, int, int, int> result; + // Dummy initial problem with csc matrix + CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); + CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); + std::vector q_ini(2, 0.0); + std::vector l_ini(4, 0.0); + std::vector u_ini(4, 0.0); + autoware::common::osqp::OSQPInterface osqp(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini, 1e-6); + osqp.optimize(); + // Redefine problem before optimization - Eigen::MatrixXd P_new(2, 2); - P_new << 4, 1, 1, 2; - Eigen::MatrixXd A_new(2, 4); - A_new << 1, 1, 1, 0, 0, 1, 0, 1; - std::vector q_new = {1.0, 1.0}; - std::vector l_new = {1.0, 0.0, 0.0, -autoware::common::osqp::INF}; - std::vector u_new = {1.0, 0.7, 0.7, autoware::common::osqp::INF}; - osqp.initializeProblem(P_new, A_new, q_new, l_new, u_new); + CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); + CSC_Matrix A_csc = calCSCMatrix(A); + osqp.initializeProblem(P_csc, A_csc, q, l, u); result = osqp.optimize(); check_result(result); }