From d33d5a7872cace2690e6f87120e0ac28d958c213 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Fri, 18 Sep 2020 14:48:09 +0900 Subject: [PATCH 0001/1765] release v0.4.0 --- .github/PULL_REQUEST_TEMPLATE.md | 15 + README.md | 2 + autoware_launch/CMakeLists.txt | 17 + autoware_launch/launch/autoware.launch | 61 + .../launch/planning_simulator.launch | 46 + autoware_launch/package.xml | 29 + autoware_launch/rviz/autoware.rviz | 1032 +++++++++++++++++ control_launch/CMakeLists.txt | 13 + .../mpc_follower/mpc_follower_param.yaml | 40 + .../pure_pursuit/pure_pursuit_param.yaml | 7 + control_launch/launch/control.launch | 50 + control_launch/package.xml | 22 + localization_launch/CMakeLists.txt | 12 + .../launch/localization.launch | 28 + .../pose_estimator/pose_estimator.launch | 15 + .../pose_twist_fusion_filter.launch | 26 + .../twist_estimator/twist_estimator.launch | 7 + localization_launch/launch/util/util.launch | 45 + localization_launch/package.xml | 58 + map_launch/CMakeLists.txt | 14 + map_launch/launch/map.launch | 20 + map_launch/package.xml | 59 + perception_launch/CMakeLists.txt | 12 + ...camera_lidar_fusion_based_detection.launch | 62 + .../detection/detection.launch | 64 + .../detection/lidar_based_detection.launch | 9 + .../prediction/prediction.launch | 21 + .../tracking/tracking.launch | 12 + perception_launch/launch/perception.launch | 73 ++ .../traffic_light.launch | 39 + perception_launch/package.xml | 27 + planning_launch/CMakeLists.txt | 13 + .../motion_velocity_optimizer.yaml | 36 + .../mission_planning/mission_planning.launch | 16 + planning_launch/launch/planning.launch | 16 + .../scenario_planning/lane_driving.launch | 16 + .../behavior_planning.launch | 47 + .../motion_planning/motion_planning.launch | 32 + .../launch/scenario_planning/parking.launch | 22 + .../scenario_planning.launch | 33 + planning_launch/package.xml | 59 + sensing_launch/CMakeLists.txt | 17 + sensing_launch/data/traffic_light_camera.yaml | 20 + .../launch/aip_customized/camera.launch | 22 + .../launch/aip_customized/gnss.launch | 30 + .../launch/aip_customized/imu.launch | 20 + .../launch/aip_customized/lidar.launch | 89 ++ sensing_launch/launch/aip_s1/camera.launch | 22 + sensing_launch/launch/aip_s1/gnss.launch | 30 + sensing_launch/launch/aip_s1/imu.launch | 20 + sensing_launch/launch/aip_s1/lidar.launch | 89 ++ sensing_launch/launch/aip_x1/camera.launch | 22 + sensing_launch/launch/aip_x1/gnss.launch | 30 + sensing_launch/launch/aip_x1/imu.launch | 20 + sensing_launch/launch/aip_x1/lidar.launch | 89 ++ sensing_launch/launch/aip_x2/camera.launch | 22 + sensing_launch/launch/aip_x2/gnss.launch | 30 + sensing_launch/launch/aip_x2/imu.launch | 20 + sensing_launch/launch/aip_x2/lidar.launch | 89 ++ sensing_launch/launch/aip_xx1/camera.launch | 19 + sensing_launch/launch/aip_xx1/gnss.launch | 30 + sensing_launch/launch/aip_xx1/imu.launch | 20 + sensing_launch/launch/aip_xx1/lidar.launch | 116 ++ sensing_launch/launch/aip_xx2/camera.launch | 22 + sensing_launch/launch/aip_xx2/gnss.launch | 30 + sensing_launch/launch/aip_xx2/imu.launch | 20 + sensing_launch/launch/aip_xx2/lidar.launch | 89 ++ sensing_launch/launch/livox_horizon.launch | 28 + sensing_launch/launch/sensing.launch | 30 + sensing_launch/launch/velodyne_VLP16.launch | 85 ++ sensing_launch/launch/velodyne_VLP32C.launch | 85 ++ sensing_launch/launch/velodyne_VLS128.launch | 87 ++ sensing_launch/package.xml | 17 + system_launch/CMakeLists.txt | 13 + system_launch/launch/system.launch | 22 + system_launch/package.xml | 14 + vehicle_launch/CMakeLists.txt | 15 + .../aip_customized/sensors_calibration.yaml | 0 .../config/aip_s1/sensors_calibration.yaml | 0 .../config/aip_x1/sensors_calibration.yaml | 0 .../config/aip_x2/sensors_calibration.yaml | 0 .../aip_xx1/sensor_kit_calibration.yaml | 91 ++ .../config/aip_xx1/sensors_calibration.yaml | 28 + .../config/aip_xx2/sensors_calibration.yaml | 0 vehicle_launch/launch/vehicle.launch | 18 + .../launch/vehicle_description.launch | 22 + .../launch/vehicle_interface.launch | 16 + vehicle_launch/package.xml | 20 + vehicle_launch/urdf/vehicle.xacro | 16 + 89 files changed, 3861 insertions(+) create mode 100644 .github/PULL_REQUEST_TEMPLATE.md create mode 100644 README.md create mode 100644 autoware_launch/CMakeLists.txt create mode 100644 autoware_launch/launch/autoware.launch create mode 100644 autoware_launch/launch/planning_simulator.launch create mode 100644 autoware_launch/package.xml create mode 100644 autoware_launch/rviz/autoware.rviz create mode 100644 control_launch/CMakeLists.txt create mode 100644 control_launch/config/mpc_follower/mpc_follower_param.yaml create mode 100644 control_launch/config/pure_pursuit/pure_pursuit_param.yaml create mode 100644 control_launch/launch/control.launch create mode 100644 control_launch/package.xml create mode 100644 localization_launch/CMakeLists.txt create mode 100644 localization_launch/launch/localization.launch create mode 100644 localization_launch/launch/pose_estimator/pose_estimator.launch create mode 100644 localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch create mode 100644 localization_launch/launch/twist_estimator/twist_estimator.launch create mode 100644 localization_launch/launch/util/util.launch create mode 100644 localization_launch/package.xml create mode 100644 map_launch/CMakeLists.txt create mode 100644 map_launch/launch/map.launch create mode 100644 map_launch/package.xml create mode 100644 perception_launch/CMakeLists.txt create mode 100644 perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch create mode 100644 perception_launch/launch/object_recognition/detection/detection.launch create mode 100644 perception_launch/launch/object_recognition/detection/lidar_based_detection.launch create mode 100644 perception_launch/launch/object_recognition/prediction/prediction.launch create mode 100644 perception_launch/launch/object_recognition/tracking/tracking.launch create mode 100644 perception_launch/launch/perception.launch create mode 100644 perception_launch/launch/traffic_light_recognition/traffic_light.launch create mode 100644 perception_launch/package.xml create mode 100644 planning_launch/CMakeLists.txt create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml create mode 100644 planning_launch/launch/mission_planning/mission_planning.launch create mode 100644 planning_launch/launch/planning.launch create mode 100644 planning_launch/launch/scenario_planning/lane_driving.launch create mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch create mode 100644 planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch create mode 100644 planning_launch/launch/scenario_planning/parking.launch create mode 100644 planning_launch/launch/scenario_planning/scenario_planning.launch create mode 100644 planning_launch/package.xml create mode 100644 sensing_launch/CMakeLists.txt create mode 100644 sensing_launch/data/traffic_light_camera.yaml create mode 100644 sensing_launch/launch/aip_customized/camera.launch create mode 100644 sensing_launch/launch/aip_customized/gnss.launch create mode 100644 sensing_launch/launch/aip_customized/imu.launch create mode 100644 sensing_launch/launch/aip_customized/lidar.launch create mode 100644 sensing_launch/launch/aip_s1/camera.launch create mode 100644 sensing_launch/launch/aip_s1/gnss.launch create mode 100644 sensing_launch/launch/aip_s1/imu.launch create mode 100644 sensing_launch/launch/aip_s1/lidar.launch create mode 100644 sensing_launch/launch/aip_x1/camera.launch create mode 100644 sensing_launch/launch/aip_x1/gnss.launch create mode 100644 sensing_launch/launch/aip_x1/imu.launch create mode 100644 sensing_launch/launch/aip_x1/lidar.launch create mode 100644 sensing_launch/launch/aip_x2/camera.launch create mode 100644 sensing_launch/launch/aip_x2/gnss.launch create mode 100644 sensing_launch/launch/aip_x2/imu.launch create mode 100644 sensing_launch/launch/aip_x2/lidar.launch create mode 100644 sensing_launch/launch/aip_xx1/camera.launch create mode 100644 sensing_launch/launch/aip_xx1/gnss.launch create mode 100644 sensing_launch/launch/aip_xx1/imu.launch create mode 100644 sensing_launch/launch/aip_xx1/lidar.launch create mode 100644 sensing_launch/launch/aip_xx2/camera.launch create mode 100644 sensing_launch/launch/aip_xx2/gnss.launch create mode 100644 sensing_launch/launch/aip_xx2/imu.launch create mode 100644 sensing_launch/launch/aip_xx2/lidar.launch create mode 100644 sensing_launch/launch/livox_horizon.launch create mode 100644 sensing_launch/launch/sensing.launch create mode 100644 sensing_launch/launch/velodyne_VLP16.launch create mode 100644 sensing_launch/launch/velodyne_VLP32C.launch create mode 100644 sensing_launch/launch/velodyne_VLS128.launch create mode 100644 sensing_launch/package.xml create mode 100644 system_launch/CMakeLists.txt create mode 100644 system_launch/launch/system.launch create mode 100644 system_launch/package.xml create mode 100644 vehicle_launch/CMakeLists.txt create mode 100644 vehicle_launch/config/aip_customized/sensors_calibration.yaml create mode 100644 vehicle_launch/config/aip_s1/sensors_calibration.yaml create mode 100644 vehicle_launch/config/aip_x1/sensors_calibration.yaml create mode 100644 vehicle_launch/config/aip_x2/sensors_calibration.yaml create mode 100644 vehicle_launch/config/aip_xx1/sensor_kit_calibration.yaml create mode 100644 vehicle_launch/config/aip_xx1/sensors_calibration.yaml create mode 100644 vehicle_launch/config/aip_xx2/sensors_calibration.yaml create mode 100644 vehicle_launch/launch/vehicle.launch create mode 100644 vehicle_launch/launch/vehicle_description.launch create mode 100644 vehicle_launch/launch/vehicle_interface.launch create mode 100644 vehicle_launch/package.xml create mode 100644 vehicle_launch/urdf/vehicle.xacro diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md new file mode 100644 index 0000000000..30faaaeaba --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -0,0 +1,15 @@ +## PRの種類 + +- [ ] 新機能 +- [ ] 既存機能の性能向上 +- [ ] バグフィックス + +## Jiraリンク + +## 変更概要 + +## レビュー方法 + +## その他 + +- [ ] [リリースノート](https://tier4.atlassian.net/wiki/spaces/AIP/pages/563774416)への記載 diff --git a/README.md b/README.md new file mode 100644 index 0000000000..a895a99a59 --- /dev/null +++ b/README.md @@ -0,0 +1,2 @@ +# autoware_launcher +launch files for autoware diff --git a/autoware_launch/CMakeLists.txt b/autoware_launch/CMakeLists.txt new file mode 100644 index 0000000000..87cc71d214 --- /dev/null +++ b/autoware_launch/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.8.3) +project(autoware_launch) + +find_package(catkin REQUIRED COMPONENTS + vehicle_launch + perception_launch + sensing_launch +) + +catkin_package() + +install( + DIRECTORY + launch + rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch new file mode 100644 index 0000000000..04b4031da8 --- /dev/null +++ b/autoware_launch/launch/autoware.launch @@ -0,0 +1,61 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch new file mode 100644 index 0000000000..daa7844bad --- /dev/null +++ b/autoware_launch/launch/planning_simulator.launch @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml new file mode 100644 index 0000000000..0e2c841c6f --- /dev/null +++ b/autoware_launch/package.xml @@ -0,0 +1,29 @@ + + + autoware_launch + 0.1.0 + The autoware_launch package + + Yukihiro Saito + Apache 2 + + catkin + vehicle_launch + perception_launch + sensing_launch + vehicle_launch + perception_launch + sensing_launch + + rosbridge_server + python-tornado + python3-tornado + python-bson + python3-bson + + + + + + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz new file mode 100644 index 0000000000..6f95da8aef --- /dev/null +++ b/autoware_launch/rviz/autoware.rviz @@ -0,0 +1,1032 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1 + - /Sensing1/GNSS1/PoseWithCovariance1/Covariance1/Position1 + - /Localization1/NDT1/PoseHistory1/Line1 + - /Localization1/NDT1/MonteCarloInitialPose1/Namespaces1 + - /Localization1/EKF1/PoseHistory1/Line1 + - /Planning1/ScenarioPlanning1 + - /Control1/Debug/MPC1/Namespaces1 + Splitter Ratio: 0.557669460773468 + Tree Height: 435 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /2D Dummy Pedestrian1 + - /2D Dummy Car1 + - /2D Checkpoint Pose1 + - /Delete All Objects1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: PointCloudMap + - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + Name: InitialPoseButtonPanel + - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + Name: InitialPoseButtonPanel +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Group + Displays: + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: {} + Update Interval: 0 + Value: false + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: false + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: false + - Class: rviz/Group + Displays: + - Class: rviz_plugins/SteeringAngle + Enabled: true + Left: 128 + Length: 256 + Name: SteeringAngle + Scale: 17 + Text Color: 25; 255; 240 + Top: 128 + Topic: /vehicle/status/steering + Unreliable: false + Value: true + Value height offset: 0 + - Class: rviz_plugins/ConsoleMeter + Enabled: true + Left: 512 + Length: 256 + Name: ConsoleMeter + Scale: 3 + Text Color: 25; 255; 240 + Top: 128 + Topic: /vehicle/status/twist + Unreliable: false + Value: true + Value height offset: 0 + - Alpha: 1 + Class: rviz_plugins/VelocityHistory + Color Border Vel Max: 3 + Constant Color: + Color: 255; 255; 255 + Value: true + Enabled: true + Name: VelocityHistory + Scale: 0.30000001192092896 + Timeout: 10 + Topic: /vehicle/status/twist + Unreliable: false + Value: true + - Alpha: 0.30000001192092896 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera1/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera1/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera2/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera2/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera3/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera3/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera4/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera4/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera5/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera5/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera6/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera6/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + gnss_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tamagawa/imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + velodyne_left: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_left_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_right: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_right_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_top_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: VehicleModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/PolarGridDisplay + Color: 255; 255; 255 + Delta Range: 10 + Enabled: true + Max Alpha: 1 + Max Range: 100 + Max Wave Alpha: 1 + Min Alpha: 0.20000000298023224 + Min Wave Alpha: 0.20000000298023224 + Name: PolarGridDisplay + Reference Frame: base_link + Value: true + Wave Color: 255; 255; 255 + Wave Velocity: 40 + - Class: rviz_plugins/TurnSignal + Enabled: true + Height: 256 + Left: 196 + Name: TurnSignal + Top: 350 + Topic: /vehicle/turn_signal_cmd + Unreliable: false + Value: true + Width: 512 + Enabled: true + Name: Vehicle + Enabled: true + Name: System + - Class: rviz/Group + Displays: + - Alpha: 0.20000000298023224 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 28.71826171875 + Min Value: -7.4224700927734375 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 237 + Min Color: 211; 215; 207 + Min Intensity: 0 + Name: PointCloudMap + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 1 + Size (m): 0.05000000074505806 + Style: Points + Topic: /map/pointcloud_map + Unreliable: false + Use Fixed Frame: true + Use rainbow: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /map/vector_map_marker + Name: Lanelet2VectorMap + Namespaces: + center_lane_line: true + crosswalk_lanelets: true + lanelet direction: true + left_lane_bound: true + parking_lots: true + parking_space: true + right_lane_bound: true + road_lanelets: false + stop_lines: true + traffic_light: true + traffic_light_triangle: true + Queue Size: 100 + Value: true + Enabled: true + Name: Map + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 30 + Min Value: -2 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: ConcatenatePointCloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 2 + Size (m): 0.009999999776482582 + Style: Points + Topic: /sensing/lidar/concatenated/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: false + Autocompute Value Bounds: + Max Value: 15 + Min Value: -2 + Value: false + Axis: Z + Channel Name: z + Class: rviz/PointCloud2 + Color: 0; 240; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 15 + Min Color: 0; 0; 0 + Min Intensity: -5 + Name: NoGroundPointCloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.009999999776482582 + Style: Points + Topic: /sensing/lidar/no_ground/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz/Polygon + Color: 25; 255; 0 + Enabled: false + Name: MesurementRange + Topic: /sensing/lidar/crop_box_filter/crop_box_polygon + Unreliable: false + Value: false + Enabled: true + Name: LiDAR + - Class: rviz/Group + Displays: + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/PoseWithCovariance + Color: 233; 185; 110 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: false + Position: + Alpha: 0.20000000298023224 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.699999988079071 + Head Radius: 1.2000000476837158 + Name: PoseWithCovariance + Shaft Length: 1 + Shaft Radius: 0.5 + Shape: Arrow + Topic: /sensing/gnss/pose_with_covariance + Unreliable: false + Value: true + Enabled: false + Name: GNSS + Enabled: true + Name: Sensing + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/PoseWithCovariance + Color: 0; 170; 255 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.4000000059604645 + Head Radius: 0.6000000238418579 + Name: PoseWithCovInitial + Shaft Length: 0.6000000238418579 + Shaft Radius: 0.30000001192092896 + Shape: Arrow + Topic: /localization/pose_estimator/initial_pose_with_covariance + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/PoseWithCovariance + Color: 0; 255; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.4000000059604645 + Head Radius: 0.6000000238418579 + Name: PoseWithCovAligned + Shaft Length: 0.6000000238418579 + Shaft Radius: 0.30000001192092896 + Shape: Arrow + Topic: /localization/pose_estimator/pose_with_covariance + Unreliable: false + Value: true + - Buffer Size: 200 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Color: 170; 255; 127 + Value: true + Width: 0.10000000149011612 + Name: PoseHistory + Topic: /localization/pose_estimator/pose + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 0; 255; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Initial + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.009999999776482582 + Style: Points + Topic: /localization/util/downsample/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 85; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 85; 255; 127 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Aligned + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.009999999776482582 + Style: Points + Topic: /localization/pose_estimator/points_aligned + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /localization/pose_estimator/monte_carlo_initial_pose_marker + Name: MonteCarloInitialPose + Namespaces: {} + Queue Size: 1 + Value: true + Enabled: true + Name: NDT + - Class: rviz/Group + Displays: + - Buffer Size: 1000 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Color: 0; 255; 255 + Value: true + Width: 0.10000000149011612 + Name: PoseHistory + Topic: /localization/pose_twist_fusion_filter/pose + Value: true + Enabled: true + Name: EKF + Enabled: true + Name: Localization + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/object_recognition/detection/objects/visualization + Name: DynamicObjects + Namespaces: {} + Queue Size: 100 + Value: true + Enabled: false + Name: Detection + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/object_recognition/tracking/objects/visualization + Name: DynamicObjects + Namespaces: {} + Queue Size: 100 + Value: true + Enabled: false + Name: Tracking + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/object_recognition/objects/visualization + Name: DynamicObjects + Namespaces: + label: true + path: true + path confidence: true + shape: true + twist: true + Queue Size: 100 + Value: true + Enabled: true + Name: Prediction + - Class: rviz/Group + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /perception/traffic_light_recognition/debug/rois + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers + Name: Beam + Namespaces: {} + Queue Size: 100 + Value: true + Enabled: true + Name: TrafficLight + Enabled: true + Name: Perception + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/mission_planning/route_marker + Name: RouteArea + Namespaces: + goal_lanelets: true + left_lane_bound: true + right_lane_bound: true + route_lanelets: true + Queue Size: 100 + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.30000001192092896 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.5 + Name: GoalPose + Shaft Length: 3 + Shaft Radius: 0.20000000298023224 + Shape: Axes + Topic: /planning/mission_planning/goal + Unreliable: false + Value: true + Enabled: true + Name: MissionPlanning + - Class: rviz/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: true + Name: ScenarioTrajectory + Topic: /planning/scenario_planning/trajectory + Unreliable: false + Value: true + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: Path + Topic: /planning/scenario_planning/lane_driving/behavior_planning/path + Unreliable: false + Value: true + View Path: + Alpha: 0.4000000059604645 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.4000000059604645 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path + Name: Arrow + Namespaces: {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk + Name: Crosswalk + Namespaces: {} + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection + Name: Intersection + Namespaces: + conflicting_targets: true + detection_area: false + ego_lane: false + factor_text: true + judge_point_pose_line: true + path_raw: false + spline: false + stop_point_pose_line: false + stop_virtual_wall: true + stuck_vehicle_detect_area: false + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot + Name: Blind Spot + Namespaces: + conflict_area_for_blind_spot: false + conflicting_targets: true + detection_area: false + detection_area_for_blind_spot: false + factor_text: true + judge_point_pose_line: true + path_raw: false + stop_virtual_wall: true + spline: false + stop_point_pose_line: false + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light + Name: TrafficLight + Namespaces: {} + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line + Name: StopLine + Namespaces: + factor_text: true + stop_virtual_wall: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area + Name: DetectionArea + Namespaces: + factor_text: true + stop_virtual_wall: true + Queue Size: 100 + Value: true + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: LaneChangeCandidate + Topic: /planning/scenario_planning/lane_driving/lane_change_candidate_path + Unreliable: false + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: true + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: true + Scale: 0.30000001192092896 + Value: false + Enabled: true + Name: BehaviorPlanning + - Class: rviz/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: Trajectory + Topic: /planning/scenario_planning/lane_driving/trajectory + Unreliable: false + Value: false + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker + Name: ObstaclePointCloudStop + Namespaces: + collision_polygons: true + detection_polygons: true + factor_text: true + stop_virtual_wall: true + stop_obstacle_point: true + stop_obstacle_text: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker + Name: SurroundObstacleCheck + Namespaces: + factor_text: true + virtual_wall: true + obstacle_point: true + no_start_obstacle_text: true + Queue Size: 100 + Value: true + Enabled: true + Name: MotionPlanning + Enabled: true + Name: LaneDriving + - Class: rviz/Group + Displays: + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Costmap + Topic: /planning/scenario_planning/parking/costmap_generator/occupancy_grid + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.05000000074505806 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.10000000149011612 + Head Radius: 0.20000000298023224 + Name: PartialPoseArray + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 + Shape: Arrow (3D) + Topic: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.5 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 255 + Enabled: true + Head Length: 0.10000000149011612 + Head Radius: 0.20000000298023224 + Name: PoseArray + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 + Shape: Arrow (Flat) + Topic: /planning/scenario_planning/parking/freespace_planner/debug/pose_array + Unreliable: false + Value: true + Enabled: true + Name: Parking + Enabled: true + Name: ScenarioPlanning + Enabled: true + Name: Planning + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /control/mpc_follower/debug/markers + Name: Debug/MPC + Namespaces: {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /control/pure_pursuit/debug/marker + Name: Debug/PurePursuit + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: true + Name: Control + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: viewer + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /planning/mission_planning/goal + - Class: rviz/PedestrianInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Theta std deviation: 0.0872664600610733 + Velocity: 1 + X std deviation: 0.009999999776482582 + Y std deviation: 0.009999999776482582 + Z position: 0 + Z std deviation: 0.009999999776482582 + - Class: rviz/CarInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Theta std deviation: 0.0872664600610733 + Velocity: 3 + X std deviation: 0.009999999776482582 + Y std deviation: 0.009999999776482582 + Z position: 0 + Z std deviation: 0.009999999776482582 + - Class: rviz/MissionCheckpointTool + Pose Topic: /planning/mission_planning/checkpoint + Theta std deviation: 0.2617993950843811 + X std deviation: 0.5 + Y std deviation: 0.5 + Z position: 0 + - Class: rviz/DeleteAllObjectsTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Value: true + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: 10 + Target Frame: viewer + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1565 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + InitialPoseButtonPanel: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000033c00000563fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001f0000000c900fffffffb0000000a005600690065007700730100000233000000f2000000a400fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073010000032b000000a10000005c00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d00610067006501000003d2000001ce0000001600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000afd0000005afc0100000002fb0000000800540069006d0065010000000000000afd000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000007bb0000056300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 2813 + X: 67 + Y: 27 diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt new file mode 100644 index 0000000000..e469a18318 --- /dev/null +++ b/control_launch/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(control_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + config + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower_param.yaml new file mode 100644 index 0000000000..cb55f92424 --- /dev/null +++ b/control_launch/config/mpc_follower/mpc_follower_param.yaml @@ -0,0 +1,40 @@ + + +# -- system -- +ctrl_period: 0.03 # control period [s] +traj_resample_dist: 0.1 # path resampling interval [m] +enable_yaw_recalculation: false # flag for recalculation of yaw angle after resampling +admisible_position_error: 5.0 # stop mpc calculation when error is larger than the following value +admisible_yaw_error_: 1.57 # stop mpc calculation when error is larger than the following value + +# -- path smoothing -- +enable_path_smoothing: false # flag for path smoothing +path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing +curvature_smoothing_num: 15 # point-to-point index distance used in curvature calculation : curvature is calculated from three points p(i-num), p(i), p(i+num) + +# -- mpc optimization -- +qpoases_max_iter: 500 # max iteration number for quadratic programming +qp_solver_type: "osqp" # optimization solver type. option is unconstraint_fast, unconstraint, and qpoases_hotstart and osqp +mpc_prediction_horizon: 50 # prediction horizon step +mpc_prediction_dt: 0.1 # prediction horizon period [s] +mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q +mpc_weight_heading_error: 0.0 # heading error weight in matrix Q +mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q +mpc_weight_steering_input: 1.0 # steering error weight in matrix R +mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R +mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R +mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R +mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R +mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability +mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability +mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero + +# -- vehicle model -- +vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics +input_delay: 0.24 # steering input delay time for delay compensation +vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] +steer_lim_deg: 40.0 # steering angle limit [deg] +steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] + +# -- lowpass filter for noise reduction -- +steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] diff --git a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml new file mode 100644 index 0000000000..9d38aefc37 --- /dev/null +++ b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml @@ -0,0 +1,7 @@ +# -- system -- +control_period: 0.033 + +# --algorithm +lookahead_distance_ratio: 2.2 +min_lookahead_distance: 2.5 +reverse_min_lookahead_distance: 7.0 diff --git a/control_launch/launch/control.launch b/control_launch/launch/control.launch new file mode 100644 index 0000000000..c2ee293fa7 --- /dev/null +++ b/control_launch/launch/control.launch @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control_launch/package.xml b/control_launch/package.xml new file mode 100644 index 0000000000..c2f9157211 --- /dev/null +++ b/control_launch/package.xml @@ -0,0 +1,22 @@ + + + control_launch + 0.1.0 + The control_launch package + + + + + Takamasa Horibe + + + + + + TODO + + catkin + + + + diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt new file mode 100644 index 0000000000..047892fac7 --- /dev/null +++ b/localization_launch/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 2.8.3) +project(localization_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/localization_launch/launch/localization.launch b/localization_launch/launch/localization.launch new file mode 100644 index 0000000000..1543c92629 --- /dev/null +++ b/localization_launch/launch/localization.launch @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch b/localization_launch/launch/pose_estimator/pose_estimator.launch new file mode 100644 index 0000000000..f70e6d3145 --- /dev/null +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch new file mode 100644 index 0000000000..76310afb0e --- /dev/null +++ b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch b/localization_launch/launch/twist_estimator/twist_estimator.launch new file mode 100644 index 0000000000..da8198ef72 --- /dev/null +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/localization_launch/launch/util/util.launch b/localization_launch/launch/util/util.launch new file mode 100644 index 0000000000..a0558ce968 --- /dev/null +++ b/localization_launch/launch/util/util.launch @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + min_x: -60.0 + max_x: 60.0 + min_y: -60.0 + max_y: 60.0 + min_z: -30.0 + max_z: 50.0 + negative: False + + + + + + + + + + + + voxel_size_x: 3.0 + voxel_size_y: 3.0 + voxel_size_z: 3.0 + + + + diff --git a/localization_launch/package.xml b/localization_launch/package.xml new file mode 100644 index 0000000000..48230f21cb --- /dev/null +++ b/localization_launch/package.xml @@ -0,0 +1,58 @@ + + + localization_launch + 0.1.0 + The localization_launch package + + + + + Yamato Ando + + + + + + Apache 2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + diff --git a/map_launch/CMakeLists.txt b/map_launch/CMakeLists.txt new file mode 100644 index 0000000000..c318300cf5 --- /dev/null +++ b/map_launch/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(map_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +include_directories() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/map_launch/launch/map.launch b/map_launch/launch/map.launch new file mode 100644 index 0000000000..efa73f802c --- /dev/null +++ b/map_launch/launch/map.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/map_launch/package.xml b/map_launch/package.xml new file mode 100644 index 0000000000..df7aacd226 --- /dev/null +++ b/map_launch/package.xml @@ -0,0 +1,59 @@ + + + map_launch + 0.1.0 + The map_launch package + + + + + mitsudome-r + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt new file mode 100644 index 0000000000..3617fa63d2 --- /dev/null +++ b/perception_launch/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 2.8.3) +project(perception_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch new file mode 100644 index 0000000000..b35bc13960 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch b/perception_launch/launch/object_recognition/detection/detection.launch new file mode 100644 index 0000000000..f72fa95b37 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/detection.launch @@ -0,0 +1,64 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch new file mode 100644 index 0000000000..6fe87c5e63 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch b/perception_launch/launch/object_recognition/prediction/prediction.launch new file mode 100644 index 0000000000..efd2535b23 --- /dev/null +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch b/perception_launch/launch/object_recognition/tracking/tracking.launch new file mode 100644 index 0000000000..a2fc3947b2 --- /dev/null +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/perception_launch/launch/perception.launch b/perception_launch/launch/perception.launch new file mode 100644 index 0000000000..ee29ebf677 --- /dev/null +++ b/perception_launch/launch/perception.launch @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch b/perception_launch/launch/traffic_light_recognition/traffic_light.launch new file mode 100644 index 0000000000..8f16904c14 --- /dev/null +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/package.xml b/perception_launch/package.xml new file mode 100644 index 0000000000..458e108e1e --- /dev/null +++ b/perception_launch/package.xml @@ -0,0 +1,27 @@ + + + perception_launch + 0.1.0 + The perception_launch package + + Yukihiro Saito + Apache2 + + + catkin + dynamic_object_visualization + euclidean_cluster + pointcloud_to_laserscan + shape_estimation + dynamic_object_visualization + euclidean_cluster + pointcloud_to_laserscan + shape_estimation + dynamic_object_visualization + euclidean_cluster + pointcloud_to_laserscan + shape_estimation + + + + diff --git a/planning_launch/CMakeLists.txt b/planning_launch/CMakeLists.txt new file mode 100644 index 0000000000..65406d7899 --- /dev/null +++ b/planning_launch/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(planning_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml new file mode 100644 index 0000000000..c324867194 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml @@ -0,0 +1,36 @@ +max_velocity: 20.0 # max velocity limit [m/s] +max_accel: 1.0 # max acceleration limit [m/ss] +min_decel: -1.0 # min deceleration limit [m/ss] + +# curve parameters +max_lateral_accel: 0.5 # max lateral acceleration limit [m/ss] +min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] +decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit +decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit + +# engage & replan parameters +replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] +engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) +engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) +engage_exit_ratio: 0.5 # exit engage sequence to normal velocity plannning when the velocity exceeds engage_exit_ratio x engage_velocity. +stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] + +extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m] +extract_behind_dist: 5.0 # backward trajectory distance used for planning [m] +delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajecotory pose [radian] + +max_trajectory_length: 200.0 # max trajectory length for resampling [m] +min_trajectory_length: 30.0 # min trajectory length for resampling [m] +resample_time: 10.0 # resample total time [s] +resample_dt: 0.1 # resample time interval [s] +min_trajectory_interval_distance: 0.1 # resample points-interval length [m] + +# default weights +# L2: jerk = 100.0, v_weight = 100000.0, a_weight = 1000.0 +# Linf: jerk = 200.0, v_weight = 100000.0, a_weight = 5000.0 + +pseudo_jerk_weight: 100.0 # weight for "smoothness" cost +over_v_weight: 100000.0 # weight for "overspeed limit" cost +over_a_weight: 1000.0 # weight for "overaccel limit" cost + +algorithm_type: "L2" # Option : L2, Linf \ No newline at end of file diff --git a/planning_launch/launch/mission_planning/mission_planning.launch b/planning_launch/launch/mission_planning/mission_planning.launch new file mode 100644 index 0000000000..d1e94f15c8 --- /dev/null +++ b/planning_launch/launch/mission_planning/mission_planning.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/planning.launch b/planning_launch/launch/planning.launch new file mode 100644 index 0000000000..d8d6dd9a10 --- /dev/null +++ b/planning_launch/launch/planning.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch b/planning_launch/launch/scenario_planning/lane_driving.launch new file mode 100644 index 0000000000..27fa088c48 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch new file mode 100644 index 0000000000..cc0e35f6be --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch new file mode 100644 index 0000000000..8ae766945d --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/parking.launch b/planning_launch/launch/scenario_planning/parking.launch new file mode 100644 index 0000000000..0198eb09d0 --- /dev/null +++ b/planning_launch/launch/scenario_planning/parking.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch b/planning_launch/launch/scenario_planning/scenario_planning.launch new file mode 100644 index 0000000000..c4d21f9103 --- /dev/null +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/package.xml b/planning_launch/package.xml new file mode 100644 index 0000000000..24d7f88c67 --- /dev/null +++ b/planning_launch/package.xml @@ -0,0 +1,59 @@ + + + planning_launch + 0.1.0 + The planning_launch package + + + + + tier4 + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt new file mode 100644 index 0000000000..ab708b8c4b --- /dev/null +++ b/sensing_launch/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.8.3) +project(sensing_launch) + +find_package(catkin REQUIRED) + +# Force Tier IV's fork version +find_package(velodyne_pointcloud 0.1.0 EXACT REQUIRED) +find_package(velodyne_vls_pointcloud 0.1.0 EXACT REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + data + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/sensing_launch/data/traffic_light_camera.yaml b/sensing_launch/data/traffic_light_camera.yaml new file mode 100644 index 0000000000..a4c99fae96 --- /dev/null +++ b/sensing_launch/data/traffic_light_camera.yaml @@ -0,0 +1,20 @@ +image_width: 1920 +image_height: 1080 +camera_name: traffic_light/camera +camera_matrix: + rows: 3 + cols: 3 + data: [2410.755261, 0.000000, 922.621401, 0.000000, 2403.573140, 534.752500, 0.000000, 0.000000, 1.000000] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000] +rectification_matrix: + rows: 3 + cols: 3 + data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] +projection_matrix: + rows: 3 + cols: 4 + data: [2370.254883, 0.000000, 920.136018, 0.000000, 0.000000, 2388.885254, 535.599668, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000] \ No newline at end of file diff --git a/sensing_launch/launch/aip_customized/camera.launch b/sensing_launch/launch/aip_customized/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_customized/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_customized/gnss.launch b/sensing_launch/launch/aip_customized/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_customized/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_customized/imu.launch b/sensing_launch/launch/aip_customized/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_customized/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_customized/lidar.launch b/sensing_launch/launch/aip_customized/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_customized/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/camera.launch b/sensing_launch/launch/aip_s1/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_s1/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/gnss.launch b/sensing_launch/launch/aip_s1/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_s1/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/imu.launch b/sensing_launch/launch/aip_s1/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_s1/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/lidar.launch b/sensing_launch/launch/aip_s1/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_s1/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/camera.launch b/sensing_launch/launch/aip_x1/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_x1/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/gnss.launch b/sensing_launch/launch/aip_x1/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_x1/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/imu.launch b/sensing_launch/launch/aip_x1/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_x1/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/lidar.launch b/sensing_launch/launch/aip_x1/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_x1/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/camera.launch b/sensing_launch/launch/aip_x2/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_x2/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/gnss.launch b/sensing_launch/launch/aip_x2/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_x2/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/imu.launch b/sensing_launch/launch/aip_x2/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_x2/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/lidar.launch b/sensing_launch/launch/aip_x2/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_x2/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/camera.launch b/sensing_launch/launch/aip_xx1/camera.launch new file mode 100644 index 0000000000..0eb3b6b0a8 --- /dev/null +++ b/sensing_launch/launch/aip_xx1/camera.launch @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch b/sensing_launch/launch/aip_xx1/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_xx1/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/imu.launch b/sensing_launch/launch/aip_xx1/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_xx1/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch new file mode 100644 index 0000000000..d575890399 --- /dev/null +++ b/sensing_launch/launch/aip_xx1/lidar.launch @@ -0,0 +1,116 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud, + /sensing/lidar/rear/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/camera.launch b/sensing_launch/launch/aip_xx2/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch b/sensing_launch/launch/aip_xx2/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/imu.launch b/sensing_launch/launch/aip_xx2/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_xx2/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/lidar.launch b/sensing_launch/launch/aip_xx2/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/livox_horizon.launch b/sensing_launch/launch/livox_horizon.launch new file mode 100644 index 0000000000..aeb1f44316 --- /dev/null +++ b/sensing_launch/launch/livox_horizon.launch @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/sensing.launch b/sensing_launch/launch/sensing.launch new file mode 100644 index 0000000000..019af23690 --- /dev/null +++ b/sensing_launch/launch/sensing.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLP16.launch b/sensing_launch/launch/velodyne_VLP16.launch new file mode 100644 index 0000000000..279c04631b --- /dev/null +++ b/sensing_launch/launch/velodyne_VLP16.launch @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch b/sensing_launch/launch/velodyne_VLP32C.launch new file mode 100644 index 0000000000..13ce69c6a2 --- /dev/null +++ b/sensing_launch/launch/velodyne_VLP32C.launch @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch b/sensing_launch/launch/velodyne_VLS128.launch new file mode 100644 index 0000000000..b2833f1195 --- /dev/null +++ b/sensing_launch/launch/velodyne_VLS128.launch @@ -0,0 +1,87 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml new file mode 100644 index 0000000000..4a87ff366b --- /dev/null +++ b/sensing_launch/package.xml @@ -0,0 +1,17 @@ + + + sensing_launch + 0.1.0 + The sensing_launch package + + Yukihiro Saito + Apache2 + + catkin + + velodyne_pointcloud + velodyne_vls_pointcloud + + + + diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt new file mode 100644 index 0000000000..2519b3e2f0 --- /dev/null +++ b/system_launch/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(system_launch) + +find_package(catkin REQUIRED COMPONENTS +) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/system_launch/launch/system.launch b/system_launch/launch/system.launch new file mode 100644 index 0000000000..b30703b4fd --- /dev/null +++ b/system_launch/launch/system.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/system_launch/package.xml b/system_launch/package.xml new file mode 100644 index 0000000000..7f5f70ae0c --- /dev/null +++ b/system_launch/package.xml @@ -0,0 +1,14 @@ + + + system_launch + 0.1.0 + The system_launch package + + Kenji Miyake + Apache 2 + + catkin + + + + diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt new file mode 100644 index 0000000000..331b62f499 --- /dev/null +++ b/vehicle_launch/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.3) +project(vehicle_launch) + +add_compile_options(-std=c++14) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY + launch + config + urdf + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/vehicle_launch/config/aip_customized/sensors_calibration.yaml b/vehicle_launch/config/aip_customized/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/aip_s1/sensors_calibration.yaml b/vehicle_launch/config/aip_s1/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/aip_x1/sensors_calibration.yaml b/vehicle_launch/config/aip_x1/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/aip_x2/sensors_calibration.yaml b/vehicle_launch/config/aip_x2/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/aip_xx1/sensor_kit_calibration.yaml b/vehicle_launch/config/aip_xx1/sensor_kit_calibration.yaml new file mode 100644 index 0000000000..d9d1f599e4 --- /dev/null +++ b/vehicle_launch/config/aip_xx1/sensor_kit_calibration.yaml @@ -0,0 +1,91 @@ +sensor_kit_base_link2camera0: + x: 0.10731 + y: 0.56343 + z: -0.27697 + roll: -0.025 + pitch: 0.315 + yaw: 1.035 +sensor_kit_base_link2camera1: + x: -0.10731 + y: -0.56343 + z: -0.27697 + roll: -0.025 + pitch: 0.32 + yaw: -2.12 +sensor_kit_base_link2camera2: + x: 0.10731 + y: -0.56343 + z: -0.27697 + roll: -0.00 + pitch: 0.335 + yaw: -1.04 +sensor_kit_base_link2camera3: + x: -0.10731 + y: 0.56343 + z: -0.27697 + roll: 0.0 + pitch: 0.325 + yaw: 2.0943951 +sensor_kit_base_link2camera4: + x: 0.07356 + y: 0.0 + z: -0.0525 + roll: 0.0 + pitch: -0.03 + yaw: -0.005 +sensor_kit_base_link2camera5: + x: -0.07356 + y: 0.0 + z: -0.0525 + roll: 0.0 + pitch: -0.01 + yaw: 3.125 +sensor_kit_base_link2traffic_light_right_camera: + x: 0.05 + y: -0.0175 + z: -0.1 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 +sensor_kit_base_link2traffic_light_left_camera: + x: 0.05 + y: 0.0175 + z: -0.1 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 +sensor_kit_base_link2velodyne_top_base_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 1.575 +sensor_kit_base_link2velodyne_left_base_link: + x: 0.0 + y: 0.56362 + z: -0.30555 + roll: -0.02 + pitch: 0.71 + yaw: 1.575 +sensor_kit_base_link2velodyne_right_base_link: + x: 0.0 + y: -0.56362 + z: -0.30555 + roll: -0.01 + pitch: 0.71 + yaw: -1.580 +sensor_kit_base_link2gnss: + x: -0.1 + y: 0.0 + z: -0.2 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 +sensor_kit_base_link2imu_tamagawa: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 3.14159265359 + pitch: 0.0 + yaw: 3.14159265359 diff --git a/vehicle_launch/config/aip_xx1/sensors_calibration.yaml b/vehicle_launch/config/aip_xx1/sensors_calibration.yaml new file mode 100644 index 0000000000..1aa0972391 --- /dev/null +++ b/vehicle_launch/config/aip_xx1/sensors_calibration.yaml @@ -0,0 +1,28 @@ +base_link2sensor_kit_base_link: + x: 0.9 + y: 0.0 + z: 2.0 + roll: -0.001 + pitch: 0.015 + yaw: -0.0364 +base_link2livox_front_right_base_link: + x: 3.290 + y: -0.65485 + z: 0.3216 + roll: 0.0 + pitch: 0.0 + yaw: -0.872664444 +base_link2livox_front_left_base_link: + x: 3.290 + y: 0.65485 + z: 0.3016 + roll: -0.021 + pitch: 0.05 + yaw: 0.872664444 +base_link2velodyne_rear_base_link: + x: -0.358 + y: 0.0 + z: 1.631 + roll: -0.02 + pitch: 0.7281317 + yaw: 3.141592 diff --git a/vehicle_launch/config/aip_xx2/sensors_calibration.yaml b/vehicle_launch/config/aip_xx2/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/launch/vehicle.launch b/vehicle_launch/launch/vehicle.launch new file mode 100644 index 0000000000..653c7b5271 --- /dev/null +++ b/vehicle_launch/launch/vehicle.launch @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/vehicle_launch/launch/vehicle_description.launch b/vehicle_launch/launch/vehicle_description.launch new file mode 100644 index 0000000000..341a2ae8ee --- /dev/null +++ b/vehicle_launch/launch/vehicle_description.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/vehicle_launch/launch/vehicle_interface.launch b/vehicle_launch/launch/vehicle_interface.launch new file mode 100644 index 0000000000..16706c1ee9 --- /dev/null +++ b/vehicle_launch/launch/vehicle_interface.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml new file mode 100644 index 0000000000..457a38c130 --- /dev/null +++ b/vehicle_launch/package.xml @@ -0,0 +1,20 @@ + + + vehicle_launch + 0.1.0 + The vehicle_launch package + + Yukihiro Saito + Apache2 + + + catkin + camera_description + imu_description + livox_description + velodyne_description + + roscpp + + + diff --git a/vehicle_launch/urdf/vehicle.xacro b/vehicle_launch/urdf/vehicle.xacro new file mode 100644 index 0000000000..30db9c6a7c --- /dev/null +++ b/vehicle_launch/urdf/vehicle.xacro @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + From f059f5a97606a2b366674e17be909bf7f01689c3 Mon Sep 17 00:00:00 2001 From: hiroyuki obinata <58019445+obi-t4@users.noreply.github.com> Date: Tue, 14 Jul 2020 19:22:34 +0900 Subject: [PATCH 0002/1765] pointcloud_map_path form autoware_launch as optional (#45) * pointcloud_map_path form autoware_launch as optional * add lanelet2_map_path * use map_file argments under map_path * Fix unnecessary "default" tag to "value" Signed-off-by: Kenji Miyake Co-authored-by: Kenji Miyake --- autoware_launch/launch/autoware.launch | 5 ++++- autoware_launch/launch/planning_simulator.launch | 5 ++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch index 04b4031da8..9324b7df50 100644 --- a/autoware_launch/launch/autoware.launch +++ b/autoware_launch/launch/autoware.launch @@ -7,6 +7,8 @@ + + @@ -23,7 +25,8 @@ - + + diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch index daa7844bad..05d09358cc 100644 --- a/autoware_launch/launch/planning_simulator.launch +++ b/autoware_launch/launch/planning_simulator.launch @@ -6,6 +6,8 @@ + + @@ -21,7 +23,8 @@ - + + From 1f914b0b1c6973ee0827fc95f9bc23e74f381301 Mon Sep 17 00:00:00 2001 From: shin <8327162+0x126@users.noreply.github.com> Date: Tue, 14 Jul 2020 20:05:09 +0900 Subject: [PATCH 0003/1765] load velocity_controller_param.yaml from launcher (#52) Signed-off-by: Shinnosuke Hirakawa --- .../velocity_controller_param.yaml | 58 +++++++++++++++++++ control_launch/launch/control.launch | 2 + 2 files changed, 60 insertions(+) create mode 100644 control_launch/config/velocity_controller/velocity_controller_param.yaml diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml new file mode 100644 index 0000000000..913422c098 --- /dev/null +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -0,0 +1,58 @@ +# closest waypoint threshold +closest_waypoint_distance_threshold: 3.0 +closest_waypoint_angle_threshold: 0.7854 + +# stop state +stop_state_velocity: 0.0 +stop_state_acc: -3.4 +stop_state_entry_ego_speed: 0.2 +stop_state_entry_target_speed: 0.1 + +# delay compensation +delay_compensation_time: 0.17 + +# emergency stop by this controller +emergency_stop_acc: -5.0 +emergency_stop_jerk: -3.0 + +# smooth stop +smooth_stop: + exit_ego_speed: 1.0 + entry_ego_speed: 0.8 + exit_target_speed: 1.0 + entry_target_speed: 0.2 + weak_brake_time: 1.0 + weak_brake_acc: -1.0 + increasing_brake_time: 1.0 + increasing_brake_gradient: -0.1 + stop_brake_time: 1.0 + stop_brake_acc: -3.4 + +# acceleration limit +max_acc: 3.0 +min_acc: -5.0 + +# jerk limit +max_jerk: 2.0 +min_jerk: -5.0 + +# slope compensation +max_pitch_rad: 0.1 +min_pitch_rad: -0.1 +lpf_pitch_gain: 0.95 + +# velocity feedback +pid_controller: + kp: 1.0 + ki: 0.1 + kd: 0 + max_out: 1.0 + min_out: -1.0 + max_p_effort: 1.0 + min_p_effort: -1.0 + max_i_effort: 0.3 + min_i_effort: -0.3 + max_d_effort: 0 + min_d_effort: 0 + current_velocity_threshold_pid_integration: 0.5 + lpf_velocity_error_gain: 0.9 \ No newline at end of file diff --git a/control_launch/launch/control.launch b/control_launch/launch/control.launch index c2ee293fa7..2a4000982c 100644 --- a/control_launch/launch/control.launch +++ b/control_launch/launch/control.launch @@ -7,6 +7,7 @@ + @@ -25,6 +26,7 @@ + From 255dd8dd6bfe0416b889c14b85662c6533a6d93d Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 16 Jul 2020 19:18:51 +0900 Subject: [PATCH 0004/1765] Modify to change calib param for each vehicle (#51) * add vehicle id to change parameter of each vehicle Signed-off-by: Yukihiro Saito * add vehicle id to change param for each vehicle Signed-off-by: Yukihiro Saito --- .../{ => default}/aip_customized/sensors_calibration.yaml | 0 .../config/{ => default}/aip_s1/sensors_calibration.yaml | 0 .../config/{ => default}/aip_x1/sensors_calibration.yaml | 0 .../config/{ => default}/aip_x2/sensors_calibration.yaml | 0 .../{ => default}/aip_xx1/sensor_kit_calibration.yaml | 0 .../config/{ => default}/aip_xx1/sensors_calibration.yaml | 0 .../config/{ => default}/aip_xx2/sensors_calibration.yaml | 0 vehicle_launch/launch/vehicle.launch | 4 ++++ vehicle_launch/launch/vehicle_description.launch | 4 +++- vehicle_launch/launch/vehicle_interface.launch | 6 ++++-- 10 files changed, 11 insertions(+), 3 deletions(-) rename vehicle_launch/config/{ => default}/aip_customized/sensors_calibration.yaml (100%) rename vehicle_launch/config/{ => default}/aip_s1/sensors_calibration.yaml (100%) rename vehicle_launch/config/{ => default}/aip_x1/sensors_calibration.yaml (100%) rename vehicle_launch/config/{ => default}/aip_x2/sensors_calibration.yaml (100%) rename vehicle_launch/config/{ => default}/aip_xx1/sensor_kit_calibration.yaml (100%) rename vehicle_launch/config/{ => default}/aip_xx1/sensors_calibration.yaml (100%) rename vehicle_launch/config/{ => default}/aip_xx2/sensors_calibration.yaml (100%) diff --git a/vehicle_launch/config/aip_customized/sensors_calibration.yaml b/vehicle_launch/config/default/aip_customized/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_customized/sensors_calibration.yaml rename to vehicle_launch/config/default/aip_customized/sensors_calibration.yaml diff --git a/vehicle_launch/config/aip_s1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_s1/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_s1/sensors_calibration.yaml rename to vehicle_launch/config/default/aip_s1/sensors_calibration.yaml diff --git a/vehicle_launch/config/aip_x1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_x1/sensors_calibration.yaml rename to vehicle_launch/config/default/aip_x1/sensors_calibration.yaml diff --git a/vehicle_launch/config/aip_x2/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x2/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_x2/sensors_calibration.yaml rename to vehicle_launch/config/default/aip_x2/sensors_calibration.yaml diff --git a/vehicle_launch/config/aip_xx1/sensor_kit_calibration.yaml b/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_xx1/sensor_kit_calibration.yaml rename to vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml diff --git a/vehicle_launch/config/aip_xx1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_xx1/sensors_calibration.yaml rename to vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml diff --git a/vehicle_launch/config/aip_xx2/sensors_calibration.yaml b/vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml similarity index 100% rename from vehicle_launch/config/aip_xx2/sensors_calibration.yaml rename to vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml diff --git a/vehicle_launch/launch/vehicle.launch b/vehicle_launch/launch/vehicle.launch index 653c7b5271..5873b2bf65 100644 --- a/vehicle_launch/launch/vehicle.launch +++ b/vehicle_launch/launch/vehicle.launch @@ -2,17 +2,21 @@ + + + + diff --git a/vehicle_launch/launch/vehicle_description.launch b/vehicle_launch/launch/vehicle_description.launch index 341a2ae8ee..7a09cd6e13 100644 --- a/vehicle_launch/launch/vehicle_description.launch +++ b/vehicle_launch/launch/vehicle_description.launch @@ -3,9 +3,11 @@ + + - + diff --git a/vehicle_launch/launch/vehicle_interface.launch b/vehicle_launch/launch/vehicle_interface.launch index 16706c1ee9..d01796fe92 100644 --- a/vehicle_launch/launch/vehicle_interface.launch +++ b/vehicle_launch/launch/vehicle_interface.launch @@ -2,15 +2,17 @@ - + + - + + From 3e4458b85db20467a97a443e9dc53c7d6d041971 Mon Sep 17 00:00:00 2001 From: Akihito Ohsato Date: Tue, 21 Jul 2020 13:21:03 +0900 Subject: [PATCH 0005/1765] Feature/phased timestamped velodyne (#53) * Replace with new velodyne driver, cutting scan based on azimuth * Fix launch/dependences * Fix version name for tier4/velodyne_vls * Add velodyne_driver dependency --- sensing_launch/CMakeLists.txt | 4 +- sensing_launch/launch/aip_xx1/lidar.launch | 8 ++++ sensing_launch/launch/velodyne_VLP16.launch | 43 ++++++++++++----- sensing_launch/launch/velodyne_VLP32C.launch | 41 +++++++++++----- sensing_launch/launch/velodyne_VLS128.launch | 49 +++++++++++++------- sensing_launch/package.xml | 2 +- 6 files changed, 104 insertions(+), 43 deletions(-) diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt index ab708b8c4b..b557b1d09b 100644 --- a/sensing_launch/CMakeLists.txt +++ b/sensing_launch/CMakeLists.txt @@ -4,8 +4,8 @@ project(sensing_launch) find_package(catkin REQUIRED) # Force Tier IV's fork version -find_package(velodyne_pointcloud 0.1.0 EXACT REQUIRED) -find_package(velodyne_vls_pointcloud 0.1.0 EXACT REQUIRED) +find_package(velodyne_driver 0.2.0 EXACT REQUIRED) +find_package(velodyne_pointcloud 0.2.0 EXACT REQUIRED) catkin_package() diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch index d575890399..6f7b36e830 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch +++ b/sensing_launch/launch/aip_xx1/lidar.launch @@ -9,6 +9,8 @@ + + @@ -18,6 +20,8 @@ + + @@ -27,6 +31,8 @@ + + @@ -36,6 +42,8 @@ + + diff --git a/sensing_launch/launch/velodyne_VLP16.launch b/sensing_launch/launch/velodyne_VLP16.launch index 279c04631b..16dfebc399 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch +++ b/sensing_launch/launch/velodyne_VLP16.launch @@ -3,36 +3,55 @@ - - + + + - - - - - - + + + + + + + + + + + + + + + - + + + + + + + + - - - + + + + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch b/sensing_launch/launch/velodyne_VLP32C.launch index 13ce69c6a2..b17b63c4d1 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch +++ b/sensing_launch/launch/velodyne_VLP32C.launch @@ -3,36 +3,53 @@ - - + + + - - - - - - + + + + + + + + + + + + + - + + + + + + + + - - - + + + + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch b/sensing_launch/launch/velodyne_VLS128.launch index b2833f1195..e8107fc7dc 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch +++ b/sensing_launch/launch/velodyne_VLS128.launch @@ -3,38 +3,55 @@ - - + + + - - - - - - - + + + + + + + + + + + + + + + - + + - + + + + + + - + - - - + + + + + @@ -70,7 +87,7 @@ - + diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index 4a87ff366b..e315fa965b 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -9,8 +9,8 @@ catkin + velodyne_driver velodyne_pointcloud - velodyne_vls_pointcloud From f158e600c3b30fa184c4e7aee137b1ea45faf9e9 Mon Sep 17 00:00:00 2001 From: hiroyuki obinata <58019445+obi-t4@users.noreply.github.com> Date: Mon, 27 Jul 2020 19:36:15 +0900 Subject: [PATCH 0006/1765] add some dependencies (#54) --- autoware_launch/package.xml | 1 + vehicle_launch/package.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 0e2c841c6f..025d0bcc0c 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -16,6 +16,7 @@ sensing_launch rosbridge_server + roswww python-tornado python3-tornado python-bson diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index 457a38c130..e20bbfeefd 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -13,6 +13,7 @@ imu_description livox_description velodyne_description + robot_state_publisher roscpp From b2f7379257a5188b110147ec1b1c0dbcf03b47d4 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 30 Jul 2020 11:28:39 +0900 Subject: [PATCH 0007/1765] Nodelet tlr (#56) * temporary commit tlr_nodelet Signed-off-by: Yukihiro Saito * compressed to compressed Signed-off-by: Yukihiro Saito * Update traffic_light.launch Signed-off-by: Daisuke Nishimatsu * fix bug Signed-off-by: Yukihiro Saito * change image_transport to relay Signed-off-by: Yukihiro Saito * fix bug Signed-off-by: Yukihiro Saito * fix bug Signed-off-by: Yukihiro Saito * decompress as rgb8 Signed-off-by: Yukihiro Saito * fix bug Signed-off-by: Yukihiro Saito Co-authored-by: Yukihiro Saito --- .../traffic_light.launch | 16 +++++++++++++++- sensing_launch/launch/aip_xx1/camera.launch | 7 +------ 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch b/perception_launch/launch/traffic_light_recognition/traffic_light.launch index 8f16904c14..72f6a0c0c4 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch @@ -6,12 +6,24 @@ + + + + + + + + + + + + @@ -26,11 +38,13 @@ + - + + diff --git a/sensing_launch/launch/aip_xx1/camera.launch b/sensing_launch/launch/aip_xx1/camera.launch index 0eb3b6b0a8..fdd4c5365d 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch +++ b/sensing_launch/launch/aip_xx1/camera.launch @@ -7,13 +7,8 @@ - - - - - + From 102faca6d92cd318d50a021d3f908d386a4e886d Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 30 Jul 2020 14:02:26 +0900 Subject: [PATCH 0008/1765] use env for livox id (#58) Signed-off-by: Yukihiro Saito --- sensing_launch/launch/aip_xx1/lidar.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch index 6f7b36e830..8a3f487c3c 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch +++ b/sensing_launch/launch/aip_xx1/lidar.launch @@ -51,7 +51,7 @@ - + @@ -60,7 +60,7 @@ - + From 90715a2920bb5313b86fcf87d642b660fd236a0c Mon Sep 17 00:00:00 2001 From: Akihito Ohsato Date: Mon, 3 Aug 2020 12:54:24 +0900 Subject: [PATCH 0009/1765] Feature/optimize scan phase (#59) * Rename parameter name, sensor_phase -> scan_phase Signed-off-by: Akihito Ohasto * Modify aip_xx1 scan_phase for better perception * Rename parameter name, sensor_phase -> scan_phase Signed-off-by: Akihito Ohasto --- sensing_launch/launch/aip_xx1/lidar.launch | 8 ++++---- sensing_launch/launch/velodyne_VLP16.launch | 6 +++--- sensing_launch/launch/velodyne_VLP32C.launch | 8 +++++--- sensing_launch/launch/velodyne_VLS128.launch | 6 +++--- 4 files changed, 15 insertions(+), 13 deletions(-) diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch index 8a3f487c3c..2382914c54 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch +++ b/sensing_launch/launch/aip_xx1/lidar.launch @@ -9,7 +9,7 @@ - + @@ -20,7 +20,7 @@ - + @@ -31,7 +31,7 @@ - + @@ -42,7 +42,7 @@ - + diff --git a/sensing_launch/launch/velodyne_VLP16.launch b/sensing_launch/launch/velodyne_VLP16.launch index 16dfebc399..6cf557309d 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch +++ b/sensing_launch/launch/velodyne_VLP16.launch @@ -17,7 +17,7 @@ - + @@ -38,7 +38,7 @@ - + @@ -51,7 +51,7 @@ - + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch b/sensing_launch/launch/velodyne_VLP32C.launch index b17b63c4d1..bce757ecb7 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch +++ b/sensing_launch/launch/velodyne_VLP32C.launch @@ -9,7 +9,7 @@ - + @@ -17,6 +17,8 @@ + + @@ -36,7 +38,7 @@ - + @@ -49,7 +51,7 @@ - + diff --git a/sensing_launch/launch/velodyne_VLS128.launch b/sensing_launch/launch/velodyne_VLS128.launch index e8107fc7dc..0d3b9abd35 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch +++ b/sensing_launch/launch/velodyne_VLS128.launch @@ -17,7 +17,7 @@ - + @@ -38,7 +38,7 @@ - + @@ -51,7 +51,7 @@ - + From 336a1276524ece7a61a94367dd0859fc908d2074 Mon Sep 17 00:00:00 2001 From: hiroyuki obinata <58019445+obi-t4@users.noreply.github.com> Date: Wed, 5 Aug 2020 20:11:02 +0900 Subject: [PATCH 0010/1765] add integration launch (#55) --- integration_launch/CMakeLists.txt | 14 ++++++++++++++ integration_launch/launch/release.launch | 13 +++++++++++++ integration_launch/package.xml | 13 +++++++++++++ 3 files changed, 40 insertions(+) create mode 100644 integration_launch/CMakeLists.txt create mode 100644 integration_launch/launch/release.launch create mode 100644 integration_launch/package.xml diff --git a/integration_launch/CMakeLists.txt b/integration_launch/CMakeLists.txt new file mode 100644 index 0000000000..d303b4a8be --- /dev/null +++ b/integration_launch/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(integration_launch) + +find_package(catkin REQUIRED COMPONENTS + autoware_launch +) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/integration_launch/launch/release.launch b/integration_launch/launch/release.launch new file mode 100644 index 0000000000..9c7ea3ac6e --- /dev/null +++ b/integration_launch/launch/release.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/integration_launch/package.xml b/integration_launch/package.xml new file mode 100644 index 0000000000..5b908622b4 --- /dev/null +++ b/integration_launch/package.xml @@ -0,0 +1,13 @@ + + + integration_launch + 0.1.0 + The integration_launch package + + Hiroyuki Obinata + Apache 2 + + catkin + autoware_launch + + From 80c81e231cc7b58d46f75e8fe3fa48a76f690698 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 6 Aug 2020 10:37:05 +0900 Subject: [PATCH 0011/1765] Include enable_slope_compensation to yaml file (#61) --- .../config/velocity_controller/velocity_controller_param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml index 913422c098..8561b1bf0b 100644 --- a/control_launch/config/velocity_controller/velocity_controller_param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -37,6 +37,7 @@ max_jerk: 2.0 min_jerk: -5.0 # slope compensation +enable_slope_compensation: true max_pitch_rad: 0.1 min_pitch_rad: -0.1 lpf_pitch_gain: 0.95 From 150a78c36c7e524293f78e30fa2b248e4f0ce75f Mon Sep 17 00:00:00 2001 From: Yamasaki Tatsuya Date: Thu, 6 Aug 2020 14:12:47 +0900 Subject: [PATCH 0012/1765] Add some scenario-simulation specifiec parameters as arguments (#57) * Add some scenario-simulation specifiec parameters as arguments * Update arg to pass 'initial_engage_state' to simple_planning_simulator * Add new optional argument 'rviz_args' * Rename some roslaunch arguments * Remove unneeded arguments --- autoware_launch/launch/planning_simulator.launch | 15 +++++++++++++-- vehicle_launch/launch/vehicle.launch | 2 ++ vehicle_launch/launch/vehicle_interface.launch | 1 + 3 files changed, 16 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch index 05d09358cc..a652340f01 100644 --- a/autoware_launch/launch/planning_simulator.launch +++ b/autoware_launch/launch/planning_simulator.launch @@ -6,14 +6,21 @@ + + + + + + + @@ -28,7 +35,11 @@ - + + + + + @@ -39,7 +50,7 @@ - + diff --git a/vehicle_launch/launch/vehicle.launch b/vehicle_launch/launch/vehicle.launch index 5873b2bf65..b6191e70cd 100644 --- a/vehicle_launch/launch/vehicle.launch +++ b/vehicle_launch/launch/vehicle.launch @@ -3,6 +3,7 @@ + @@ -15,6 +16,7 @@ + diff --git a/vehicle_launch/launch/vehicle_interface.launch b/vehicle_launch/launch/vehicle_interface.launch index d01796fe92..675ff78397 100644 --- a/vehicle_launch/launch/vehicle_interface.launch +++ b/vehicle_launch/launch/vehicle_interface.launch @@ -3,6 +3,7 @@ + From e8d98c066580b768829d5c1bc54530fcb644c7ae Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Thu, 6 Aug 2020 15:29:03 +0900 Subject: [PATCH 0013/1765] Fix typo (#63) Signed-off-by: Kenji Miyake --- autoware_launch/launch/planning_simulator.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch index a652340f01..d049c4271d 100644 --- a/autoware_launch/launch/planning_simulator.launch +++ b/autoware_launch/launch/planning_simulator.launch @@ -6,7 +6,7 @@ - + From 223f99a801980cbd585dca359923783b1f81226a Mon Sep 17 00:00:00 2001 From: Kosuke Murakami Date: Thu, 6 Aug 2020 20:58:10 +0900 Subject: [PATCH 0014/1765] add obstacle avoid param (#62) --- autoware_launch/rviz/autoware.rviz | 36 ++++++++ .../obstacle_avoidance_planner.yaml | 88 +++++++++++++++++++ .../motion_planning/motion_planning.launch | 1 + 3 files changed, 125 insertions(+) create mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 6f95da8aef..34abe11a03 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -871,6 +871,42 @@ Visualization Manager: no_start_obstacle_text: true Queue Size: 100 Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker + Name: ObstacleAvoidance + Namespaces: + base_bounds_line: false + bounds_candidate_base_text: false + bounds_candidate_for_base: false + bounds_candidate_for_top: false + bounds_candidate_top_text: false + constrain_rect: false + constrain_rect_text: false + constrain_rectlocation: false + current_vehicle_footprint: false + extending_constrain_rect: false + extending_constrain_rect_text: false + extending_constrain_rectlocation: false + fixed_mpt_points: false + fixed_points_for_extending: false + fixed_points_marker: false + interpolated_points_for_extending: false + interpolated_points_marker: false + interpolated_points_text_marker: false + non_fixed_points_for_extending: false + non_fixed_points_marker: false + num_vehicle_footprint: false + optimized_points_marker: false + optimized_points_text_marker: false + smoothed_points_text: false + straight_points_marker: false + top_bounds_line: false + vehicle_footprint: false + virtual_wall: true + virtual_wall_text: true + Queue Size: 100 + Value: true Enabled: true Name: MotionPlanning Enabled: true diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml new file mode 100644 index 0000000000..2f4677ee8c --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml @@ -0,0 +1,88 @@ +# trajectory total/fixing length +trajectory_length: 200 # total trajectory length[m] +forward_fixing_distance: 20.0 # forward fixing length from base_link[m] +backward_fixing_distance: 5.0 # backward fixing length from base_link[m] + +# clearance(distance) when generating trajectory +clearance_from_road: 0.2 # clearance from road boundary[m] +clearance_from_object: 1.0 # clearance from object[m] +min_object_clearance_for_joint: 3.2 # minimum clearance from object[m] when judging is_including_only_smooth_range +extra_desired_clearance_from_road: 0.0 # extra desired clearance from road + +# clearance for unique points +clearance_for_straight_line_: 0.05 # minimum optimizing range around straight points +clearance_for_joint_: 3.2 # minimum optimizing range around joint points +clearance_for_only_smoothing: 0.1 # minimum optimizing range when applygin only smoothing +range_for_extend_joint: 0.1 # minimum optimizing range around joint points for extending +clearance_from_object_for_straight: 10.0 # minimum clearance from object when judging straight line + +# avoiding param +max_avoiding_objects_velocity_ms: .5 # maximum velocity for avoiding objects[m/s] +max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects[m/s] +center_line_width: 1.7 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, center line width around path points used for judging that object is required to avoid or not +acceleration_for_non_deceleration_range: 1.0 # assumed acceleration for calculating non deceleration range + +# solving quadratic programming +qp_max_iteration: 10000 # max iteration when solving QP +qp_eps_abs: 1.0e-8 # eps abs when solving OSQP +qp_eps_rel: 1.0e-11 # eps rel when solving OSQP +qp_eps_abs_for_extending: 1.0e-8 # eps abs when solving OSQP for extending +qp_eps_rel_for_extending: 1.0e-9 # eps rel when solving OSQP for extending +qp_eps_abs_for_visualizing: 1.0e-6 # eps abs when solving OSQP for visualizing +qp_eps_rel_for_visualizing: 1.0e-8 # eps rel when solving OSQP for visualizing + +# constrain space +is_getting_constraints_close2path_points: true # generate trajectory closer to path points +max_x_constrain_search_range: 0.0 # maximum x search range in local coordinate +coef_x_cosntrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction +coef_y_cosntrain_search_resolution: 0.5 # coef for fine sampling when exploring y direction +keep_space_shape_x: 0.2 # keep space for x direction from base_link[m] +keep_space_shape_y: 0.1 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, keep space for y direction from base_link[m] +max_lon_space_for_driveable_constraint: 0.5 # maximum lon(x) space when optimizing point[m] + +is_publishing_clearance_map: true # publish clearance map as nav_msgs::OccupancyGrid +is_publishing_area_with_objects: true # publish occupancy map as nav_msgs::OccupancyGrid +enable_avoidance: true # enable avoidance function +is_using_vehicle_config: true # use vehicle config +num_sampling_points: 100 # number of optimizing points +num_joint_buffer_points: 3 # number of joint buffer points +num_joint_buffer_points_for_extending: 6 # number of joint buffer points for extending +num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx +num_fix_points_for_extending: 50 # number of fixing points when extending +delta_arc_length_for_optimization: 1.0 # delta arc length when optimizing[m] +delta_arc_length_for_trajectory: 0.1 # delta arc length for trajectory[m] +delta_dist_threshold_for_closest_point: 3.0 # delta dist thres for closest point[m] +delta_yaw_threshold_for_closest_point: 1.046 #M_PI/3.0, delta yaw thres for closest point +delta_yaw_threshold_for_straight: 0.02 # delta dist thres for straight point + +# mpt param +# vehicle param for mpt +max_steer_deg: 30.0 # max steering angle [deg] +steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] + +# trajectory param for mpt +num_curvature_sampling_points: 5 # number of sampling points when calculating curvature +delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt[m] +num_fix_points_for_mpt: 8 # number of fixing points around ego vehicle + +# optimization param for mpt +is_hard_fixing_terminal_point: true # hard fixing terminal point +base_point_weight: 2000 # slack weight for lateral error around base_link +top_point_weight: 1000 # slack weight for lateral error around vehicle-top point +mid_point_weight: 1000 # slack weight for lateral error around the middle point +lat_error_weight: 10.0 # weight for lateral error +yaw_error_weight: 0.0 # weight for yaw error +steer_input_weight: 0.01 # weight for steering input +steer_rate_weight: 1 # weight for sttering rate +steer_acc_weight: 0.000001 # weight for steering acceration +terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point +terminal_yaw_error_weight: 100.0 # weight for yaw errror at terminal point +terminal_path_lat_error_weight: 1000.0 # weight for lateral errro at path end point +terminal_path_yaw_error_weight: 1000.0 # weight for yaw errro at path end point +zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero + +# replanning & trimming trajectory param outside algorithm +min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] +min_delta_time_sec_for_replan: 1.0 # minimum delta time for replan[second] +max_dist_for_extending_end_point: 5.0 # minimum delta dist thres for extending last point[m] +distance_for_path_shape_chagne_detection: 2.0 # minimum delta dist thres for detecting path shape change diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch index 8ae766945d..df97661f99 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch @@ -6,6 +6,7 @@ + From bcfb5fc5afffc165b252b7d6fd0e66459ecd30b8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 12 Aug 2020 16:27:11 +0900 Subject: [PATCH 0015/1765] Logging simulator (#65) * Add logging_simulator.launch Signed-off-by: Daisuke Nishimatsu * Don't load env when launch driver is false Signed-off-by: Daisuke Nishimatsu --- autoware_launch/launch/autoware.launch | 6 +- .../launch/logging_simulator.launch | 70 +++++++++++++++++++ sensing_launch/launch/aip_xx1/lidar.launch | 6 +- sensing_launch/launch/livox_horizon.launch | 3 +- 4 files changed, 74 insertions(+), 11 deletions(-) create mode 100644 autoware_launch/launch/logging_simulator.launch diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch index 9324b7df50..f1b72306ee 100644 --- a/autoware_launch/launch/autoware.launch +++ b/autoware_launch/launch/autoware.launch @@ -5,13 +5,10 @@ - - - @@ -31,8 +28,7 @@ - - + diff --git a/autoware_launch/launch/logging_simulator.launch b/autoware_launch/launch/logging_simulator.launch new file mode 100644 index 0000000000..675df2d413 --- /dev/null +++ b/autoware_launch/launch/logging_simulator.launch @@ -0,0 +1,70 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch index 2382914c54..46925430a2 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch +++ b/sensing_launch/launch/aip_xx1/lidar.launch @@ -49,20 +49,18 @@ - + - - + - diff --git a/sensing_launch/launch/livox_horizon.launch b/sensing_launch/launch/livox_horizon.launch index aeb1f44316..1e5c5d8e7a 100644 --- a/sensing_launch/launch/livox_horizon.launch +++ b/sensing_launch/launch/livox_horizon.launch @@ -1,6 +1,5 @@ - @@ -11,7 +10,7 @@ - + From 395656ee319b03eab83aed87a2968284dcbbc013 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 12 Aug 2020 22:09:56 +0900 Subject: [PATCH 0016/1765] Launch vehicle description in logging simulator (#67) Signed-off-by: Daisuke Nishimatsu --- autoware_launch/launch/logging_simulator.launch | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/autoware_launch/launch/logging_simulator.launch b/autoware_launch/launch/logging_simulator.launch index 675df2d413..e364f63097 100644 --- a/autoware_launch/launch/logging_simulator.launch +++ b/autoware_launch/launch/logging_simulator.launch @@ -4,6 +4,7 @@ + @@ -19,10 +20,10 @@ - + - + From ec8d14ad50c43785e999024509e451958f9888d1 Mon Sep 17 00:00:00 2001 From: hiroyuki obinata <58019445+obi-t4@users.noreply.github.com> Date: Thu, 13 Aug 2020 15:38:46 +0900 Subject: [PATCH 0017/1765] add autoware api launcher (#64) --- autoware_launch/launch/autoware.launch | 3 +++ autoware_launch/launch/planning_simulator.launch | 3 +++ 2 files changed, 6 insertions(+) diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch index f1b72306ee..cb4520f1a6 100644 --- a/autoware_launch/launch/autoware.launch +++ b/autoware_launch/launch/autoware.launch @@ -49,6 +49,9 @@ + + + diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch index d049c4271d..ad9eb20702 100644 --- a/autoware_launch/launch/planning_simulator.launch +++ b/autoware_launch/launch/planning_simulator.launch @@ -49,6 +49,9 @@ + + + From 12814a819452b4780343e64b3d7ab3c02348f685 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Fri, 14 Aug 2020 03:08:49 +0900 Subject: [PATCH 0018/1765] add blocked by obstacle (#68) --- autoware_launch/rviz/autoware.rviz | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 34abe11a03..ca82a62717 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -805,6 +805,20 @@ Visualization Manager: stop_virtual_wall: true Queue Size: 100 Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/debug/predicted_path_markers + Name: LaneChange + Namespaces: + candidate_lane_change_path: false + ego_lane_change_path: false + ego_lane_follow_path: false + factor_text: true + object_predicted_path: false + selected_path: false + stop_virtual_wall: true + Queue Size: 100 + Value: true - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true From 075bda184b1bcb98bd8a912780a41f932d552357 Mon Sep 17 00:00:00 2001 From: Makoto Tokunaga Date: Fri, 14 Aug 2020 03:11:18 +0900 Subject: [PATCH 0019/1765] Feature/add ci launch (#60) * add integration launch * feat: add integration launch for PSim CI * feat: update for planning_simulator_launcher/scenario_launcher.launch Co-authored-by: hiroyuki.obinata --- .../launch/ci_planning_simulator.launch | 14 ++++++++++++++ 1 file changed, 14 insertions(+) create mode 100644 integration_launch/launch/ci_planning_simulator.launch diff --git a/integration_launch/launch/ci_planning_simulator.launch b/integration_launch/launch/ci_planning_simulator.launch new file mode 100644 index 0000000000..e36fc1707d --- /dev/null +++ b/integration_launch/launch/ci_planning_simulator.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + From 06b356fbfe2349b77b095ad1f00baf0a12b31643 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Thu, 20 Aug 2020 21:56:25 +0900 Subject: [PATCH 0020/1765] Feature/add stop reason lane change (#69) * add blocked by obstacle * add stop reason topic to lane change planner * Revert "add blocked by obstacle" This reverts commit 1f5ecdb30c04f7ee70a4b3271bb2099c44752801. --- .../lane_driving/behavior_planning/behavior_planning.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch index cc0e35f6be..e67dde71cd 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch @@ -12,6 +12,7 @@ + From 7cb3c32eda2f9911dc19d6968ccc4d34810949ba Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 24 Aug 2020 12:15:50 +0900 Subject: [PATCH 0021/1765] Sync mpc param (#74) Signed-off-by: wep21 --- control_launch/config/mpc_follower/mpc_follower_param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower_param.yaml index cb55f92424..c8d036356b 100644 --- a/control_launch/config/mpc_follower/mpc_follower_param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower_param.yaml @@ -35,6 +35,8 @@ input_delay: 0.24 # steering input delay time for delay compensation vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] steer_lim_deg: 40.0 # steering angle limit [deg] steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] +acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] +velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s] # -- lowpass filter for noise reduction -- steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] From 8d8ac3f14e9e6bc5ee63031f50bef3dcbe7aec29 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 26 Aug 2020 11:29:45 +0900 Subject: [PATCH 0022/1765] Fix turn signal topic name (#75) --- autoware_launch/rviz/autoware.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index ca82a62717..0f90b750e8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -262,7 +262,7 @@ Visualization Manager: Left: 196 Name: TurnSignal Top: 350 - Topic: /vehicle/turn_signal_cmd + Topic: /vehicle/status/turn_signal_cmd Unreliable: false Value: true Width: 512 From 7186bc4982d86473ac5cc2a307484816fc584a8b Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Wed, 26 Aug 2020 11:34:39 +0900 Subject: [PATCH 0023/1765] Revert "Fix turn signal topic name (#75)" (#76) This reverts commit f384b9f7b2e59b7f048926e7eb0fe7c936f5cd3b. --- autoware_launch/rviz/autoware.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 0f90b750e8..ca82a62717 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -262,7 +262,7 @@ Visualization Manager: Left: 196 Name: TurnSignal Top: 350 - Topic: /vehicle/status/turn_signal_cmd + Topic: /vehicle/turn_signal_cmd Unreliable: false Value: true Width: 512 From c5c2a7f4fb631e7e1fa9aa6e1946136eef0fea0d Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Wed, 26 Aug 2020 19:30:22 +0900 Subject: [PATCH 0024/1765] add stop dist param (#73) * add stop dist param * add keep stopping dist param --- .../config/velocity_controller/velocity_controller_param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml index 8561b1bf0b..8c3149074a 100644 --- a/control_launch/config/velocity_controller/velocity_controller_param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -7,6 +7,7 @@ stop_state_velocity: 0.0 stop_state_acc: -3.4 stop_state_entry_ego_speed: 0.2 stop_state_entry_target_speed: 0.1 +stop_state_keep_stopping_dist: 0.5 # delay compensation delay_compensation_time: 0.17 @@ -17,6 +18,7 @@ emergency_stop_jerk: -3.0 # smooth stop smooth_stop: + stop_dist: 3.0 exit_ego_speed: 1.0 entry_ego_speed: 0.8 exit_target_speed: 1.0 From b10bfc92aaa36999c00758778622a38f869aea05 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Thu, 27 Aug 2020 11:28:59 +0900 Subject: [PATCH 0025/1765] Fix namespace in autoware.rviz (#78) --- autoware_launch/rviz/autoware.rviz | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index ca82a62717..2ee3e693df 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -979,14 +979,14 @@ Visualization Manager: Displays: - Class: rviz/MarkerArray Enabled: false - Marker Topic: /control/mpc_follower/debug/markers + Marker Topic: /control/trajectory_follower/mpc_follower/debug/markers Name: Debug/MPC Namespaces: {} Queue Size: 100 Value: false - Class: rviz/MarkerArray Enabled: false - Marker Topic: /control/pure_pursuit/debug/marker + Marker Topic: /control/trajectory_follower/pure_pursuit/debug/marker Name: Debug/PurePursuit Namespaces: {} From 522718e2fc8d5c494d4741c5e6d4165c9d2739ff Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 27 Aug 2020 16:45:28 +0900 Subject: [PATCH 0026/1765] Fix/turn signal topic name (#77) --- autoware_launch/rviz/autoware.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 2ee3e693df..cbc0107cc8 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -262,7 +262,7 @@ Visualization Manager: Left: 196 Name: TurnSignal Top: 350 - Topic: /vehicle/turn_signal_cmd + Topic: /control/turn_signal_cmd Unreliable: false Value: true Width: 512 From b1d9af046b393b0b54e7c185f6bccdfb32415467 Mon Sep 17 00:00:00 2001 From: Kenji Miyake Date: Fri, 28 Aug 2020 12:09:53 +0900 Subject: [PATCH 0027/1765] Add sensor_model and vehicle_model Signed-off-by: Kenji Miyake --- integration_launch/launch/ci_planning_simulator.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/integration_launch/launch/ci_planning_simulator.launch b/integration_launch/launch/ci_planning_simulator.launch index e36fc1707d..6ee6bff390 100644 --- a/integration_launch/launch/ci_planning_simulator.launch +++ b/integration_launch/launch/ci_planning_simulator.launch @@ -1,7 +1,7 @@ - - + + From 038ff4f7a7c7b98ad333089319c94845d2202973 Mon Sep 17 00:00:00 2001 From: UMiho <58927122+UMiho@users.noreply.github.com> Date: Thu, 24 Sep 2020 16:54:11 +0900 Subject: [PATCH 0028/1765] Create LICENSE --- LICENSE | 201 ++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 201 insertions(+) create mode 100644 LICENSE diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000000..261eeb9e9f --- /dev/null +++ b/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. From f8b455f1317c369b5082a8dcb3bf116300a597b4 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 30 Sep 2020 18:45:59 +0200 Subject: [PATCH 0029/1765] Create build_and_test.yml --- .github/workflows/build_and_test.yml | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 .github/workflows/build_and_test.yml diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml new file mode 100644 index 0000000000..79dd0ab0a1 --- /dev/null +++ b/.github/workflows/build_and_test.yml @@ -0,0 +1,25 @@ +name: Build and test + +on: + pull_request: + push: + branches: + - master + +jobs: + build-and-test: + runs-on: ubuntu-20.04 + container: ros:foxy + + steps: + - name: Check out repo + uses: actions/checkout@v2 + + - name: Install missing dependencies + run: rosdep update && DEBIAN_FRONTEND=noninteractive sudo rosdep install --from-paths . --ignore-src --rosdistro foxy -y + + - name: Build + run: . /opt/ros/foxy/setup.sh && colcon build --event-handlers console_cohesion+ + + - name: Run tests + run: . /opt/ros/foxy/setup.sh && colcon test --event-handlers console_cohesion+ From ed1bb98621c1dd7f3a7fd4f8dd772934168a7a09 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Tue, 6 Oct 2020 13:34:48 +0900 Subject: [PATCH 0030/1765] removed ROS1 package Signed-off-by: mitsudome-r --- autoware_launch/CMakeLists.txt | 17 - autoware_launch/launch/autoware.launch | 63 - .../launch/logging_simulator.launch | 71 -- .../launch/planning_simulator.launch | 63 - autoware_launch/package.xml | 30 - autoware_launch/rviz/autoware.rviz | 1082 ----------------- control_launch/CMakeLists.txt | 13 - .../mpc_follower/mpc_follower_param.yaml | 42 - .../pure_pursuit/pure_pursuit_param.yaml | 7 - .../velocity_controller_param.yaml | 61 - control_launch/launch/control.launch | 52 - control_launch/package.xml | 22 - integration_launch/CMakeLists.txt | 14 - .../launch/ci_planning_simulator.launch | 14 - integration_launch/launch/release.launch | 13 - integration_launch/package.xml | 13 - localization_launch/CMakeLists.txt | 12 - .../launch/localization.launch | 28 - .../pose_estimator/pose_estimator.launch | 15 - .../pose_twist_fusion_filter.launch | 26 - .../twist_estimator/twist_estimator.launch | 7 - localization_launch/launch/util/util.launch | 45 - localization_launch/package.xml | 58 - map_launch/CMakeLists.txt | 14 - map_launch/launch/map.launch | 20 - map_launch/package.xml | 59 - perception_launch/CMakeLists.txt | 12 - ...camera_lidar_fusion_based_detection.launch | 62 - .../detection/detection.launch | 64 - .../detection/lidar_based_detection.launch | 9 - .../prediction/prediction.launch | 21 - .../tracking/tracking.launch | 12 - perception_launch/launch/perception.launch | 73 -- .../traffic_light.launch | 53 - perception_launch/package.xml | 27 - planning_launch/CMakeLists.txt | 13 - .../motion_velocity_optimizer.yaml | 36 - .../obstacle_avoidance_planner.yaml | 88 -- .../mission_planning/mission_planning.launch | 16 - planning_launch/launch/planning.launch | 16 - .../scenario_planning/lane_driving.launch | 16 - .../behavior_planning.launch | 48 - .../motion_planning/motion_planning.launch | 33 - .../launch/scenario_planning/parking.launch | 22 - .../scenario_planning.launch | 33 - planning_launch/package.xml | 59 - sensing_launch/CMakeLists.txt | 17 - sensing_launch/data/traffic_light_camera.yaml | 20 - .../launch/aip_customized/camera.launch | 22 - .../launch/aip_customized/gnss.launch | 30 - .../launch/aip_customized/imu.launch | 20 - .../launch/aip_customized/lidar.launch | 89 -- sensing_launch/launch/aip_s1/camera.launch | 22 - sensing_launch/launch/aip_s1/gnss.launch | 30 - sensing_launch/launch/aip_s1/imu.launch | 20 - sensing_launch/launch/aip_s1/lidar.launch | 89 -- sensing_launch/launch/aip_x1/camera.launch | 22 - sensing_launch/launch/aip_x1/gnss.launch | 30 - sensing_launch/launch/aip_x1/imu.launch | 20 - sensing_launch/launch/aip_x1/lidar.launch | 89 -- sensing_launch/launch/aip_x2/camera.launch | 22 - sensing_launch/launch/aip_x2/gnss.launch | 30 - sensing_launch/launch/aip_x2/imu.launch | 20 - sensing_launch/launch/aip_x2/lidar.launch | 89 -- sensing_launch/launch/aip_xx1/camera.launch | 14 - sensing_launch/launch/aip_xx1/gnss.launch | 30 - sensing_launch/launch/aip_xx1/imu.launch | 20 - sensing_launch/launch/aip_xx1/lidar.launch | 122 -- sensing_launch/launch/aip_xx2/camera.launch | 22 - sensing_launch/launch/aip_xx2/gnss.launch | 30 - sensing_launch/launch/aip_xx2/imu.launch | 20 - sensing_launch/launch/aip_xx2/lidar.launch | 89 -- sensing_launch/launch/livox_horizon.launch | 27 - sensing_launch/launch/sensing.launch | 30 - sensing_launch/launch/velodyne_VLP16.launch | 104 -- sensing_launch/launch/velodyne_VLP32C.launch | 104 -- sensing_launch/launch/velodyne_VLS128.launch | 104 -- sensing_launch/package.xml | 17 - system_launch/CMakeLists.txt | 13 - system_launch/launch/system.launch | 22 - system_launch/package.xml | 14 - vehicle_launch/CMakeLists.txt | 15 - .../aip_customized/sensors_calibration.yaml | 0 .../default/aip_s1/sensors_calibration.yaml | 0 .../default/aip_x1/sensors_calibration.yaml | 0 .../default/aip_x2/sensors_calibration.yaml | 0 .../aip_xx1/sensor_kit_calibration.yaml | 91 -- .../default/aip_xx1/sensors_calibration.yaml | 28 - .../default/aip_xx2/sensors_calibration.yaml | 0 vehicle_launch/launch/vehicle.launch | 24 - .../launch/vehicle_description.launch | 24 - .../launch/vehicle_interface.launch | 19 - vehicle_launch/package.xml | 21 - vehicle_launch/urdf/vehicle.xacro | 16 - 94 files changed, 4275 deletions(-) delete mode 100644 autoware_launch/CMakeLists.txt delete mode 100644 autoware_launch/launch/autoware.launch delete mode 100644 autoware_launch/launch/logging_simulator.launch delete mode 100644 autoware_launch/launch/planning_simulator.launch delete mode 100644 autoware_launch/package.xml delete mode 100644 autoware_launch/rviz/autoware.rviz delete mode 100644 control_launch/CMakeLists.txt delete mode 100644 control_launch/config/mpc_follower/mpc_follower_param.yaml delete mode 100644 control_launch/config/pure_pursuit/pure_pursuit_param.yaml delete mode 100644 control_launch/config/velocity_controller/velocity_controller_param.yaml delete mode 100644 control_launch/launch/control.launch delete mode 100644 control_launch/package.xml delete mode 100644 integration_launch/CMakeLists.txt delete mode 100644 integration_launch/launch/ci_planning_simulator.launch delete mode 100644 integration_launch/launch/release.launch delete mode 100644 integration_launch/package.xml delete mode 100644 localization_launch/CMakeLists.txt delete mode 100644 localization_launch/launch/localization.launch delete mode 100644 localization_launch/launch/pose_estimator/pose_estimator.launch delete mode 100644 localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch delete mode 100644 localization_launch/launch/twist_estimator/twist_estimator.launch delete mode 100644 localization_launch/launch/util/util.launch delete mode 100644 localization_launch/package.xml delete mode 100644 map_launch/CMakeLists.txt delete mode 100644 map_launch/launch/map.launch delete mode 100644 map_launch/package.xml delete mode 100644 perception_launch/CMakeLists.txt delete mode 100644 perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch delete mode 100644 perception_launch/launch/object_recognition/detection/detection.launch delete mode 100644 perception_launch/launch/object_recognition/detection/lidar_based_detection.launch delete mode 100644 perception_launch/launch/object_recognition/prediction/prediction.launch delete mode 100644 perception_launch/launch/object_recognition/tracking/tracking.launch delete mode 100644 perception_launch/launch/perception.launch delete mode 100644 perception_launch/launch/traffic_light_recognition/traffic_light.launch delete mode 100644 perception_launch/package.xml delete mode 100644 planning_launch/CMakeLists.txt delete mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml delete mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml delete mode 100644 planning_launch/launch/mission_planning/mission_planning.launch delete mode 100644 planning_launch/launch/planning.launch delete mode 100644 planning_launch/launch/scenario_planning/lane_driving.launch delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch delete mode 100644 planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch delete mode 100644 planning_launch/launch/scenario_planning/parking.launch delete mode 100644 planning_launch/launch/scenario_planning/scenario_planning.launch delete mode 100644 planning_launch/package.xml delete mode 100644 sensing_launch/CMakeLists.txt delete mode 100644 sensing_launch/data/traffic_light_camera.yaml delete mode 100644 sensing_launch/launch/aip_customized/camera.launch delete mode 100644 sensing_launch/launch/aip_customized/gnss.launch delete mode 100644 sensing_launch/launch/aip_customized/imu.launch delete mode 100644 sensing_launch/launch/aip_customized/lidar.launch delete mode 100644 sensing_launch/launch/aip_s1/camera.launch delete mode 100644 sensing_launch/launch/aip_s1/gnss.launch delete mode 100644 sensing_launch/launch/aip_s1/imu.launch delete mode 100644 sensing_launch/launch/aip_s1/lidar.launch delete mode 100644 sensing_launch/launch/aip_x1/camera.launch delete mode 100644 sensing_launch/launch/aip_x1/gnss.launch delete mode 100644 sensing_launch/launch/aip_x1/imu.launch delete mode 100644 sensing_launch/launch/aip_x1/lidar.launch delete mode 100644 sensing_launch/launch/aip_x2/camera.launch delete mode 100644 sensing_launch/launch/aip_x2/gnss.launch delete mode 100644 sensing_launch/launch/aip_x2/imu.launch delete mode 100644 sensing_launch/launch/aip_x2/lidar.launch delete mode 100644 sensing_launch/launch/aip_xx1/camera.launch delete mode 100644 sensing_launch/launch/aip_xx1/gnss.launch delete mode 100644 sensing_launch/launch/aip_xx1/imu.launch delete mode 100644 sensing_launch/launch/aip_xx1/lidar.launch delete mode 100644 sensing_launch/launch/aip_xx2/camera.launch delete mode 100644 sensing_launch/launch/aip_xx2/gnss.launch delete mode 100644 sensing_launch/launch/aip_xx2/imu.launch delete mode 100644 sensing_launch/launch/aip_xx2/lidar.launch delete mode 100644 sensing_launch/launch/livox_horizon.launch delete mode 100644 sensing_launch/launch/sensing.launch delete mode 100644 sensing_launch/launch/velodyne_VLP16.launch delete mode 100644 sensing_launch/launch/velodyne_VLP32C.launch delete mode 100644 sensing_launch/launch/velodyne_VLS128.launch delete mode 100644 sensing_launch/package.xml delete mode 100644 system_launch/CMakeLists.txt delete mode 100644 system_launch/launch/system.launch delete mode 100644 system_launch/package.xml delete mode 100644 vehicle_launch/CMakeLists.txt delete mode 100644 vehicle_launch/config/default/aip_customized/sensors_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_s1/sensors_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_x1/sensors_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_x2/sensors_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml delete mode 100644 vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml delete mode 100644 vehicle_launch/launch/vehicle.launch delete mode 100644 vehicle_launch/launch/vehicle_description.launch delete mode 100644 vehicle_launch/launch/vehicle_interface.launch delete mode 100644 vehicle_launch/package.xml delete mode 100644 vehicle_launch/urdf/vehicle.xacro diff --git a/autoware_launch/CMakeLists.txt b/autoware_launch/CMakeLists.txt deleted file mode 100644 index 87cc71d214..0000000000 --- a/autoware_launch/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(autoware_launch) - -find_package(catkin REQUIRED COMPONENTS - vehicle_launch - perception_launch - sensing_launch -) - -catkin_package() - -install( - DIRECTORY - launch - rviz - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch deleted file mode 100644 index cb4520f1a6..0000000000 --- a/autoware_launch/launch/autoware.launch +++ /dev/null @@ -1,63 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/autoware_launch/launch/logging_simulator.launch b/autoware_launch/launch/logging_simulator.launch deleted file mode 100644 index e364f63097..0000000000 --- a/autoware_launch/launch/logging_simulator.launch +++ /dev/null @@ -1,71 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch deleted file mode 100644 index ad9eb20702..0000000000 --- a/autoware_launch/launch/planning_simulator.launch +++ /dev/null @@ -1,63 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml deleted file mode 100644 index 025d0bcc0c..0000000000 --- a/autoware_launch/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - autoware_launch - 0.1.0 - The autoware_launch package - - Yukihiro Saito - Apache 2 - - catkin - vehicle_launch - perception_launch - sensing_launch - vehicle_launch - perception_launch - sensing_launch - - rosbridge_server - roswww - python-tornado - python3-tornado - python-bson - python3-bson - - - - - - - diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz deleted file mode 100644 index cbc0107cc8..0000000000 --- a/autoware_launch/rviz/autoware.rviz +++ /dev/null @@ -1,1082 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1 - - /Sensing1/GNSS1/PoseWithCovariance1/Covariance1/Position1 - - /Localization1/NDT1/PoseHistory1/Line1 - - /Localization1/NDT1/MonteCarloInitialPose1/Namespaces1 - - /Localization1/EKF1/PoseHistory1/Line1 - - /Planning1/ScenarioPlanning1 - - /Control1/Debug/MPC1/Namespaces1 - Splitter Ratio: 0.557669460773468 - Tree Height: 435 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /2D Dummy Pedestrian1 - - /2D Dummy Car1 - - /2D Checkpoint Pose1 - - /Delete All Objects1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: PointCloudMap - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel - Name: InitialPoseButtonPanel - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel - Name: InitialPoseButtonPanel -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Class: rviz/Group - Displays: - - Class: rviz/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: {} - Update Interval: 0 - Value: false - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: false - - Class: rviz/Group - Displays: - - Class: rviz_plugins/SteeringAngle - Enabled: true - Left: 128 - Length: 256 - Name: SteeringAngle - Scale: 17 - Text Color: 25; 255; 240 - Top: 128 - Topic: /vehicle/status/steering - Unreliable: false - Value: true - Value height offset: 0 - - Class: rviz_plugins/ConsoleMeter - Enabled: true - Left: 512 - Length: 256 - Name: ConsoleMeter - Scale: 3 - Text Color: 25; 255; 240 - Top: 128 - Topic: /vehicle/status/twist - Unreliable: false - Value: true - Value height offset: 0 - - Alpha: 1 - Class: rviz_plugins/VelocityHistory - Color Border Vel Max: 3 - Constant Color: - Color: 255; 255; 255 - Value: true - Enabled: true - Name: VelocityHistory - Scale: 0.30000001192092896 - Timeout: 10 - Topic: /vehicle/status/twist - Unreliable: false - Value: true - - Alpha: 0.30000001192092896 - Class: rviz/RobotModel - Collision Enabled: false - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera1/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera1/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera2/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera2/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera3/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera3/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera4/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera4/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera5/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera5/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera6/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera6/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - gnss_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - tamagawa/imu_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - traffic_light/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - traffic_light/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - velodyne_left: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_left_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_right: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_right_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_top: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_top_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Name: VehicleModel - Robot Description: robot_description - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz/PolarGridDisplay - Color: 255; 255; 255 - Delta Range: 10 - Enabled: true - Max Alpha: 1 - Max Range: 100 - Max Wave Alpha: 1 - Min Alpha: 0.20000000298023224 - Min Wave Alpha: 0.20000000298023224 - Name: PolarGridDisplay - Reference Frame: base_link - Value: true - Wave Color: 255; 255; 255 - Wave Velocity: 40 - - Class: rviz_plugins/TurnSignal - Enabled: true - Height: 256 - Left: 196 - Name: TurnSignal - Top: 350 - Topic: /control/turn_signal_cmd - Unreliable: false - Value: true - Width: 512 - Enabled: true - Name: Vehicle - Enabled: true - Name: System - - Class: rviz/Group - Displays: - - Alpha: 0.20000000298023224 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 28.71826171875 - Min Value: -7.4224700927734375 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 237 - Min Color: 211; 215; 207 - Min Intensity: 0 - Name: PointCloudMap - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 1 - Size (m): 0.05000000074505806 - Style: Points - Topic: /map/pointcloud_map - Unreliable: false - Use Fixed Frame: true - Use rainbow: false - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /map/vector_map_marker - Name: Lanelet2VectorMap - Namespaces: - center_lane_line: true - crosswalk_lanelets: true - lanelet direction: true - left_lane_bound: true - parking_lots: true - parking_space: true - right_lane_bound: true - road_lanelets: false - stop_lines: true - traffic_light: true - traffic_light_triangle: true - Queue Size: 100 - Value: true - Enabled: true - Name: Map - - Class: rviz/Group - Displays: - - Class: rviz/Group - Displays: - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 30 - Min Value: -2 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: ConcatenatePointCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 2 - Size (m): 0.009999999776482582 - Style: Points - Topic: /sensing/lidar/concatenated/pointcloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: false - Autocompute Value Bounds: - Max Value: 15 - Min Value: -2 - Value: false - Axis: Z - Channel Name: z - Class: rviz/PointCloud2 - Color: 0; 240; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 15 - Min Color: 0; 0; 0 - Min Intensity: -5 - Name: NoGroundPointCloud - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 10 - Size (m): 0.009999999776482582 - Style: Points - Topic: /sensing/lidar/no_ground/pointcloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Class: rviz/Polygon - Color: 25; 255; 0 - Enabled: false - Name: MesurementRange - Topic: /sensing/lidar/crop_box_filter/crop_box_polygon - Unreliable: false - Value: false - Enabled: true - Name: LiDAR - - Class: rviz/Group - Displays: - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz/PoseWithCovariance - Color: 233; 185; 110 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: false - Position: - Alpha: 0.20000000298023224 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Head Length: 0.699999988079071 - Head Radius: 1.2000000476837158 - Name: PoseWithCovariance - Shaft Length: 1 - Shaft Radius: 0.5 - Shape: Arrow - Topic: /sensing/gnss/pose_with_covariance - Unreliable: false - Value: true - Enabled: false - Name: GNSS - Enabled: true - Name: Sensing - - Class: rviz/Group - Displays: - - Class: rviz/Group - Displays: - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz/PoseWithCovariance - Color: 0; 170; 255 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovInitial - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: /localization/pose_estimator/initial_pose_with_covariance - Unreliable: false - Value: true - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz/PoseWithCovariance - Color: 0; 255; 0 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovAligned - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: /localization/pose_estimator/pose_with_covariance - Unreliable: false - Value: true - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: /localization/pose_estimator/pose - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 0; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Initial - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 10 - Size (m): 0.009999999776482582 - Style: Points - Topic: /localization/util/downsample/pointcloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Aligned - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 10 - Size (m): 0.009999999776482582 - Style: Points - Topic: /localization/pose_estimator/points_aligned - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /localization/pose_estimator/monte_carlo_initial_pose_marker - Name: MonteCarloInitialPose - Namespaces: {} - Queue Size: 1 - Value: true - Enabled: true - Name: NDT - - Class: rviz/Group - Displays: - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: /localization/pose_twist_fusion_filter/pose - Value: true - Enabled: true - Name: EKF - Enabled: true - Name: Localization - - Class: rviz/Group - Displays: - - Class: rviz/Group - Displays: - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /perception/object_recognition/detection/objects/visualization - Name: DynamicObjects - Namespaces: {} - Queue Size: 100 - Value: true - Enabled: false - Name: Detection - - Class: rviz/Group - Displays: - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /perception/object_recognition/tracking/objects/visualization - Name: DynamicObjects - Namespaces: {} - Queue Size: 100 - Value: true - Enabled: false - Name: Tracking - - Class: rviz/Group - Displays: - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /perception/object_recognition/objects/visualization - Name: DynamicObjects - Namespaces: - label: true - path: true - path confidence: true - shape: true - twist: true - Queue Size: 100 - Value: true - Enabled: true - Name: Prediction - - Class: rviz/Group - Displays: - - Class: rviz/Image - Enabled: true - Image Topic: /perception/traffic_light_recognition/debug/rois - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers - Name: Beam - Namespaces: {} - Queue Size: 100 - Value: true - Enabled: true - Name: TrafficLight - Enabled: true - Name: Perception - - Class: rviz/Group - Displays: - - Class: rviz/Group - Displays: - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/mission_planning/route_marker - Name: RouteArea - Namespaces: - goal_lanelets: true - left_lane_bound: true - right_lane_bound: true - route_lanelets: true - Queue Size: 100 - Value: true - - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.30000001192092896 - Class: rviz/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.5 - Name: GoalPose - Shaft Length: 3 - Shaft Radius: 0.20000000298023224 - Shape: Axes - Topic: /planning/mission_planning/goal - Unreliable: false - Value: true - Enabled: true - Name: MissionPlanning - - Class: rviz/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: ScenarioTrajectory - Topic: /planning/scenario_planning/trajectory - Unreliable: false - Value: true - View Path: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz/Group - Displays: - - Class: rviz/Group - Displays: - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: Path - Topic: /planning/scenario_planning/lane_driving/behavior_planning/path - Unreliable: false - Value: true - View Path: - Alpha: 0.4000000059604645 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 0.4000000059604645 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz/MarkerArray - Enabled: false - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path - Name: Arrow - Namespaces: {} - Queue Size: 100 - Value: false - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk - Name: Crosswalk - Namespaces: {} - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection - Name: Intersection - Namespaces: - conflicting_targets: true - detection_area: false - ego_lane: false - factor_text: true - judge_point_pose_line: true - path_raw: false - spline: false - stop_point_pose_line: false - stop_virtual_wall: true - stuck_vehicle_detect_area: false - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot - Name: Blind Spot - Namespaces: - conflict_area_for_blind_spot: false - conflicting_targets: true - detection_area: false - detection_area_for_blind_spot: false - factor_text: true - judge_point_pose_line: true - path_raw: false - stop_virtual_wall: true - spline: false - stop_point_pose_line: false - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light - Name: TrafficLight - Namespaces: {} - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line - Name: StopLine - Namespaces: - factor_text: true - stop_virtual_wall: true - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area - Name: DetectionArea - Namespaces: - factor_text: true - stop_virtual_wall: true - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/debug/predicted_path_markers - Name: LaneChange - Namespaces: - candidate_lane_change_path: false - ego_lane_change_path: false - ego_lane_follow_path: false - factor_text: true - object_predicted_path: false - selected_path: false - stop_virtual_wall: true - Queue Size: 100 - Value: true - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: LaneChangeCandidate - Topic: /planning/scenario_planning/lane_driving/lane_change_candidate_path - Unreliable: false - Value: true - View Path: - Alpha: 0.30000001192092896 - Color: 115; 210; 22 - Constant Color: true - Value: true - Width: 2 - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: true - Scale: 0.30000001192092896 - Value: false - Enabled: true - Name: BehaviorPlanning - - Class: rviz/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: false - Name: Trajectory - Topic: /planning/scenario_planning/lane_driving/trajectory - Unreliable: false - Value: false - View Path: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Name: ObstaclePointCloudStop - Namespaces: - collision_polygons: true - detection_polygons: true - factor_text: true - stop_virtual_wall: true - stop_obstacle_point: true - stop_obstacle_text: true - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker - Name: SurroundObstacleCheck - Namespaces: - factor_text: true - virtual_wall: true - obstacle_point: true - no_start_obstacle_text: true - Queue Size: 100 - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker - Name: ObstacleAvoidance - Namespaces: - base_bounds_line: false - bounds_candidate_base_text: false - bounds_candidate_for_base: false - bounds_candidate_for_top: false - bounds_candidate_top_text: false - constrain_rect: false - constrain_rect_text: false - constrain_rectlocation: false - current_vehicle_footprint: false - extending_constrain_rect: false - extending_constrain_rect_text: false - extending_constrain_rectlocation: false - fixed_mpt_points: false - fixed_points_for_extending: false - fixed_points_marker: false - interpolated_points_for_extending: false - interpolated_points_marker: false - interpolated_points_text_marker: false - non_fixed_points_for_extending: false - non_fixed_points_marker: false - num_vehicle_footprint: false - optimized_points_marker: false - optimized_points_text_marker: false - smoothed_points_text: false - straight_points_marker: false - top_bounds_line: false - vehicle_footprint: false - virtual_wall: true - virtual_wall_text: true - Queue Size: 100 - Value: true - Enabled: true - Name: MotionPlanning - Enabled: true - Name: LaneDriving - - Class: rviz/Group - Displays: - - Alpha: 0.699999988079071 - Class: rviz/Map - Color Scheme: map - Draw Behind: false - Enabled: false - Name: Costmap - Topic: /planning/scenario_planning/parking/costmap_generator/occupancy_grid - Unreliable: false - Use Timestamp: false - Value: false - - Alpha: 1 - Arrow Length: 0.30000001192092896 - Axes Length: 0.30000001192092896 - Axes Radius: 0.05000000074505806 - Class: rviz/PoseArray - Color: 255; 25; 0 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PartialPoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (3D) - Topic: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array - Unreliable: false - Value: true - - Alpha: 1 - Arrow Length: 0.5 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz/PoseArray - Color: 0; 0; 255 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (Flat) - Topic: /planning/scenario_planning/parking/freespace_planner/debug/pose_array - Unreliable: false - Value: true - Enabled: true - Name: Parking - Enabled: true - Name: ScenarioPlanning - Enabled: true - Name: Planning - - Class: rviz/Group - Displays: - - Class: rviz/MarkerArray - Enabled: false - Marker Topic: /control/trajectory_follower/mpc_follower/debug/markers - Name: Debug/MPC - Namespaces: {} - Queue Size: 100 - Value: false - - Class: rviz/MarkerArray - Enabled: false - Marker Topic: /control/trajectory_follower/pure_pursuit/debug/marker - Name: Debug/PurePursuit - Namespaces: - {} - Queue Size: 100 - Value: false - Enabled: true - Name: Control - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: viewer - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /planning/mission_planning/goal - - Class: rviz/PedestrianInitialPoseTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Theta std deviation: 0.0872664600610733 - Velocity: 1 - X std deviation: 0.009999999776482582 - Y std deviation: 0.009999999776482582 - Z position: 0 - Z std deviation: 0.009999999776482582 - - Class: rviz/CarInitialPoseTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Theta std deviation: 0.0872664600610733 - Velocity: 3 - X std deviation: 0.009999999776482582 - Y std deviation: 0.009999999776482582 - Z position: 0 - Z std deviation: 0.009999999776482582 - - Class: rviz/MissionCheckpointTool - Pose Topic: /planning/mission_planning/checkpoint - Theta std deviation: 0.2617993950843811 - X std deviation: 0.5 - Y std deviation: 0.5 - Z position: 0 - - Class: rviz/DeleteAllObjectsTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Value: true - Views: - Current: - Angle: 0 - Class: rviz/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz) - X: 0 - Y: 0 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1565 - Hide Left Dock: false - Hide Right Dock: false - Image: - collapsed: false - InitialPoseButtonPanel: - collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000033c00000563fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001f0000000c900fffffffb0000000a005600690065007700730100000233000000f2000000a400fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073010000032b000000a10000005c00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d00610067006501000003d2000001ce0000001600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000afd0000005afc0100000002fb0000000800540069006d0065010000000000000afd000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000007bb0000056300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 2813 - X: 67 - Y: 27 diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt deleted file mode 100644 index e469a18318..0000000000 --- a/control_launch/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(control_launch) - -find_package(catkin REQUIRED) - -catkin_package() - -install( - DIRECTORY - config - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower_param.yaml deleted file mode 100644 index c8d036356b..0000000000 --- a/control_launch/config/mpc_follower/mpc_follower_param.yaml +++ /dev/null @@ -1,42 +0,0 @@ - - -# -- system -- -ctrl_period: 0.03 # control period [s] -traj_resample_dist: 0.1 # path resampling interval [m] -enable_yaw_recalculation: false # flag for recalculation of yaw angle after resampling -admisible_position_error: 5.0 # stop mpc calculation when error is larger than the following value -admisible_yaw_error_: 1.57 # stop mpc calculation when error is larger than the following value - -# -- path smoothing -- -enable_path_smoothing: false # flag for path smoothing -path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing -curvature_smoothing_num: 15 # point-to-point index distance used in curvature calculation : curvature is calculated from three points p(i-num), p(i), p(i+num) - -# -- mpc optimization -- -qpoases_max_iter: 500 # max iteration number for quadratic programming -qp_solver_type: "osqp" # optimization solver type. option is unconstraint_fast, unconstraint, and qpoases_hotstart and osqp -mpc_prediction_horizon: 50 # prediction horizon step -mpc_prediction_dt: 0.1 # prediction horizon period [s] -mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q -mpc_weight_heading_error: 0.0 # heading error weight in matrix Q -mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q -mpc_weight_steering_input: 1.0 # steering error weight in matrix R -mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R -mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R -mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R -mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R -mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability -mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability -mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero - -# -- vehicle model -- -vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics -input_delay: 0.24 # steering input delay time for delay compensation -vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] -steer_lim_deg: 40.0 # steering angle limit [deg] -steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] -acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] -velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s] - -# -- lowpass filter for noise reduction -- -steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] diff --git a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml deleted file mode 100644 index 9d38aefc37..0000000000 --- a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml +++ /dev/null @@ -1,7 +0,0 @@ -# -- system -- -control_period: 0.033 - -# --algorithm -lookahead_distance_ratio: 2.2 -min_lookahead_distance: 2.5 -reverse_min_lookahead_distance: 7.0 diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml deleted file mode 100644 index 8c3149074a..0000000000 --- a/control_launch/config/velocity_controller/velocity_controller_param.yaml +++ /dev/null @@ -1,61 +0,0 @@ -# closest waypoint threshold -closest_waypoint_distance_threshold: 3.0 -closest_waypoint_angle_threshold: 0.7854 - -# stop state -stop_state_velocity: 0.0 -stop_state_acc: -3.4 -stop_state_entry_ego_speed: 0.2 -stop_state_entry_target_speed: 0.1 -stop_state_keep_stopping_dist: 0.5 - -# delay compensation -delay_compensation_time: 0.17 - -# emergency stop by this controller -emergency_stop_acc: -5.0 -emergency_stop_jerk: -3.0 - -# smooth stop -smooth_stop: - stop_dist: 3.0 - exit_ego_speed: 1.0 - entry_ego_speed: 0.8 - exit_target_speed: 1.0 - entry_target_speed: 0.2 - weak_brake_time: 1.0 - weak_brake_acc: -1.0 - increasing_brake_time: 1.0 - increasing_brake_gradient: -0.1 - stop_brake_time: 1.0 - stop_brake_acc: -3.4 - -# acceleration limit -max_acc: 3.0 -min_acc: -5.0 - -# jerk limit -max_jerk: 2.0 -min_jerk: -5.0 - -# slope compensation -enable_slope_compensation: true -max_pitch_rad: 0.1 -min_pitch_rad: -0.1 -lpf_pitch_gain: 0.95 - -# velocity feedback -pid_controller: - kp: 1.0 - ki: 0.1 - kd: 0 - max_out: 1.0 - min_out: -1.0 - max_p_effort: 1.0 - min_p_effort: -1.0 - max_i_effort: 0.3 - min_i_effort: -0.3 - max_d_effort: 0 - min_d_effort: 0 - current_velocity_threshold_pid_integration: 0.5 - lpf_velocity_error_gain: 0.9 \ No newline at end of file diff --git a/control_launch/launch/control.launch b/control_launch/launch/control.launch deleted file mode 100644 index 2a4000982c..0000000000 --- a/control_launch/launch/control.launch +++ /dev/null @@ -1,52 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/control_launch/package.xml b/control_launch/package.xml deleted file mode 100644 index c2f9157211..0000000000 --- a/control_launch/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - control_launch - 0.1.0 - The control_launch package - - - - - Takamasa Horibe - - - - - - TODO - - catkin - - - - diff --git a/integration_launch/CMakeLists.txt b/integration_launch/CMakeLists.txt deleted file mode 100644 index d303b4a8be..0000000000 --- a/integration_launch/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(integration_launch) - -find_package(catkin REQUIRED COMPONENTS - autoware_launch -) - -catkin_package() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/integration_launch/launch/ci_planning_simulator.launch b/integration_launch/launch/ci_planning_simulator.launch deleted file mode 100644 index 6ee6bff390..0000000000 --- a/integration_launch/launch/ci_planning_simulator.launch +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/integration_launch/launch/release.launch b/integration_launch/launch/release.launch deleted file mode 100644 index 9c7ea3ac6e..0000000000 --- a/integration_launch/launch/release.launch +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/integration_launch/package.xml b/integration_launch/package.xml deleted file mode 100644 index 5b908622b4..0000000000 --- a/integration_launch/package.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - integration_launch - 0.1.0 - The integration_launch package - - Hiroyuki Obinata - Apache 2 - - catkin - autoware_launch - - diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt deleted file mode 100644 index 047892fac7..0000000000 --- a/localization_launch/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(localization_launch) - -find_package(catkin REQUIRED) - -catkin_package() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/localization_launch/launch/localization.launch b/localization_launch/launch/localization.launch deleted file mode 100644 index 1543c92629..0000000000 --- a/localization_launch/launch/localization.launch +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch b/localization_launch/launch/pose_estimator/pose_estimator.launch deleted file mode 100644 index f70e6d3145..0000000000 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch deleted file mode 100644 index 76310afb0e..0000000000 --- a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch b/localization_launch/launch/twist_estimator/twist_estimator.launch deleted file mode 100644 index da8198ef72..0000000000 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/localization_launch/launch/util/util.launch b/localization_launch/launch/util/util.launch deleted file mode 100644 index a0558ce968..0000000000 --- a/localization_launch/launch/util/util.launch +++ /dev/null @@ -1,45 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - min_x: -60.0 - max_x: 60.0 - min_y: -60.0 - max_y: 60.0 - min_z: -30.0 - max_z: 50.0 - negative: False - - - - - - - - - - - - voxel_size_x: 3.0 - voxel_size_y: 3.0 - voxel_size_z: 3.0 - - - - diff --git a/localization_launch/package.xml b/localization_launch/package.xml deleted file mode 100644 index 48230f21cb..0000000000 --- a/localization_launch/package.xml +++ /dev/null @@ -1,58 +0,0 @@ - - - localization_launch - 0.1.0 - The localization_launch package - - - - - Yamato Ando - - - - - - Apache 2 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - - - - - diff --git a/map_launch/CMakeLists.txt b/map_launch/CMakeLists.txt deleted file mode 100644 index c318300cf5..0000000000 --- a/map_launch/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(map_launch) - -find_package(catkin REQUIRED) - -catkin_package() - -include_directories() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/map_launch/launch/map.launch b/map_launch/launch/map.launch deleted file mode 100644 index efa73f802c..0000000000 --- a/map_launch/launch/map.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/map_launch/package.xml b/map_launch/package.xml deleted file mode 100644 index df7aacd226..0000000000 --- a/map_launch/package.xml +++ /dev/null @@ -1,59 +0,0 @@ - - - map_launch - 0.1.0 - The map_launch package - - - - - mitsudome-r - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - - - - - - diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt deleted file mode 100644 index 3617fa63d2..0000000000 --- a/perception_launch/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(perception_launch) - -find_package(catkin REQUIRED) - -catkin_package() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch deleted file mode 100644 index b35bc13960..0000000000 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch +++ /dev/null @@ -1,62 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/detection/detection.launch b/perception_launch/launch/object_recognition/detection/detection.launch deleted file mode 100644 index f72fa95b37..0000000000 --- a/perception_launch/launch/object_recognition/detection/detection.launch +++ /dev/null @@ -1,64 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch deleted file mode 100644 index 6fe87c5e63..0000000000 --- a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch b/perception_launch/launch/object_recognition/prediction/prediction.launch deleted file mode 100644 index efd2535b23..0000000000 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch b/perception_launch/launch/object_recognition/tracking/tracking.launch deleted file mode 100644 index a2fc3947b2..0000000000 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/perception_launch/launch/perception.launch b/perception_launch/launch/perception.launch deleted file mode 100644 index ee29ebf677..0000000000 --- a/perception_launch/launch/perception.launch +++ /dev/null @@ -1,73 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch b/perception_launch/launch/traffic_light_recognition/traffic_light.launch deleted file mode 100644 index 72f6a0c0c4..0000000000 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/perception_launch/package.xml b/perception_launch/package.xml deleted file mode 100644 index 458e108e1e..0000000000 --- a/perception_launch/package.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - perception_launch - 0.1.0 - The perception_launch package - - Yukihiro Saito - Apache2 - - - catkin - dynamic_object_visualization - euclidean_cluster - pointcloud_to_laserscan - shape_estimation - dynamic_object_visualization - euclidean_cluster - pointcloud_to_laserscan - shape_estimation - dynamic_object_visualization - euclidean_cluster - pointcloud_to_laserscan - shape_estimation - - - - diff --git a/planning_launch/CMakeLists.txt b/planning_launch/CMakeLists.txt deleted file mode 100644 index 65406d7899..0000000000 --- a/planning_launch/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(planning_launch) - -find_package(catkin REQUIRED) - -catkin_package() - -install( - DIRECTORY - launch - config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml deleted file mode 100644 index c324867194..0000000000 --- a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml +++ /dev/null @@ -1,36 +0,0 @@ -max_velocity: 20.0 # max velocity limit [m/s] -max_accel: 1.0 # max acceleration limit [m/ss] -min_decel: -1.0 # min deceleration limit [m/ss] - -# curve parameters -max_lateral_accel: 0.5 # max lateral acceleration limit [m/ss] -min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] -decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit -decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit - -# engage & replan parameters -replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] -engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) -engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) -engage_exit_ratio: 0.5 # exit engage sequence to normal velocity plannning when the velocity exceeds engage_exit_ratio x engage_velocity. -stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] - -extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m] -extract_behind_dist: 5.0 # backward trajectory distance used for planning [m] -delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajecotory pose [radian] - -max_trajectory_length: 200.0 # max trajectory length for resampling [m] -min_trajectory_length: 30.0 # min trajectory length for resampling [m] -resample_time: 10.0 # resample total time [s] -resample_dt: 0.1 # resample time interval [s] -min_trajectory_interval_distance: 0.1 # resample points-interval length [m] - -# default weights -# L2: jerk = 100.0, v_weight = 100000.0, a_weight = 1000.0 -# Linf: jerk = 200.0, v_weight = 100000.0, a_weight = 5000.0 - -pseudo_jerk_weight: 100.0 # weight for "smoothness" cost -over_v_weight: 100000.0 # weight for "overspeed limit" cost -over_a_weight: 1000.0 # weight for "overaccel limit" cost - -algorithm_type: "L2" # Option : L2, Linf \ No newline at end of file diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml deleted file mode 100644 index 2f4677ee8c..0000000000 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml +++ /dev/null @@ -1,88 +0,0 @@ -# trajectory total/fixing length -trajectory_length: 200 # total trajectory length[m] -forward_fixing_distance: 20.0 # forward fixing length from base_link[m] -backward_fixing_distance: 5.0 # backward fixing length from base_link[m] - -# clearance(distance) when generating trajectory -clearance_from_road: 0.2 # clearance from road boundary[m] -clearance_from_object: 1.0 # clearance from object[m] -min_object_clearance_for_joint: 3.2 # minimum clearance from object[m] when judging is_including_only_smooth_range -extra_desired_clearance_from_road: 0.0 # extra desired clearance from road - -# clearance for unique points -clearance_for_straight_line_: 0.05 # minimum optimizing range around straight points -clearance_for_joint_: 3.2 # minimum optimizing range around joint points -clearance_for_only_smoothing: 0.1 # minimum optimizing range when applygin only smoothing -range_for_extend_joint: 0.1 # minimum optimizing range around joint points for extending -clearance_from_object_for_straight: 10.0 # minimum clearance from object when judging straight line - -# avoiding param -max_avoiding_objects_velocity_ms: .5 # maximum velocity for avoiding objects[m/s] -max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects[m/s] -center_line_width: 1.7 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, center line width around path points used for judging that object is required to avoid or not -acceleration_for_non_deceleration_range: 1.0 # assumed acceleration for calculating non deceleration range - -# solving quadratic programming -qp_max_iteration: 10000 # max iteration when solving QP -qp_eps_abs: 1.0e-8 # eps abs when solving OSQP -qp_eps_rel: 1.0e-11 # eps rel when solving OSQP -qp_eps_abs_for_extending: 1.0e-8 # eps abs when solving OSQP for extending -qp_eps_rel_for_extending: 1.0e-9 # eps rel when solving OSQP for extending -qp_eps_abs_for_visualizing: 1.0e-6 # eps abs when solving OSQP for visualizing -qp_eps_rel_for_visualizing: 1.0e-8 # eps rel when solving OSQP for visualizing - -# constrain space -is_getting_constraints_close2path_points: true # generate trajectory closer to path points -max_x_constrain_search_range: 0.0 # maximum x search range in local coordinate -coef_x_cosntrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction -coef_y_cosntrain_search_resolution: 0.5 # coef for fine sampling when exploring y direction -keep_space_shape_x: 0.2 # keep space for x direction from base_link[m] -keep_space_shape_y: 0.1 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, keep space for y direction from base_link[m] -max_lon_space_for_driveable_constraint: 0.5 # maximum lon(x) space when optimizing point[m] - -is_publishing_clearance_map: true # publish clearance map as nav_msgs::OccupancyGrid -is_publishing_area_with_objects: true # publish occupancy map as nav_msgs::OccupancyGrid -enable_avoidance: true # enable avoidance function -is_using_vehicle_config: true # use vehicle config -num_sampling_points: 100 # number of optimizing points -num_joint_buffer_points: 3 # number of joint buffer points -num_joint_buffer_points_for_extending: 6 # number of joint buffer points for extending -num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx -num_fix_points_for_extending: 50 # number of fixing points when extending -delta_arc_length_for_optimization: 1.0 # delta arc length when optimizing[m] -delta_arc_length_for_trajectory: 0.1 # delta arc length for trajectory[m] -delta_dist_threshold_for_closest_point: 3.0 # delta dist thres for closest point[m] -delta_yaw_threshold_for_closest_point: 1.046 #M_PI/3.0, delta yaw thres for closest point -delta_yaw_threshold_for_straight: 0.02 # delta dist thres for straight point - -# mpt param -# vehicle param for mpt -max_steer_deg: 30.0 # max steering angle [deg] -steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] - -# trajectory param for mpt -num_curvature_sampling_points: 5 # number of sampling points when calculating curvature -delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt[m] -num_fix_points_for_mpt: 8 # number of fixing points around ego vehicle - -# optimization param for mpt -is_hard_fixing_terminal_point: true # hard fixing terminal point -base_point_weight: 2000 # slack weight for lateral error around base_link -top_point_weight: 1000 # slack weight for lateral error around vehicle-top point -mid_point_weight: 1000 # slack weight for lateral error around the middle point -lat_error_weight: 10.0 # weight for lateral error -yaw_error_weight: 0.0 # weight for yaw error -steer_input_weight: 0.01 # weight for steering input -steer_rate_weight: 1 # weight for sttering rate -steer_acc_weight: 0.000001 # weight for steering acceration -terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point -terminal_yaw_error_weight: 100.0 # weight for yaw errror at terminal point -terminal_path_lat_error_weight: 1000.0 # weight for lateral errro at path end point -terminal_path_yaw_error_weight: 1000.0 # weight for yaw errro at path end point -zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero - -# replanning & trimming trajectory param outside algorithm -min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] -min_delta_time_sec_for_replan: 1.0 # minimum delta time for replan[second] -max_dist_for_extending_end_point: 5.0 # minimum delta dist thres for extending last point[m] -distance_for_path_shape_chagne_detection: 2.0 # minimum delta dist thres for detecting path shape change diff --git a/planning_launch/launch/mission_planning/mission_planning.launch b/planning_launch/launch/mission_planning/mission_planning.launch deleted file mode 100644 index d1e94f15c8..0000000000 --- a/planning_launch/launch/mission_planning/mission_planning.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/planning.launch b/planning_launch/launch/planning.launch deleted file mode 100644 index d8d6dd9a10..0000000000 --- a/planning_launch/launch/planning.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch b/planning_launch/launch/scenario_planning/lane_driving.launch deleted file mode 100644 index 27fa088c48..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch deleted file mode 100644 index e67dde71cd..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch deleted file mode 100644 index df97661f99..0000000000 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch +++ /dev/null @@ -1,33 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/parking.launch b/planning_launch/launch/scenario_planning/parking.launch deleted file mode 100644 index 0198eb09d0..0000000000 --- a/planning_launch/launch/scenario_planning/parking.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch b/planning_launch/launch/scenario_planning/scenario_planning.launch deleted file mode 100644 index c4d21f9103..0000000000 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch +++ /dev/null @@ -1,33 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning_launch/package.xml b/planning_launch/package.xml deleted file mode 100644 index 24d7f88c67..0000000000 --- a/planning_launch/package.xml +++ /dev/null @@ -1,59 +0,0 @@ - - - planning_launch - 0.1.0 - The planning_launch package - - - - - tier4 - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - - - - - - diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt deleted file mode 100644 index b557b1d09b..0000000000 --- a/sensing_launch/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(sensing_launch) - -find_package(catkin REQUIRED) - -# Force Tier IV's fork version -find_package(velodyne_driver 0.2.0 EXACT REQUIRED) -find_package(velodyne_pointcloud 0.2.0 EXACT REQUIRED) - -catkin_package() - -install( - DIRECTORY - launch - data - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/sensing_launch/data/traffic_light_camera.yaml b/sensing_launch/data/traffic_light_camera.yaml deleted file mode 100644 index a4c99fae96..0000000000 --- a/sensing_launch/data/traffic_light_camera.yaml +++ /dev/null @@ -1,20 +0,0 @@ -image_width: 1920 -image_height: 1080 -camera_name: traffic_light/camera -camera_matrix: - rows: 3 - cols: 3 - data: [2410.755261, 0.000000, 922.621401, 0.000000, 2403.573140, 534.752500, 0.000000, 0.000000, 1.000000] -distortion_model: plumb_bob -distortion_coefficients: - rows: 1 - cols: 5 - data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000] -rectification_matrix: - rows: 3 - cols: 3 - data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] -projection_matrix: - rows: 3 - cols: 4 - data: [2370.254883, 0.000000, 920.136018, 0.000000, 0.000000, 2388.885254, 535.599668, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000] \ No newline at end of file diff --git a/sensing_launch/launch/aip_customized/camera.launch b/sensing_launch/launch/aip_customized/camera.launch deleted file mode 100644 index c9e5fa4f26..0000000000 --- a/sensing_launch/launch/aip_customized/camera.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/gnss.launch b/sensing_launch/launch/aip_customized/gnss.launch deleted file mode 100644 index 51b386c056..0000000000 --- a/sensing_launch/launch/aip_customized/gnss.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/imu.launch b/sensing_launch/launch/aip_customized/imu.launch deleted file mode 100644 index b55a51ea8d..0000000000 --- a/sensing_launch/launch/aip_customized/imu.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_customized/lidar.launch b/sensing_launch/launch/aip_customized/lidar.launch deleted file mode 100644 index 0d8fdb3084..0000000000 --- a/sensing_launch/launch/aip_customized/lidar.launch +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/camera.launch b/sensing_launch/launch/aip_s1/camera.launch deleted file mode 100644 index c9e5fa4f26..0000000000 --- a/sensing_launch/launch/aip_s1/camera.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/gnss.launch b/sensing_launch/launch/aip_s1/gnss.launch deleted file mode 100644 index 51b386c056..0000000000 --- a/sensing_launch/launch/aip_s1/gnss.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/imu.launch b/sensing_launch/launch/aip_s1/imu.launch deleted file mode 100644 index b55a51ea8d..0000000000 --- a/sensing_launch/launch/aip_s1/imu.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_s1/lidar.launch b/sensing_launch/launch/aip_s1/lidar.launch deleted file mode 100644 index 0d8fdb3084..0000000000 --- a/sensing_launch/launch/aip_s1/lidar.launch +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/camera.launch b/sensing_launch/launch/aip_x1/camera.launch deleted file mode 100644 index c9e5fa4f26..0000000000 --- a/sensing_launch/launch/aip_x1/camera.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/gnss.launch b/sensing_launch/launch/aip_x1/gnss.launch deleted file mode 100644 index 51b386c056..0000000000 --- a/sensing_launch/launch/aip_x1/gnss.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/imu.launch b/sensing_launch/launch/aip_x1/imu.launch deleted file mode 100644 index b55a51ea8d..0000000000 --- a/sensing_launch/launch/aip_x1/imu.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x1/lidar.launch b/sensing_launch/launch/aip_x1/lidar.launch deleted file mode 100644 index 0d8fdb3084..0000000000 --- a/sensing_launch/launch/aip_x1/lidar.launch +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/camera.launch b/sensing_launch/launch/aip_x2/camera.launch deleted file mode 100644 index c9e5fa4f26..0000000000 --- a/sensing_launch/launch/aip_x2/camera.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/gnss.launch b/sensing_launch/launch/aip_x2/gnss.launch deleted file mode 100644 index 51b386c056..0000000000 --- a/sensing_launch/launch/aip_x2/gnss.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/imu.launch b/sensing_launch/launch/aip_x2/imu.launch deleted file mode 100644 index b55a51ea8d..0000000000 --- a/sensing_launch/launch/aip_x2/imu.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_x2/lidar.launch b/sensing_launch/launch/aip_x2/lidar.launch deleted file mode 100644 index 0d8fdb3084..0000000000 --- a/sensing_launch/launch/aip_x2/lidar.launch +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/camera.launch b/sensing_launch/launch/aip_xx1/camera.launch deleted file mode 100644 index fdd4c5365d..0000000000 --- a/sensing_launch/launch/aip_xx1/camera.launch +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/gnss.launch b/sensing_launch/launch/aip_xx1/gnss.launch deleted file mode 100644 index 51b386c056..0000000000 --- a/sensing_launch/launch/aip_xx1/gnss.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/imu.launch b/sensing_launch/launch/aip_xx1/imu.launch deleted file mode 100644 index b55a51ea8d..0000000000 --- a/sensing_launch/launch/aip_xx1/imu.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch deleted file mode 100644 index 46925430a2..0000000000 --- a/sensing_launch/launch/aip_xx1/lidar.launch +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud, - /sensing/lidar/rear/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/camera.launch b/sensing_launch/launch/aip_xx2/camera.launch deleted file mode 100644 index c9e5fa4f26..0000000000 --- a/sensing_launch/launch/aip_xx2/camera.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/gnss.launch b/sensing_launch/launch/aip_xx2/gnss.launch deleted file mode 100644 index 51b386c056..0000000000 --- a/sensing_launch/launch/aip_xx2/gnss.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/imu.launch b/sensing_launch/launch/aip_xx2/imu.launch deleted file mode 100644 index b55a51ea8d..0000000000 --- a/sensing_launch/launch/aip_xx2/imu.launch +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/aip_xx2/lidar.launch b/sensing_launch/launch/aip_xx2/lidar.launch deleted file mode 100644 index 0d8fdb3084..0000000000 --- a/sensing_launch/launch/aip_xx2/lidar.launch +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/livox_horizon.launch b/sensing_launch/launch/livox_horizon.launch deleted file mode 100644 index 1e5c5d8e7a..0000000000 --- a/sensing_launch/launch/livox_horizon.launch +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/sensing.launch b/sensing_launch/launch/sensing.launch deleted file mode 100644 index 019af23690..0000000000 --- a/sensing_launch/launch/sensing.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_VLP16.launch b/sensing_launch/launch/velodyne_VLP16.launch deleted file mode 100644 index 6cf557309d..0000000000 --- a/sensing_launch/launch/velodyne_VLP16.launch +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_VLP32C.launch b/sensing_launch/launch/velodyne_VLP32C.launch deleted file mode 100644 index bce757ecb7..0000000000 --- a/sensing_launch/launch/velodyne_VLP32C.launch +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/launch/velodyne_VLS128.launch b/sensing_launch/launch/velodyne_VLS128.launch deleted file mode 100644 index 0d3b9abd35..0000000000 --- a/sensing_launch/launch/velodyne_VLS128.launch +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml deleted file mode 100644 index e315fa965b..0000000000 --- a/sensing_launch/package.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - sensing_launch - 0.1.0 - The sensing_launch package - - Yukihiro Saito - Apache2 - - catkin - - velodyne_driver - velodyne_pointcloud - - - - diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt deleted file mode 100644 index 2519b3e2f0..0000000000 --- a/system_launch/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(system_launch) - -find_package(catkin REQUIRED COMPONENTS -) - -catkin_package() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/system_launch/launch/system.launch b/system_launch/launch/system.launch deleted file mode 100644 index b30703b4fd..0000000000 --- a/system_launch/launch/system.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/system_launch/package.xml b/system_launch/package.xml deleted file mode 100644 index 7f5f70ae0c..0000000000 --- a/system_launch/package.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - system_launch - 0.1.0 - The system_launch package - - Kenji Miyake - Apache 2 - - catkin - - - - diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt deleted file mode 100644 index 331b62f499..0000000000 --- a/vehicle_launch/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(vehicle_launch) - -add_compile_options(-std=c++14) - -find_package(catkin REQUIRED) - -catkin_package() - -install(DIRECTORY - launch - config - urdf - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/vehicle_launch/config/default/aip_customized/sensors_calibration.yaml b/vehicle_launch/config/default/aip_customized/sensors_calibration.yaml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/vehicle_launch/config/default/aip_s1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_s1/sensors_calibration.yaml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/vehicle_launch/config/default/aip_x2/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x2/sensors_calibration.yaml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml b/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml deleted file mode 100644 index d9d1f599e4..0000000000 --- a/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml +++ /dev/null @@ -1,91 +0,0 @@ -sensor_kit_base_link2camera0: - x: 0.10731 - y: 0.56343 - z: -0.27697 - roll: -0.025 - pitch: 0.315 - yaw: 1.035 -sensor_kit_base_link2camera1: - x: -0.10731 - y: -0.56343 - z: -0.27697 - roll: -0.025 - pitch: 0.32 - yaw: -2.12 -sensor_kit_base_link2camera2: - x: 0.10731 - y: -0.56343 - z: -0.27697 - roll: -0.00 - pitch: 0.335 - yaw: -1.04 -sensor_kit_base_link2camera3: - x: -0.10731 - y: 0.56343 - z: -0.27697 - roll: 0.0 - pitch: 0.325 - yaw: 2.0943951 -sensor_kit_base_link2camera4: - x: 0.07356 - y: 0.0 - z: -0.0525 - roll: 0.0 - pitch: -0.03 - yaw: -0.005 -sensor_kit_base_link2camera5: - x: -0.07356 - y: 0.0 - z: -0.0525 - roll: 0.0 - pitch: -0.01 - yaw: 3.125 -sensor_kit_base_link2traffic_light_right_camera: - x: 0.05 - y: -0.0175 - z: -0.1 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 -sensor_kit_base_link2traffic_light_left_camera: - x: 0.05 - y: 0.0175 - z: -0.1 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 -sensor_kit_base_link2velodyne_top_base_link: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 0.0 - pitch: 0.0 - yaw: 1.575 -sensor_kit_base_link2velodyne_left_base_link: - x: 0.0 - y: 0.56362 - z: -0.30555 - roll: -0.02 - pitch: 0.71 - yaw: 1.575 -sensor_kit_base_link2velodyne_right_base_link: - x: 0.0 - y: -0.56362 - z: -0.30555 - roll: -0.01 - pitch: 0.71 - yaw: -1.580 -sensor_kit_base_link2gnss: - x: -0.1 - y: 0.0 - z: -0.2 - roll: 0.0 - pitch: 0.0 - yaw: 0.0 -sensor_kit_base_link2imu_tamagawa: - x: 0.0 - y: 0.0 - z: 0.0 - roll: 3.14159265359 - pitch: 0.0 - yaw: 3.14159265359 diff --git a/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml deleted file mode 100644 index 1aa0972391..0000000000 --- a/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml +++ /dev/null @@ -1,28 +0,0 @@ -base_link2sensor_kit_base_link: - x: 0.9 - y: 0.0 - z: 2.0 - roll: -0.001 - pitch: 0.015 - yaw: -0.0364 -base_link2livox_front_right_base_link: - x: 3.290 - y: -0.65485 - z: 0.3216 - roll: 0.0 - pitch: 0.0 - yaw: -0.872664444 -base_link2livox_front_left_base_link: - x: 3.290 - y: 0.65485 - z: 0.3016 - roll: -0.021 - pitch: 0.05 - yaw: 0.872664444 -base_link2velodyne_rear_base_link: - x: -0.358 - y: 0.0 - z: 1.631 - roll: -0.02 - pitch: 0.7281317 - yaw: 3.141592 diff --git a/vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml b/vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/vehicle_launch/launch/vehicle.launch b/vehicle_launch/launch/vehicle.launch deleted file mode 100644 index b6191e70cd..0000000000 --- a/vehicle_launch/launch/vehicle.launch +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle_launch/launch/vehicle_description.launch b/vehicle_launch/launch/vehicle_description.launch deleted file mode 100644 index 7a09cd6e13..0000000000 --- a/vehicle_launch/launch/vehicle_description.launch +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/vehicle_launch/launch/vehicle_interface.launch b/vehicle_launch/launch/vehicle_interface.launch deleted file mode 100644 index 675ff78397..0000000000 --- a/vehicle_launch/launch/vehicle_interface.launch +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml deleted file mode 100644 index e20bbfeefd..0000000000 --- a/vehicle_launch/package.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - vehicle_launch - 0.1.0 - The vehicle_launch package - - Yukihiro Saito - Apache2 - - - catkin - camera_description - imu_description - livox_description - velodyne_description - robot_state_publisher - - roscpp - - - diff --git a/vehicle_launch/urdf/vehicle.xacro b/vehicle_launch/urdf/vehicle.xacro deleted file mode 100644 index 30db9c6a7c..0000000000 --- a/vehicle_launch/urdf/vehicle.xacro +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - From 73844703f2d60624a5b461af055eeefa932d91c5 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Tue, 6 Oct 2020 13:37:35 +0900 Subject: [PATCH 0031/1765] fix branch name in ci Signed-off-by: mitsudome-r --- .github/workflows/build_and_test.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 79dd0ab0a1..fb0faf937a 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -4,7 +4,7 @@ on: pull_request: push: branches: - - master + - ros2 jobs: build-and-test: From 90521ba4a5920aad4d2c250026c5c11161a7c5ce Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Thu, 8 Oct 2020 17:42:29 +0900 Subject: [PATCH 0032/1765] Revert "removed ROS1 package" This reverts commit ed1bb98621c1dd7f3a7fd4f8dd772934168a7a09. --- autoware_launch/CMakeLists.txt | 17 + autoware_launch/launch/autoware.launch | 63 + .../launch/logging_simulator.launch | 71 ++ .../launch/planning_simulator.launch | 63 + autoware_launch/package.xml | 30 + autoware_launch/rviz/autoware.rviz | 1082 +++++++++++++++++ control_launch/CMakeLists.txt | 13 + .../mpc_follower/mpc_follower_param.yaml | 42 + .../pure_pursuit/pure_pursuit_param.yaml | 7 + .../velocity_controller_param.yaml | 61 + control_launch/launch/control.launch | 52 + control_launch/package.xml | 22 + integration_launch/CMakeLists.txt | 14 + .../launch/ci_planning_simulator.launch | 14 + integration_launch/launch/release.launch | 13 + integration_launch/package.xml | 13 + localization_launch/CMakeLists.txt | 12 + .../launch/localization.launch | 28 + .../pose_estimator/pose_estimator.launch | 15 + .../pose_twist_fusion_filter.launch | 26 + .../twist_estimator/twist_estimator.launch | 7 + localization_launch/launch/util/util.launch | 45 + localization_launch/package.xml | 58 + map_launch/CMakeLists.txt | 14 + map_launch/launch/map.launch | 20 + map_launch/package.xml | 59 + perception_launch/CMakeLists.txt | 12 + ...camera_lidar_fusion_based_detection.launch | 62 + .../detection/detection.launch | 64 + .../detection/lidar_based_detection.launch | 9 + .../prediction/prediction.launch | 21 + .../tracking/tracking.launch | 12 + perception_launch/launch/perception.launch | 73 ++ .../traffic_light.launch | 53 + perception_launch/package.xml | 27 + planning_launch/CMakeLists.txt | 13 + .../motion_velocity_optimizer.yaml | 36 + .../obstacle_avoidance_planner.yaml | 88 ++ .../mission_planning/mission_planning.launch | 16 + planning_launch/launch/planning.launch | 16 + .../scenario_planning/lane_driving.launch | 16 + .../behavior_planning.launch | 48 + .../motion_planning/motion_planning.launch | 33 + .../launch/scenario_planning/parking.launch | 22 + .../scenario_planning.launch | 33 + planning_launch/package.xml | 59 + sensing_launch/CMakeLists.txt | 17 + sensing_launch/data/traffic_light_camera.yaml | 20 + .../launch/aip_customized/camera.launch | 22 + .../launch/aip_customized/gnss.launch | 30 + .../launch/aip_customized/imu.launch | 20 + .../launch/aip_customized/lidar.launch | 89 ++ sensing_launch/launch/aip_s1/camera.launch | 22 + sensing_launch/launch/aip_s1/gnss.launch | 30 + sensing_launch/launch/aip_s1/imu.launch | 20 + sensing_launch/launch/aip_s1/lidar.launch | 89 ++ sensing_launch/launch/aip_x1/camera.launch | 22 + sensing_launch/launch/aip_x1/gnss.launch | 30 + sensing_launch/launch/aip_x1/imu.launch | 20 + sensing_launch/launch/aip_x1/lidar.launch | 89 ++ sensing_launch/launch/aip_x2/camera.launch | 22 + sensing_launch/launch/aip_x2/gnss.launch | 30 + sensing_launch/launch/aip_x2/imu.launch | 20 + sensing_launch/launch/aip_x2/lidar.launch | 89 ++ sensing_launch/launch/aip_xx1/camera.launch | 14 + sensing_launch/launch/aip_xx1/gnss.launch | 30 + sensing_launch/launch/aip_xx1/imu.launch | 20 + sensing_launch/launch/aip_xx1/lidar.launch | 122 ++ sensing_launch/launch/aip_xx2/camera.launch | 22 + sensing_launch/launch/aip_xx2/gnss.launch | 30 + sensing_launch/launch/aip_xx2/imu.launch | 20 + sensing_launch/launch/aip_xx2/lidar.launch | 89 ++ sensing_launch/launch/livox_horizon.launch | 27 + sensing_launch/launch/sensing.launch | 30 + sensing_launch/launch/velodyne_VLP16.launch | 104 ++ sensing_launch/launch/velodyne_VLP32C.launch | 104 ++ sensing_launch/launch/velodyne_VLS128.launch | 104 ++ sensing_launch/package.xml | 17 + system_launch/CMakeLists.txt | 13 + system_launch/launch/system.launch | 22 + system_launch/package.xml | 14 + vehicle_launch/CMakeLists.txt | 15 + .../aip_customized/sensors_calibration.yaml | 0 .../default/aip_s1/sensors_calibration.yaml | 0 .../default/aip_x1/sensors_calibration.yaml | 0 .../default/aip_x2/sensors_calibration.yaml | 0 .../aip_xx1/sensor_kit_calibration.yaml | 91 ++ .../default/aip_xx1/sensors_calibration.yaml | 28 + .../default/aip_xx2/sensors_calibration.yaml | 0 vehicle_launch/launch/vehicle.launch | 24 + .../launch/vehicle_description.launch | 24 + .../launch/vehicle_interface.launch | 19 + vehicle_launch/package.xml | 21 + vehicle_launch/urdf/vehicle.xacro | 16 + 94 files changed, 4275 insertions(+) create mode 100644 autoware_launch/CMakeLists.txt create mode 100644 autoware_launch/launch/autoware.launch create mode 100644 autoware_launch/launch/logging_simulator.launch create mode 100644 autoware_launch/launch/planning_simulator.launch create mode 100644 autoware_launch/package.xml create mode 100644 autoware_launch/rviz/autoware.rviz create mode 100644 control_launch/CMakeLists.txt create mode 100644 control_launch/config/mpc_follower/mpc_follower_param.yaml create mode 100644 control_launch/config/pure_pursuit/pure_pursuit_param.yaml create mode 100644 control_launch/config/velocity_controller/velocity_controller_param.yaml create mode 100644 control_launch/launch/control.launch create mode 100644 control_launch/package.xml create mode 100644 integration_launch/CMakeLists.txt create mode 100644 integration_launch/launch/ci_planning_simulator.launch create mode 100644 integration_launch/launch/release.launch create mode 100644 integration_launch/package.xml create mode 100644 localization_launch/CMakeLists.txt create mode 100644 localization_launch/launch/localization.launch create mode 100644 localization_launch/launch/pose_estimator/pose_estimator.launch create mode 100644 localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch create mode 100644 localization_launch/launch/twist_estimator/twist_estimator.launch create mode 100644 localization_launch/launch/util/util.launch create mode 100644 localization_launch/package.xml create mode 100644 map_launch/CMakeLists.txt create mode 100644 map_launch/launch/map.launch create mode 100644 map_launch/package.xml create mode 100644 perception_launch/CMakeLists.txt create mode 100644 perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch create mode 100644 perception_launch/launch/object_recognition/detection/detection.launch create mode 100644 perception_launch/launch/object_recognition/detection/lidar_based_detection.launch create mode 100644 perception_launch/launch/object_recognition/prediction/prediction.launch create mode 100644 perception_launch/launch/object_recognition/tracking/tracking.launch create mode 100644 perception_launch/launch/perception.launch create mode 100644 perception_launch/launch/traffic_light_recognition/traffic_light.launch create mode 100644 perception_launch/package.xml create mode 100644 planning_launch/CMakeLists.txt create mode 100644 planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml create mode 100644 planning_launch/launch/mission_planning/mission_planning.launch create mode 100644 planning_launch/launch/planning.launch create mode 100644 planning_launch/launch/scenario_planning/lane_driving.launch create mode 100644 planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch create mode 100644 planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch create mode 100644 planning_launch/launch/scenario_planning/parking.launch create mode 100644 planning_launch/launch/scenario_planning/scenario_planning.launch create mode 100644 planning_launch/package.xml create mode 100644 sensing_launch/CMakeLists.txt create mode 100644 sensing_launch/data/traffic_light_camera.yaml create mode 100644 sensing_launch/launch/aip_customized/camera.launch create mode 100644 sensing_launch/launch/aip_customized/gnss.launch create mode 100644 sensing_launch/launch/aip_customized/imu.launch create mode 100644 sensing_launch/launch/aip_customized/lidar.launch create mode 100644 sensing_launch/launch/aip_s1/camera.launch create mode 100644 sensing_launch/launch/aip_s1/gnss.launch create mode 100644 sensing_launch/launch/aip_s1/imu.launch create mode 100644 sensing_launch/launch/aip_s1/lidar.launch create mode 100644 sensing_launch/launch/aip_x1/camera.launch create mode 100644 sensing_launch/launch/aip_x1/gnss.launch create mode 100644 sensing_launch/launch/aip_x1/imu.launch create mode 100644 sensing_launch/launch/aip_x1/lidar.launch create mode 100644 sensing_launch/launch/aip_x2/camera.launch create mode 100644 sensing_launch/launch/aip_x2/gnss.launch create mode 100644 sensing_launch/launch/aip_x2/imu.launch create mode 100644 sensing_launch/launch/aip_x2/lidar.launch create mode 100644 sensing_launch/launch/aip_xx1/camera.launch create mode 100644 sensing_launch/launch/aip_xx1/gnss.launch create mode 100644 sensing_launch/launch/aip_xx1/imu.launch create mode 100644 sensing_launch/launch/aip_xx1/lidar.launch create mode 100644 sensing_launch/launch/aip_xx2/camera.launch create mode 100644 sensing_launch/launch/aip_xx2/gnss.launch create mode 100644 sensing_launch/launch/aip_xx2/imu.launch create mode 100644 sensing_launch/launch/aip_xx2/lidar.launch create mode 100644 sensing_launch/launch/livox_horizon.launch create mode 100644 sensing_launch/launch/sensing.launch create mode 100644 sensing_launch/launch/velodyne_VLP16.launch create mode 100644 sensing_launch/launch/velodyne_VLP32C.launch create mode 100644 sensing_launch/launch/velodyne_VLS128.launch create mode 100644 sensing_launch/package.xml create mode 100644 system_launch/CMakeLists.txt create mode 100644 system_launch/launch/system.launch create mode 100644 system_launch/package.xml create mode 100644 vehicle_launch/CMakeLists.txt create mode 100644 vehicle_launch/config/default/aip_customized/sensors_calibration.yaml create mode 100644 vehicle_launch/config/default/aip_s1/sensors_calibration.yaml create mode 100644 vehicle_launch/config/default/aip_x1/sensors_calibration.yaml create mode 100644 vehicle_launch/config/default/aip_x2/sensors_calibration.yaml create mode 100644 vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml create mode 100644 vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml create mode 100644 vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml create mode 100644 vehicle_launch/launch/vehicle.launch create mode 100644 vehicle_launch/launch/vehicle_description.launch create mode 100644 vehicle_launch/launch/vehicle_interface.launch create mode 100644 vehicle_launch/package.xml create mode 100644 vehicle_launch/urdf/vehicle.xacro diff --git a/autoware_launch/CMakeLists.txt b/autoware_launch/CMakeLists.txt new file mode 100644 index 0000000000..87cc71d214 --- /dev/null +++ b/autoware_launch/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.8.3) +project(autoware_launch) + +find_package(catkin REQUIRED COMPONENTS + vehicle_launch + perception_launch + sensing_launch +) + +catkin_package() + +install( + DIRECTORY + launch + rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch new file mode 100644 index 0000000000..cb4520f1a6 --- /dev/null +++ b/autoware_launch/launch/autoware.launch @@ -0,0 +1,63 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/logging_simulator.launch b/autoware_launch/launch/logging_simulator.launch new file mode 100644 index 0000000000..e364f63097 --- /dev/null +++ b/autoware_launch/launch/logging_simulator.launch @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch new file mode 100644 index 0000000000..ad9eb20702 --- /dev/null +++ b/autoware_launch/launch/planning_simulator.launch @@ -0,0 +1,63 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml new file mode 100644 index 0000000000..025d0bcc0c --- /dev/null +++ b/autoware_launch/package.xml @@ -0,0 +1,30 @@ + + + autoware_launch + 0.1.0 + The autoware_launch package + + Yukihiro Saito + Apache 2 + + catkin + vehicle_launch + perception_launch + sensing_launch + vehicle_launch + perception_launch + sensing_launch + + rosbridge_server + roswww + python-tornado + python3-tornado + python-bson + python3-bson + + + + + + + diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz new file mode 100644 index 0000000000..cbc0107cc8 --- /dev/null +++ b/autoware_launch/rviz/autoware.rviz @@ -0,0 +1,1082 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1 + - /Sensing1/GNSS1/PoseWithCovariance1/Covariance1/Position1 + - /Localization1/NDT1/PoseHistory1/Line1 + - /Localization1/NDT1/MonteCarloInitialPose1/Namespaces1 + - /Localization1/EKF1/PoseHistory1/Line1 + - /Planning1/ScenarioPlanning1 + - /Control1/Debug/MPC1/Namespaces1 + Splitter Ratio: 0.557669460773468 + Tree Height: 435 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /2D Dummy Pedestrian1 + - /2D Dummy Car1 + - /2D Checkpoint Pose1 + - /Delete All Objects1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: PointCloudMap + - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + Name: InitialPoseButtonPanel + - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + Name: InitialPoseButtonPanel +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Group + Displays: + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: {} + Update Interval: 0 + Value: false + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: false + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: false + - Class: rviz/Group + Displays: + - Class: rviz_plugins/SteeringAngle + Enabled: true + Left: 128 + Length: 256 + Name: SteeringAngle + Scale: 17 + Text Color: 25; 255; 240 + Top: 128 + Topic: /vehicle/status/steering + Unreliable: false + Value: true + Value height offset: 0 + - Class: rviz_plugins/ConsoleMeter + Enabled: true + Left: 512 + Length: 256 + Name: ConsoleMeter + Scale: 3 + Text Color: 25; 255; 240 + Top: 128 + Topic: /vehicle/status/twist + Unreliable: false + Value: true + Value height offset: 0 + - Alpha: 1 + Class: rviz_plugins/VelocityHistory + Color Border Vel Max: 3 + Constant Color: + Color: 255; 255; 255 + Value: true + Enabled: true + Name: VelocityHistory + Scale: 0.30000001192092896 + Timeout: 10 + Topic: /vehicle/status/twist + Unreliable: false + Value: true + - Alpha: 0.30000001192092896 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera1/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera1/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera2/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera2/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera3/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera3/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera4/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera4/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera5/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera5/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + camera6/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera6/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + gnss_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tamagawa/imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + velodyne_left: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_left_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_right: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_right_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_top: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_top_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: VehicleModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/PolarGridDisplay + Color: 255; 255; 255 + Delta Range: 10 + Enabled: true + Max Alpha: 1 + Max Range: 100 + Max Wave Alpha: 1 + Min Alpha: 0.20000000298023224 + Min Wave Alpha: 0.20000000298023224 + Name: PolarGridDisplay + Reference Frame: base_link + Value: true + Wave Color: 255; 255; 255 + Wave Velocity: 40 + - Class: rviz_plugins/TurnSignal + Enabled: true + Height: 256 + Left: 196 + Name: TurnSignal + Top: 350 + Topic: /control/turn_signal_cmd + Unreliable: false + Value: true + Width: 512 + Enabled: true + Name: Vehicle + Enabled: true + Name: System + - Class: rviz/Group + Displays: + - Alpha: 0.20000000298023224 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 28.71826171875 + Min Value: -7.4224700927734375 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 237 + Min Color: 211; 215; 207 + Min Intensity: 0 + Name: PointCloudMap + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 1 + Size (m): 0.05000000074505806 + Style: Points + Topic: /map/pointcloud_map + Unreliable: false + Use Fixed Frame: true + Use rainbow: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /map/vector_map_marker + Name: Lanelet2VectorMap + Namespaces: + center_lane_line: true + crosswalk_lanelets: true + lanelet direction: true + left_lane_bound: true + parking_lots: true + parking_space: true + right_lane_bound: true + road_lanelets: false + stop_lines: true + traffic_light: true + traffic_light_triangle: true + Queue Size: 100 + Value: true + Enabled: true + Name: Map + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 30 + Min Value: -2 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: ConcatenatePointCloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 2 + Size (m): 0.009999999776482582 + Style: Points + Topic: /sensing/lidar/concatenated/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: false + Autocompute Value Bounds: + Max Value: 15 + Min Value: -2 + Value: false + Axis: Z + Channel Name: z + Class: rviz/PointCloud2 + Color: 0; 240; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 15 + Min Color: 0; 0; 0 + Min Intensity: -5 + Name: NoGroundPointCloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.009999999776482582 + Style: Points + Topic: /sensing/lidar/no_ground/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz/Polygon + Color: 25; 255; 0 + Enabled: false + Name: MesurementRange + Topic: /sensing/lidar/crop_box_filter/crop_box_polygon + Unreliable: false + Value: false + Enabled: true + Name: LiDAR + - Class: rviz/Group + Displays: + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/PoseWithCovariance + Color: 233; 185; 110 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: false + Position: + Alpha: 0.20000000298023224 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.699999988079071 + Head Radius: 1.2000000476837158 + Name: PoseWithCovariance + Shaft Length: 1 + Shaft Radius: 0.5 + Shape: Arrow + Topic: /sensing/gnss/pose_with_covariance + Unreliable: false + Value: true + Enabled: false + Name: GNSS + Enabled: true + Name: Sensing + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/PoseWithCovariance + Color: 0; 170; 255 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.4000000059604645 + Head Radius: 0.6000000238418579 + Name: PoseWithCovInitial + Shaft Length: 0.6000000238418579 + Shaft Radius: 0.30000001192092896 + Shape: Arrow + Topic: /localization/pose_estimator/initial_pose_with_covariance + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/PoseWithCovariance + Color: 0; 255; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.4000000059604645 + Head Radius: 0.6000000238418579 + Name: PoseWithCovAligned + Shaft Length: 0.6000000238418579 + Shaft Radius: 0.30000001192092896 + Shape: Arrow + Topic: /localization/pose_estimator/pose_with_covariance + Unreliable: false + Value: true + - Buffer Size: 200 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Color: 170; 255; 127 + Value: true + Width: 0.10000000149011612 + Name: PoseHistory + Topic: /localization/pose_estimator/pose + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 0; 255; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Initial + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.009999999776482582 + Style: Points + Topic: /localization/util/downsample/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 85; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 85; 255; 127 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Aligned + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.009999999776482582 + Style: Points + Topic: /localization/pose_estimator/points_aligned + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /localization/pose_estimator/monte_carlo_initial_pose_marker + Name: MonteCarloInitialPose + Namespaces: {} + Queue Size: 1 + Value: true + Enabled: true + Name: NDT + - Class: rviz/Group + Displays: + - Buffer Size: 1000 + Class: rviz_plugins::PoseHistory + Enabled: true + Line: + Color: 0; 255; 255 + Value: true + Width: 0.10000000149011612 + Name: PoseHistory + Topic: /localization/pose_twist_fusion_filter/pose + Value: true + Enabled: true + Name: EKF + Enabled: true + Name: Localization + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/object_recognition/detection/objects/visualization + Name: DynamicObjects + Namespaces: {} + Queue Size: 100 + Value: true + Enabled: false + Name: Detection + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/object_recognition/tracking/objects/visualization + Name: DynamicObjects + Namespaces: {} + Queue Size: 100 + Value: true + Enabled: false + Name: Tracking + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/object_recognition/objects/visualization + Name: DynamicObjects + Namespaces: + label: true + path: true + path confidence: true + shape: true + twist: true + Queue Size: 100 + Value: true + Enabled: true + Name: Prediction + - Class: rviz/Group + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /perception/traffic_light_recognition/debug/rois + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers + Name: Beam + Namespaces: {} + Queue Size: 100 + Value: true + Enabled: true + Name: TrafficLight + Enabled: true + Name: Perception + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/mission_planning/route_marker + Name: RouteArea + Namespaces: + goal_lanelets: true + left_lane_bound: true + right_lane_bound: true + route_lanelets: true + Queue Size: 100 + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.30000001192092896 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.5 + Name: GoalPose + Shaft Length: 3 + Shaft Radius: 0.20000000298023224 + Shape: Axes + Topic: /planning/mission_planning/goal + Unreliable: false + Value: true + Enabled: true + Name: MissionPlanning + - Class: rviz/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: true + Name: ScenarioTrajectory + Topic: /planning/scenario_planning/trajectory + Unreliable: false + Value: true + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz/Group + Displays: + - Class: rviz/Group + Displays: + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: Path + Topic: /planning/scenario_planning/lane_driving/behavior_planning/path + Unreliable: false + Value: true + View Path: + Alpha: 0.4000000059604645 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 0.4000000059604645 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path + Name: Arrow + Namespaces: {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk + Name: Crosswalk + Namespaces: {} + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection + Name: Intersection + Namespaces: + conflicting_targets: true + detection_area: false + ego_lane: false + factor_text: true + judge_point_pose_line: true + path_raw: false + spline: false + stop_point_pose_line: false + stop_virtual_wall: true + stuck_vehicle_detect_area: false + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot + Name: Blind Spot + Namespaces: + conflict_area_for_blind_spot: false + conflicting_targets: true + detection_area: false + detection_area_for_blind_spot: false + factor_text: true + judge_point_pose_line: true + path_raw: false + stop_virtual_wall: true + spline: false + stop_point_pose_line: false + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light + Name: TrafficLight + Namespaces: {} + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line + Name: StopLine + Namespaces: + factor_text: true + stop_virtual_wall: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area + Name: DetectionArea + Namespaces: + factor_text: true + stop_virtual_wall: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/debug/predicted_path_markers + Name: LaneChange + Namespaces: + candidate_lane_change_path: false + ego_lane_change_path: false + ego_lane_follow_path: false + factor_text: true + object_predicted_path: false + selected_path: false + stop_virtual_wall: true + Queue Size: 100 + Value: true + - Class: rviz_plugins/Path + Color Border Vel Max: 3 + Enabled: true + Name: LaneChangeCandidate + Topic: /planning/scenario_planning/lane_driving/lane_change_candidate_path + Unreliable: false + Value: true + View Path: + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: true + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: true + Scale: 0.30000001192092896 + Value: false + Enabled: true + Name: BehaviorPlanning + - Class: rviz/Group + Displays: + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: false + Name: Trajectory + Topic: /planning/scenario_planning/lane_driving/trajectory + Unreliable: false + Value: false + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker + Name: ObstaclePointCloudStop + Namespaces: + collision_polygons: true + detection_polygons: true + factor_text: true + stop_virtual_wall: true + stop_obstacle_point: true + stop_obstacle_text: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker + Name: SurroundObstacleCheck + Namespaces: + factor_text: true + virtual_wall: true + obstacle_point: true + no_start_obstacle_text: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker + Name: ObstacleAvoidance + Namespaces: + base_bounds_line: false + bounds_candidate_base_text: false + bounds_candidate_for_base: false + bounds_candidate_for_top: false + bounds_candidate_top_text: false + constrain_rect: false + constrain_rect_text: false + constrain_rectlocation: false + current_vehicle_footprint: false + extending_constrain_rect: false + extending_constrain_rect_text: false + extending_constrain_rectlocation: false + fixed_mpt_points: false + fixed_points_for_extending: false + fixed_points_marker: false + interpolated_points_for_extending: false + interpolated_points_marker: false + interpolated_points_text_marker: false + non_fixed_points_for_extending: false + non_fixed_points_marker: false + num_vehicle_footprint: false + optimized_points_marker: false + optimized_points_text_marker: false + smoothed_points_text: false + straight_points_marker: false + top_bounds_line: false + vehicle_footprint: false + virtual_wall: true + virtual_wall_text: true + Queue Size: 100 + Value: true + Enabled: true + Name: MotionPlanning + Enabled: true + Name: LaneDriving + - Class: rviz/Group + Displays: + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Costmap + Topic: /planning/scenario_planning/parking/costmap_generator/occupancy_grid + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.05000000074505806 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.10000000149011612 + Head Radius: 0.20000000298023224 + Name: PartialPoseArray + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 + Shape: Arrow (3D) + Topic: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.5 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 255 + Enabled: true + Head Length: 0.10000000149011612 + Head Radius: 0.20000000298023224 + Name: PoseArray + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 + Shape: Arrow (Flat) + Topic: /planning/scenario_planning/parking/freespace_planner/debug/pose_array + Unreliable: false + Value: true + Enabled: true + Name: Parking + Enabled: true + Name: ScenarioPlanning + Enabled: true + Name: Planning + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /control/trajectory_follower/mpc_follower/debug/markers + Name: Debug/MPC + Namespaces: {} + Queue Size: 100 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /control/trajectory_follower/pure_pursuit/debug/marker + Name: Debug/PurePursuit + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: true + Name: Control + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: viewer + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /planning/mission_planning/goal + - Class: rviz/PedestrianInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Theta std deviation: 0.0872664600610733 + Velocity: 1 + X std deviation: 0.009999999776482582 + Y std deviation: 0.009999999776482582 + Z position: 0 + Z std deviation: 0.009999999776482582 + - Class: rviz/CarInitialPoseTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Theta std deviation: 0.0872664600610733 + Velocity: 3 + X std deviation: 0.009999999776482582 + Y std deviation: 0.009999999776482582 + Z position: 0 + Z std deviation: 0.009999999776482582 + - Class: rviz/MissionCheckpointTool + Pose Topic: /planning/mission_planning/checkpoint + Theta std deviation: 0.2617993950843811 + X std deviation: 0.5 + Y std deviation: 0.5 + Z position: 0 + - Class: rviz/DeleteAllObjectsTool + Pose Topic: /simulation/dummy_perception_publisher/object_info + Value: true + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: 10 + Target Frame: viewer + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1565 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + InitialPoseButtonPanel: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000033c00000563fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001f0000000c900fffffffb0000000a005600690065007700730100000233000000f2000000a400fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073010000032b000000a10000005c00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d00610067006501000003d2000001ce0000001600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000afd0000005afc0100000002fb0000000800540069006d0065010000000000000afd000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000007bb0000056300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 2813 + X: 67 + Y: 27 diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt new file mode 100644 index 0000000000..e469a18318 --- /dev/null +++ b/control_launch/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(control_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + config + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower_param.yaml new file mode 100644 index 0000000000..c8d036356b --- /dev/null +++ b/control_launch/config/mpc_follower/mpc_follower_param.yaml @@ -0,0 +1,42 @@ + + +# -- system -- +ctrl_period: 0.03 # control period [s] +traj_resample_dist: 0.1 # path resampling interval [m] +enable_yaw_recalculation: false # flag for recalculation of yaw angle after resampling +admisible_position_error: 5.0 # stop mpc calculation when error is larger than the following value +admisible_yaw_error_: 1.57 # stop mpc calculation when error is larger than the following value + +# -- path smoothing -- +enable_path_smoothing: false # flag for path smoothing +path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing +curvature_smoothing_num: 15 # point-to-point index distance used in curvature calculation : curvature is calculated from three points p(i-num), p(i), p(i+num) + +# -- mpc optimization -- +qpoases_max_iter: 500 # max iteration number for quadratic programming +qp_solver_type: "osqp" # optimization solver type. option is unconstraint_fast, unconstraint, and qpoases_hotstart and osqp +mpc_prediction_horizon: 50 # prediction horizon step +mpc_prediction_dt: 0.1 # prediction horizon period [s] +mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q +mpc_weight_heading_error: 0.0 # heading error weight in matrix Q +mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q +mpc_weight_steering_input: 1.0 # steering error weight in matrix R +mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R +mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R +mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R +mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R +mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability +mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability +mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero + +# -- vehicle model -- +vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics +input_delay: 0.24 # steering input delay time for delay compensation +vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] +steer_lim_deg: 40.0 # steering angle limit [deg] +steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] +acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] +velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s] + +# -- lowpass filter for noise reduction -- +steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] diff --git a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml new file mode 100644 index 0000000000..9d38aefc37 --- /dev/null +++ b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml @@ -0,0 +1,7 @@ +# -- system -- +control_period: 0.033 + +# --algorithm +lookahead_distance_ratio: 2.2 +min_lookahead_distance: 2.5 +reverse_min_lookahead_distance: 7.0 diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml new file mode 100644 index 0000000000..8c3149074a --- /dev/null +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -0,0 +1,61 @@ +# closest waypoint threshold +closest_waypoint_distance_threshold: 3.0 +closest_waypoint_angle_threshold: 0.7854 + +# stop state +stop_state_velocity: 0.0 +stop_state_acc: -3.4 +stop_state_entry_ego_speed: 0.2 +stop_state_entry_target_speed: 0.1 +stop_state_keep_stopping_dist: 0.5 + +# delay compensation +delay_compensation_time: 0.17 + +# emergency stop by this controller +emergency_stop_acc: -5.0 +emergency_stop_jerk: -3.0 + +# smooth stop +smooth_stop: + stop_dist: 3.0 + exit_ego_speed: 1.0 + entry_ego_speed: 0.8 + exit_target_speed: 1.0 + entry_target_speed: 0.2 + weak_brake_time: 1.0 + weak_brake_acc: -1.0 + increasing_brake_time: 1.0 + increasing_brake_gradient: -0.1 + stop_brake_time: 1.0 + stop_brake_acc: -3.4 + +# acceleration limit +max_acc: 3.0 +min_acc: -5.0 + +# jerk limit +max_jerk: 2.0 +min_jerk: -5.0 + +# slope compensation +enable_slope_compensation: true +max_pitch_rad: 0.1 +min_pitch_rad: -0.1 +lpf_pitch_gain: 0.95 + +# velocity feedback +pid_controller: + kp: 1.0 + ki: 0.1 + kd: 0 + max_out: 1.0 + min_out: -1.0 + max_p_effort: 1.0 + min_p_effort: -1.0 + max_i_effort: 0.3 + min_i_effort: -0.3 + max_d_effort: 0 + min_d_effort: 0 + current_velocity_threshold_pid_integration: 0.5 + lpf_velocity_error_gain: 0.9 \ No newline at end of file diff --git a/control_launch/launch/control.launch b/control_launch/launch/control.launch new file mode 100644 index 0000000000..2a4000982c --- /dev/null +++ b/control_launch/launch/control.launch @@ -0,0 +1,52 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control_launch/package.xml b/control_launch/package.xml new file mode 100644 index 0000000000..c2f9157211 --- /dev/null +++ b/control_launch/package.xml @@ -0,0 +1,22 @@ + + + control_launch + 0.1.0 + The control_launch package + + + + + Takamasa Horibe + + + + + + TODO + + catkin + + + + diff --git a/integration_launch/CMakeLists.txt b/integration_launch/CMakeLists.txt new file mode 100644 index 0000000000..d303b4a8be --- /dev/null +++ b/integration_launch/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(integration_launch) + +find_package(catkin REQUIRED COMPONENTS + autoware_launch +) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/integration_launch/launch/ci_planning_simulator.launch b/integration_launch/launch/ci_planning_simulator.launch new file mode 100644 index 0000000000..6ee6bff390 --- /dev/null +++ b/integration_launch/launch/ci_planning_simulator.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/integration_launch/launch/release.launch b/integration_launch/launch/release.launch new file mode 100644 index 0000000000..9c7ea3ac6e --- /dev/null +++ b/integration_launch/launch/release.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/integration_launch/package.xml b/integration_launch/package.xml new file mode 100644 index 0000000000..5b908622b4 --- /dev/null +++ b/integration_launch/package.xml @@ -0,0 +1,13 @@ + + + integration_launch + 0.1.0 + The integration_launch package + + Hiroyuki Obinata + Apache 2 + + catkin + autoware_launch + + diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt new file mode 100644 index 0000000000..047892fac7 --- /dev/null +++ b/localization_launch/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 2.8.3) +project(localization_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/localization_launch/launch/localization.launch b/localization_launch/launch/localization.launch new file mode 100644 index 0000000000..1543c92629 --- /dev/null +++ b/localization_launch/launch/localization.launch @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch b/localization_launch/launch/pose_estimator/pose_estimator.launch new file mode 100644 index 0000000000..f70e6d3145 --- /dev/null +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch new file mode 100644 index 0000000000..76310afb0e --- /dev/null +++ b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch b/localization_launch/launch/twist_estimator/twist_estimator.launch new file mode 100644 index 0000000000..da8198ef72 --- /dev/null +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/localization_launch/launch/util/util.launch b/localization_launch/launch/util/util.launch new file mode 100644 index 0000000000..a0558ce968 --- /dev/null +++ b/localization_launch/launch/util/util.launch @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + min_x: -60.0 + max_x: 60.0 + min_y: -60.0 + max_y: 60.0 + min_z: -30.0 + max_z: 50.0 + negative: False + + + + + + + + + + + + voxel_size_x: 3.0 + voxel_size_y: 3.0 + voxel_size_z: 3.0 + + + + diff --git a/localization_launch/package.xml b/localization_launch/package.xml new file mode 100644 index 0000000000..48230f21cb --- /dev/null +++ b/localization_launch/package.xml @@ -0,0 +1,58 @@ + + + localization_launch + 0.1.0 + The localization_launch package + + + + + Yamato Ando + + + + + + Apache 2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + diff --git a/map_launch/CMakeLists.txt b/map_launch/CMakeLists.txt new file mode 100644 index 0000000000..c318300cf5 --- /dev/null +++ b/map_launch/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(map_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +include_directories() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/map_launch/launch/map.launch b/map_launch/launch/map.launch new file mode 100644 index 0000000000..efa73f802c --- /dev/null +++ b/map_launch/launch/map.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/map_launch/package.xml b/map_launch/package.xml new file mode 100644 index 0000000000..df7aacd226 --- /dev/null +++ b/map_launch/package.xml @@ -0,0 +1,59 @@ + + + map_launch + 0.1.0 + The map_launch package + + + + + mitsudome-r + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt new file mode 100644 index 0000000000..3617fa63d2 --- /dev/null +++ b/perception_launch/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 2.8.3) +project(perception_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch new file mode 100644 index 0000000000..b35bc13960 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch b/perception_launch/launch/object_recognition/detection/detection.launch new file mode 100644 index 0000000000..f72fa95b37 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/detection.launch @@ -0,0 +1,64 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch new file mode 100644 index 0000000000..6fe87c5e63 --- /dev/null +++ b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch b/perception_launch/launch/object_recognition/prediction/prediction.launch new file mode 100644 index 0000000000..efd2535b23 --- /dev/null +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch b/perception_launch/launch/object_recognition/tracking/tracking.launch new file mode 100644 index 0000000000..a2fc3947b2 --- /dev/null +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/perception_launch/launch/perception.launch b/perception_launch/launch/perception.launch new file mode 100644 index 0000000000..ee29ebf677 --- /dev/null +++ b/perception_launch/launch/perception.launch @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch b/perception_launch/launch/traffic_light_recognition/traffic_light.launch new file mode 100644 index 0000000000..72f6a0c0c4 --- /dev/null +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception_launch/package.xml b/perception_launch/package.xml new file mode 100644 index 0000000000..458e108e1e --- /dev/null +++ b/perception_launch/package.xml @@ -0,0 +1,27 @@ + + + perception_launch + 0.1.0 + The perception_launch package + + Yukihiro Saito + Apache2 + + + catkin + dynamic_object_visualization + euclidean_cluster + pointcloud_to_laserscan + shape_estimation + dynamic_object_visualization + euclidean_cluster + pointcloud_to_laserscan + shape_estimation + dynamic_object_visualization + euclidean_cluster + pointcloud_to_laserscan + shape_estimation + + + + diff --git a/planning_launch/CMakeLists.txt b/planning_launch/CMakeLists.txt new file mode 100644 index 0000000000..65406d7899 --- /dev/null +++ b/planning_launch/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(planning_launch) + +find_package(catkin REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml new file mode 100644 index 0000000000..c324867194 --- /dev/null +++ b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml @@ -0,0 +1,36 @@ +max_velocity: 20.0 # max velocity limit [m/s] +max_accel: 1.0 # max acceleration limit [m/ss] +min_decel: -1.0 # min deceleration limit [m/ss] + +# curve parameters +max_lateral_accel: 0.5 # max lateral acceleration limit [m/ss] +min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] +decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit +decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit + +# engage & replan parameters +replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] +engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) +engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) +engage_exit_ratio: 0.5 # exit engage sequence to normal velocity plannning when the velocity exceeds engage_exit_ratio x engage_velocity. +stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] + +extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m] +extract_behind_dist: 5.0 # backward trajectory distance used for planning [m] +delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajecotory pose [radian] + +max_trajectory_length: 200.0 # max trajectory length for resampling [m] +min_trajectory_length: 30.0 # min trajectory length for resampling [m] +resample_time: 10.0 # resample total time [s] +resample_dt: 0.1 # resample time interval [s] +min_trajectory_interval_distance: 0.1 # resample points-interval length [m] + +# default weights +# L2: jerk = 100.0, v_weight = 100000.0, a_weight = 1000.0 +# Linf: jerk = 200.0, v_weight = 100000.0, a_weight = 5000.0 + +pseudo_jerk_weight: 100.0 # weight for "smoothness" cost +over_v_weight: 100000.0 # weight for "overspeed limit" cost +over_a_weight: 1000.0 # weight for "overaccel limit" cost + +algorithm_type: "L2" # Option : L2, Linf \ No newline at end of file diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml new file mode 100644 index 0000000000..2f4677ee8c --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml @@ -0,0 +1,88 @@ +# trajectory total/fixing length +trajectory_length: 200 # total trajectory length[m] +forward_fixing_distance: 20.0 # forward fixing length from base_link[m] +backward_fixing_distance: 5.0 # backward fixing length from base_link[m] + +# clearance(distance) when generating trajectory +clearance_from_road: 0.2 # clearance from road boundary[m] +clearance_from_object: 1.0 # clearance from object[m] +min_object_clearance_for_joint: 3.2 # minimum clearance from object[m] when judging is_including_only_smooth_range +extra_desired_clearance_from_road: 0.0 # extra desired clearance from road + +# clearance for unique points +clearance_for_straight_line_: 0.05 # minimum optimizing range around straight points +clearance_for_joint_: 3.2 # minimum optimizing range around joint points +clearance_for_only_smoothing: 0.1 # minimum optimizing range when applygin only smoothing +range_for_extend_joint: 0.1 # minimum optimizing range around joint points for extending +clearance_from_object_for_straight: 10.0 # minimum clearance from object when judging straight line + +# avoiding param +max_avoiding_objects_velocity_ms: .5 # maximum velocity for avoiding objects[m/s] +max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects[m/s] +center_line_width: 1.7 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, center line width around path points used for judging that object is required to avoid or not +acceleration_for_non_deceleration_range: 1.0 # assumed acceleration for calculating non deceleration range + +# solving quadratic programming +qp_max_iteration: 10000 # max iteration when solving QP +qp_eps_abs: 1.0e-8 # eps abs when solving OSQP +qp_eps_rel: 1.0e-11 # eps rel when solving OSQP +qp_eps_abs_for_extending: 1.0e-8 # eps abs when solving OSQP for extending +qp_eps_rel_for_extending: 1.0e-9 # eps rel when solving OSQP for extending +qp_eps_abs_for_visualizing: 1.0e-6 # eps abs when solving OSQP for visualizing +qp_eps_rel_for_visualizing: 1.0e-8 # eps rel when solving OSQP for visualizing + +# constrain space +is_getting_constraints_close2path_points: true # generate trajectory closer to path points +max_x_constrain_search_range: 0.0 # maximum x search range in local coordinate +coef_x_cosntrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction +coef_y_cosntrain_search_resolution: 0.5 # coef for fine sampling when exploring y direction +keep_space_shape_x: 0.2 # keep space for x direction from base_link[m] +keep_space_shape_y: 0.1 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, keep space for y direction from base_link[m] +max_lon_space_for_driveable_constraint: 0.5 # maximum lon(x) space when optimizing point[m] + +is_publishing_clearance_map: true # publish clearance map as nav_msgs::OccupancyGrid +is_publishing_area_with_objects: true # publish occupancy map as nav_msgs::OccupancyGrid +enable_avoidance: true # enable avoidance function +is_using_vehicle_config: true # use vehicle config +num_sampling_points: 100 # number of optimizing points +num_joint_buffer_points: 3 # number of joint buffer points +num_joint_buffer_points_for_extending: 6 # number of joint buffer points for extending +num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx +num_fix_points_for_extending: 50 # number of fixing points when extending +delta_arc_length_for_optimization: 1.0 # delta arc length when optimizing[m] +delta_arc_length_for_trajectory: 0.1 # delta arc length for trajectory[m] +delta_dist_threshold_for_closest_point: 3.0 # delta dist thres for closest point[m] +delta_yaw_threshold_for_closest_point: 1.046 #M_PI/3.0, delta yaw thres for closest point +delta_yaw_threshold_for_straight: 0.02 # delta dist thres for straight point + +# mpt param +# vehicle param for mpt +max_steer_deg: 30.0 # max steering angle [deg] +steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] + +# trajectory param for mpt +num_curvature_sampling_points: 5 # number of sampling points when calculating curvature +delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt[m] +num_fix_points_for_mpt: 8 # number of fixing points around ego vehicle + +# optimization param for mpt +is_hard_fixing_terminal_point: true # hard fixing terminal point +base_point_weight: 2000 # slack weight for lateral error around base_link +top_point_weight: 1000 # slack weight for lateral error around vehicle-top point +mid_point_weight: 1000 # slack weight for lateral error around the middle point +lat_error_weight: 10.0 # weight for lateral error +yaw_error_weight: 0.0 # weight for yaw error +steer_input_weight: 0.01 # weight for steering input +steer_rate_weight: 1 # weight for sttering rate +steer_acc_weight: 0.000001 # weight for steering acceration +terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point +terminal_yaw_error_weight: 100.0 # weight for yaw errror at terminal point +terminal_path_lat_error_weight: 1000.0 # weight for lateral errro at path end point +terminal_path_yaw_error_weight: 1000.0 # weight for yaw errro at path end point +zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero + +# replanning & trimming trajectory param outside algorithm +min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] +min_delta_time_sec_for_replan: 1.0 # minimum delta time for replan[second] +max_dist_for_extending_end_point: 5.0 # minimum delta dist thres for extending last point[m] +distance_for_path_shape_chagne_detection: 2.0 # minimum delta dist thres for detecting path shape change diff --git a/planning_launch/launch/mission_planning/mission_planning.launch b/planning_launch/launch/mission_planning/mission_planning.launch new file mode 100644 index 0000000000..d1e94f15c8 --- /dev/null +++ b/planning_launch/launch/mission_planning/mission_planning.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/planning.launch b/planning_launch/launch/planning.launch new file mode 100644 index 0000000000..d8d6dd9a10 --- /dev/null +++ b/planning_launch/launch/planning.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch b/planning_launch/launch/scenario_planning/lane_driving.launch new file mode 100644 index 0000000000..27fa088c48 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch new file mode 100644 index 0000000000..e67dde71cd --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch new file mode 100644 index 0000000000..df97661f99 --- /dev/null +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/parking.launch b/planning_launch/launch/scenario_planning/parking.launch new file mode 100644 index 0000000000..0198eb09d0 --- /dev/null +++ b/planning_launch/launch/scenario_planning/parking.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch b/planning_launch/launch/scenario_planning/scenario_planning.launch new file mode 100644 index 0000000000..c4d21f9103 --- /dev/null +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning_launch/package.xml b/planning_launch/package.xml new file mode 100644 index 0000000000..24d7f88c67 --- /dev/null +++ b/planning_launch/package.xml @@ -0,0 +1,59 @@ + + + planning_launch + 0.1.0 + The planning_launch package + + + + + tier4 + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt new file mode 100644 index 0000000000..b557b1d09b --- /dev/null +++ b/sensing_launch/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.8.3) +project(sensing_launch) + +find_package(catkin REQUIRED) + +# Force Tier IV's fork version +find_package(velodyne_driver 0.2.0 EXACT REQUIRED) +find_package(velodyne_pointcloud 0.2.0 EXACT REQUIRED) + +catkin_package() + +install( + DIRECTORY + launch + data + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/sensing_launch/data/traffic_light_camera.yaml b/sensing_launch/data/traffic_light_camera.yaml new file mode 100644 index 0000000000..a4c99fae96 --- /dev/null +++ b/sensing_launch/data/traffic_light_camera.yaml @@ -0,0 +1,20 @@ +image_width: 1920 +image_height: 1080 +camera_name: traffic_light/camera +camera_matrix: + rows: 3 + cols: 3 + data: [2410.755261, 0.000000, 922.621401, 0.000000, 2403.573140, 534.752500, 0.000000, 0.000000, 1.000000] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [-0.126600, 0.152594, 0.002432, -0.001244, 0.000000] +rectification_matrix: + rows: 3 + cols: 3 + data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] +projection_matrix: + rows: 3 + cols: 4 + data: [2370.254883, 0.000000, 920.136018, 0.000000, 0.000000, 2388.885254, 535.599668, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000] \ No newline at end of file diff --git a/sensing_launch/launch/aip_customized/camera.launch b/sensing_launch/launch/aip_customized/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_customized/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_customized/gnss.launch b/sensing_launch/launch/aip_customized/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_customized/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_customized/imu.launch b/sensing_launch/launch/aip_customized/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_customized/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_customized/lidar.launch b/sensing_launch/launch/aip_customized/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_customized/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/camera.launch b/sensing_launch/launch/aip_s1/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_s1/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/gnss.launch b/sensing_launch/launch/aip_s1/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_s1/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/imu.launch b/sensing_launch/launch/aip_s1/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_s1/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_s1/lidar.launch b/sensing_launch/launch/aip_s1/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_s1/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/camera.launch b/sensing_launch/launch/aip_x1/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_x1/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/gnss.launch b/sensing_launch/launch/aip_x1/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_x1/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/imu.launch b/sensing_launch/launch/aip_x1/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_x1/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/lidar.launch b/sensing_launch/launch/aip_x1/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_x1/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/camera.launch b/sensing_launch/launch/aip_x2/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_x2/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/gnss.launch b/sensing_launch/launch/aip_x2/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_x2/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/imu.launch b/sensing_launch/launch/aip_x2/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_x2/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x2/lidar.launch b/sensing_launch/launch/aip_x2/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_x2/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/camera.launch b/sensing_launch/launch/aip_xx1/camera.launch new file mode 100644 index 0000000000..fdd4c5365d --- /dev/null +++ b/sensing_launch/launch/aip_xx1/camera.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch b/sensing_launch/launch/aip_xx1/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_xx1/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/imu.launch b/sensing_launch/launch/aip_xx1/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_xx1/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch new file mode 100644 index 0000000000..46925430a2 --- /dev/null +++ b/sensing_launch/launch/aip_xx1/lidar.launch @@ -0,0 +1,122 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud, + /sensing/lidar/rear/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/camera.launch b/sensing_launch/launch/aip_xx2/camera.launch new file mode 100644 index 0000000000..c9e5fa4f26 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/camera.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch b/sensing_launch/launch/aip_xx2/gnss.launch new file mode 100644 index 0000000000..51b386c056 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/gnss.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/imu.launch b/sensing_launch/launch/aip_xx2/imu.launch new file mode 100644 index 0000000000..b55a51ea8d --- /dev/null +++ b/sensing_launch/launch/aip_xx2/imu.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx2/lidar.launch b/sensing_launch/launch/aip_xx2/lidar.launch new file mode 100644 index 0000000000..0d8fdb3084 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/lidar.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [/sensing/lidar/top/outlier_filtered/pointcloud, + /sensing/lidar/left/outlier_filtered/pointcloud, + /sensing/lidar/right/outlier_filtered/pointcloud] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/livox_horizon.launch b/sensing_launch/launch/livox_horizon.launch new file mode 100644 index 0000000000..1e5c5d8e7a --- /dev/null +++ b/sensing_launch/launch/livox_horizon.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/sensing.launch b/sensing_launch/launch/sensing.launch new file mode 100644 index 0000000000..019af23690 --- /dev/null +++ b/sensing_launch/launch/sensing.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLP16.launch b/sensing_launch/launch/velodyne_VLP16.launch new file mode 100644 index 0000000000..6cf557309d --- /dev/null +++ b/sensing_launch/launch/velodyne_VLP16.launch @@ -0,0 +1,104 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch b/sensing_launch/launch/velodyne_VLP32C.launch new file mode 100644 index 0000000000..bce757ecb7 --- /dev/null +++ b/sensing_launch/launch/velodyne_VLP32C.launch @@ -0,0 +1,104 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch b/sensing_launch/launch/velodyne_VLS128.launch new file mode 100644 index 0000000000..0d3b9abd35 --- /dev/null +++ b/sensing_launch/launch/velodyne_VLS128.launch @@ -0,0 +1,104 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml new file mode 100644 index 0000000000..e315fa965b --- /dev/null +++ b/sensing_launch/package.xml @@ -0,0 +1,17 @@ + + + sensing_launch + 0.1.0 + The sensing_launch package + + Yukihiro Saito + Apache2 + + catkin + + velodyne_driver + velodyne_pointcloud + + + + diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt new file mode 100644 index 0000000000..2519b3e2f0 --- /dev/null +++ b/system_launch/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(system_launch) + +find_package(catkin REQUIRED COMPONENTS +) + +catkin_package() + +install( + DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/system_launch/launch/system.launch b/system_launch/launch/system.launch new file mode 100644 index 0000000000..b30703b4fd --- /dev/null +++ b/system_launch/launch/system.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/system_launch/package.xml b/system_launch/package.xml new file mode 100644 index 0000000000..7f5f70ae0c --- /dev/null +++ b/system_launch/package.xml @@ -0,0 +1,14 @@ + + + system_launch + 0.1.0 + The system_launch package + + Kenji Miyake + Apache 2 + + catkin + + + + diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt new file mode 100644 index 0000000000..331b62f499 --- /dev/null +++ b/vehicle_launch/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.3) +project(vehicle_launch) + +add_compile_options(-std=c++14) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY + launch + config + urdf + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/vehicle_launch/config/default/aip_customized/sensors_calibration.yaml b/vehicle_launch/config/default/aip_customized/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/default/aip_s1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_s1/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/default/aip_x2/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x2/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml b/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml new file mode 100644 index 0000000000..d9d1f599e4 --- /dev/null +++ b/vehicle_launch/config/default/aip_xx1/sensor_kit_calibration.yaml @@ -0,0 +1,91 @@ +sensor_kit_base_link2camera0: + x: 0.10731 + y: 0.56343 + z: -0.27697 + roll: -0.025 + pitch: 0.315 + yaw: 1.035 +sensor_kit_base_link2camera1: + x: -0.10731 + y: -0.56343 + z: -0.27697 + roll: -0.025 + pitch: 0.32 + yaw: -2.12 +sensor_kit_base_link2camera2: + x: 0.10731 + y: -0.56343 + z: -0.27697 + roll: -0.00 + pitch: 0.335 + yaw: -1.04 +sensor_kit_base_link2camera3: + x: -0.10731 + y: 0.56343 + z: -0.27697 + roll: 0.0 + pitch: 0.325 + yaw: 2.0943951 +sensor_kit_base_link2camera4: + x: 0.07356 + y: 0.0 + z: -0.0525 + roll: 0.0 + pitch: -0.03 + yaw: -0.005 +sensor_kit_base_link2camera5: + x: -0.07356 + y: 0.0 + z: -0.0525 + roll: 0.0 + pitch: -0.01 + yaw: 3.125 +sensor_kit_base_link2traffic_light_right_camera: + x: 0.05 + y: -0.0175 + z: -0.1 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 +sensor_kit_base_link2traffic_light_left_camera: + x: 0.05 + y: 0.0175 + z: -0.1 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 +sensor_kit_base_link2velodyne_top_base_link: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 1.575 +sensor_kit_base_link2velodyne_left_base_link: + x: 0.0 + y: 0.56362 + z: -0.30555 + roll: -0.02 + pitch: 0.71 + yaw: 1.575 +sensor_kit_base_link2velodyne_right_base_link: + x: 0.0 + y: -0.56362 + z: -0.30555 + roll: -0.01 + pitch: 0.71 + yaw: -1.580 +sensor_kit_base_link2gnss: + x: -0.1 + y: 0.0 + z: -0.2 + roll: 0.0 + pitch: 0.0 + yaw: 0.0 +sensor_kit_base_link2imu_tamagawa: + x: 0.0 + y: 0.0 + z: 0.0 + roll: 3.14159265359 + pitch: 0.0 + yaw: 3.14159265359 diff --git a/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml new file mode 100644 index 0000000000..1aa0972391 --- /dev/null +++ b/vehicle_launch/config/default/aip_xx1/sensors_calibration.yaml @@ -0,0 +1,28 @@ +base_link2sensor_kit_base_link: + x: 0.9 + y: 0.0 + z: 2.0 + roll: -0.001 + pitch: 0.015 + yaw: -0.0364 +base_link2livox_front_right_base_link: + x: 3.290 + y: -0.65485 + z: 0.3216 + roll: 0.0 + pitch: 0.0 + yaw: -0.872664444 +base_link2livox_front_left_base_link: + x: 3.290 + y: 0.65485 + z: 0.3016 + roll: -0.021 + pitch: 0.05 + yaw: 0.872664444 +base_link2velodyne_rear_base_link: + x: -0.358 + y: 0.0 + z: 1.631 + roll: -0.02 + pitch: 0.7281317 + yaw: 3.141592 diff --git a/vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml b/vehicle_launch/config/default/aip_xx2/sensors_calibration.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/launch/vehicle.launch b/vehicle_launch/launch/vehicle.launch new file mode 100644 index 0000000000..b6191e70cd --- /dev/null +++ b/vehicle_launch/launch/vehicle.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/vehicle_launch/launch/vehicle_description.launch b/vehicle_launch/launch/vehicle_description.launch new file mode 100644 index 0000000000..7a09cd6e13 --- /dev/null +++ b/vehicle_launch/launch/vehicle_description.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/vehicle_launch/launch/vehicle_interface.launch b/vehicle_launch/launch/vehicle_interface.launch new file mode 100644 index 0000000000..675ff78397 --- /dev/null +++ b/vehicle_launch/launch/vehicle_interface.launch @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml new file mode 100644 index 0000000000..e20bbfeefd --- /dev/null +++ b/vehicle_launch/package.xml @@ -0,0 +1,21 @@ + + + vehicle_launch + 0.1.0 + The vehicle_launch package + + Yukihiro Saito + Apache2 + + + catkin + camera_description + imu_description + livox_description + velodyne_description + robot_state_publisher + + roscpp + + + diff --git a/vehicle_launch/urdf/vehicle.xacro b/vehicle_launch/urdf/vehicle.xacro new file mode 100644 index 0000000000..30db9c6a7c --- /dev/null +++ b/vehicle_launch/urdf/vehicle.xacro @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + From f6bdaa973ce8c15981c6c51bddb4d25bdcc8162c Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Thu, 8 Oct 2020 17:43:36 +0900 Subject: [PATCH 0033/1765] add COLCON_IGNORE file to all ROS1 packages Signed-off-by: mitsudome-r --- autoware_launch/COLCON_IGNORE | 0 control_launch/COLCON_IGNORE | 0 integration_launch/COLCON_IGNORE | 0 localization_launch/COLCON_IGNORE | 0 map_launch/COLCON_IGNORE | 0 perception_launch/COLCON_IGNORE | 0 planning_launch/COLCON_IGNORE | 0 sensing_launch/COLCON_IGNORE | 0 system_launch/COLCON_IGNORE | 0 vehicle_launch/COLCON_IGNORE | 0 10 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 autoware_launch/COLCON_IGNORE create mode 100644 control_launch/COLCON_IGNORE create mode 100644 integration_launch/COLCON_IGNORE create mode 100644 localization_launch/COLCON_IGNORE create mode 100644 map_launch/COLCON_IGNORE create mode 100644 perception_launch/COLCON_IGNORE create mode 100644 planning_launch/COLCON_IGNORE create mode 100644 sensing_launch/COLCON_IGNORE create mode 100644 system_launch/COLCON_IGNORE create mode 100644 vehicle_launch/COLCON_IGNORE diff --git a/autoware_launch/COLCON_IGNORE b/autoware_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/control_launch/COLCON_IGNORE b/control_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/integration_launch/COLCON_IGNORE b/integration_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/localization_launch/COLCON_IGNORE b/localization_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/map_launch/COLCON_IGNORE b/map_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/perception_launch/COLCON_IGNORE b/perception_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/planning_launch/COLCON_IGNORE b/planning_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/sensing_launch/COLCON_IGNORE b/sensing_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/system_launch/COLCON_IGNORE b/system_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/vehicle_launch/COLCON_IGNORE b/vehicle_launch/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 From 2ada2e16adbd23a631fdb7fbc729327a84e7ee4f Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Fri, 23 Oct 2020 17:34:33 +0900 Subject: [PATCH 0034/1765] rename *.launch files to *.launch.xml Signed-off-by: mitsudome-r --- autoware_launch/launch/{autoware.launch => autoware.launch.xml} | 0 .../{logging_simulator.launch => logging_simulator.launch.xml} | 0 .../{planning_simulator.launch => planning_simulator.launch.xml} | 0 control_launch/launch/{control.launch => control.launch.xml} | 0 ...planning_simulator.launch => ci_planning_simulator.launch.xml} | 0 integration_launch/launch/{release.launch => release.launch.xml} | 0 .../launch/{localization.launch => localization.launch.xml} | 0 .../{pose_estimator.launch => pose_estimator.launch.xml} | 0 ...t_fusion_filter.launch => pose_twist_fusion_filter.launch.xml} | 0 .../{twist_estimator.launch => twist_estimator.launch.xml} | 0 localization_launch/launch/util/{util.launch => util.launch.xml} | 0 map_launch/launch/{map.launch => map.launch.xml} | 0 ...tion.launch => camera_lidar_fusion_based_detection.launch.xml} | 0 .../detection/{detection.launch => detection.launch.xml} | 0 ...ar_based_detection.launch => lidar_based_detection.launch.xml} | 0 .../prediction/{prediction.launch => prediction.launch.xml} | 0 .../tracking/{tracking.launch => tracking.launch.xml} | 0 .../launch/{perception.launch => perception.launch.xml} | 0 .../{traffic_light.launch => traffic_light.launch.xml} | 0 .../{mission_planning.launch => mission_planning.launch.xml} | 0 planning_launch/launch/{planning.launch => planning.launch.xml} | 0 .../{lane_driving.launch => lane_driving.launch.xml} | 0 .../{behavior_planning.launch => behavior_planning.launch.xml} | 0 .../{motion_planning.launch => motion_planning.launch.xml} | 0 .../scenario_planning/{parking.launch => parking.launch.xml} | 0 .../{scenario_planning.launch => scenario_planning.launch.xml} | 0 .../launch/aip_customized/{camera.launch => camera.launch.xml} | 0 .../launch/aip_customized/{gnss.launch => gnss.launch.xml} | 0 .../launch/aip_customized/{imu.launch => imu.launch.xml} | 0 .../launch/aip_customized/{lidar.launch => lidar.launch.xml} | 0 sensing_launch/launch/aip_s1/{camera.launch => camera.launch.xml} | 0 sensing_launch/launch/aip_s1/{gnss.launch => gnss.launch.xml} | 0 sensing_launch/launch/aip_s1/{imu.launch => imu.launch.xml} | 0 sensing_launch/launch/aip_s1/{lidar.launch => lidar.launch.xml} | 0 sensing_launch/launch/aip_x1/{camera.launch => camera.launch.xml} | 0 sensing_launch/launch/aip_x1/{gnss.launch => gnss.launch.xml} | 0 sensing_launch/launch/aip_x1/{imu.launch => imu.launch.xml} | 0 sensing_launch/launch/aip_x1/{lidar.launch => lidar.launch.xml} | 0 sensing_launch/launch/aip_x2/{camera.launch => camera.launch.xml} | 0 sensing_launch/launch/aip_x2/{gnss.launch => gnss.launch.xml} | 0 sensing_launch/launch/aip_x2/{imu.launch => imu.launch.xml} | 0 sensing_launch/launch/aip_x2/{lidar.launch => lidar.launch.xml} | 0 .../launch/aip_xx1/{camera.launch => camera.launch.xml} | 0 sensing_launch/launch/aip_xx1/{gnss.launch => gnss.launch.xml} | 0 sensing_launch/launch/aip_xx1/{imu.launch => imu.launch.xml} | 0 sensing_launch/launch/aip_xx1/{lidar.launch => lidar.launch.xml} | 0 .../launch/aip_xx2/{camera.launch => camera.launch.xml} | 0 sensing_launch/launch/aip_xx2/{gnss.launch => gnss.launch.xml} | 0 sensing_launch/launch/aip_xx2/{imu.launch => imu.launch.xml} | 0 sensing_launch/launch/aip_xx2/{lidar.launch => lidar.launch.xml} | 0 .../launch/{livox_horizon.launch => livox_horizon.launch.xml} | 0 sensing_launch/launch/{sensing.launch => sensing.launch.xml} | 0 .../launch/{velodyne_VLP16.launch => velodyne_VLP16.launch.xml} | 0 .../launch/{velodyne_VLP32C.launch => velodyne_VLP32C.launch.xml} | 0 .../launch/{velodyne_VLS128.launch => velodyne_VLS128.launch.xml} | 0 system_launch/launch/{system.launch => system.launch.xml} | 0 vehicle_launch/launch/{vehicle.launch => vehicle.launch.xml} | 0 ...{vehicle_description.launch => vehicle_description.launch.xml} | 0 .../{vehicle_interface.launch => vehicle_interface.launch.xml} | 0 59 files changed, 0 insertions(+), 0 deletions(-) rename autoware_launch/launch/{autoware.launch => autoware.launch.xml} (100%) rename autoware_launch/launch/{logging_simulator.launch => logging_simulator.launch.xml} (100%) rename autoware_launch/launch/{planning_simulator.launch => planning_simulator.launch.xml} (100%) rename control_launch/launch/{control.launch => control.launch.xml} (100%) rename integration_launch/launch/{ci_planning_simulator.launch => ci_planning_simulator.launch.xml} (100%) rename integration_launch/launch/{release.launch => release.launch.xml} (100%) rename localization_launch/launch/{localization.launch => localization.launch.xml} (100%) rename localization_launch/launch/pose_estimator/{pose_estimator.launch => pose_estimator.launch.xml} (100%) rename localization_launch/launch/pose_twist_fusion_filter/{pose_twist_fusion_filter.launch => pose_twist_fusion_filter.launch.xml} (100%) rename localization_launch/launch/twist_estimator/{twist_estimator.launch => twist_estimator.launch.xml} (100%) rename localization_launch/launch/util/{util.launch => util.launch.xml} (100%) rename map_launch/launch/{map.launch => map.launch.xml} (100%) rename perception_launch/launch/object_recognition/detection/{camera_lidar_fusion_based_detection.launch => camera_lidar_fusion_based_detection.launch.xml} (100%) rename perception_launch/launch/object_recognition/detection/{detection.launch => detection.launch.xml} (100%) rename perception_launch/launch/object_recognition/detection/{lidar_based_detection.launch => lidar_based_detection.launch.xml} (100%) rename perception_launch/launch/object_recognition/prediction/{prediction.launch => prediction.launch.xml} (100%) rename perception_launch/launch/object_recognition/tracking/{tracking.launch => tracking.launch.xml} (100%) rename perception_launch/launch/{perception.launch => perception.launch.xml} (100%) rename perception_launch/launch/traffic_light_recognition/{traffic_light.launch => traffic_light.launch.xml} (100%) rename planning_launch/launch/mission_planning/{mission_planning.launch => mission_planning.launch.xml} (100%) rename planning_launch/launch/{planning.launch => planning.launch.xml} (100%) rename planning_launch/launch/scenario_planning/{lane_driving.launch => lane_driving.launch.xml} (100%) rename planning_launch/launch/scenario_planning/lane_driving/behavior_planning/{behavior_planning.launch => behavior_planning.launch.xml} (100%) rename planning_launch/launch/scenario_planning/lane_driving/motion_planning/{motion_planning.launch => motion_planning.launch.xml} (100%) rename planning_launch/launch/scenario_planning/{parking.launch => parking.launch.xml} (100%) rename planning_launch/launch/scenario_planning/{scenario_planning.launch => scenario_planning.launch.xml} (100%) rename sensing_launch/launch/aip_customized/{camera.launch => camera.launch.xml} (100%) rename sensing_launch/launch/aip_customized/{gnss.launch => gnss.launch.xml} (100%) rename sensing_launch/launch/aip_customized/{imu.launch => imu.launch.xml} (100%) rename sensing_launch/launch/aip_customized/{lidar.launch => lidar.launch.xml} (100%) rename sensing_launch/launch/aip_s1/{camera.launch => camera.launch.xml} (100%) rename sensing_launch/launch/aip_s1/{gnss.launch => gnss.launch.xml} (100%) rename sensing_launch/launch/aip_s1/{imu.launch => imu.launch.xml} (100%) rename sensing_launch/launch/aip_s1/{lidar.launch => lidar.launch.xml} (100%) rename sensing_launch/launch/aip_x1/{camera.launch => camera.launch.xml} (100%) rename sensing_launch/launch/aip_x1/{gnss.launch => gnss.launch.xml} (100%) rename sensing_launch/launch/aip_x1/{imu.launch => imu.launch.xml} (100%) rename sensing_launch/launch/aip_x1/{lidar.launch => lidar.launch.xml} (100%) rename sensing_launch/launch/aip_x2/{camera.launch => camera.launch.xml} (100%) rename sensing_launch/launch/aip_x2/{gnss.launch => gnss.launch.xml} (100%) rename sensing_launch/launch/aip_x2/{imu.launch => imu.launch.xml} (100%) rename sensing_launch/launch/aip_x2/{lidar.launch => lidar.launch.xml} (100%) rename sensing_launch/launch/aip_xx1/{camera.launch => camera.launch.xml} (100%) rename sensing_launch/launch/aip_xx1/{gnss.launch => gnss.launch.xml} (100%) rename sensing_launch/launch/aip_xx1/{imu.launch => imu.launch.xml} (100%) rename sensing_launch/launch/aip_xx1/{lidar.launch => lidar.launch.xml} (100%) rename sensing_launch/launch/aip_xx2/{camera.launch => camera.launch.xml} (100%) rename sensing_launch/launch/aip_xx2/{gnss.launch => gnss.launch.xml} (100%) rename sensing_launch/launch/aip_xx2/{imu.launch => imu.launch.xml} (100%) rename sensing_launch/launch/aip_xx2/{lidar.launch => lidar.launch.xml} (100%) rename sensing_launch/launch/{livox_horizon.launch => livox_horizon.launch.xml} (100%) rename sensing_launch/launch/{sensing.launch => sensing.launch.xml} (100%) rename sensing_launch/launch/{velodyne_VLP16.launch => velodyne_VLP16.launch.xml} (100%) rename sensing_launch/launch/{velodyne_VLP32C.launch => velodyne_VLP32C.launch.xml} (100%) rename sensing_launch/launch/{velodyne_VLS128.launch => velodyne_VLS128.launch.xml} (100%) rename system_launch/launch/{system.launch => system.launch.xml} (100%) rename vehicle_launch/launch/{vehicle.launch => vehicle.launch.xml} (100%) rename vehicle_launch/launch/{vehicle_description.launch => vehicle_description.launch.xml} (100%) rename vehicle_launch/launch/{vehicle_interface.launch => vehicle_interface.launch.xml} (100%) diff --git a/autoware_launch/launch/autoware.launch b/autoware_launch/launch/autoware.launch.xml similarity index 100% rename from autoware_launch/launch/autoware.launch rename to autoware_launch/launch/autoware.launch.xml diff --git a/autoware_launch/launch/logging_simulator.launch b/autoware_launch/launch/logging_simulator.launch.xml similarity index 100% rename from autoware_launch/launch/logging_simulator.launch rename to autoware_launch/launch/logging_simulator.launch.xml diff --git a/autoware_launch/launch/planning_simulator.launch b/autoware_launch/launch/planning_simulator.launch.xml similarity index 100% rename from autoware_launch/launch/planning_simulator.launch rename to autoware_launch/launch/planning_simulator.launch.xml diff --git a/control_launch/launch/control.launch b/control_launch/launch/control.launch.xml similarity index 100% rename from control_launch/launch/control.launch rename to control_launch/launch/control.launch.xml diff --git a/integration_launch/launch/ci_planning_simulator.launch b/integration_launch/launch/ci_planning_simulator.launch.xml similarity index 100% rename from integration_launch/launch/ci_planning_simulator.launch rename to integration_launch/launch/ci_planning_simulator.launch.xml diff --git a/integration_launch/launch/release.launch b/integration_launch/launch/release.launch.xml similarity index 100% rename from integration_launch/launch/release.launch rename to integration_launch/launch/release.launch.xml diff --git a/localization_launch/launch/localization.launch b/localization_launch/launch/localization.launch.xml similarity index 100% rename from localization_launch/launch/localization.launch rename to localization_launch/launch/localization.launch.xml diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml similarity index 100% rename from localization_launch/launch/pose_estimator/pose_estimator.launch rename to localization_launch/launch/pose_estimator/pose_estimator.launch.xml diff --git a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml similarity index 100% rename from localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch rename to localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml similarity index 100% rename from localization_launch/launch/twist_estimator/twist_estimator.launch rename to localization_launch/launch/twist_estimator/twist_estimator.launch.xml diff --git a/localization_launch/launch/util/util.launch b/localization_launch/launch/util/util.launch.xml similarity index 100% rename from localization_launch/launch/util/util.launch rename to localization_launch/launch/util/util.launch.xml diff --git a/map_launch/launch/map.launch b/map_launch/launch/map.launch.xml similarity index 100% rename from map_launch/launch/map.launch rename to map_launch/launch/map.launch.xml diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml similarity index 100% rename from perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch rename to perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml diff --git a/perception_launch/launch/object_recognition/detection/detection.launch b/perception_launch/launch/object_recognition/detection/detection.launch.xml similarity index 100% rename from perception_launch/launch/object_recognition/detection/detection.launch rename to perception_launch/launch/object_recognition/detection/detection.launch.xml diff --git a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml similarity index 100% rename from perception_launch/launch/object_recognition/detection/lidar_based_detection.launch rename to perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml similarity index 100% rename from perception_launch/launch/object_recognition/prediction/prediction.launch rename to perception_launch/launch/object_recognition/prediction/prediction.launch.xml diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml similarity index 100% rename from perception_launch/launch/object_recognition/tracking/tracking.launch rename to perception_launch/launch/object_recognition/tracking/tracking.launch.xml diff --git a/perception_launch/launch/perception.launch b/perception_launch/launch/perception.launch.xml similarity index 100% rename from perception_launch/launch/perception.launch rename to perception_launch/launch/perception.launch.xml diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml similarity index 100% rename from perception_launch/launch/traffic_light_recognition/traffic_light.launch rename to perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml diff --git a/planning_launch/launch/mission_planning/mission_planning.launch b/planning_launch/launch/mission_planning/mission_planning.launch.xml similarity index 100% rename from planning_launch/launch/mission_planning/mission_planning.launch rename to planning_launch/launch/mission_planning/mission_planning.launch.xml diff --git a/planning_launch/launch/planning.launch b/planning_launch/launch/planning.launch.xml similarity index 100% rename from planning_launch/launch/planning.launch rename to planning_launch/launch/planning.launch.xml diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch b/planning_launch/launch/scenario_planning/lane_driving.launch.xml similarity index 100% rename from planning_launch/launch/scenario_planning/lane_driving.launch rename to planning_launch/launch/scenario_planning/lane_driving.launch.xml diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml similarity index 100% rename from planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch rename to planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml similarity index 100% rename from planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch rename to planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml diff --git a/planning_launch/launch/scenario_planning/parking.launch b/planning_launch/launch/scenario_planning/parking.launch.xml similarity index 100% rename from planning_launch/launch/scenario_planning/parking.launch rename to planning_launch/launch/scenario_planning/parking.launch.xml diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml similarity index 100% rename from planning_launch/launch/scenario_planning/scenario_planning.launch rename to planning_launch/launch/scenario_planning/scenario_planning.launch.xml diff --git a/sensing_launch/launch/aip_customized/camera.launch b/sensing_launch/launch/aip_customized/camera.launch.xml similarity index 100% rename from sensing_launch/launch/aip_customized/camera.launch rename to sensing_launch/launch/aip_customized/camera.launch.xml diff --git a/sensing_launch/launch/aip_customized/gnss.launch b/sensing_launch/launch/aip_customized/gnss.launch.xml similarity index 100% rename from sensing_launch/launch/aip_customized/gnss.launch rename to sensing_launch/launch/aip_customized/gnss.launch.xml diff --git a/sensing_launch/launch/aip_customized/imu.launch b/sensing_launch/launch/aip_customized/imu.launch.xml similarity index 100% rename from sensing_launch/launch/aip_customized/imu.launch rename to sensing_launch/launch/aip_customized/imu.launch.xml diff --git a/sensing_launch/launch/aip_customized/lidar.launch b/sensing_launch/launch/aip_customized/lidar.launch.xml similarity index 100% rename from sensing_launch/launch/aip_customized/lidar.launch rename to sensing_launch/launch/aip_customized/lidar.launch.xml diff --git a/sensing_launch/launch/aip_s1/camera.launch b/sensing_launch/launch/aip_s1/camera.launch.xml similarity index 100% rename from sensing_launch/launch/aip_s1/camera.launch rename to sensing_launch/launch/aip_s1/camera.launch.xml diff --git a/sensing_launch/launch/aip_s1/gnss.launch b/sensing_launch/launch/aip_s1/gnss.launch.xml similarity index 100% rename from sensing_launch/launch/aip_s1/gnss.launch rename to sensing_launch/launch/aip_s1/gnss.launch.xml diff --git a/sensing_launch/launch/aip_s1/imu.launch b/sensing_launch/launch/aip_s1/imu.launch.xml similarity index 100% rename from sensing_launch/launch/aip_s1/imu.launch rename to sensing_launch/launch/aip_s1/imu.launch.xml diff --git a/sensing_launch/launch/aip_s1/lidar.launch b/sensing_launch/launch/aip_s1/lidar.launch.xml similarity index 100% rename from sensing_launch/launch/aip_s1/lidar.launch rename to sensing_launch/launch/aip_s1/lidar.launch.xml diff --git a/sensing_launch/launch/aip_x1/camera.launch b/sensing_launch/launch/aip_x1/camera.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x1/camera.launch rename to sensing_launch/launch/aip_x1/camera.launch.xml diff --git a/sensing_launch/launch/aip_x1/gnss.launch b/sensing_launch/launch/aip_x1/gnss.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x1/gnss.launch rename to sensing_launch/launch/aip_x1/gnss.launch.xml diff --git a/sensing_launch/launch/aip_x1/imu.launch b/sensing_launch/launch/aip_x1/imu.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x1/imu.launch rename to sensing_launch/launch/aip_x1/imu.launch.xml diff --git a/sensing_launch/launch/aip_x1/lidar.launch b/sensing_launch/launch/aip_x1/lidar.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x1/lidar.launch rename to sensing_launch/launch/aip_x1/lidar.launch.xml diff --git a/sensing_launch/launch/aip_x2/camera.launch b/sensing_launch/launch/aip_x2/camera.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x2/camera.launch rename to sensing_launch/launch/aip_x2/camera.launch.xml diff --git a/sensing_launch/launch/aip_x2/gnss.launch b/sensing_launch/launch/aip_x2/gnss.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x2/gnss.launch rename to sensing_launch/launch/aip_x2/gnss.launch.xml diff --git a/sensing_launch/launch/aip_x2/imu.launch b/sensing_launch/launch/aip_x2/imu.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x2/imu.launch rename to sensing_launch/launch/aip_x2/imu.launch.xml diff --git a/sensing_launch/launch/aip_x2/lidar.launch b/sensing_launch/launch/aip_x2/lidar.launch.xml similarity index 100% rename from sensing_launch/launch/aip_x2/lidar.launch rename to sensing_launch/launch/aip_x2/lidar.launch.xml diff --git a/sensing_launch/launch/aip_xx1/camera.launch b/sensing_launch/launch/aip_xx1/camera.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx1/camera.launch rename to sensing_launch/launch/aip_xx1/camera.launch.xml diff --git a/sensing_launch/launch/aip_xx1/gnss.launch b/sensing_launch/launch/aip_xx1/gnss.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx1/gnss.launch rename to sensing_launch/launch/aip_xx1/gnss.launch.xml diff --git a/sensing_launch/launch/aip_xx1/imu.launch b/sensing_launch/launch/aip_xx1/imu.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx1/imu.launch rename to sensing_launch/launch/aip_xx1/imu.launch.xml diff --git a/sensing_launch/launch/aip_xx1/lidar.launch b/sensing_launch/launch/aip_xx1/lidar.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx1/lidar.launch rename to sensing_launch/launch/aip_xx1/lidar.launch.xml diff --git a/sensing_launch/launch/aip_xx2/camera.launch b/sensing_launch/launch/aip_xx2/camera.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx2/camera.launch rename to sensing_launch/launch/aip_xx2/camera.launch.xml diff --git a/sensing_launch/launch/aip_xx2/gnss.launch b/sensing_launch/launch/aip_xx2/gnss.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx2/gnss.launch rename to sensing_launch/launch/aip_xx2/gnss.launch.xml diff --git a/sensing_launch/launch/aip_xx2/imu.launch b/sensing_launch/launch/aip_xx2/imu.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx2/imu.launch rename to sensing_launch/launch/aip_xx2/imu.launch.xml diff --git a/sensing_launch/launch/aip_xx2/lidar.launch b/sensing_launch/launch/aip_xx2/lidar.launch.xml similarity index 100% rename from sensing_launch/launch/aip_xx2/lidar.launch rename to sensing_launch/launch/aip_xx2/lidar.launch.xml diff --git a/sensing_launch/launch/livox_horizon.launch b/sensing_launch/launch/livox_horizon.launch.xml similarity index 100% rename from sensing_launch/launch/livox_horizon.launch rename to sensing_launch/launch/livox_horizon.launch.xml diff --git a/sensing_launch/launch/sensing.launch b/sensing_launch/launch/sensing.launch.xml similarity index 100% rename from sensing_launch/launch/sensing.launch rename to sensing_launch/launch/sensing.launch.xml diff --git a/sensing_launch/launch/velodyne_VLP16.launch b/sensing_launch/launch/velodyne_VLP16.launch.xml similarity index 100% rename from sensing_launch/launch/velodyne_VLP16.launch rename to sensing_launch/launch/velodyne_VLP16.launch.xml diff --git a/sensing_launch/launch/velodyne_VLP32C.launch b/sensing_launch/launch/velodyne_VLP32C.launch.xml similarity index 100% rename from sensing_launch/launch/velodyne_VLP32C.launch rename to sensing_launch/launch/velodyne_VLP32C.launch.xml diff --git a/sensing_launch/launch/velodyne_VLS128.launch b/sensing_launch/launch/velodyne_VLS128.launch.xml similarity index 100% rename from sensing_launch/launch/velodyne_VLS128.launch rename to sensing_launch/launch/velodyne_VLS128.launch.xml diff --git a/system_launch/launch/system.launch b/system_launch/launch/system.launch.xml similarity index 100% rename from system_launch/launch/system.launch rename to system_launch/launch/system.launch.xml diff --git a/vehicle_launch/launch/vehicle.launch b/vehicle_launch/launch/vehicle.launch.xml similarity index 100% rename from vehicle_launch/launch/vehicle.launch rename to vehicle_launch/launch/vehicle.launch.xml diff --git a/vehicle_launch/launch/vehicle_description.launch b/vehicle_launch/launch/vehicle_description.launch.xml similarity index 100% rename from vehicle_launch/launch/vehicle_description.launch rename to vehicle_launch/launch/vehicle_description.launch.xml diff --git a/vehicle_launch/launch/vehicle_interface.launch b/vehicle_launch/launch/vehicle_interface.launch.xml similarity index 100% rename from vehicle_launch/launch/vehicle_interface.launch rename to vehicle_launch/launch/vehicle_interface.launch.xml From a86a53260eab819189bdd75ce0737e0728bc062a Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Fri, 30 Oct 2020 21:17:08 +0900 Subject: [PATCH 0035/1765] port map_launch package Signed-off-by: mitsudome-r --- map_launch/CMakeLists.txt | 21 +++++++------ map_launch/COLCON_IGNORE | 0 map_launch/launch/map.launch.xml | 17 ++++++----- map_launch/package.xml | 51 +++----------------------------- 4 files changed, 25 insertions(+), 64 deletions(-) delete mode 100644 map_launch/COLCON_IGNORE diff --git a/map_launch/CMakeLists.txt b/map_launch/CMakeLists.txt index c318300cf5..346ccdb967 100644 --- a/map_launch/CMakeLists.txt +++ b/map_launch/CMakeLists.txt @@ -1,14 +1,17 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(map_launch) -find_package(catkin REQUIRED) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-unused-parameter -Wall -Wextra -Wpedantic) +endif() -catkin_package() +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -include_directories() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package( + INSTALL_TO_SHARE + launch ) diff --git a/map_launch/COLCON_IGNORE b/map_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/map_launch/launch/map.launch.xml b/map_launch/launch/map.launch.xml index efa73f802c..2d792eb3fe 100644 --- a/map_launch/launch/map.launch.xml +++ b/map_launch/launch/map.launch.xml @@ -1,18 +1,19 @@ - - + + - - - + + + + - - + + - + diff --git a/map_launch/package.xml b/map_launch/package.xml index df7aacd226..d50ed78acd 100644 --- a/map_launch/package.xml +++ b/map_launch/package.xml @@ -4,56 +4,13 @@ 0.1.0 The map_launch package - - - - mitsudome-r + mitsudome-r + Apache 2 - - - - TODO + ament_cmake_auto - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - - - + ament_cmake From 03ef27c361cd65d83a93e0864524e8744bdeb598 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Sat, 7 Nov 2020 00:21:21 +0900 Subject: [PATCH 0036/1765] port planning launch Signed-off-by: Takamasa Horibe --- planning_launch/CMakeLists.txt | 21 ++- planning_launch/COLCON_IGNORE | 0 .../motion_velocity_optimizer.yaml | 60 +++---- .../obstacle_avoidance_planner.yaml | 158 +++++++++--------- .../mission_planning.launch.xml | 12 +- planning_launch/launch/planning.launch.xml | 13 +- .../scenario_planning/lane_driving.launch.xml | 14 +- .../scenario_planning/parking.launch.xml | 7 +- .../scenario_planning.launch.xml | 10 +- planning_launch/package.xml | 51 +----- 10 files changed, 160 insertions(+), 186 deletions(-) delete mode 100644 planning_launch/COLCON_IGNORE diff --git a/planning_launch/CMakeLists.txt b/planning_launch/CMakeLists.txt index 65406d7899..042004c192 100644 --- a/planning_launch/CMakeLists.txt +++ b/planning_launch/CMakeLists.txt @@ -1,13 +1,18 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(planning_launch) -find_package(catkin REQUIRED) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-unused-parameter -Wall -Wextra -Wpedantic) +endif() -catkin_package() +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -install( - DIRECTORY - launch - config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package( + INSTALL_TO_SHARE + launch + config ) diff --git a/planning_launch/COLCON_IGNORE b/planning_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml index c324867194..c94f2dbffe 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml @@ -1,36 +1,38 @@ -max_velocity: 20.0 # max velocity limit [m/s] -max_accel: 1.0 # max acceleration limit [m/ss] -min_decel: -1.0 # min deceleration limit [m/ss] +/**: + ros__parameters: + max_velocity: 20.0 # max velocity limit [m/s] + max_accel: 1.0 # max acceleration limit [m/ss] + min_decel: -1.0 # min deceleration limit [m/ss] -# curve parameters -max_lateral_accel: 0.5 # max lateral acceleration limit [m/ss] -min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] -decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit -decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit + # curve parameters + max_lateral_accel: 0.5 # max lateral acceleration limit [m/ss] + min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] + decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit + decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit -# engage & replan parameters -replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] -engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) -engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) -engage_exit_ratio: 0.5 # exit engage sequence to normal velocity plannning when the velocity exceeds engage_exit_ratio x engage_velocity. -stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] + # engage & replan parameters + replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s] + engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed) + engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement) + engage_exit_ratio: 0.5 # exit engage sequence to normal velocity plannning when the velocity exceeds engage_exit_ratio x engage_velocity. + stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] -extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m] -extract_behind_dist: 5.0 # backward trajectory distance used for planning [m] -delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajecotory pose [radian] + extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m] + extract_behind_dist: 5.0 # backward trajectory distance used for planning [m] + delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajecotory pose [radian] -max_trajectory_length: 200.0 # max trajectory length for resampling [m] -min_trajectory_length: 30.0 # min trajectory length for resampling [m] -resample_time: 10.0 # resample total time [s] -resample_dt: 0.1 # resample time interval [s] -min_trajectory_interval_distance: 0.1 # resample points-interval length [m] + max_trajectory_length: 200.0 # max trajectory length for resampling [m] + min_trajectory_length: 30.0 # min trajectory length for resampling [m] + resample_time: 10.0 # resample total time [s] + resample_dt: 0.1 # resample time interval [s] + min_trajectory_interval_distance: 0.1 # resample points-interval length [m] -# default weights -# L2: jerk = 100.0, v_weight = 100000.0, a_weight = 1000.0 -# Linf: jerk = 200.0, v_weight = 100000.0, a_weight = 5000.0 + # default weights + # L2: jerk = 100.0, v_weight = 100000.0, a_weight = 1000.0 + # Linf: jerk = 200.0, v_weight = 100000.0, a_weight = 5000.0 -pseudo_jerk_weight: 100.0 # weight for "smoothness" cost -over_v_weight: 100000.0 # weight for "overspeed limit" cost -over_a_weight: 1000.0 # weight for "overaccel limit" cost + pseudo_jerk_weight: 100.0 # weight for "smoothness" cost + over_v_weight: 100000.0 # weight for "overspeed limit" cost + over_a_weight: 1000.0 # weight for "overaccel limit" cost -algorithm_type: "L2" # Option : L2, Linf \ No newline at end of file + algorithm_type: "L2" # Option : L2, Linf diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml index 2f4677ee8c..dc5764a4e0 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml @@ -1,88 +1,90 @@ -# trajectory total/fixing length -trajectory_length: 200 # total trajectory length[m] -forward_fixing_distance: 20.0 # forward fixing length from base_link[m] -backward_fixing_distance: 5.0 # backward fixing length from base_link[m] +/**: + ros__parameters: + # trajectory total/fixing length + trajectory_length: 200 # total trajectory length[m] + forward_fixing_distance: 20.0 # forward fixing length from base_link[m] + backward_fixing_distance: 5.0 # backward fixing length from base_link[m] -# clearance(distance) when generating trajectory -clearance_from_road: 0.2 # clearance from road boundary[m] -clearance_from_object: 1.0 # clearance from object[m] -min_object_clearance_for_joint: 3.2 # minimum clearance from object[m] when judging is_including_only_smooth_range -extra_desired_clearance_from_road: 0.0 # extra desired clearance from road + # clearance(distance) when generating trajectory + clearance_from_road: 0.2 # clearance from road boundary[m] + clearance_from_object: 1.0 # clearance from object[m] + min_object_clearance_for_joint: 3.2 # minimum clearance from object[m] when judging is_including_only_smooth_range + extra_desired_clearance_from_road: 0.0 # extra desired clearance from road -# clearance for unique points -clearance_for_straight_line_: 0.05 # minimum optimizing range around straight points -clearance_for_joint_: 3.2 # minimum optimizing range around joint points -clearance_for_only_smoothing: 0.1 # minimum optimizing range when applygin only smoothing -range_for_extend_joint: 0.1 # minimum optimizing range around joint points for extending -clearance_from_object_for_straight: 10.0 # minimum clearance from object when judging straight line + # clearance for unique points + clearance_for_straight_line_: 0.05 # minimum optimizing range around straight points + clearance_for_joint_: 3.2 # minimum optimizing range around joint points + clearance_for_only_smoothing: 0.1 # minimum optimizing range when applygin only smoothing + range_for_extend_joint: 0.1 # minimum optimizing range around joint points for extending + clearance_from_object_for_straight: 10.0 # minimum clearance from object when judging straight line -# avoiding param -max_avoiding_objects_velocity_ms: .5 # maximum velocity for avoiding objects[m/s] -max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects[m/s] -center_line_width: 1.7 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, center line width around path points used for judging that object is required to avoid or not -acceleration_for_non_deceleration_range: 1.0 # assumed acceleration for calculating non deceleration range + # avoiding param + max_avoiding_objects_velocity_ms: .5 # maximum velocity for avoiding objects[m/s] + max_avoiding_ego_velocity_ms: 6.0 # maximum ego velocity when avoiding objects[m/s] + center_line_width: 1.7 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, center line width around path points used for judging that object is required to avoid or not + acceleration_for_non_deceleration_range: 1.0 # assumed acceleration for calculating non deceleration range -# solving quadratic programming -qp_max_iteration: 10000 # max iteration when solving QP -qp_eps_abs: 1.0e-8 # eps abs when solving OSQP -qp_eps_rel: 1.0e-11 # eps rel when solving OSQP -qp_eps_abs_for_extending: 1.0e-8 # eps abs when solving OSQP for extending -qp_eps_rel_for_extending: 1.0e-9 # eps rel when solving OSQP for extending -qp_eps_abs_for_visualizing: 1.0e-6 # eps abs when solving OSQP for visualizing -qp_eps_rel_for_visualizing: 1.0e-8 # eps rel when solving OSQP for visualizing + # solving quadratic programming + qp_max_iteration: 10000 # max iteration when solving QP + qp_eps_abs: 1.0e-8 # eps abs when solving OSQP + qp_eps_rel: 1.0e-11 # eps rel when solving OSQP + qp_eps_abs_for_extending: 1.0e-8 # eps abs when solving OSQP for extending + qp_eps_rel_for_extending: 1.0e-9 # eps rel when solving OSQP for extending + qp_eps_abs_for_visualizing: 1.0e-6 # eps abs when solving OSQP for visualizing + qp_eps_rel_for_visualizing: 1.0e-8 # eps rel when solving OSQP for visualizing -# constrain space -is_getting_constraints_close2path_points: true # generate trajectory closer to path points -max_x_constrain_search_range: 0.0 # maximum x search range in local coordinate -coef_x_cosntrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction -coef_y_cosntrain_search_resolution: 0.5 # coef for fine sampling when exploring y direction -keep_space_shape_x: 0.2 # keep space for x direction from base_link[m] -keep_space_shape_y: 0.1 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, keep space for y direction from base_link[m] -max_lon_space_for_driveable_constraint: 0.5 # maximum lon(x) space when optimizing point[m] + # constrain space + is_getting_constraints_close2path_points: true # generate trajectory closer to path points + max_x_constrain_search_range: 0.0 # maximum x search range in local coordinate + coef_x_cosntrain_search_resolution: 1.0 # coef for fine sampling when exploring x direction + coef_y_cosntrain_search_resolution: 0.5 # coef for fine sampling when exploring y direction + keep_space_shape_x: 0.2 # keep space for x direction from base_link[m] + keep_space_shape_y: 0.1 # replaced with /vehicle_info/vehicle_width when is_using_vehicle_config is true, keep space for y direction from base_link[m] + max_lon_space_for_driveable_constraint: 0.5 # maximum lon(x) space when optimizing point[m] -is_publishing_clearance_map: true # publish clearance map as nav_msgs::OccupancyGrid -is_publishing_area_with_objects: true # publish occupancy map as nav_msgs::OccupancyGrid -enable_avoidance: true # enable avoidance function -is_using_vehicle_config: true # use vehicle config -num_sampling_points: 100 # number of optimizing points -num_joint_buffer_points: 3 # number of joint buffer points -num_joint_buffer_points_for_extending: 6 # number of joint buffer points for extending -num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx -num_fix_points_for_extending: 50 # number of fixing points when extending -delta_arc_length_for_optimization: 1.0 # delta arc length when optimizing[m] -delta_arc_length_for_trajectory: 0.1 # delta arc length for trajectory[m] -delta_dist_threshold_for_closest_point: 3.0 # delta dist thres for closest point[m] -delta_yaw_threshold_for_closest_point: 1.046 #M_PI/3.0, delta yaw thres for closest point -delta_yaw_threshold_for_straight: 0.02 # delta dist thres for straight point + is_publishing_clearance_map: true # publish clearance map as nav_msgs::OccupancyGrid + is_publishing_area_with_objects: true # publish occupancy map as nav_msgs::OccupancyGrid + enable_avoidance: true # enable avoidance function + is_using_vehicle_config: true # use vehicle config + num_sampling_points: 100 # number of optimizing points + num_joint_buffer_points: 3 # number of joint buffer points + num_joint_buffer_points_for_extending: 6 # number of joint buffer points for extending + num_offset_for_begin_idx: 2 # number of shifting points for beginning non-fix idx + num_fix_points_for_extending: 50 # number of fixing points when extending + delta_arc_length_for_optimization: 1.0 # delta arc length when optimizing[m] + delta_arc_length_for_trajectory: 0.1 # delta arc length for trajectory[m] + delta_dist_threshold_for_closest_point: 3.0 # delta dist thres for closest point[m] + delta_yaw_threshold_for_closest_point: 1.046 #M_PI/3.0, delta yaw thres for closest point + delta_yaw_threshold_for_straight: 0.02 # delta dist thres for straight point -# mpt param -# vehicle param for mpt -max_steer_deg: 30.0 # max steering angle [deg] -steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] + # mpt param + # vehicle param for mpt + max_steer_deg: 30.0 # max steering angle [deg] + steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] -# trajectory param for mpt -num_curvature_sampling_points: 5 # number of sampling points when calculating curvature -delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt[m] -num_fix_points_for_mpt: 8 # number of fixing points around ego vehicle + # trajectory param for mpt + num_curvature_sampling_points: 5 # number of sampling points when calculating curvature + delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt[m] + num_fix_points_for_mpt: 8 # number of fixing points around ego vehicle -# optimization param for mpt -is_hard_fixing_terminal_point: true # hard fixing terminal point -base_point_weight: 2000 # slack weight for lateral error around base_link -top_point_weight: 1000 # slack weight for lateral error around vehicle-top point -mid_point_weight: 1000 # slack weight for lateral error around the middle point -lat_error_weight: 10.0 # weight for lateral error -yaw_error_weight: 0.0 # weight for yaw error -steer_input_weight: 0.01 # weight for steering input -steer_rate_weight: 1 # weight for sttering rate -steer_acc_weight: 0.000001 # weight for steering acceration -terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point -terminal_yaw_error_weight: 100.0 # weight for yaw errror at terminal point -terminal_path_lat_error_weight: 1000.0 # weight for lateral errro at path end point -terminal_path_yaw_error_weight: 1000.0 # weight for yaw errro at path end point -zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero + # optimization param for mpt + is_hard_fixing_terminal_point: true # hard fixing terminal point + base_point_weight: 2000 # slack weight for lateral error around base_link + top_point_weight: 1000 # slack weight for lateral error around vehicle-top point + mid_point_weight: 1000 # slack weight for lateral error around the middle point + lat_error_weight: 10.0 # weight for lateral error + yaw_error_weight: 0.0 # weight for yaw error + steer_input_weight: 0.01 # weight for steering input + steer_rate_weight: 1 # weight for sttering rate + steer_acc_weight: 0.000001 # weight for steering acceration + terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point + terminal_yaw_error_weight: 100.0 # weight for yaw errror at terminal point + terminal_path_lat_error_weight: 1000.0 # weight for lateral errro at path end point + terminal_path_yaw_error_weight: 1000.0 # weight for yaw errro at path end point + zero_ff_steer_angle: 0.5 # threshold that feed-forward angle becomes zero -# replanning & trimming trajectory param outside algorithm -min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] -min_delta_time_sec_for_replan: 1.0 # minimum delta time for replan[second] -max_dist_for_extending_end_point: 5.0 # minimum delta dist thres for extending last point[m] -distance_for_path_shape_chagne_detection: 2.0 # minimum delta dist thres for detecting path shape change + # replanning & trimming trajectory param outside algorithm + min_delta_dist_for_replan: 10.0 # minimum delta dist thres for replan[m] + min_delta_time_sec_for_replan: 1.0 # minimum delta time for replan[second] + max_dist_for_extending_end_point: 5.0 # minimum delta dist thres for extending last point[m] + distance_for_path_shape_chagne_detection: 2.0 # minimum delta dist thres for detecting path shape change diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.xml b/planning_launch/launch/mission_planning/mission_planning.launch.xml index d1e94f15c8..9bbc44e98a 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.xml +++ b/planning_launch/launch/mission_planning/mission_planning.launch.xml @@ -4,13 +4,13 @@ - + - - - - - + + + + + diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index d8d6dd9a10..bfc5e01110 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -1,15 +1,18 @@ - + + - - + + + - - + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index 27fa088c48..f3d6507a5d 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -1,15 +1,19 @@ - + + - - + + + + - - + + + diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index 0198eb09d0..9ecae8013a 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -1,7 +1,8 @@ - - + + + @@ -10,7 +11,7 @@ - + diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index c4d21f9103..9d56792fdd 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -1,6 +1,6 @@ - + @@ -15,8 +15,8 @@ - - + + @@ -24,10 +24,10 @@ - + - + diff --git a/planning_launch/package.xml b/planning_launch/package.xml index 24d7f88c67..79b6dee507 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -4,56 +4,13 @@ 0.1.0 The planning_launch package - - - - tier4 + Takamasa Horibe + Apache 2.0 - - - - TODO + ament_cmake_auto - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - - - + ament_cmake From ed547c0c8eb5ea0f0f126d6c2741c70b87f50522 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Mon, 9 Nov 2020 12:13:34 +0100 Subject: [PATCH 0037/1765] Report errors on CI --- .github/workflows/build_and_test.yml | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index fb0faf937a..8fa3b58f67 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -2,13 +2,15 @@ name: Build and test on: pull_request: + branches: + - ros2 push: branches: - ros2 jobs: build-and-test: - runs-on: ubuntu-20.04 + runs-on: ubuntu-latest container: ros:foxy steps: @@ -16,10 +18,19 @@ jobs: uses: actions/checkout@v2 - name: Install missing dependencies - run: rosdep update && DEBIAN_FRONTEND=noninteractive sudo rosdep install --from-paths . --ignore-src --rosdistro foxy -y + run: | + sudo apt update + rosdep update + DEBIAN_FRONTEND=noninteractive rosdep install --from-paths . --ignore-src --rosdistro foxy -y - name: Build - run: . /opt/ros/foxy/setup.sh && colcon build --event-handlers console_cohesion+ + run: | + . /opt/ros/foxy/setup.sh + colcon build --event-handlers console_cohesion+ - name: Run tests - run: . /opt/ros/foxy/setup.sh && colcon test --event-handlers console_cohesion+ + run: | + . /opt/ros/foxy/setup.sh + colcon test \ + --event-handlers console_cohesion+ \ + --return-code-on-test-failure From 861fa1e51053216c309abd0742b564290c296f8e Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Mon, 16 Nov 2020 23:41:00 +0900 Subject: [PATCH 0038/1765] update ci, and add build_depends.repos (#12) Signed-off-by: mitsudome-r --- .github/workflows/build_and_test.yml | 5 +++++ build_depends.repos | 9 +++++++++ 2 files changed, 14 insertions(+) create mode 100644 build_depends.repos diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 8fa3b58f67..d9b74f146e 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -17,6 +17,11 @@ jobs: - name: Check out repo uses: actions/checkout@v2 + - name: Clone dependency packages + run: | + mkdir dependency_ws + vcs import dependency_ws < build_depends.repos + - name: Install missing dependencies run: | sudo apt update diff --git a/build_depends.repos b/build_depends.repos new file mode 100644 index 0000000000..ce95738362 --- /dev/null +++ b/build_depends.repos @@ -0,0 +1,9 @@ +repositories: + description/sensor/velodyne_simulator: + type: git + url: https://github.com/tier4/velodyne_simulator.git + version: ros2 + description/sensor/sensor_description: + type: git + url: https://github.com/tier4/sensor_description.iv.universe.git + version: ros2 From 3c8c16d67c168712665d5621c2558502202f2b13 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 6 Nov 2020 23:41:37 +0900 Subject: [PATCH 0039/1765] port vehicle_launch Signed-off-by: Takamasa Horibe --- vehicle_launch/CMakeLists.txt | 10 ++++---- vehicle_launch/COLCON_IGNORE | 0 vehicle_launch/launch/vehicle.launch.xml | 24 ++++++++++--------- .../launch/vehicle_description.launch.xml | 20 +++++----------- .../launch/vehicle_interface.launch.xml | 19 ++++++++------- vehicle_launch/package.xml | 7 ++++-- 6 files changed, 40 insertions(+), 40 deletions(-) delete mode 100644 vehicle_launch/COLCON_IGNORE diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt index 331b62f499..d49a9be1bf 100644 --- a/vehicle_launch/CMakeLists.txt +++ b/vehicle_launch/CMakeLists.txt @@ -1,15 +1,15 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(vehicle_launch) add_compile_options(-std=c++14) -find_package(catkin REQUIRED) +find_package(ament_cmake_auto REQUIRED) +find_package(xacro REQUIRED) -catkin_package() +ament_auto_find_build_dependencies() -install(DIRECTORY +ament_auto_package(INSTALL_TO_SHARE launch config urdf - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) diff --git a/vehicle_launch/COLCON_IGNORE b/vehicle_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/vehicle_launch/launch/vehicle.launch.xml b/vehicle_launch/launch/vehicle.launch.xml index b6191e70cd..09d534a88a 100644 --- a/vehicle_launch/launch/vehicle.launch.xml +++ b/vehicle_launch/launch/vehicle.launch.xml @@ -5,20 +5,22 @@ - + - - - - - + + + + + + + - - - - - + + + + + diff --git a/vehicle_launch/launch/vehicle_description.launch.xml b/vehicle_launch/launch/vehicle_description.launch.xml index 7a09cd6e13..d1ccd1f318 100644 --- a/vehicle_launch/launch/vehicle_description.launch.xml +++ b/vehicle_launch/launch/vehicle_description.launch.xml @@ -3,22 +3,14 @@ - + - - - - - - - - - - - - - + + + + + diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml index 675ff78397..5eb4ba2d2c 100644 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ b/vehicle_launch/launch/vehicle_interface.launch.xml @@ -1,19 +1,22 @@ - - - + + + + + + - - - + + + - - + + diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index e20bbfeefd..8509d9580e 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -8,14 +8,17 @@ Apache2 - catkin + ament_cmake_auto + + xacro + camera_description imu_description livox_description velodyne_description robot_state_publisher - roscpp + ament_cmake From b6dde780a3f7da77609dfd33a52eb39a5c1e08bc Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Thu, 19 Nov 2020 19:44:20 +0100 Subject: [PATCH 0040/1765] Update dependencies (#16) * Update dependencies * Add more dependencies --- build_depends.repos | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/build_depends.repos b/build_depends.repos index ce95738362..6da6212c60 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -7,3 +7,19 @@ repositories: type: git url: https://github.com/tier4/sensor_description.iv.universe.git version: ros2 + vendor/grid_map: + type: git + url: https://github.com/mitsudome-r/grid_map.git + version: ros2-fix-ci + vendor/perception_pcl: + type: git + url: https://github.com/ros-perception/perception_pcl.git + version: foxy-devel + vendor/rclcpp_generic: + type: git + url: https://github.com/ApexAI/rclcpp_generic.git + version: autoware + vendor/topic_tools: + type: git + url: https://github.com/ApexAI/topic_tools.git + version: autoware From d93a58eb0baa45f52f3d892873d81d2e8d4195d0 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 20 Nov 2020 17:11:04 +0900 Subject: [PATCH 0041/1765] port control launch (#7) * port control launch Signed-off-by: Takamasa Horibe * fix license Signed-off-by: Takamasa Horibe --- control_launch/CMakeLists.txt | 21 +-- control_launch/COLCON_IGNORE | 0 .../mpc_follower/mpc_follower_param.yaml | 76 +++++------ .../pure_pursuit/pure_pursuit_param.yaml | 14 +- .../velocity_controller_param.yaml | 124 +++++++++--------- control_launch/launch/control.launch.xml | 38 +++--- control_launch/package.xml | 12 +- 7 files changed, 145 insertions(+), 140 deletions(-) delete mode 100644 control_launch/COLCON_IGNORE diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt index e469a18318..7774343a37 100644 --- a/control_launch/CMakeLists.txt +++ b/control_launch/CMakeLists.txt @@ -1,13 +1,18 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(control_launch) -find_package(catkin REQUIRED) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wno-unused-parameter -Wall -Wextra -Wpedantic) +endif() -catkin_package() +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -install( - DIRECTORY - config - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package( + INSTALL_TO_SHARE + config + launch ) diff --git a/control_launch/COLCON_IGNORE b/control_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower_param.yaml index c8d036356b..3d6171ce7d 100644 --- a/control_launch/config/mpc_follower/mpc_follower_param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower_param.yaml @@ -1,42 +1,42 @@ +/**: + ros__parameters: + # -- system -- + ctrl_period: 0.03 # control period [s] + traj_resample_dist: 0.1 # path resampling interval [m] + enable_yaw_recalculation: false # flag for recalculation of yaw angle after resampling + admisible_position_error: 5.0 # stop mpc calculation when error is larger than the following value + admisible_yaw_error_: 1.57 # stop mpc calculation when error is larger than the following value + # -- path smoothing -- + enable_path_smoothing: false # flag for path smoothing + path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing + curvature_smoothing_num: 15 # point-to-point index distance used in curvature calculation : curvature is calculated from three points p(i-num), p(i), p(i+num) -# -- system -- -ctrl_period: 0.03 # control period [s] -traj_resample_dist: 0.1 # path resampling interval [m] -enable_yaw_recalculation: false # flag for recalculation of yaw angle after resampling -admisible_position_error: 5.0 # stop mpc calculation when error is larger than the following value -admisible_yaw_error_: 1.57 # stop mpc calculation when error is larger than the following value + # -- mpc optimization -- + qpoases_max_iter: 500 # max iteration number for quadratic programming + qp_solver_type: "osqp" # optimization solver type. option is unconstraint_fast, unconstraint, and qpoases_hotstart and osqp + mpc_prediction_horizon: 50 # prediction horizon step + mpc_prediction_dt: 0.1 # prediction horizon period [s] + mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q + mpc_weight_heading_error: 0.0 # heading error weight in matrix Q + mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q + mpc_weight_steering_input: 1.0 # steering error weight in matrix R + mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R + mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R + mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R + mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R + mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability + mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability + mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero -# -- path smoothing -- -enable_path_smoothing: false # flag for path smoothing -path_filter_moving_ave_num: 25 # param of moving average filter for path smoothing -curvature_smoothing_num: 15 # point-to-point index distance used in curvature calculation : curvature is calculated from three points p(i-num), p(i), p(i+num) + # -- vehicle model -- + vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics + input_delay: 0.24 # steering input delay time for delay compensation + vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] + steer_lim_deg: 40.0 # steering angle limit [deg] + steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] + acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] + velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s] -# -- mpc optimization -- -qpoases_max_iter: 500 # max iteration number for quadratic programming -qp_solver_type: "osqp" # optimization solver type. option is unconstraint_fast, unconstraint, and qpoases_hotstart and osqp -mpc_prediction_horizon: 50 # prediction horizon step -mpc_prediction_dt: 0.1 # prediction horizon period [s] -mpc_weight_lat_error: 0.1 # lateral error weight in matrix Q -mpc_weight_heading_error: 0.0 # heading error weight in matrix Q -mpc_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q -mpc_weight_steering_input: 1.0 # steering error weight in matrix R -mpc_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R -mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R -mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R -mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R -mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability -mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability -mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero - -# -- vehicle model -- -vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics -input_delay: 0.24 # steering input delay time for delay compensation -vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] -steer_lim_deg: 40.0 # steering angle limit [deg] -steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] -acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] -velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s] - -# -- lowpass filter for noise reduction -- -steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] + # -- lowpass filter for noise reduction -- + steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] diff --git a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml index 9d38aefc37..51cb3acb5d 100644 --- a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml +++ b/control_launch/config/pure_pursuit/pure_pursuit_param.yaml @@ -1,7 +1,9 @@ -# -- system -- -control_period: 0.033 +/**: + ros__parameters: + # -- system -- + control_period: 0.033 -# --algorithm -lookahead_distance_ratio: 2.2 -min_lookahead_distance: 2.5 -reverse_min_lookahead_distance: 7.0 + # --algorithm + lookahead_distance_ratio: 2.2 + min_lookahead_distance: 2.5 + reverse_min_lookahead_distance: 7.0 diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml index 8c3149074a..45b5c6dc2f 100644 --- a/control_launch/config/velocity_controller/velocity_controller_param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -1,61 +1,63 @@ -# closest waypoint threshold -closest_waypoint_distance_threshold: 3.0 -closest_waypoint_angle_threshold: 0.7854 - -# stop state -stop_state_velocity: 0.0 -stop_state_acc: -3.4 -stop_state_entry_ego_speed: 0.2 -stop_state_entry_target_speed: 0.1 -stop_state_keep_stopping_dist: 0.5 - -# delay compensation -delay_compensation_time: 0.17 - -# emergency stop by this controller -emergency_stop_acc: -5.0 -emergency_stop_jerk: -3.0 - -# smooth stop -smooth_stop: - stop_dist: 3.0 - exit_ego_speed: 1.0 - entry_ego_speed: 0.8 - exit_target_speed: 1.0 - entry_target_speed: 0.2 - weak_brake_time: 1.0 - weak_brake_acc: -1.0 - increasing_brake_time: 1.0 - increasing_brake_gradient: -0.1 - stop_brake_time: 1.0 - stop_brake_acc: -3.4 - -# acceleration limit -max_acc: 3.0 -min_acc: -5.0 - -# jerk limit -max_jerk: 2.0 -min_jerk: -5.0 - -# slope compensation -enable_slope_compensation: true -max_pitch_rad: 0.1 -min_pitch_rad: -0.1 -lpf_pitch_gain: 0.95 - -# velocity feedback -pid_controller: - kp: 1.0 - ki: 0.1 - kd: 0 - max_out: 1.0 - min_out: -1.0 - max_p_effort: 1.0 - min_p_effort: -1.0 - max_i_effort: 0.3 - min_i_effort: -0.3 - max_d_effort: 0 - min_d_effort: 0 - current_velocity_threshold_pid_integration: 0.5 - lpf_velocity_error_gain: 0.9 \ No newline at end of file +/**: + ros__parameters: + # closest waypoint threshold + closest_waypoint_distance_threshold: 3.0 + closest_waypoint_angle_threshold: 0.7854 + + # stop state + stop_state_velocity: 0.0 + stop_state_acc: -3.4 + stop_state_entry_ego_speed: 0.2 + stop_state_entry_target_speed: 0.1 + stop_state_keep_stopping_dist: 0.5 + + # delay compensation + delay_compensation_time: 0.17 + + # emergency stop by this controller + emergency_stop_acc: -5.0 + emergency_stop_jerk: -3.0 + + # smooth stop + smooth_stop: + stop_dist: 3.0 + exit_ego_speed: 1.0 + entry_ego_speed: 0.8 + exit_target_speed: 1.0 + entry_target_speed: 0.2 + weak_brake_time: 1.0 + weak_brake_acc: -1.0 + increasing_brake_time: 1.0 + increasing_brake_gradient: -0.1 + stop_brake_time: 1.0 + stop_brake_acc: -3.4 + + # acceleration limit + max_acc: 3.0 + min_acc: -5.0 + + # jerk limit + max_jerk: 2.0 + min_jerk: -5.0 + + # slope compensation + enable_slope_compensation: true + max_pitch_rad: 0.1 + min_pitch_rad: -0.1 + lpf_pitch_gain: 0.95 + + # velocity feedback + pid_controller: + kp: 1.0 + ki: 0.1 + kd: 0 + max_out: 1.0 + min_out: -1.0 + max_p_effort: 1.0 + min_p_effort: -1.0 + max_i_effort: 0.3 + min_i_effort: -0.3 + max_d_effort: 0 + min_d_effort: 0 + current_velocity_threshold_pid_integration: 0.5 + lpf_velocity_error_gain: 0.9 diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 2a4000982c..2a74551c53 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -5,48 +5,50 @@ - - - + + + - + + - + + - - + + - - + + - - + + - - - - + + + + - + - + - + diff --git a/control_launch/package.xml b/control_launch/package.xml index c2f9157211..28899dfcf8 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -4,19 +4,13 @@ 0.1.0 The control_launch package - - - Takamasa Horibe + Apache License 2.0 - - - - TODO - - catkin + ament_cmake_auto + ament_cmake From 28980f08398de4b2ba127e2acf926be486c45fd0 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 20 Nov 2020 19:28:32 +0100 Subject: [PATCH 0042/1765] Install geometry packages (#17) --- .github/workflows/build_and_test.yml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index d9b74f146e..3d63f5456d 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -27,6 +27,11 @@ jobs: sudo apt update rosdep update DEBIAN_FRONTEND=noninteractive rosdep install --from-paths . --ignore-src --rosdistro foxy -y + sudo apt-get install -y \ + ros-foxy-tf2>=0.13.6-1focal.20201028.172335 \ + ros-foxy-tf2-geometry-msgs>=0.13.6-1focal.20201028.172335 \ + ros-foxy-tf2-ros>=0.13.6-1focal.20201028.172335 \ + ros-foxy-tf2-sensor-msgs>=0.13.6-1focal.20201028.172335 - name: Build run: | From ea92a6dff07db099761dfc7526018e475fa8ddfa Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Tue, 24 Nov 2020 12:03:37 +0100 Subject: [PATCH 0043/1765] Only build the launch subset of packages (#18) * Only build the launch subset of packages * Fix missing colcon verb --- .github/workflows/build_and_test.yml | 29 ++++++++++++++++++++++++++-- 1 file changed, 27 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 3d63f5456d..5efd3725bb 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -36,11 +36,36 @@ jobs: - name: Build run: | . /opt/ros/foxy/setup.sh - colcon build --event-handlers console_cohesion+ + colcon build \ + --event-handlers console_cohesion+ \ + --packages-ignore \ + autoware_launch \ + integration_launch \ + localization_launch \ + perception_launch \ + planning_launch \ + sensing_launch \ + system_launch \ + --packages-up-to \ + control_launch \ + map_launch \ + vehicle_launch - name: Run tests run: | . /opt/ros/foxy/setup.sh colcon test \ + --return-code-on-test-failure \ --event-handlers console_cohesion+ \ - --return-code-on-test-failure + --packages-ignore \ + autoware_launch \ + integration_launch \ + localization_launch \ + perception_launch \ + planning_launch \ + sensing_launch \ + system_launch \ + --packages-up-to \ + control_launch \ + map_launch \ + vehicle_launch From 33667ae773f18286daa82a7b827062d8f2cfe114 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 6 Nov 2020 16:21:14 +0100 Subject: [PATCH 0044/1765] Port to ROS 2 --- .github/workflows/build_and_test.yml | 4 ++-- build_depends.repos | 4 ++++ system_launch/CMakeLists.txt | 17 +++++++++-------- system_launch/COLCON_IGNORE | 0 system_launch/launch/system.launch.xml | 19 ++++++++++--------- system_launch/package.xml | 15 ++++++++++++--- 6 files changed, 37 insertions(+), 22 deletions(-) delete mode 100644 system_launch/COLCON_IGNORE diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 5efd3725bb..cfae0b1267 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -45,10 +45,10 @@ jobs: perception_launch \ planning_launch \ sensing_launch \ - system_launch \ --packages-up-to \ control_launch \ map_launch \ + system_launch \ vehicle_launch - name: Run tests @@ -64,8 +64,8 @@ jobs: perception_launch \ planning_launch \ sensing_launch \ - system_launch \ --packages-up-to \ control_launch \ map_launch \ + system_launch \ vehicle_launch diff --git a/build_depends.repos b/build_depends.repos index 6da6212c60..7a6ca070b4 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -1,4 +1,8 @@ repositories: + dependencies/Pilot.Auto: + type: git + url: https://github.com/tier4/Pilot.Auto.git + version: ros2 description/sensor/velodyne_simulator: type: git url: https://github.com/tier4/velodyne_simulator.git diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt index 2519b3e2f0..13d73f858f 100644 --- a/system_launch/CMakeLists.txt +++ b/system_launch/CMakeLists.txt @@ -1,13 +1,14 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(system_launch) -find_package(catkin REQUIRED COMPONENTS -) +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -catkin_package() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package(INSTALL_TO_SHARE + launch ) diff --git a/system_launch/COLCON_IGNORE b/system_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index b30703b4fd..bf86d92b7e 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -2,21 +2,22 @@ - + - - - - + + - - + + - - + + diff --git a/system_launch/package.xml b/system_launch/package.xml index 7f5f70ae0c..317d79b4ba 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -1,14 +1,23 @@ - + + system_launch 0.1.0 The system_launch package Kenji Miyake - Apache 2 + Apache License 2.0 - catkin + ament_cmake_auto + + ament_lint_auto + ament_lint_common + + + autoware_error_monitor + emergency_handler + ament_cmake From eba01272738b9dd68a1dd8111c6b141b962fb51d Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 25 Nov 2020 18:09:58 +0900 Subject: [PATCH 0045/1765] add missing porting Signed-off-by: Takamasa Horibe --- .../behavior_planning.launch.xml | 34 +++++++++---------- .../motion_planning.launch.xml | 22 ++++++------ 2 files changed, 28 insertions(+), 28 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index e67dde71cd..008daae9cc 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -2,18 +2,18 @@ - - - - - - - - - - - - + + + + + + + + + + + + @@ -34,15 +34,15 @@ - - - - + + + + - + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index df97661f99..2d225ef190 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -3,19 +3,19 @@ - - - - + + + + - - - + + + @@ -23,10 +23,10 @@ - - - - + + + + From c22e7c008196a13c48443be6ee10fca29d26b125 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Wed, 25 Nov 2020 20:16:13 +0900 Subject: [PATCH 0046/1765] replace rostopic pub with executable in behavior_planning.launch.xml Signed-off-by: mitsudome-r --- .../lane_driving/behavior_planning/behavior_planning.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 008daae9cc..b032b00c34 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -32,7 +32,7 @@ - + From fa8a9aad3c1824fe56f057e4f4bfce2b7a9aeb99 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Wed, 25 Nov 2020 20:17:20 +0900 Subject: [PATCH 0047/1765] fix remapping of topics in launch files Signed-off-by: mitsudome-r --- .../motion_planning.launch.xml | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 2d225ef190..d0e6f5d6fa 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -3,31 +3,31 @@ - - - + + + - - - + + + - - - - + + + + From 59c93187afdbc83777a9291e140e4cf02228183a Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Wed, 25 Nov 2020 20:17:44 +0900 Subject: [PATCH 0048/1765] modify integer parameters to double parameters Signed-off-by: mitsudome-r --- .../obstacle_avoidance_planner.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml index dc5764a4e0..7b37f0aedd 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml @@ -69,13 +69,13 @@ # optimization param for mpt is_hard_fixing_terminal_point: true # hard fixing terminal point - base_point_weight: 2000 # slack weight for lateral error around base_link - top_point_weight: 1000 # slack weight for lateral error around vehicle-top point - mid_point_weight: 1000 # slack weight for lateral error around the middle point + base_point_weight: 2000.0 # slack weight for lateral error around base_link + top_point_weight: 1000.0 # slack weight for lateral error around vehicle-top point + mid_point_weight: 1000.0 # slack weight for lateral error around the middle point lat_error_weight: 10.0 # weight for lateral error yaw_error_weight: 0.0 # weight for yaw error steer_input_weight: 0.01 # weight for steering input - steer_rate_weight: 1 # weight for sttering rate + steer_rate_weight: 1.0 # weight for steering rate steer_acc_weight: 0.000001 # weight for steering acceration terminal_lat_error_weight: 0.0 # weight for lateral error at terminal point terminal_yaw_error_weight: 100.0 # weight for yaw errror at terminal point From 982d85573ba2118de15b28f6c45a28dc074f47d0 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Wed, 25 Nov 2020 20:18:34 +0900 Subject: [PATCH 0049/1765] fix arguments in parking.launch.xml Signed-off-by: mitsudome-r --- planning_launch/launch/scenario_planning/parking.launch.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/planning_launch/launch/scenario_planning/parking.launch.xml b/planning_launch/launch/scenario_planning/parking.launch.xml index 9ecae8013a..726d8b7121 100644 --- a/planning_launch/launch/scenario_planning/parking.launch.xml +++ b/planning_launch/launch/scenario_planning/parking.launch.xml @@ -7,15 +7,15 @@ - - + + - + From ad42b91da6ed603eb937ed8376b622ef7c168ccf Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Wed, 25 Nov 2020 20:18:58 +0900 Subject: [PATCH 0050/1765] fix remapping of topics in scenario_planning.launch.xml Signed-off-by: mitsudome-r --- .../launch/scenario_planning/scenario_planning.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 9d56792fdd..e33d1c162f 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -13,9 +13,9 @@ - - + + From 46aa1dd3ef5d8cccf5453c3aa9746cdbb9167b46 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 25 Nov 2020 17:50:57 +0100 Subject: [PATCH 0051/1765] Fix params file paths --- system_launch/launch/system.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index bf86d92b7e..b8d66ab303 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -12,12 +12,12 @@ - + - + From 624243f63221ceea313784cfeed5a27f282a6801 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 25 Nov 2020 18:11:04 +0100 Subject: [PATCH 0052/1765] Re-add autoware_state_monitor --- system_launch/launch/system.launch.xml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index b8d66ab303..ca5c72683e 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -5,10 +5,10 @@ - + + + + From 5f13b3975a0464a1fd0353bba2373988aea193bf Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Thu, 26 Nov 2020 08:22:31 +0100 Subject: [PATCH 0053/1765] Update system_launch/launch/system.launch.xml Co-authored-by: Takamasa Horibe --- system_launch/launch/system.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index ca5c72683e..d13998a655 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -6,8 +6,8 @@ - - + + From 29cfcda27a20e48a9479d85defe52eca7c0b07c8 Mon Sep 17 00:00:00 2001 From: Yunus Emre Caliskan Date: Tue, 10 Nov 2020 15:44:47 +0100 Subject: [PATCH 0054/1765] Port localization_launch to ros2 --- localization_launch/CMakeLists.txt | 20 +++++---- localization_launch/COLCON_IGNORE | 0 .../launch/localization.launch.xml | 29 +++++++----- .../pose_estimator/pose_estimator.launch.xml | 2 +- .../pose_twist_fusion_filter.launch.xml | 40 ++++++++--------- .../twist_estimator.launch.xml | 2 +- .../launch/util/util.launch.xml | 20 ++++----- localization_launch/package.xml | 45 +++++-------------- 8 files changed, 73 insertions(+), 85 deletions(-) delete mode 100644 localization_launch/COLCON_IGNORE diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt index 047892fac7..ccb239a68a 100644 --- a/localization_launch/CMakeLists.txt +++ b/localization_launch/CMakeLists.txt @@ -1,12 +1,16 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(localization_launch) -find_package(catkin REQUIRED) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-parameter) +endif() -catkin_package() +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +ament_auto_package(INSTALL_TO_SHARE + launch + ) \ No newline at end of file diff --git a/localization_launch/COLCON_IGNORE b/localization_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/localization_launch/launch/localization.launch.xml b/localization_launch/launch/localization.launch.xml index 1543c92629..151d482dea 100644 --- a/localization_launch/launch/localization.launch.xml +++ b/localization_launch/launch/localization.launch.xml @@ -1,28 +1,37 @@ - + + - - + + + - - + + + - - + + + - - + + + - + + + + + diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index f70e6d3145..2ceb02097a 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -1,6 +1,6 @@ - + diff --git a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml index 76310afb0e..6af8ed22ee 100644 --- a/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml +++ b/localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml @@ -1,26 +1,26 @@ - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + - + - - + + diff --git a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml index da8198ef72..8b8eb79601 100644 --- a/localization_launch/launch/twist_estimator/twist_estimator.launch.xml +++ b/localization_launch/launch/twist_estimator/twist_estimator.launch.xml @@ -1,6 +1,6 @@ - + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index a0558ce968..18e0f0a2ae 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -10,13 +10,13 @@ - - + + - - - + + + min_x: -60.0 max_x: 60.0 @@ -26,15 +26,15 @@ max_z: 50.0 negative: False - - + + - - - + + + voxel_size_x: 3.0 voxel_size_y: 3.0 diff --git a/localization_launch/package.xml b/localization_launch/package.xml index 48230f21cb..e4ccb2e7c6 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -1,5 +1,6 @@ - + + localization_launch 0.1.0 The localization_launch package @@ -15,44 +16,18 @@ Apache 2 + ament_cmake_auto - - - - + ndt_scan_matcher + ekf_localizer + gyro_odometer + pose_initializer + pointcloud_preprocessor + topic_tools - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - + ament_cmake From 9798068d66cc3f5e8fec4824da55092062f25c9f Mon Sep 17 00:00:00 2001 From: Yunus Emre Caliskan Date: Thu, 26 Nov 2020 09:23:52 +0100 Subject: [PATCH 0055/1765] Include localization launch in github workflow file --- .github/workflows/build_and_test.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index cfae0b1267..8496171f37 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -41,7 +41,6 @@ jobs: --packages-ignore \ autoware_launch \ integration_launch \ - localization_launch \ perception_launch \ planning_launch \ sensing_launch \ @@ -49,7 +48,8 @@ jobs: control_launch \ map_launch \ system_launch \ - vehicle_launch + vehicle_launch \ + localization_launch - name: Run tests run: | @@ -60,7 +60,6 @@ jobs: --packages-ignore \ autoware_launch \ integration_launch \ - localization_launch \ perception_launch \ planning_launch \ sensing_launch \ @@ -68,4 +67,5 @@ jobs: control_launch \ map_launch \ system_launch \ - vehicle_launch + vehicle_launch \ + localization_launch From bc0aab83a920d3b5023713a529718cd6e04a1da9 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Mon, 30 Nov 2020 03:51:06 +0100 Subject: [PATCH 0056/1765] [ROS2 Porting] perception_launch (#6) * Initial port to ROS 2 * Port to ROS 2 * Added dependencies * fix perception_launch Signed-off-by: mitsudome-r * Use arg instead of let Co-authored-by: mitsudome-r --- build_depends.repos | 4 ++ perception_launch/CMakeLists.txt | 14 ++-- perception_launch/COLCON_IGNORE | 0 ...ra_lidar_fusion_based_detection.launch.xml | 58 ++++++++-------- .../detection/detection.launch.xml | 52 +++++++------- .../lidar_based_detection.launch.xml | 8 +-- .../prediction/prediction.launch.xml | 16 +++-- .../tracking/tracking.launch.xml | 4 +- .../launch/perception.launch.xml | 67 ++++++++++--------- .../traffic_light.launch.xml | 60 ++++++++--------- perception_launch/package.xml | 30 ++++----- 11 files changed, 161 insertions(+), 152 deletions(-) delete mode 100644 perception_launch/COLCON_IGNORE diff --git a/build_depends.repos b/build_depends.repos index 7a6ca070b4..a2bc4751d2 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -27,3 +27,7 @@ repositories: type: git url: https://github.com/ApexAI/topic_tools.git version: autoware + dependencies/Pilot.Auto: + type: git + url: https://github.com/tier4/Pilot.Auto.git + version: ros2 diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt index 3617fa63d2..1ded711b02 100644 --- a/perception_launch/CMakeLists.txt +++ b/perception_launch/CMakeLists.txt @@ -1,12 +1,10 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(perception_launch) -find_package(catkin REQUIRED) +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -catkin_package() - -install( - DIRECTORY - launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package( + INSTALL_TO_SHARE + launch ) diff --git a/perception_launch/COLCON_IGNORE b/perception_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index b35bc13960..5f35a20c09 100644 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -20,43 +20,43 @@ - + - + - - + + - - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index f72fa95b37..1f371d7580 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -23,42 +23,42 @@ - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + - - - + + + - + - + diff --git a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 6fe87c5e63..b4f388d4e9 100644 --- a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -1,9 +1,9 @@ - - - - + + + + diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml index efd2535b23..22a29f97c8 100644 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -3,17 +3,19 @@ - - - - + + + + - - + + + + - + diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index a2fc3947b2..164b37688f 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -1,10 +1,10 @@ - + - + diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index ee29ebf677..a692624f30 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -24,49 +24,56 @@ - + + + - + + - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + - - + + + - - - + + + + - - + + + diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index 72f6a0c0c4..4651d65233 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -7,47 +7,45 @@ - - + + - - - - + - - - - + + + + + - - - - - + + + + + - - - - + + + + - - - - - - - - - - - - + + + + + + + + + + + + diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 458e108e1e..db4b9e5f10 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -1,27 +1,27 @@ - + + perception_launch 0.1.0 The perception_launch package Yukihiro Saito - Apache2 + Apache License 2.0 + ament_cmake_auto - catkin - dynamic_object_visualization - euclidean_cluster - pointcloud_to_laserscan - shape_estimation - dynamic_object_visualization - euclidean_cluster - pointcloud_to_laserscan - shape_estimation - dynamic_object_visualization - euclidean_cluster - pointcloud_to_laserscan - shape_estimation + dynamic_object_visualization + image_transport_plugins + + + ament_lint_auto + ament_lint_common + ament_cmake From c03008b7dca10d82d85deed1e378e0c85828192f Mon Sep 17 00:00:00 2001 From: Frederik Beaujean <72439809+fred-apex-ai@users.noreply.github.com> Date: Mon, 30 Nov 2020 18:40:27 +0100 Subject: [PATCH 0057/1765] [build_depends] Add usb_cam as another dependency (#19) --- build_depends.repos | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/build_depends.repos b/build_depends.repos index a2bc4751d2..3df2748787 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -31,3 +31,7 @@ repositories: type: git url: https://github.com/tier4/Pilot.Auto.git version: ros2 + vendor/usb_cam: + type: git + url: https://github.com/flynneva/usb_cam.git + version: foxy From 6282691ac756ba1150e33cbdf9bc5a8ff0c2089b Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Wed, 16 Dec 2020 04:14:03 +0900 Subject: [PATCH 0058/1765] Add sensing launch build depends (#28) * add tamagawa_imu as build depend Signed-off-by: mitsudome-r * add livox-driver to build depends Signed-off-by: mitsudome-r --- build_depends.repos | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/build_depends.repos b/build_depends.repos index 3df2748787..9c98243c2b 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -27,10 +27,14 @@ repositories: type: git url: https://github.com/ApexAI/topic_tools.git version: autoware - dependencies/Pilot.Auto: + vendor/tamagawa_imu_driver: type: git - url: https://github.com/tier4/Pilot.Auto.git + url: https://github.com/tier4/tamagawa_imu_driver.git version: ros2 + vendor/livox-driver: + type: git + url: https://github.com/fred-apex-ai/livox_ros2_driver.git + version: master vendor/usb_cam: type: git url: https://github.com/flynneva/usb_cam.git From b3df09c4c2fca905ef60bca6d36793dc54571a3f Mon Sep 17 00:00:00 2001 From: Frederik Beaujean <72439809+fred-apex-ai@users.noreply.github.com> Date: Thu, 17 Dec 2020 19:57:06 +0100 Subject: [PATCH 0059/1765] Port sensing_launch (#14) * [sensing_launch] Initial port without actually launching * [sensing_launch] default -> value, namespace, first nodelet porting * [sensing_launch] use usb_cam, eval -> var * [sensing_launch] Fix syntax errors in pointcloud_preprocessor.launch.py * [pointcloud-preprocessor] fix ground-filter component name * [pointcloud-preprocessor] Polish aip_s1/pointcloud_preprocessor.launch.py Only one error at runtime remains when testing on dev laptop due to pointclouds that need to be available for concatenation * [sensing_launch] ublox_gps refer to config file properly * (wip) velodyne_node_container before opaque * [sensing_launch] Port aip-s1 as far as possible * [sensing_launch] remove unused pointcloud_preprocessor_nodes.py * [sensing_launch] Manage to add ComposableNode conditionally * [sensing_launch] Update camera for s1, x1 * [sensing_launch] Copy aip_s1/ content to aip_customized, aip_x1, aip_x2 because they were identical before the porting * [sensing_launch] Port livox * [sensing_launch] Port aip_xx1 * [sensing_launch] Port aip_xx2 * [sensing_launch] Remove superfluous passthrough filter, min_z, max_z * [sensing_launch] Incorporate changes from vehicle testing * [sensing_launch] Declare launch argument for base_frame * [sensing_launch] Missing fixes to launch/velodyne* * [sensing_launch] Update copied configs --- sensing_launch/CMakeLists.txt | 18 +- sensing_launch/COLCON_IGNORE | 0 .../launch/aip_customized/camera.launch.xml | 20 ++- .../launch/aip_customized/gnss.launch.xml | 14 +- .../launch/aip_customized/imu.launch.xml | 14 +- .../launch/aip_customized/lidar.launch.xml | 86 +++------ .../pointcloud_preprocessor.launch.py | 115 ++++++++++++ .../launch/aip_s1/camera.launch.xml | 20 ++- sensing_launch/launch/aip_s1/gnss.launch.xml | 14 +- sensing_launch/launch/aip_s1/imu.launch.xml | 14 +- sensing_launch/launch/aip_s1/lidar.launch.xml | 86 +++------ .../aip_s1/pointcloud_preprocessor.launch.py | 115 ++++++++++++ .../launch/aip_x1/camera.launch.xml | 20 ++- sensing_launch/launch/aip_x1/gnss.launch.xml | 14 +- sensing_launch/launch/aip_x1/imu.launch.xml | 14 +- sensing_launch/launch/aip_x1/lidar.launch.xml | 86 +++------ .../aip_x1/pointcloud_preprocessor.launch.py | 115 ++++++++++++ .../launch/aip_x2/camera.launch.xml | 20 ++- sensing_launch/launch/aip_x2/gnss.launch.xml | 14 +- sensing_launch/launch/aip_x2/imu.launch.xml | 14 +- sensing_launch/launch/aip_x2/lidar.launch.xml | 86 +++------ .../aip_x2/pointcloud_preprocessor.launch.py | 115 ++++++++++++ .../launch/aip_xx1/camera.launch.xml | 17 +- sensing_launch/launch/aip_xx1/gnss.launch.xml | 14 +- sensing_launch/launch/aip_xx1/imu.launch.xml | 14 +- .../launch/aip_xx1/lidar.launch.xml | 131 +++++--------- .../aip_xx1/pointcloud_preprocessor.launch.py | 116 ++++++++++++ .../launch/aip_xx2/camera.launch.xml | 20 ++- sensing_launch/launch/aip_xx2/gnss.launch.xml | 14 +- sensing_launch/launch/aip_xx2/imu.launch.xml | 14 +- .../launch/aip_xx2/lidar.launch.xml | 86 +++------ .../aip_xx2/pointcloud_preprocessor.launch.py | 115 ++++++++++++ .../launch/livox_horizon.launch.xml | 24 +-- sensing_launch/launch/sensing.launch.xml | 19 +- .../launch/velodyne_VLP16.launch.xml | 111 ++---------- .../launch/velodyne_VLP32C.launch.xml | 111 ++---------- .../launch/velodyne_VLS128.launch.xml | 111 ++---------- .../launch/velodyne_node_container.launch.py | 169 ++++++++++++++++++ sensing_launch/package.xml | 14 +- 39 files changed, 1267 insertions(+), 847 deletions(-) delete mode 100644 sensing_launch/COLCON_IGNORE create mode 100644 sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py create mode 100644 sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py create mode 100644 sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py create mode 100644 sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py create mode 100644 sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py create mode 100644 sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py create mode 100644 sensing_launch/launch/velodyne_node_container.launch.py diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt index b557b1d09b..47900571d1 100644 --- a/sensing_launch/CMakeLists.txt +++ b/sensing_launch/CMakeLists.txt @@ -1,17 +1,9 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(sensing_launch) -find_package(catkin REQUIRED) +find_package(ament_cmake_auto REQUIRED) -# Force Tier IV's fork version -find_package(velodyne_driver 0.2.0 EXACT REQUIRED) -find_package(velodyne_pointcloud 0.2.0 EXACT REQUIRED) - -catkin_package() - -install( - DIRECTORY - launch - data - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package(INSTALL_TO_SHARE + launch + data ) diff --git a/sensing_launch/COLCON_IGNORE b/sensing_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/sensing_launch/launch/aip_customized/camera.launch.xml b/sensing_launch/launch/aip_customized/camera.launch.xml index c9e5fa4f26..16fb4435fe 100644 --- a/sensing_launch/launch/aip_customized/camera.launch.xml +++ b/sensing_launch/launch/aip_customized/camera.launch.xml @@ -2,17 +2,19 @@ - - - - - + + + + + + + - - - - + + + + diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index 51b386c056..4b29a1a1d2 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -2,17 +2,17 @@ - + + - - - - - + + + + - + diff --git a/sensing_launch/launch/aip_customized/imu.launch.xml b/sensing_launch/launch/aip_customized/imu.launch.xml index b55a51ea8d..52355261b1 100644 --- a/sensing_launch/launch/aip_customized/imu.launch.xml +++ b/sensing_launch/launch/aip_customized/imu.launch.xml @@ -2,10 +2,12 @@ - + + - - + + + @@ -14,7 +16,11 @@ - + + + + + diff --git a/sensing_launch/launch/aip_customized/lidar.launch.xml b/sensing_launch/launch/aip_customized/lidar.launch.xml index 0d8fdb3084..732b24f6a3 100644 --- a/sensing_launch/launch/aip_customized/lidar.launch.xml +++ b/sensing_launch/launch/aip_customized/lidar.launch.xml @@ -2,88 +2,42 @@ - + + - - - + + + + - + - - - + + + + - + - - - + + + + - + - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..19a68e1e85 --- /dev/null +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -0,0 +1,115 @@ + +# Copyright 2020 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. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +def generate_launch_description(): + + pkg = 'pointcloud_preprocessor' + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[ + { + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + } + ] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'mesurement_range_cropped/pointcloud'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ], + parameters=[ + { + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'negative': False, + } + ] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'mesurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + ) + + return launch.LaunchDescription(launch_arguments + [container]) diff --git a/sensing_launch/launch/aip_s1/camera.launch.xml b/sensing_launch/launch/aip_s1/camera.launch.xml index c9e5fa4f26..16fb4435fe 100644 --- a/sensing_launch/launch/aip_s1/camera.launch.xml +++ b/sensing_launch/launch/aip_s1/camera.launch.xml @@ -2,17 +2,19 @@ - - - - - + + + + + + + - - - - + + + + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index 51b386c056..4b29a1a1d2 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -2,17 +2,17 @@ - + + - - - - - + + + + - + diff --git a/sensing_launch/launch/aip_s1/imu.launch.xml b/sensing_launch/launch/aip_s1/imu.launch.xml index b55a51ea8d..52355261b1 100644 --- a/sensing_launch/launch/aip_s1/imu.launch.xml +++ b/sensing_launch/launch/aip_s1/imu.launch.xml @@ -2,10 +2,12 @@ - + + - - + + + @@ -14,7 +16,11 @@ - + + + + + diff --git a/sensing_launch/launch/aip_s1/lidar.launch.xml b/sensing_launch/launch/aip_s1/lidar.launch.xml index 0d8fdb3084..a3cb7d6fca 100644 --- a/sensing_launch/launch/aip_s1/lidar.launch.xml +++ b/sensing_launch/launch/aip_s1/lidar.launch.xml @@ -2,88 +2,42 @@ - + + - - - + + + + - + - - - + + + + - + - - - + + + + - + - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..19a68e1e85 --- /dev/null +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -0,0 +1,115 @@ + +# Copyright 2020 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. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +def generate_launch_description(): + + pkg = 'pointcloud_preprocessor' + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[ + { + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + } + ] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'mesurement_range_cropped/pointcloud'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ], + parameters=[ + { + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'negative': False, + } + ] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'mesurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + ) + + return launch.LaunchDescription(launch_arguments + [container]) diff --git a/sensing_launch/launch/aip_x1/camera.launch.xml b/sensing_launch/launch/aip_x1/camera.launch.xml index c9e5fa4f26..16fb4435fe 100644 --- a/sensing_launch/launch/aip_x1/camera.launch.xml +++ b/sensing_launch/launch/aip_x1/camera.launch.xml @@ -2,17 +2,19 @@ - - - - - + + + + + + + - - - - + + + + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index 51b386c056..4b29a1a1d2 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -2,17 +2,17 @@ - + + - - - - - + + + + - + diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index b55a51ea8d..52355261b1 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -2,10 +2,12 @@ - + + - - + + + @@ -14,7 +16,11 @@ - + + + + + diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml index 0d8fdb3084..56a20e0f96 100644 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ b/sensing_launch/launch/aip_x1/lidar.launch.xml @@ -2,88 +2,42 @@ - + + - - - + + + + - + - - - + + + + - + - - - + + + + - + - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..19a68e1e85 --- /dev/null +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -0,0 +1,115 @@ + +# Copyright 2020 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. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +def generate_launch_description(): + + pkg = 'pointcloud_preprocessor' + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[ + { + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + } + ] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'mesurement_range_cropped/pointcloud'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ], + parameters=[ + { + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'negative': False, + } + ] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'mesurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + ) + + return launch.LaunchDescription(launch_arguments + [container]) diff --git a/sensing_launch/launch/aip_x2/camera.launch.xml b/sensing_launch/launch/aip_x2/camera.launch.xml index c9e5fa4f26..16fb4435fe 100644 --- a/sensing_launch/launch/aip_x2/camera.launch.xml +++ b/sensing_launch/launch/aip_x2/camera.launch.xml @@ -2,17 +2,19 @@ - - - - - + + + + + + + - - - - + + + + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index 51b386c056..4b29a1a1d2 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -2,17 +2,17 @@ - + + - - - - - + + + + - + diff --git a/sensing_launch/launch/aip_x2/imu.launch.xml b/sensing_launch/launch/aip_x2/imu.launch.xml index b55a51ea8d..52355261b1 100644 --- a/sensing_launch/launch/aip_x2/imu.launch.xml +++ b/sensing_launch/launch/aip_x2/imu.launch.xml @@ -2,10 +2,12 @@ - + + - - + + + @@ -14,7 +16,11 @@ - + + + + + diff --git a/sensing_launch/launch/aip_x2/lidar.launch.xml b/sensing_launch/launch/aip_x2/lidar.launch.xml index 0d8fdb3084..f5efc314a8 100644 --- a/sensing_launch/launch/aip_x2/lidar.launch.xml +++ b/sensing_launch/launch/aip_x2/lidar.launch.xml @@ -2,88 +2,42 @@ - + + - - - + + + + - + - - - + + + + - + - - - + + + + - + - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..19a68e1e85 --- /dev/null +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -0,0 +1,115 @@ + +# Copyright 2020 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. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +def generate_launch_description(): + + pkg = 'pointcloud_preprocessor' + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[ + { + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + } + ] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'mesurement_range_cropped/pointcloud'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ], + parameters=[ + { + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'negative': False, + } + ] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'mesurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + ) + + return launch.LaunchDescription(launch_arguments + [container]) diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml index fdd4c5365d..bec110eb90 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ b/sensing_launch/launch/aip_xx1/camera.launch.xml @@ -3,12 +3,21 @@ - - + + + + - - + + + + + + + + + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index 51b386c056..4b29a1a1d2 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -2,17 +2,17 @@ - + + - - - - - + + + + - + diff --git a/sensing_launch/launch/aip_xx1/imu.launch.xml b/sensing_launch/launch/aip_xx1/imu.launch.xml index b55a51ea8d..52355261b1 100644 --- a/sensing_launch/launch/aip_xx1/imu.launch.xml +++ b/sensing_launch/launch/aip_xx1/imu.launch.xml @@ -2,10 +2,12 @@ - + + - - + + + @@ -14,7 +16,11 @@ - + + + + + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 46925430a2..909712cb72 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -2,121 +2,84 @@ - + + - - - + + + + - - - + + + + - - - + + + + - - - + + + + - - - + + + + - - - + + + + - - - + + + + - - - + + + + - - - + + + + + - - - + + + + + - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud, - /sensing/lidar/rear/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..a1a91360a2 --- /dev/null +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -0,0 +1,116 @@ + +# Copyright 2020 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. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +def generate_launch_description(): + + pkg = 'pointcloud_preprocessor' + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[ + { + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud', + '/sensing/lidar/rear/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + } + ] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'mesurement_range_cropped/pointcloud'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ], + parameters=[ + { + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'negative': False, + } + ] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'mesurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + ) + + return launch.LaunchDescription(launch_arguments + [container]) diff --git a/sensing_launch/launch/aip_xx2/camera.launch.xml b/sensing_launch/launch/aip_xx2/camera.launch.xml index c9e5fa4f26..16fb4435fe 100644 --- a/sensing_launch/launch/aip_xx2/camera.launch.xml +++ b/sensing_launch/launch/aip_xx2/camera.launch.xml @@ -2,17 +2,19 @@ - - - - - + + + + + + + - - - - + + + + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml index 51b386c056..4b29a1a1d2 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -2,17 +2,17 @@ - + + - - - - - + + + + - + diff --git a/sensing_launch/launch/aip_xx2/imu.launch.xml b/sensing_launch/launch/aip_xx2/imu.launch.xml index b55a51ea8d..52355261b1 100644 --- a/sensing_launch/launch/aip_xx2/imu.launch.xml +++ b/sensing_launch/launch/aip_xx2/imu.launch.xml @@ -2,10 +2,12 @@ - + + - - + + + @@ -14,7 +16,11 @@ - + + + + + diff --git a/sensing_launch/launch/aip_xx2/lidar.launch.xml b/sensing_launch/launch/aip_xx2/lidar.launch.xml index 0d8fdb3084..8f8ca8299f 100644 --- a/sensing_launch/launch/aip_xx2/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx2/lidar.launch.xml @@ -2,88 +2,42 @@ - + + - - - + + + + - + - - - + + + + - + - - - + + + + - + - - - - - - - - - - - - - [/sensing/lidar/top/outlier_filtered/pointcloud, - /sensing/lidar/left/outlier_filtered/pointcloud, - /sensing/lidar/right/outlier_filtered/pointcloud] - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..19a68e1e85 --- /dev/null +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -0,0 +1,115 @@ + +# Copyright 2020 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. + +import launch +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +def generate_launch_description(): + + pkg = 'pointcloud_preprocessor' + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[ + { + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + } + ] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'mesurement_range_cropped/pointcloud'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ], + parameters=[ + { + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'negative': False, + } + ] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'mesurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + ) + + return launch.LaunchDescription(launch_arguments + [container]) diff --git a/sensing_launch/launch/livox_horizon.launch.xml b/sensing_launch/launch/livox_horizon.launch.xml index 1e5c5d8e7a..8fc76a9d5e 100644 --- a/sensing_launch/launch/livox_horizon.launch.xml +++ b/sensing_launch/launch/livox_horizon.launch.xml @@ -8,20 +8,20 @@ - + - - - - - - - - - - - + + + + + + + + + + + diff --git a/sensing_launch/launch/sensing.launch.xml b/sensing_launch/launch/sensing.launch.xml index 019af23690..f432a05cbb 100644 --- a/sensing_launch/launch/sensing.launch.xml +++ b/sensing_launch/launch/sensing.launch.xml @@ -3,26 +3,27 @@ - + + - - + + - - + + - - + + - - + + diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml index 6cf557309d..be08fe7646 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ b/sensing_launch/launch/velodyne_VLP16.launch.xml @@ -4,101 +4,24 @@ - - - - - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch.xml b/sensing_launch/launch/velodyne_VLP32C.launch.xml index bce757ecb7..b131bf3176 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch.xml +++ b/sensing_launch/launch/velodyne_VLP32C.launch.xml @@ -4,101 +4,24 @@ - - - - - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml index 0d3b9abd35..2269f87eef 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ b/sensing_launch/launch/velodyne_VLS128.launch.xml @@ -4,101 +4,24 @@ - - - - - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py new file mode 100644 index 0000000000..189ae333d6 --- /dev/null +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -0,0 +1,169 @@ +# Copyright 2020 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. + +import launch +from launch import LaunchContext +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, PythonExpression +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.descriptions import ComposableNode +import uuid + + +def acceptable_unique_name(prefix): + id = str(uuid.uuid4()) + # ros2 apparently doesn't accept the UUID with hyphens in node names + return prefix + id.replace('-', '_') + + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('model') + add_launch_arg('launch_driver', 'True') + add_launch_arg('calibration') + add_launch_arg('device_ip', '192.168.1.201') + add_launch_arg('sensor_frame', 'velodyne') + add_launch_arg('base_frame', 'base_link') + add_launch_arg('container_name', 'velodyne_composable_node_container') + add_launch_arg('min_range') + add_launch_arg('max_range') + add_launch_arg('pcap', '') + add_launch_arg('port', '2368') + add_launch_arg('read_fast', 'False') + add_launch_arg('read_once', 'False') + add_launch_arg('repeat_delay', '0.0') + add_launch_arg('rpm', '600.0') + add_launch_arg('laserscan_ring', '-1') + add_launch_arg('laserscan_resolution', '0.007') + add_launch_arg('num_points_thresholds', '300') + add_launch_arg('invalid_intensity') + add_launch_arg('frame_id', 'velodyne') + add_launch_arg('gps_time', 'False') + add_launch_arg('input_frame', LaunchConfiguration('base_frame')) + add_launch_arg('output_frame', LaunchConfiguration('base_frame')) + + def create_parameter_dict(*args): + result = {} + for x in args: + result[x] = LaunchConfiguration(x) + return result + + nodes = [] + + # turn packets into pointcloud as in + # https://github.com/ros-drivers/velodyne/blob/ros2/velodyne_pointcloud/launch/velodyne_convert_node-VLP16-composed-launch.py + nodes.append(ComposableNode( + package='velodyne_pointcloud', + plugin='velodyne_pointcloud::Convert', + name='velodyne_convert_node', + parameters=[create_parameter_dict('calibration', 'min_range', 'max_range', + 'num_points_thresholds', 'invalid_intensity', 'sensor_frame')], + remappings=[('velodyne_points', 'pointcloud_raw'), + ('velodyne_points_ex', 'pointcloud_raw_ex')], + ) + ) + + cropbox_parameters = create_parameter_dict('input_frame', 'output_frame') + cropbox_parameters['negative'] = True + + cropbox_remappings = [ + ('/min_x', '/vehicle_info/min_longitudinal_offset'), + ('/max_x', '/vehicle_info/max_longitudinal_offset'), + ('/min_z', '/vehicle_info/min_lateral_offset'), + ('/max_z', '/vehicle_info/max_lateral_offset'), + ('/min_z', '/vehicle_info/min_height_offset'), + ('/max_z', '/vehicle_info/max_height_offset'), + ] + + nodes.append(ComposableNode( + package='pointcloud_preprocessor', + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter_self', + remappings=[('/input', 'pointcloud_raw_ex'), + ('/output', 'self_cropped/pointcloud_ex') + ] + cropbox_remappings, + parameters=[cropbox_parameters], + ) + ) + + nodes.append(ComposableNode( + package='pointcloud_preprocessor', + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter_mirror', + remappings=[('/input', 'self_cropped/pointcloud_ex'), + ('/output', 'mirror_cropped/pointcloud_ex'), + ] + cropbox_remappings, + parameters=[cropbox_parameters], + ) + ) + + # TODO(fred-apex-ai) Still need the distortion component + if False: + nodes.append(ComposableNode( + package='TODO', + plugin='TODO', + name='fix_distortion', + remappings=[ + ('velodyne_points_ex', 'mirror_cropped/pointcloud_ex'), + ('velodyne_points_interpolate', 'rectified/pointcloud'), + ('velodyne_points_interpolate_ex', 'rectified/pointcloud_ex'), + ], + ) + ) + + nodes.append(ComposableNode( + package='pointcloud_preprocessor', + plugin='pointcloud_preprocessor::RingOutlierFilterComponent', + name='ring_outlier_filter', + remappings=[ + ('/input', 'rectified/pointcloud_ex'), + ('/output', 'outlier_filtered/pointcloud') + ], + ) + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + # need unique name, otherwise all processes in same container and the node names then clash + name=acceptable_unique_name('velodyne_node_container'), + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=nodes, + ) + + driver_component = ComposableNode( + package='velodyne_driver', + plugin='velodyne_driver::VelodyneDriver', + # node is created in a global context, need to avoid name clash + name='velodyne_driver', + parameters=[create_parameter_dict('device_ip', 'gps_time', 'read_once', 'read_fast', + 'repeat_delay', 'frame_id', 'model', 'rpm', 'port', + 'pcap')], + ) + + # one way to add a ComposableNode conditional on a launch argument to a + # container. The `ComposableNode` itself doesn't accept a condition + loader = LoadComposableNodes( + composable_node_descriptions=[driver_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('launch_driver')), + ) + + return launch.LaunchDescription(launch_arguments + [container, loader]) diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index e315fa965b..1b80231f27 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -1,5 +1,6 @@ - + + sensing_launch 0.1.0 The sensing_launch package @@ -7,11 +8,20 @@ Yukihiro Saito Apache2 - catkin + ament_cmake_auto + + gnss_poser + livox_ros2_driver + pointcloud_preprocessor + tamagawa_imu_driver + topic_tools + ublox_gps + usb_cam velodyne_driver velodyne_pointcloud + ament_cmake From 5408c4e846dc9ca43277602815a20f1dff9c35a9 Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Sat, 19 Dec 2020 02:30:41 +0900 Subject: [PATCH 0060/1765] Add linters (#30) --- vehicle_launch/CMakeLists.txt | 5 +++++ vehicle_launch/package.xml | 6 +++++- 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/vehicle_launch/CMakeLists.txt b/vehicle_launch/CMakeLists.txt index d49a9be1bf..cf8c1e942d 100644 --- a/vehicle_launch/CMakeLists.txt +++ b/vehicle_launch/CMakeLists.txt @@ -8,6 +8,11 @@ find_package(xacro REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/vehicle_launch/package.xml b/vehicle_launch/package.xml index 8509d9580e..0b76112636 100644 --- a/vehicle_launch/package.xml +++ b/vehicle_launch/package.xml @@ -5,7 +5,7 @@ The vehicle_launch package Yukihiro Saito - Apache2 + Apache License 2.0 ament_cmake_auto @@ -17,6 +17,10 @@ livox_description velodyne_description robot_state_publisher + simple_planning_simulator + + ament_lint_auto + ament_lint_common ament_cmake From e4ab419cec0187f2d6f2c99a641159af9fe55e8c Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Sun, 20 Dec 2020 22:54:09 +0100 Subject: [PATCH 0061/1765] Added linters (#32) --- sensing_launch/CMakeLists.txt | 6 ++++++ sensing_launch/package.xml | 5 ++++- 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt index 47900571d1..036e5b89af 100644 --- a/sensing_launch/CMakeLists.txt +++ b/sensing_launch/CMakeLists.txt @@ -2,6 +2,12 @@ cmake_minimum_required(VERSION 3.5) project(sensing_launch) find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() ament_auto_package(INSTALL_TO_SHARE launch diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index 1b80231f27..de5d5a3357 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -6,7 +6,7 @@ The sensing_launch package Yukihiro Saito - Apache2 + Apache License 2.0 ament_cmake_auto @@ -21,6 +21,9 @@ velodyne_driver velodyne_pointcloud + ament_lint_auto + ament_lint_common + ament_cmake From 051a4a1d78f5eea2a6ae88c8f1339036aee7b4e2 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Mon, 21 Dec 2020 16:57:19 +0900 Subject: [PATCH 0062/1765] fix syntax (#33) Signed-off-by: Takamasa Horibe --- .../launch/util/util.launch.xml | 24 ++++++++----------- 1 file changed, 10 insertions(+), 14 deletions(-) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 18e0f0a2ae..3904103c02 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -17,15 +17,13 @@ - - min_x: -60.0 - max_x: 60.0 - min_y: -60.0 - max_y: 60.0 - min_z: -30.0 - max_z: 50.0 - negative: False - + + + + + + + @@ -35,11 +33,9 @@ - - voxel_size_x: 3.0 - voxel_size_y: 3.0 - voxel_size_z: 3.0 - + + + From 9d48a292fa846dbedd98b0b77392e74b9640cf96 Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Tue, 22 Dec 2020 11:51:13 +0900 Subject: [PATCH 0063/1765] ROS2 Linting: control_launch (#29) * Add linter tests and completepackage dependencies list * Reorder alphabetically * Comment out pure_pursuit dependency - not ported yet * Add back pure_pursuit package post port --- control_launch/CMakeLists.txt | 5 +++++ control_launch/package.xml | 14 +++++++++++++- 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/control_launch/CMakeLists.txt b/control_launch/CMakeLists.txt index 7774343a37..206bb55e10 100644 --- a/control_launch/CMakeLists.txt +++ b/control_launch/CMakeLists.txt @@ -11,6 +11,11 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package( INSTALL_TO_SHARE config diff --git a/control_launch/package.xml b/control_launch/package.xml index 28899dfcf8..7793c033db 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -1,5 +1,6 @@ - + + control_launch 0.1.0 The control_launch package @@ -10,6 +11,17 @@ ament_cmake_auto + latlon_muxer + mpc_follower + pure_pursuit + remote_cmd_converter + shift_decider + vehicle_cmd_gate + velocity_controller + + ament_lint_auto + ament_lint_common + ament_cmake From c76bbe77d99e8fd5d7c3dc99a22081ffc73f744c Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 22 Dec 2020 15:22:04 +0900 Subject: [PATCH 0064/1765] [perception_launch] fix perception_launch (#34) Signed-off-by: mitsudome-r --- .../object_recognition/prediction/prediction.launch.xml | 4 ++-- .../launch/object_recognition/tracking/tracking.launch.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml index 22a29f97c8..eefa357751 100644 --- a/perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -5,7 +5,7 @@ - + @@ -18,6 +18,6 @@ - + diff --git a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml index 164b37688f..2492a096e9 100644 --- a/perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -7,6 +7,6 @@ - + From 34d619d300aee4e14274f6421d50a0d272b5e96f Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Wed, 23 Dec 2020 11:06:49 +0900 Subject: [PATCH 0065/1765] Add linters and missing pakcages dependencies (#37) --- system_launch/CMakeLists.txt | 5 +++++ system_launch/package.xml | 8 ++++---- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt index 13d73f858f..1d58a61079 100644 --- a/system_launch/CMakeLists.txt +++ b/system_launch/CMakeLists.txt @@ -9,6 +9,11 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package(INSTALL_TO_SHARE launch ) diff --git a/system_launch/package.xml b/system_launch/package.xml index 317d79b4ba..cd1a54517d 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -10,13 +10,13 @@ ament_cmake_auto - ament_lint_auto - ament_lint_common - - + autoware_state_monitor autoware_error_monitor emergency_handler + ament_lint_auto + ament_lint_common + ament_cmake From 8a17d45bea155e42676f4e30cc64938b659f1251 Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Wed, 23 Dec 2020 11:07:21 +0900 Subject: [PATCH 0066/1765] ROS2 Linting: planning_launch (#38) --- planning_launch/CMakeLists.txt | 5 +++++ planning_launch/package.xml | 17 ++++++++++++++++- 2 files changed, 21 insertions(+), 1 deletion(-) diff --git a/planning_launch/CMakeLists.txt b/planning_launch/CMakeLists.txt index 042004c192..de7ef164be 100644 --- a/planning_launch/CMakeLists.txt +++ b/planning_launch/CMakeLists.txt @@ -11,6 +11,11 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/planning_launch/package.xml b/planning_launch/package.xml index 79b6dee507..7260c959c5 100644 --- a/planning_launch/package.xml +++ b/planning_launch/package.xml @@ -6,10 +6,25 @@ Takamasa Horibe - Apache 2.0 + Apache License 2.0 ament_cmake_auto + behavior_velocity_planner + costmap_generator + freespace_planner + lane_change_planner + mission_planner + motion_velocity_optimizer + obstacle_avoidance_planner + obstacle_stop_planner + scenario_selector + surround_obstacle_checker + turn_signal_decider + + ament_lint_auto + ament_lint_common + ament_cmake From 469298b04c0d22485cabd23e6032b8ff6054b234 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Thu, 7 Jan 2021 13:18:13 +0900 Subject: [PATCH 0067/1765] Ros2 port autoware launch (#35) * [autoware_launch] port CMakelists.txt and remove COLCON_IGNORE Signed-off-by: mitsudome-r * [autoware_launch] fix planning_simulator.launch.xml Signed-off-by: mitsudome-r * [autoware_launch] add rviz config Signed-off-by: mitsudome-r * [autoware_launch] first port of autoware_launch Signed-off-by: mitsudome-r * lanuch rviz with config file Signed-off-by: kosuke murakami * modify launch file for making psim work Signed-off-by: kosuke murakami * add vehicle model in launch Signed-off-by: kosuke murakami * change from vehicle_model to vehicle_param_file Signed-off-by: kosuke murakami * [autoware_launch] add autoware_web_controller and system launch Signed-off-by: mitsudome-r * add rosbrdige_suite to build_depends.repos Signed-off-by: mitsudome-r * Update rviz Signed-off-by: wep21 * update autoware.rviz Signed-off-by: mitsudome-r * remove autoware_ros2.rviz Signed-off-by: mitsudome-r Co-authored-by: kosuke murakami Co-authored-by: wep21 --- autoware_launch/CMakeLists.txt | 20 +- autoware_launch/COLCON_IGNORE | 0 autoware_launch/launch/autoware.launch.xml | 40 +- .../launch/planning_simulator.launch.xml | 43 +- autoware_launch/package.xml | 10 +- autoware_launch/rviz/autoware.rviz | 1004 +++++++++-------- build_depends.repos | 8 + control_launch/launch/control.launch.xml | 3 + planning_launch/launch/planning.launch.xml | 2 + .../scenario_planning/lane_driving.launch.xml | 3 + .../behavior_planning.launch.xml | 2 + .../motion_planning.launch.xml | 10 +- .../scenario_planning.launch.xml | 3 + 13 files changed, 642 insertions(+), 506 deletions(-) delete mode 100644 autoware_launch/COLCON_IGNORE diff --git a/autoware_launch/CMakeLists.txt b/autoware_launch/CMakeLists.txt index 87cc71d214..4c62c75a53 100644 --- a/autoware_launch/CMakeLists.txt +++ b/autoware_launch/CMakeLists.txt @@ -1,17 +1,11 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(autoware_launch) -find_package(catkin REQUIRED COMPONENTS - vehicle_launch - perception_launch - sensing_launch -) - -catkin_package() +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() -install( - DIRECTORY - launch - rviz - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +ament_auto_package( + INSTALL_TO_SHARE + launch + rviz ) diff --git a/autoware_launch/COLCON_IGNORE b/autoware_launch/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index cb4520f1a6..c45e93675a 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -10,54 +10,54 @@ - - - + + + - + - - - + + + - - - + + + - + - - + + - + - - + + - + - + - + - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index ad9eb20702..7ba60c1f1c 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -6,58 +6,57 @@ - - + - - - + + + - + - + - - - + + + - - - - + + + + - + + + - + + - + - + - - - - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index 025d0bcc0c..b9f32201f9 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -5,9 +5,9 @@ The autoware_launch package Yukihiro Saito - Apache 2 + Apache License 2.0 - catkin + ament_cmake_auto vehicle_launch perception_launch sensing_launch @@ -15,8 +15,7 @@ perception_launch sensing_launch - rosbridge_server - roswww + autoware_web_controller python-tornado python3-tornado python-bson @@ -24,7 +23,6 @@ - - + ament_cmake diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index cbc0107cc8..1e2964ad3f 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1,54 +1,49 @@ Panels: - - Class: rviz/Displays - Help Height: 0 + - Class: rviz_common/Displays + Help Height: 138 Name: Displays Property Tree Widget: Expanded: - - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1 - - /Sensing1/GNSS1/PoseWithCovariance1/Covariance1/Position1 - - /Localization1/NDT1/PoseHistory1/Line1 - - /Localization1/NDT1/MonteCarloInitialPose1/Namespaces1 - - /Localization1/EKF1/PoseHistory1/Line1 + - /Perception1/Detection1 + - /Perception1/Tracking1 + - /Perception1/Prediction1 - /Planning1/ScenarioPlanning1 - - /Control1/Debug/MPC1/Namespaces1 - Splitter Ratio: 0.557669460773468 - Tree Height: 435 - - Class: rviz/Selection + - /Planning1/ScenarioPlanning1/LaneDriving1 + - /Planning1/ScenarioPlanning1/LaneDriving1/MotionPlanning1 + - /Planning1/ScenarioPlanning1/Parking1 + Splitter Ratio: 0.5345016717910767 + Tree Height: 334 + - Class: rviz_common/Selection Name: Selection - - Class: rviz/Tool Properties + - Class: rviz_common/Tool Properties Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 + - /2D Goal Pose1 + - /Publish Point1 - /2D Dummy Pedestrian1 - /2D Dummy Car1 - /2D Checkpoint Pose1 - /Delete All Objects1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views + - Class: rviz_common/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: PointCloudMap - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel - Name: InitialPoseButtonPanel - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel - Name: InitialPoseButtonPanel -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 + - Class: rviz_common/Tool Properties + Expanded: + - /2D Dummy Pedestrian1 + - /2D Dummy Car1 + - /2D Checkpoint Pose1 + - /Delete All Objects1 + Name: Tool Properties + Splitter Ratio: 0.5 Visualization Manager: Class: "" Displays: - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/TF + - Class: rviz_default_plugins/TF Enabled: false Frame Timeout: 15 Frames: @@ -58,12 +53,13 @@ Visualization Manager: Show Arrows: true Show Axes: true Show Names: true - Tree: {} + Tree: + {} Update Interval: 0 Value: false - Alpha: 0.5 Cell Size: 1 - Class: rviz/Grid + Class: rviz_default_plugins/Grid Color: 160; 160; 164 Enabled: false Line Style: @@ -79,48 +75,49 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: false - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz_plugins/SteeringAngle - Enabled: true - Left: 128 - Length: 256 - Name: SteeringAngle - Scale: 17 - Text Color: 25; 255; 240 - Top: 128 - Topic: /vehicle/status/steering - Unreliable: false - Value: true - Value height offset: 0 - Class: rviz_plugins/ConsoleMeter Enabled: true - Left: 512 + Left: 128 Length: 256 Name: ConsoleMeter Scale: 3 Text Color: 25; 255; 240 Top: 128 - Topic: /vehicle/status/twist - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/twist Value: true Value height offset: 0 - - Alpha: 1 - Class: rviz_plugins/VelocityHistory - Color Border Vel Max: 3 - Constant Color: - Color: 255; 255; 255 - Value: true + - Class: rviz_plugins/TurnSignal Enabled: true - Name: VelocityHistory - Scale: 0.30000001192092896 - Timeout: 10 - Topic: /vehicle/status/twist - Unreliable: false + Height: 256 + Left: 128 + Name: TurnSignal + Top: 128 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/turn_signal_cmd Value: true + Width: 256 - Alpha: 0.30000001192092896 - Class: rviz/RobotModel + Class: rviz_default_plugins/RobotModel Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description Enabled: true Links: All Links Enabled: true @@ -133,6 +130,15 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + camera0/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera0/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false camera1/camera_link: Alpha: 1 Show Axes: false @@ -178,31 +184,53 @@ Visualization Manager: Alpha: 1 Show Axes: false Show Trail: false - camera6/camera_link: + gnss_link: Alpha: 1 Show Axes: false Show Trail: false Value: true - camera6/camera_optical_link: + livox_front_left: Alpha: 1 Show Axes: false Show Trail: false - gnss_link: + livox_front_left_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + livox_front_right: + Alpha: 1 + Show Axes: false + Show Trail: false + livox_front_right_base_link: Alpha: 1 Show Axes: false Show Trail: false Value: true + sensor_kit_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false tamagawa/imu_link: Alpha: 1 Show Axes: false Show Trail: false Value: true - traffic_light/camera_link: + traffic_light_left_camera/camera_link: Alpha: 1 Show Axes: false Show Trail: false Value: true - traffic_light/camera_optical_link: + traffic_light_left_camera/camera_optical_link: + Alpha: 1 + Show Axes: false + Show Trail: false + traffic_light_right_camera/camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + traffic_light_right_camera/camera_optical_link: Alpha: 1 Show Axes: false Show Trail: false @@ -216,6 +244,16 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + velodyne_rear: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_rear_base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true velodyne_right: Alpha: 1 Show Axes: false @@ -237,106 +275,88 @@ Visualization Manager: Show Trail: false Value: true Name: VehicleModel - Robot Description: robot_description TF Prefix: "" Update Interval: 0 Value: true Visual Enabled: true - - Class: rviz/PolarGridDisplay - Color: 255; 255; 255 - Delta Range: 10 - Enabled: true - Max Alpha: 1 - Max Range: 100 - Max Wave Alpha: 1 - Min Alpha: 0.20000000298023224 - Min Wave Alpha: 0.20000000298023224 - Name: PolarGridDisplay - Reference Frame: base_link - Value: true - Wave Color: 255; 255; 255 - Wave Velocity: 40 - - Class: rviz_plugins/TurnSignal - Enabled: true - Height: 256 - Left: 196 - Name: TurnSignal - Top: 350 - Topic: /control/turn_signal_cmd - Unreliable: false - Value: true - Width: 512 Enabled: true Name: Vehicle Enabled: true Name: System - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Alpha: 0.20000000298023224 + - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 28.71826171875 - Min Value: -7.4224700927734375 + Max Value: 10 + Min Value: -10 Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 237 - Min Color: 211; 215; 207 + Max Intensity: 4096 + Min Color: 0; 0; 0 Min Intensity: 0 Name: PointCloudMap Position Transformer: XYZ - Queue Size: 10 Selectable: true - Size (Pixels): 1 - Size (m): 0.05000000074505806 - Style: Points - Topic: /map/pointcloud_map - Unreliable: false + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map/pointcloud_map Use Fixed Frame: true - Use rainbow: false + Use rainbow: true Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /map/vector_map_marker Name: Lanelet2VectorMap Namespaces: center_lane_line: true crosswalk_lanelets: true + detection_area: true lanelet direction: true left_lane_bound: true - parking_lots: true - parking_space: true right_lane_bound: true - road_lanelets: false + road_lanelets: true stop_lines: true traffic_light: true traffic_light_triangle: true - Queue Size: 100 + walkway_lanelets: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map/vector_map_marker Value: true Enabled: true Name: Map - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Alpha: 1 + - Alpha: 0.9990000128746033 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 30 - Min Value: -2 - Value: false + Max Value: 10 + Min Value: -10 + Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 + Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 - Color Transformer: AxisColor + Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false @@ -346,62 +366,72 @@ Visualization Manager: Min Intensity: 0 Name: ConcatenatePointCloud Position Transformer: XYZ - Queue Size: 10 Selectable: true Size (Pixels): 2 - Size (m): 0.009999999776482582 + Size (m): 0.20000000298023224 Style: Points - Topic: /sensing/lidar/concatenated/pointcloud - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensing/lidar/concatenated/pointcloud Use Fixed Frame: true Use rainbow: true Value: true - - Alpha: 1 - Autocompute Intensity Bounds: false + - Alpha: 0.9990000128746033 + Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 15 - Min Value: -2 - Value: false + Max Value: 10 + Min Value: -10 + Value: true Axis: Z - Channel Name: z - Class: rviz/PointCloud2 - Color: 0; 240; 255 - Color Transformer: FlatColor + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 15 + Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: -5 + Min Intensity: 0 Name: NoGroundPointCloud Position Transformer: XYZ - Queue Size: 10 Selectable: true - Size (Pixels): 10 - Size (m): 0.009999999776482582 + Size (Pixels): 5 + Size (m): 0.20000000298023224 Style: Points - Topic: /sensing/lidar/no_ground/pointcloud - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensing/lidar/no_ground/pointcloud Use Fixed Frame: true Use rainbow: true Value: true - Alpha: 1 - Class: rviz/Polygon + Class: rviz_default_plugins/Polygon Color: 25; 255; 0 Enabled: false - Name: MesurementRange - Topic: /sensing/lidar/crop_box_filter/crop_box_polygon - Unreliable: false + Name: MeasurementRange + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensing/lidar/crop_box_filter/crop_box_polygon Value: false Enabled: true Name: LiDAR - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Alpha: 1 + - Alpha: 0.9990000128746033 Axes Length: 1 Axes Radius: 0.10000000149011612 - Class: rviz/PoseWithCovariance + Class: rviz_default_plugins/PoseWithCovariance Color: 233; 185; 110 Covariance: Orientation: @@ -411,9 +441,9 @@ Visualization Manager: Frame: Local Offset: 1 Scale: 1 - Value: false + Value: true Position: - Alpha: 0.20000000298023224 + Alpha: 0.30000001192092896 Color: 204; 51; 204 Scale: 1 Value: true @@ -425,21 +455,25 @@ Visualization Manager: Shaft Length: 1 Shaft Radius: 0.5 Shape: Arrow - Topic: /sensing/gnss/pose_with_covariance - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensing/gnss/pose_with_covariance Value: true Enabled: false Name: GNSS Enabled: true Name: Sensing - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Alpha: 1 + - Alpha: 0.9990000128746033 Axes Length: 1 Axes Radius: 0.10000000149011612 - Class: rviz/PoseWithCovariance + Class: rviz_default_plugins/PoseWithCovariance Color: 0; 170; 255 Covariance: Orientation: @@ -463,13 +497,17 @@ Visualization Manager: Shaft Length: 0.6000000238418579 Shaft Radius: 0.30000001192092896 Shape: Arrow - Topic: /localization/pose_estimator/initial_pose_with_covariance - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/initial_pose_with_covariance Value: true - - Alpha: 1 + - Alpha: 0.9990000128746033 Axes Length: 1 Axes Radius: 0.10000000149011612 - Class: rviz/PoseWithCovariance + Class: rviz_default_plugins/PoseWithCovariance Color: 0; 255; 0 Covariance: Orientation: @@ -493,20 +531,14 @@ Visualization Manager: Shaft Length: 0.6000000238418579 Shaft Radius: 0.30000001192092896 Shape: Arrow - Topic: /localization/pose_estimator/pose_with_covariance - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/pose_with_covariance Value: true - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: /localization/pose_estimator/pose - Value: true - - Alpha: 1 + - Alpha: 0.9990000128746033 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 @@ -514,9 +546,9 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 - Color: 0; 255; 255 - Color Transformer: FlatColor + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" Decay Time: 0 Enabled: false Invert Rainbow: false @@ -525,18 +557,21 @@ Visualization Manager: Min Color: 0; 0; 0 Min Intensity: 0 Name: Initial - Position Transformer: XYZ - Queue Size: 10 + Position Transformer: "" Selectable: true Size (Pixels): 10 Size (m): 0.009999999776482582 Style: Points - Topic: /localization/util/downsample/pointcloud - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/util/downsample/pointcloud Use Fixed Frame: true Use rainbow: true Value: false - - Alpha: 1 + - Alpha: 0.9990000128746033 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 @@ -544,158 +579,182 @@ Visualization Manager: Value: true Axis: Z Channel Name: intensity - Class: rviz/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" Decay Time: 0 Enabled: false Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 + Max Color: 255; 255; 255 + Max Intensity: 4096 Min Color: 0; 0; 0 Min Intensity: 0 Name: Aligned - Position Transformer: XYZ - Queue Size: 10 + Position Transformer: "" Selectable: true Size (Pixels): 10 Size (m): 0.009999999776482582 Style: Points - Topic: /localization/pose_estimator/points_aligned - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/points_aligned Use Fixed Frame: true Use rainbow: true Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /localization/pose_estimator/monte_carlo_initial_pose_marker Name: MonteCarloInitialPose - Namespaces: {} - Queue Size: 1 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /localization/pose_estimator/monte_calro_initial_pose_marker Value: true Enabled: true Name: NDT - - Class: rviz/Group - Displays: - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: /localization/pose_twist_fusion_filter/pose - Value: true + - Class: rviz_common/Group + Displays: ~ Enabled: true Name: EKF Enabled: true Name: Localization - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /perception/object_recognition/detection/objects/visualization Name: DynamicObjects - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/detection/objects/visualization Value: true Enabled: false Name: Detection - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /perception/object_recognition/tracking/objects/visualization Name: DynamicObjects - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/tracking/objects/visualization Value: true Enabled: false Name: Tracking - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /perception/object_recognition/objects/visualization Name: DynamicObjects Namespaces: - label: true - path: true - path confidence: true - shape: true - twist: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/object_recognition/objects/visualization Value: true Enabled: true Name: Prediction - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/Image + - Class: rviz_default_plugins/Image Enabled: true - Image Topic: /perception/traffic_light_recognition/debug/rois Max Value: 1 Median window: 5 Min Value: 0 Name: Image Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/traffic_light_recognition/debug/rois Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers Name: Beam - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers Value: true Enabled: true Name: TrafficLight Enabled: true Name: Perception - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/mission_planning/route_marker Name: RouteArea Namespaces: - goal_lanelets: true - left_lane_bound: true - right_lane_bound: true - route_lanelets: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/route_marker Value: true - Alpha: 1 Axes Length: 1 Axes Radius: 0.30000001192092896 - Class: rviz/Pose + Class: rviz_default_plugins/Pose Color: 255; 25; 0 Enabled: true Head Length: 0.30000001192092896 - Head Radius: 0.5 + Head Radius: 0.10000000149011612 Name: GoalPose - Shaft Length: 3 - Shaft Radius: 0.20000000298023224 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 Shape: Axes - Topic: /planning/mission_planning/goal - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/goal Value: true Enabled: true Name: MissionPlanning - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Class: rviz_plugins/Trajectory Color Border Vel Max: 3 Enabled: true Name: ScenarioTrajectory - Topic: /planning/scenario_planning/trajectory - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/trajectory Value: true View Path: Alpha: 1 @@ -709,145 +768,166 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true Name: Path - Topic: /planning/scenario_planning/lane_driving/behavior_planning/path - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/path Value: true View Path: - Alpha: 0.4000000059604645 + Alpha: 1 Color: 0; 0; 0 Constant Color: false Value: true Width: 2 View Velocity: - Alpha: 0.4000000059604645 + Alpha: 1 Color: 0; 0; 0 Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path Name: Arrow - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk Name: Crosswalk - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/crosswalk Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection Name: Intersection Namespaces: - conflicting_targets: true - detection_area: false - ego_lane: false - factor_text: true - judge_point_pose_line: true - path_raw: false - spline: false - stop_point_pose_line: false - stop_virtual_wall: true - stuck_vehicle_detect_area: false - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/intersection Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot Name: Blind Spot Namespaces: - conflict_area_for_blind_spot: false - conflicting_targets: true - detection_area: false - detection_area_for_blind_spot: false - factor_text: true - judge_point_pose_line: true - path_raw: false - stop_virtual_wall: true - spline: false - stop_point_pose_line: false - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/blind_spot Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light Name: TrafficLight - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_light Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line Name: StopLine Namespaces: - factor_text: true - stop_virtual_wall: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/stop_line Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area Name: DetectionArea Namespaces: - factor_text: true - stop_virtual_wall: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/debug/detection_area Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/debug/predicted_path_markers Name: LaneChange Namespaces: - candidate_lane_change_path: false - ego_lane_change_path: false - ego_lane_follow_path: false - factor_text: true - object_predicted_path: false - selected_path: false - stop_virtual_wall: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/debug/predicted_path_markers Value: true - - Class: rviz_plugins/Path + - Class: rviz_plugins/Trajectory Color Border Vel Max: 3 Enabled: true - Name: LaneChangeCandidate - Topic: /planning/scenario_planning/lane_driving/lane_change_candidate_path - Unreliable: false + Name: LaneChangeCanditate + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/lane_change_candidate_path Value: true View Path: - Alpha: 0.30000001192092896 - Color: 115; 210; 22 - Constant Color: true + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false Value: true Width: 2 View Velocity: Alpha: 1 Color: 0; 0; 0 - Constant Color: true + Constant Color: false Scale: 0.30000001192092896 Value: false Enabled: true Name: BehaviorPlanning - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Class: rviz_plugins/Trajectory Color Border Vel Max: 3 Enabled: false Name: Trajectory - Topic: /planning/scenario_planning/lane_driving/trajectory - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/trajectory Value: false View Path: Alpha: 1 @@ -861,87 +941,73 @@ Visualization Manager: Constant Color: false Scale: 0.30000001192092896 Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Name: ObstaclePointCloudStop + Name: ObstaclePointCLoudStop Namespaces: - collision_polygons: true - detection_polygons: true - factor_text: true - stop_virtual_wall: true - stop_obstacle_point: true - stop_obstacle_text: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obststacle_stop_planner/debug/marker Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker Name: SurroundObstacleCheck Namespaces: - factor_text: true - virtual_wall: true - obstacle_point: true - no_start_obstacle_text: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker Value: true - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: true - Marker Topic: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker Name: ObstacleAvoidance Namespaces: - base_bounds_line: false - bounds_candidate_base_text: false - bounds_candidate_for_base: false - bounds_candidate_for_top: false - bounds_candidate_top_text: false - constrain_rect: false - constrain_rect_text: false - constrain_rectlocation: false - current_vehicle_footprint: false - extending_constrain_rect: false - extending_constrain_rect_text: false - extending_constrain_rectlocation: false - fixed_mpt_points: false - fixed_points_for_extending: false - fixed_points_marker: false - interpolated_points_for_extending: false - interpolated_points_marker: false - interpolated_points_text_marker: false - non_fixed_points_for_extending: false - non_fixed_points_marker: false - num_vehicle_footprint: false - optimized_points_marker: false - optimized_points_text_marker: false - smoothed_points_text: false - straight_points_marker: false - top_bounds_line: false - vehicle_footprint: false - virtual_wall: true - virtual_wall_text: true - Queue Size: 100 + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/lane_driving/motion_planning/obststacle_avoidance_planner/debug/marker Value: true Enabled: true Name: MotionPlanning Enabled: true Name: LaneDriving - - Class: rviz/Group + - Class: rviz_common/Group Displays: - Alpha: 0.699999988079071 - Class: rviz/Map + Class: rviz_default_plugins/Map Color Scheme: map Draw Behind: false Enabled: false Name: Costmap - Topic: /planning/scenario_planning/parking/costmap_generator/occupancy_grid - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid_updates Use Timestamp: false Value: false - - Alpha: 1 + - Alpha: 0.9990000128746033 Arrow Length: 0.30000001192092896 Axes Length: 0.30000001192092896 - Axes Radius: 0.05000000074505806 - Class: rviz/PoseArray + Axes Radius: 0.009999999776482582 + Class: rviz_default_plugins/PoseArray Color: 255; 25; 0 Enabled: true Head Length: 0.10000000149011612 @@ -950,24 +1016,32 @@ Visualization Manager: Shaft Length: 0.20000000298023224 Shaft Radius: 0.05000000074505806 Shape: Arrow (3D) - Topic: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/parking/debug/partial_pose_array Value: true - - Alpha: 1 + - Alpha: 0.9990000128746033 Arrow Length: 0.5 Axes Length: 0.30000001192092896 Axes Radius: 0.009999999776482582 - Class: rviz/PoseArray + Class: rviz_default_plugins/PoseArray Color: 0; 0; 255 Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 Name: PoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 Shape: Arrow (Flat) - Topic: /planning/scenario_planning/parking/freespace_planner/debug/pose_array - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/scenario_planning/parking/debug/pose_array Value: true Enabled: true Name: Parking @@ -975,75 +1049,125 @@ Visualization Manager: Name: ScenarioPlanning Enabled: true Name: Planning - - Class: rviz/Group + - Class: rviz_common/Group Displays: - - Class: rviz/MarkerArray + - Class: rviz_plugins/Trajectory + Color Border Vel Max: 3 + Enabled: true + Name: Predicted Trajectory + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/trajectory_follower/predicted_trajectory + Value: true + View Path: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Value: true + Width: 2 + View Velocity: + Alpha: 1 + Color: 0; 0; 0 + Constant Color: false + Scale: 0.30000001192092896 + Value: false + - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /control/trajectory_follower/mpc_follower/debug/markers Name: Debug/MPC - Namespaces: {} - Queue Size: 100 + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/trajectory_follower/mpc_follower/debug/markers Value: false - - Class: rviz/MarkerArray + - Class: rviz_default_plugins/MarkerArray Enabled: false - Marker Topic: /control/trajectory_follower/pure_pursuit/debug/marker Name: Debug/PurePursuit Namespaces: {} - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/trajectory_follower/pure_pursuit/debug/markers Value: false Enabled: true Name: Control Enabled: true Global Options: - Background Color: 48; 48; 48 - Default Light: true + Background Color: 10; 10; 10 Fixed Frame: viewer Frame Rate: 30 Name: root Tools: - - Class: rviz/Interact + - Class: rviz_default_plugins/Interact Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /planning/mission_planning/goal - - Class: rviz/PedestrianInitialPoseTool + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /planning/mission_planning/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + - Class: rviz_plugins/PedestrianInitialPoseTool Pose Topic: /simulation/dummy_perception_publisher/object_info Theta std deviation: 0.0872664600610733 - Velocity: 1 - X std deviation: 0.009999999776482582 - Y std deviation: 0.009999999776482582 - Z position: 0 - Z std deviation: 0.009999999776482582 - - Class: rviz/CarInitialPoseTool + Velocity: 0 + X std deviation: 0.029999999329447746 + Y std deviation: 0.029999999329447746 + Z position: 1 + Z std deviation: 0.029999999329447746 + - Class: rviz_plugins/CarInitialPoseTool Pose Topic: /simulation/dummy_perception_publisher/object_info Theta std deviation: 0.0872664600610733 Velocity: 3 - X std deviation: 0.009999999776482582 - Y std deviation: 0.009999999776482582 + X std deviation: 0.029999999329447746 + Y std deviation: 0.029999999329447746 Z position: 0 - Z std deviation: 0.009999999776482582 - - Class: rviz/MissionCheckpointTool - Pose Topic: /planning/mission_planning/checkpoint + Z std deviation: 0.029999999329447746 + - Class: rviz_plugins/MissionCheckpointTool + Pose Topic: mission_checkpoint Theta std deviation: 0.2617993950843811 X std deviation: 0.5 Y std deviation: 0.5 Z position: 0 - - Class: rviz/DeleteAllObjectsTool + - Class: rviz_plugins/DeleteAllObjectsTool Pose Topic: /simulation/dummy_perception_publisher/object_info + Transformation: + Current: + Class: rviz_default_plugins/TF Value: true Views: Current: - Angle: 0 - Class: rviz/TopDownOrtho + Angle: 0.07999998331069946 + Class: rviz_default_plugins/TopDownOrtho Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -1052,31 +1176,27 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Scale: 10 + Scale: -5.74001932144165 Target Frame: viewer - Value: TopDownOrtho (rviz) - X: 0 - Y: 0 + Value: TopDownOrtho (rviz_default_plugins) + X: -38.261173248291016 + Y: 29.38650894165039 Saved: ~ Window Geometry: Displays: collapsed: false - Height: 1565 + Height: 2032 Hide Left Dock: false Hide Right Dock: false Image: collapsed: false - InitialPoseButtonPanel: - collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000033c00000563fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001f0000000c900fffffffb0000000a005600690065007700730100000233000000f2000000a400fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073010000032b000000a10000005c00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d00610067006501000003d2000001ce0000001600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000007700ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000afd0000005afc0100000002fb0000000800540069006d0065010000000000000afd000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000007bb0000056300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000055e0000075efc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b000000ab00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000690000023c0000017800fffffffc000002b10000026c0000015801000034fa000000000100000002fb0000000a005600690065007700730100000000ffffffff0000014f00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007301000000000000055e000000f500fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000035400000090000000ab00fffffffb0000000a0049006d00610067006501000005290000029e0000004500ffffff00000001000001570000075efc0200000001fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000009060000075e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false - Time: - collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 2813 - X: 67 - Y: 27 + Width: 3696 + X: 144 + Y: 54 diff --git a/build_depends.repos b/build_depends.repos index 9c98243c2b..1823b96c23 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -39,3 +39,11 @@ repositories: type: git url: https://github.com/flynneva/usb_cam.git version: foxy + vendor/rosbridge_suite: + type: git + url: https://github.com/RobotWebTools/rosbridge_suite.git + version: ros2 + vendor/rosauth: + type: git + url: https://github.com/GT-RAIL/rosauth.git + version: ros2 diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 2a74551c53..40a4690e38 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -1,6 +1,8 @@ + + @@ -45,6 +47,7 @@ + diff --git a/planning_launch/launch/planning.launch.xml b/planning_launch/launch/planning.launch.xml index bfc5e01110..4c58bdfd46 100644 --- a/planning_launch/launch/planning.launch.xml +++ b/planning_launch/launch/planning.launch.xml @@ -1,4 +1,5 @@ + @@ -13,6 +14,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving.launch.xml b/planning_launch/launch/scenario_planning/lane_driving.launch.xml index f3d6507a5d..661590e042 100644 --- a/planning_launch/launch/scenario_planning/lane_driving.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving.launch.xml @@ -1,4 +1,5 @@ + @@ -7,6 +8,7 @@ + @@ -14,6 +16,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index b032b00c34..60fa2e2afa 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -1,6 +1,7 @@ + @@ -43,6 +44,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index d0e6f5d6fa..da8f228236 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -1,5 +1,6 @@ + @@ -7,7 +8,8 @@ - + + @@ -16,7 +18,8 @@ - + + @@ -27,7 +30,8 @@ - + + diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index e33d1c162f..20ac205141 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -1,4 +1,6 @@ + + @@ -25,6 +27,7 @@ + From 174cfb617811ac157757b808c5a76ff9d320da44 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 11 Jan 2021 11:26:55 +0900 Subject: [PATCH 0068/1765] Update rviz config for vehicle rviz plugins (#41) Signed-off-by: wep21 --- autoware_launch/rviz/autoware.rviz | 41 +++++++++++++++++++++++++++--- 1 file changed, 37 insertions(+), 4 deletions(-) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 1e2964ad3f..36abca3067 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -79,7 +79,7 @@ Visualization Manager: Displays: - Class: rviz_plugins/ConsoleMeter Enabled: true - Left: 128 + Left: 512 Length: 256 Name: ConsoleMeter Scale: 3 @@ -93,12 +93,28 @@ Visualization Manager: Value: /vehicle/status/twist Value: true Value height offset: 0 + - Class: rviz_plugins/SteeringAngle + Enabled: true + Left: 128 + Length: 256 + Name: SteeringAngle + Scale: 3 + Text Color: 25; 255; 240 + Top: 128 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/steering + Value: true + Value height offset: 0 - Class: rviz_plugins/TurnSignal Enabled: true Height: 256 - Left: 128 + Left: 196 Name: TurnSignal - Top: 128 + Top: 350 Topic: Depth: 5 Durability Policy: Volatile @@ -106,7 +122,7 @@ Visualization Manager: Reliability Policy: Reliable Value: /control/turn_signal_cmd Value: true - Width: 256 + Width: 512 - Alpha: 0.30000001192092896 Class: rviz_default_plugins/RobotModel Collision Enabled: false @@ -279,6 +295,23 @@ Visualization Manager: Update Interval: 0 Value: true Visual Enabled: true + - Alpha: 0.9990000128746033 + Class: rviz_plugins/VelocityHistory + Color Border Vel Max: 3 + Constant Color: + Color: 0; 0; 0 + Value: false + Enabled: true + Name: VelocityHistory + Scale: 0.30000001192092896 + Timeout: 10 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /vehicle/status/twist + Value: true Enabled: true Name: Vehicle Enabled: true From fbaa31ce7a318a056448b519ca02d74bdd99c420 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 13 Jan 2021 13:11:47 +0900 Subject: [PATCH 0069/1765] perception_launch: Fix lidar based detection launch (#42) Signed-off-by: wep21 --- .../detection/lidar_based_detection.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index b4f388d4e9..be91b84912 100644 --- a/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -3,7 +3,7 @@ - - + + From 53352c3d107e331cf31739394fde9560869619ed Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Thu, 14 Jan 2021 00:06:19 +0900 Subject: [PATCH 0070/1765] ROS2 Linting: map_launch (#31) * Add linter tests and missing exec dependencies * Address PR comment: - Use ament_lint_common --- map_launch/CMakeLists.txt | 5 +++++ map_launch/package.xml | 8 +++++++- 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/map_launch/CMakeLists.txt b/map_launch/CMakeLists.txt index 346ccdb967..d32f7c28c9 100644 --- a/map_launch/CMakeLists.txt +++ b/map_launch/CMakeLists.txt @@ -11,6 +11,11 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/map_launch/package.xml b/map_launch/package.xml index d50ed78acd..9faf46ebd9 100644 --- a/map_launch/package.xml +++ b/map_launch/package.xml @@ -6,10 +6,16 @@ mitsudome-r - Apache 2 + Apache License 2.0 ament_cmake_auto + map_loader + map_tf_generator + + ament_lint_auto + ament_lint_common + ament_cmake From 4d735faee4ed239aa2663e1c82242bf184b83bed Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Thu, 14 Jan 2021 00:06:59 +0900 Subject: [PATCH 0071/1765] ROS2 Linting: perception_launch (#36) * Add linters and missing package dependencies * Alphabetise packages --- perception_launch/CMakeLists.txt | 5 +++++ perception_launch/package.xml | 17 ++++++++++------- 2 files changed, 15 insertions(+), 7 deletions(-) diff --git a/perception_launch/CMakeLists.txt b/perception_launch/CMakeLists.txt index 1ded711b02..4b21dc3b05 100644 --- a/perception_launch/CMakeLists.txt +++ b/perception_launch/CMakeLists.txt @@ -4,6 +4,11 @@ project(perception_launch) find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/perception_launch/package.xml b/perception_launch/package.xml index db4b9e5f10..724f2c0aee 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -10,13 +10,16 @@ ament_cmake_auto - dynamic_object_visualization - image_transport_plugins - + cluster_data_association + dynamic_object_visualization + euclidean_cluster + lidar_apollo_instance_segmentation + map_based_prediction + multi_object_tracker + naive_path_prediction + roi_cluster_fusion + shape_estimation + tensorrt_yolo3 ament_lint_auto ament_lint_common From 52fbfebc266bff3753dc42821fe9d612cf32d987 Mon Sep 17 00:00:00 2001 From: Jilada Eccleston Date: Thu, 14 Jan 2021 00:08:19 +0900 Subject: [PATCH 0072/1765] ROS2 Linting: localization_launch (#39) * Add linters to localization_launch package * Add new line * Fix indentation --- localization_launch/CMakeLists.txt | 13 +++++++++---- localization_launch/package.xml | 12 +++--------- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt index ccb239a68a..5f76d89e42 100644 --- a/localization_launch/CMakeLists.txt +++ b/localization_launch/CMakeLists.txt @@ -2,15 +2,20 @@ cmake_minimum_required(VERSION 3.5) project(localization_launch) if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD 14) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-parameter) + add_compile_options(-Wall -Wextra -Wpedantic -Wno-unused-parameter) endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package(INSTALL_TO_SHARE - launch - ) \ No newline at end of file + launch +) diff --git a/localization_launch/package.xml b/localization_launch/package.xml index e4ccb2e7c6..3dc295d636 100644 --- a/localization_launch/package.xml +++ b/localization_launch/package.xml @@ -5,16 +5,9 @@ 0.1.0 The localization_launch package - - - Yamato Ando - - - - - Apache 2 + Apache License 2.0 ament_cmake_auto @@ -25,8 +18,9 @@ pointcloud_preprocessor topic_tools + ament_lint_auto + ament_lint_common - ament_cmake From 5fb3133cc2269de3e35e13fa0d400e258b7a52bb Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 18 Feb 2021 13:02:51 +0900 Subject: [PATCH 0073/1765] perception_launch: Traffic light composable nodes (#43) * perception_launch: Traffic light composable nodes Signed-off-by: wep21 * Fix arg Signed-off-by: wep21 --- .../traffic_light.launch.xml | 25 +--- .../traffic_light_node_container.launch.py | 129 ++++++++++++++++++ 2 files changed, 133 insertions(+), 21 deletions(-) create mode 100644 perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml index 4651d65233..29ad7c1a43 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml +++ b/perception_launch/launch/traffic_light_recognition/traffic_light.launch.xml @@ -6,12 +6,10 @@ - - - - - + + + @@ -20,12 +18,6 @@ - - - - - - @@ -35,17 +27,8 @@ - - + - - - - - - - - diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py new file mode 100644 index 0000000000..2248b21dd6 --- /dev/null +++ b/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -0,0 +1,129 @@ +# Copyright 2020 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. + +import os +import yaml + +from ament_index_python.packages import get_package_share_directory + +import launch +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes +from launch_ros.descriptions import ComposableNode + + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + ssd_fine_detector_share_dir = get_package_share_directory( + 'traffic_light_ssd_fine_detector' + ) + classifier_share_dir = get_package_share_directory( + 'traffic_light_classifier' + ) + add_launch_arg('enable_fine_detection', 'True') + add_launch_arg('input/image', '/sensing/camera/traffic_light/image_raw') + + # traffic_light_ssd_fine_detector + add_launch_arg('onnx_file', + os.path.join(ssd_fine_detector_share_dir, 'data', 'mb2-ssd-lite-tlr.onnx')) + add_launch_arg('label_file', + os.path.join(ssd_fine_detector_share_dir, 'data', 'voc_labels_tl.txt')) + add_launch_arg('fine_detector_precision', 'FP32') + add_launch_arg('score_thresh', '0.7') + add_launch_arg('max_batch_size', '8') + add_launch_arg('approximate_sync', 'False') + add_launch_arg('mean', '[0.5, 0.5, 0.5]') + add_launch_arg('std', '[0.5, 0.5, 0.5]') + + # traffic_light_classifier + add_launch_arg('classifier_type', '1') + add_launch_arg('model_file_path', + os.path.join(classifier_share_dir, + 'data', + 'traffic_light_classifier_mobilenetv2.onnx')) + add_launch_arg('label_file_path', + os.path.join(classifier_share_dir, 'data', 'lamp_labels.txt')) + add_launch_arg('precision', 'fp16') + add_launch_arg('input_c', '3') + add_launch_arg('input_h', '224') + add_launch_arg('input_w', '224') + + def create_parameter_dict(*args): + result = {} + for x in args: + result[x] = LaunchConfiguration(x) + return result + + container = ComposableNodeContainer( + name='traffic_light_node_container', + namespace='/perception/traffic_light_recognition', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='traffic_light_classifier', + plugin='traffic_light::TrafficLightClassifierNodelet', + name='traffic_light_classifier', + parameters=[create_parameter_dict('approximate_sync', 'classifier_type', + 'model_file_path', 'label_file_path', + 'precision', 'input_c', 'input_h', 'input_w')], + remappings=[('input/image', LaunchConfiguration('input/image')), + ('input/rois', 'rois'), + ('output/traffic_light_states', 'traffic_light_states')] + ), + ComposableNode( + package='traffic_light_visualization', + plugin='traffic_light::TrafficLightRoiVisualizerNodelet', + name='traffic_light_roi_visualizer', + parameters=[create_parameter_dict('enable_fine_detection')], + remappings=[('input/image', LaunchConfiguration('input/image')), + ('input/rois', 'rois'), + ('input/rough/rois', 'rough/rois'), + ('output/image', 'debug/rois'), + ('output/image/compressed', 'debug/rois/compressed'), + ('output/image/compressedDepth', 'debug/rois/compressedDepth')] + ) + ], + output='both', + ) + + ssd_fine_detector_param = create_parameter_dict('onnx_file', 'label_file', + 'score_thresh', 'max_batch_size', + 'approximate_sync', 'mean', 'std') + ssd_fine_detector_param['mode'] = LaunchConfiguration('fine_detector_precision') + + loader = LoadComposableNodes( + composable_node_descriptions=[ + ComposableNode( + package='traffic_light_ssd_fine_detector', + plugin='traffic_light::TrafficLightSSDFineDetectorNodelet', + name='traffic_light_ssd_fine_detector', + parameters=[ssd_fine_detector_param], + remappings=[('input/image', LaunchConfiguration('input/image')), + ('input/rois', 'rough/rois'), + ('output/rois', 'rois')] + ), + ], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('enable_fine_detection')), + ) + + return LaunchDescription(launch_arguments + [container, loader]) From 7fa6fe3f906c74bcad91b4f75e91c4751bf5fcb6 Mon Sep 17 00:00:00 2001 From: wep21 Date: Thu, 18 Feb 2021 13:46:25 +0900 Subject: [PATCH 0074/1765] [perception launch]: Remove unused import Signed-off-by: wep21 --- .../traffic_light_node_container.launch.py | 1 - 1 file changed, 1 deletion(-) diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index 2248b21dd6..5fcc08e634 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -13,7 +13,6 @@ # limitations under the License. import os -import yaml from ament_index_python.packages import get_package_share_directory From 2c8ea2b28d1fe58e1283b459f91575cde764ab16 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 9 Feb 2021 23:41:53 +0900 Subject: [PATCH 0075/1765] Update target branch for ci (#52) Signed-off-by: wep21 --- .github/workflows/build_and_test.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/build_and_test.yml b/.github/workflows/build_and_test.yml index 8496171f37..cfb1ed8fc2 100644 --- a/.github/workflows/build_and_test.yml +++ b/.github/workflows/build_and_test.yml @@ -4,9 +4,11 @@ on: pull_request: branches: - ros2 + - ros2-v0.8.0-beta push: branches: - ros2 + - ros2-v0.8.0-beta jobs: build-and-test: From 0ab8a057f2624c204bfb71ea7dc2e5905f42001a Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Tue, 16 Feb 2021 12:41:14 +0900 Subject: [PATCH 0076/1765] Fix dependency temporarily for v0.8.0 update. (#60) * Fix build_depends.repos temporarily Signed-off-by: wep21 * Remove deprecated packages Signed-off-by: wep21 --- build_depends.repos | 2 +- perception_launch/package.xml | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/build_depends.repos b/build_depends.repos index 1823b96c23..0b96d6e6c3 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -2,7 +2,7 @@ repositories: dependencies/Pilot.Auto: type: git url: https://github.com/tier4/Pilot.Auto.git - version: ros2 + version: ros2-v0.8.0-beta description/sensor/velodyne_simulator: type: git url: https://github.com/tier4/velodyne_simulator.git diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 724f2c0aee..9680249fb5 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -10,7 +10,6 @@ ament_cmake_auto - cluster_data_association dynamic_object_visualization euclidean_cluster lidar_apollo_instance_segmentation @@ -19,7 +18,6 @@ naive_path_prediction roi_cluster_fusion shape_estimation - tensorrt_yolo3 ament_lint_auto ament_lint_common From 3fb38aef527404518a62a8b3660b6c4a02a20b85 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 16 Feb 2021 13:47:58 +0900 Subject: [PATCH 0077/1765] Ros2 v0.8.0 control launch (#53) * restore file name for v0.8.0 update Signed-off-by: Takamasa Horibe * Add use_emergency_handling arg to vehicle_cmd_gate.launch (#83) Signed-off-by: Kenji Miyake * Add parameter for using steer prediction (#88) * change stop dist param (#85) * mpc: change param name steer_rate_lim_deg -> steer_rate_lim_dps (#79) Signed-off-by: Takamasa Horibe * add mpc parameter (#105) * Add parameters for stop state (#126) * Add parameters for stop state * Change default value * Add vehicle cmd gate config (#136) * Add config_file of vehicle_cmd_gate Signed-off-by: Kenji Miyake * Add use_emergency_stop Signed-off-by: Kenji Miyake * Rename emergency_stop to external_emergency_stop Signed-off-by: Kenji Miyake * Fix command_gate diag Signed-off-by: Kenji Miyake * Add lane_departure_checker (#123) Signed-off-by: Kenji Miyake * Revert "restore file name for v0.8.0 update" This reverts commit 516b366819f7f9d69b9bc3e2de180d4523794bcd. * fix control launch Signed-off-by: Takamasa Horibe * fix args Signed-off-by: Takamasa Horibe * fix param type Signed-off-by: Takamasa Horibe * fix lane departure checker Signed-off-by: Takamasa Horibe Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Fumiya Watanabe Co-authored-by: tkimura4 --- .../mpc_follower/mpc_follower_param.yaml | 17 +++++++++++++++- .../vehicle_cmd_gate/vehicle_cmd_gate.yaml | 11 ++++++++++ .../velocity_controller_param.yaml | 2 +- control_launch/launch/control.launch.xml | 20 +++++++++++++++++-- control_launch/package.xml | 1 + 5 files changed, 47 insertions(+), 4 deletions(-) create mode 100644 control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.yaml diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower_param.yaml index 3d6171ce7d..9156175f2d 100644 --- a/control_launch/config/mpc_follower/mpc_follower_param.yaml +++ b/control_launch/config/mpc_follower/mpc_follower_param.yaml @@ -4,6 +4,7 @@ ctrl_period: 0.03 # control period [s] traj_resample_dist: 0.1 # path resampling interval [m] enable_yaw_recalculation: false # flag for recalculation of yaw angle after resampling + use_steer_prediction: false # flag for using steer prediction (do not use steer measurement) admisible_position_error: 5.0 # stop mpc calculation when error is larger than the following value admisible_yaw_error_: 1.57 # stop mpc calculation when error is larger than the following value @@ -25,6 +26,15 @@ mpc_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R mpc_weight_steer_rate: 0.0 # steering rate weight in matrix R mpc_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R + mpc_low_curvature_weight_lat_error: 0.1 # lateral error weight in matrix Q in low curvature point + mpc_low_curvature_weight_heading_error: 0.0 # heading error weight in matrix Q in low curvature point + mpc_low_curvature_weight_heading_error_squared_vel: 0.3 # heading error * velocity weight in matrix Q in low curvature point + mpc_low_curvature_weight_steering_input: 1.0 # steering error weight in matrix R in low curvature point + mpc_low_curvature_weight_steering_input_squared_vel: 0.25 # steering error * velocity weight in matrix R in low curvature point + mpc_low_curvature_weight_lat_jerk: 0.0 # lateral jerk weight in matrix R in low curvature point + mpc_low_curvature_weight_steer_rate: 0.0 # steering rate weight in matrix R in low curvature point + mpc_low_curvature_weight_steer_acc: 0.000001 # steering angular acceleration weight in matrix R in low curvature point + mpc_low_curvature_thresh_curvature: 0.00 # threshold of curvature to use "low vurvature" parameter (0: do not use low curvature parameter) mpc_weight_terminal_lat_error: 1.0 # terminal lateral error weight in matrix Q to improve mpc stability mpc_weight_terminal_heading_error: 0.1 # terminal heading error weight in matrix Q to improve mpc stability mpc_zero_ff_steer_deg: 0.5 # threshold that feed-forward angle becomes zero @@ -34,9 +44,14 @@ input_delay: 0.24 # steering input delay time for delay compensation vehicle_model_steer_tau: 0.3 # steering dynamics time constant (1d approzimation) [s] steer_lim_deg: 40.0 # steering angle limit [deg] - steer_rate_lim_deg: 600.0 # steering angle rate limit [deg/s] + steer_rate_lim_dps: 600.0 # steering angle rate limit [deg/s] acceleration_limit: 2.0 # acceleration limit for trajectory velocity modification [m/ss] velocity_time_constant: 0.3 # velocity dynamics time constant for trajectory velocity modification [s] # -- lowpass filter for noise reduction -- steering_lpf_cutoff_hz: 3.0 # cutoff frequency of lowpass filter for steering command [Hz] + + # stop state + stop_state_entry_ego_speed: 0.2 + stop_state_entry_target_speed: 0.5 + stop_state_keep_stopping_dist: 0.5 diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.yaml b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.yaml new file mode 100644 index 0000000000..fbded96a7b --- /dev/null +++ b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + update_rate: 10.0 + system_emergency_heartbeat_timeout: 0.5 + external_emergency_stop_heartbeat_timeout: 0.0 + + vel_lim: 25.0 + lon_acc_lim: 5.0 + lon_jerk_lim: 5.0 + lat_acc_lim: 5.0 + lat_jerk_lim: 5.0 diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml index 45b5c6dc2f..c661125702 100644 --- a/control_launch/config/velocity_controller/velocity_controller_param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -20,7 +20,7 @@ # smooth stop smooth_stop: - stop_dist: 3.0 + stop_dist: 0.5 exit_ego_speed: 1.0 entry_ego_speed: 0.8 exit_target_speed: 1.0 diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 40a4690e38..886c2cd9c4 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -10,6 +10,7 @@ + @@ -21,16 +22,23 @@ - + + + + - + + + + + @@ -39,6 +47,11 @@ + + + + + @@ -48,6 +61,9 @@ + + + diff --git a/control_launch/package.xml b/control_launch/package.xml index 7793c033db..c668eb210e 100644 --- a/control_launch/package.xml +++ b/control_launch/package.xml @@ -18,6 +18,7 @@ shift_decider vehicle_cmd_gate velocity_controller + lane_departure_checker ament_lint_auto ament_lint_common From 9d887e85bce5fd23fd96dfd12e89000e0d9b8805 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 16 Feb 2021 14:05:23 +0900 Subject: [PATCH 0078/1765] Ros2 v0.8.0 localization launch (#54) * restore file name for v0.8.0 update in localization launch Signed-off-by: Takamasa Horibe * add random sample (#84) Signed-off-by: Yamato Ando * Add ndt_scan_matcher.yaml (#162) Signed-off-by: Yuma Nihei * ]Revert "restore file name for v0.8.0 update in localization launch" This reverts commit f589733f7dad05989bde323baeb5c43a62cd26e1. * fix param type Signed-off-by: Takamasa Horibe * fix exec name Signed-off-by: Takamasa Horibe Co-authored-by: YamatoAndo Co-authored-by: Yuma Nihei --- localization_launch/CMakeLists.txt | 1 + .../config/ndt_scan_matcher.yaml | 34 +++++++++++++++++++ .../pose_estimator/pose_estimator.launch.xml | 1 + .../launch/util/util.launch.xml | 11 ++++-- 4 files changed, 45 insertions(+), 2 deletions(-) create mode 100644 localization_launch/config/ndt_scan_matcher.yaml diff --git a/localization_launch/CMakeLists.txt b/localization_launch/CMakeLists.txt index 5f76d89e42..9815ea4b7c 100644 --- a/localization_launch/CMakeLists.txt +++ b/localization_launch/CMakeLists.txt @@ -18,4 +18,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/localization_launch/config/ndt_scan_matcher.yaml b/localization_launch/config/ndt_scan_matcher.yaml new file mode 100644 index 0000000000..0956b33082 --- /dev/null +++ b/localization_launch/config/ndt_scan_matcher.yaml @@ -0,0 +1,34 @@ +/**: + ros__parameters: + # Vehicle reference frame + base_frame: "base_link" + + # Subscriber queue size + input_sensor_points_queue_size: 1 + + # NDT implementation type + # 0=PCL_GENERIC, 1=PCL_MODIFIED, 2=OMP + ndt_implement_type: 2 + + # The maximum difference between two consecutive + # transformations in order to consider convergence + trans_epsilon: 0.01 + + # The newton line search maximum step length + step_size: 0.1 + + # The ND voxel grid resolution + resolution: 2.0 + + # The number of iterations required to calculate alignment + max_iterations: 30 + + # Threshold for deciding whetherto trust the estimation result + converged_param_transform_probability: 3.0 + + # neighborhood search method in OMP + # 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1 + omp_neighborhood_search_method: 0 + + # Number of threads used for parallel computing + omp_num_threads: 4 diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index 2ceb02097a..3b5bd6ab94 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -10,6 +10,7 @@ + diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 3904103c02..ebae50cf3f 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -4,6 +4,7 @@ + @@ -30,12 +31,18 @@ - + - + + + + + + + From 9d820791c648f45f3c60c4dc97b57860e4b407c7 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 16 Feb 2021 16:59:45 +0900 Subject: [PATCH 0079/1765] Ros2 v0.8.0 vehicle launch (#55) * restore file name Signed-off-by: Takamasa Horibe * Add default config of aip_x1 (#141) Signed-off-by: Kenji Miyake * Pass all args to vehicle_interface.launch (#147) Signed-off-by: Kenji Miyake * Revert "restore file name" This reverts commit 3e28661e8ba1a44cc570ca19b7b4759ba0bf0941. * fix vehicle_interface.launch arg Signed-off-by: Takamasa Horibe * [vehicle_launch]: Remove pass_all_args Signed-off-by: wep21 Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: wep21 --- .../aip_x1/sensor_kit_calibration.yaml | 28 +++++++++++++++++++ .../default/aip_x1/sensors_calibration.yaml | 7 +++++ .../launch/vehicle_interface.launch.xml | 6 +++- 3 files changed, 40 insertions(+), 1 deletion(-) create mode 100644 vehicle_launch/config/default/aip_x1/sensor_kit_calibration.yaml diff --git a/vehicle_launch/config/default/aip_x1/sensor_kit_calibration.yaml b/vehicle_launch/config/default/aip_x1/sensor_kit_calibration.yaml new file mode 100644 index 0000000000..0f3489dd61 --- /dev/null +++ b/vehicle_launch/config/default/aip_x1/sensor_kit_calibration.yaml @@ -0,0 +1,28 @@ +sensor_kit_base_link2velodyne_top_base_link: + x: 0.000 + y: 0.000 + z: 0.000 + roll: 0.000 + pitch: 0.000 + yaw: 0.000 +sensor_kit_base_link2livox_front_left_base_link: + x: 1.054 + y: 0.260 + z: -1.330 + roll: 0.000 + pitch: 0.000 + yaw: 1.047 +sensor_kit_base_link2livox_front_center_base_link: + x: 1.054 + y: 0.000 + z: -1.330 + roll: 0.000 + pitch: 0.000 + yaw: 0.000 +sensor_kit_base_link2livox_front_right_base_link: + x: 1.054 + y: -0.260 + z: -1.330 + roll: 0.000 + pitch: 0.000 + yaw: -1.047 diff --git a/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml b/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml index e69de29bb2..462d27f042 100644 --- a/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml +++ b/vehicle_launch/config/default/aip_x1/sensors_calibration.yaml @@ -0,0 +1,7 @@ +base_link2sensor_kit_base_link: + x: 0.555 + y: 0.000 + z: 1.810 + roll: 0.000 + pitch: 0.000 + yaw: 0.000 diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml index 5eb4ba2d2c..9867e34f0f 100644 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ b/vehicle_launch/launch/vehicle_interface.launch.xml @@ -11,12 +11,16 @@ - + + + + + From 3885d12d22bed13633cd29d9c68e53ea71832c0a Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 17 Feb 2021 14:45:47 +0900 Subject: [PATCH 0080/1765] [velocity controller]: Fix parameter type (#62) Signed-off-by: wep21 --- .../velocity_controller/velocity_controller_param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller_param.yaml index c661125702..e268548e5f 100644 --- a/control_launch/config/velocity_controller/velocity_controller_param.yaml +++ b/control_launch/config/velocity_controller/velocity_controller_param.yaml @@ -50,14 +50,14 @@ pid_controller: kp: 1.0 ki: 0.1 - kd: 0 + kd: 0.0 max_out: 1.0 min_out: -1.0 max_p_effort: 1.0 min_p_effort: -1.0 max_i_effort: 0.3 min_i_effort: -0.3 - max_d_effort: 0 - min_d_effort: 0 + max_d_effort: 0.0 + min_d_effort: 0.0 current_velocity_threshold_pid_integration: 0.5 lpf_velocity_error_gain: 0.9 From 95c13d55ff333e601951af8c995a68cb01a93820 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 18 Feb 2021 02:00:23 +0900 Subject: [PATCH 0081/1765] Ros2 v0.8.0 planning launch (#59) * [planning_launch] restore file name for ros2 porting Signed-off-by: Takamasa Horibe * Add obstacle_stop_planner.yaml (#82) Signed-off-by: Kenji Miyake * add surround obstacle checker options (#86) * fix slow down param related to https://github.com/tier4/autoware.iv/commit/a9cdcb2e9c4e7afbe50bfc15a86f6c525b8294bd (#91) * fix parame max_steer_deg (#92) * add refine_goal_search_radius_range (#93) * Change default evaluation in motion velocity optimizer (#97) * Use Linf * Add new line * Add maximum_deceleration parameter (#98) * Add maximum_deceleration parameter * Change default value * Unable abort lane change (#102) * add param stoping velocity and fix typo (#106) * Add a parameter for minimum velocity for lane change (#109) * Add parameters for collision check for lane change (#110) * Add a parameter for disable collision check at prepare phase * Add parameters for collision check with predicted_path * Add a parameter for backward buffer for end of lane (#114) * Add parameters for backward buffer for end of lane * Remove comment out * add extend_distance param (#107) * add parameter of acc (#129) Signed-off-by: Yuma Nihei * fix typo & change static object velocity thres in lane_change_planner (#104) * change static object velocity thres Signed-off-by: Kosuke Murakami * fix typo Signed-off-by: Kosuke Murakami * Change minimum_lane_change_velocity (#131) * Feature/update avoidance param (#140) * update avoidance param Signed-off-by: Kosuke Murakami * disable unnecesarry marker Signed-off-by: Kosuke Murakami * modify min_behavior_stop_margin (#127) * modify min_behavior_stop_margin Signed-off-by: Yamato Ando * Update obstacle_stop_planner.yaml Co-authored-by: Yukihiro Saito * Add expand_stop_range to obstacle_stop_planner.yaml (#152) Signed-off-by: Kenji Miyake * Update obstacle_stop_planner.yaml (#153) * Visualize echo back goal_pose instead of 2D Nav Goal (#150) * Visualize echo back goal_pose instead of 2D Nav Goal Signed-off-by: Kenji Miyake * Fix mission_planning.launch Signed-off-by: Kenji Miyake * Add surround_obstacle_checker.yaml (#157) * Add parameter (#158) * Revert "[planning_launch] restore file name for ros2 porting" This reverts commit 275f0df232323bf24627adea9cb08888c250625e. * fix namespace Signed-off-by: Takamasa Horibe * fix relay Signed-off-by: Takamasa Horibe * [planning_launch]: Add vehicle_param_file for turn signal decider Signed-off-by: wep21 * [planning_launch]: Change topic type of lane change approval Signed-off-by: wep21 Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: tkimura4 Co-authored-by: Taichi Higashide Co-authored-by: Satoshi Tanaka Co-authored-by: Fumiya Watanabe Co-authored-by: Yuma Nihei Co-authored-by: Kosuke Murakami Co-authored-by: YamatoAndo Co-authored-by: Yukihiro Saito Co-authored-by: hiroaki-ishikawa-t4 <57431939+hiroaki-ishikawa-t4@users.noreply.github.com> Co-authored-by: wep21 --- .../config/adaptive_cruise_control.yaml | 37 +++++++++++++++++++ .../config/obstacle_stop_planner.yaml | 15 ++++++++ .../motion_velocity_optimizer.yaml | 12 ++++-- .../obstacle_avoidance_planner.yaml | 8 ++-- .../surround_obstacle_checker.yaml | 12 ++++++ .../mission_planning.launch.xml | 19 +++------- .../behavior_planning.launch.xml | 16 ++++++-- .../motion_planning.launch.xml | 16 +++++++- 8 files changed, 108 insertions(+), 27 deletions(-) create mode 100644 planning_launch/config/adaptive_cruise_control.yaml create mode 100644 planning_launch/config/obstacle_stop_planner.yaml create mode 100644 planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.yaml diff --git a/planning_launch/config/adaptive_cruise_control.yaml b/planning_launch/config/adaptive_cruise_control.yaml new file mode 100644 index 0000000000..8734776b34 --- /dev/null +++ b/planning_launch/config/adaptive_cruise_control.yaml @@ -0,0 +1,37 @@ +/**: + ros__parameters: + adaptive_cruise_control: + # Adaptive Cruise Control (ACC) config + use_object_to_estimate_vel: true # use tracking objects for estimating object velocity or not + use_pcl_to_estimate_vel: true # use pcl for estimating object velocity or not + consider_obj_velocity: true # consider forward vehicle velocity to ACC or not + + # general parameter for ACC + obstacle_stop_velocity_thresh: 1.0 # threshold of forward obstacle velocity to insert stop line (to stop acc) [m/s] + emergency_stop_acceleration: -5.0 # supposed minimum acceleration (deceleration) in emergency stop [m/ss] + emergency_stop_idling_time: 0.5 # supposed idling time to start emergency stop [s] + min_dist_stop: 4.0 # minimum distance of emergency stop [m] + max_standard_acceleration: 0.5 # supposed maximum acceleration in active cruise control [m/ss] + min_standard_acceleration: -1.0 # supposed minimum acceleration (deceleration) in active cruise control + standard_idling_time: 0.5 # supposed idling time to react object in active cruise control [s] + min_dist_standard: 4.0 # minimum distance in active cruise control [m] + obstacle_min_standard_acceleration: -1.5 # supposed minimum acceleration of forward obstacle [m/ss] + margin_rate_to_change_vel: 0.3 # margin to insert upper velocity [-] + + # pid parameter for ACC + p_coefficient_positive: 0.1 # coefficient P in PID control (used when target dist -current_dist >=0) [-] + p_coefficient_negative: 0.3 # coefficient P in PID control (used when target dist -current_dist <0) [-] + d_coefficient_positive: 0.0 # coefficient D in PID control (used when delta_dist >=0) [-] + d_coefficient_negative: 0.2 # coefficient D in PID control (used when delta_dist <0) [-] + + # parameter for object velocity estimation + object_polygon_length_margin: 2.0 # The distance to extend the polygon length the object in pointcloud-object matching [m] + object_polygon_width_margin: 0.5 # The distance to extend the polygon width the object in pointcloud-object matching [m] + valid_estimated_vel_diff_time: 1.0 # Maximum time difference treated as continuous points in speed estimation using a point cloud [s] + valid_vel_que_time: 0.5 # Time width of information used for speed estimation in speed estimation using a point cloud [s] + valid_estimated_vel_max: 20.0 # Maximum value of valid speed estimation results in speed estimation using a point cloud [m/s] + valid_estimated_vel_min: -20.0 # Minimum value of valid speed estimation results in speed estimation using a point cloud [m/s] + thresh_vel_to_stop: 1.5 # Embed a stop line if the maximum speed calculated by ACC is lower than this speed [m/s] + lowpass_gain_of_upper_velocity: 0.75 # Lowpass-gain of upper velocity + use_rough_velocity_estimation: false # Use rough estimated velocity if the velocity estimation is failed (#### If this parameter is true, the vehicle may collide with the front car. Be careful. ####) + rough_velocity_rate: 0.9 # In the rough velocity estimation, the velocity of front car is estimated as self current velocity * this value diff --git a/planning_launch/config/obstacle_stop_planner.yaml b/planning_launch/config/obstacle_stop_planner.yaml new file mode 100644 index 0000000000..91beb1e1ca --- /dev/null +++ b/planning_launch/config/obstacle_stop_planner.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + stop_planner: + stop_margin: 5.0 # stop margin distance from obstacle on the path [m] + min_behavior_stop_margin: 5.0 # stop margin distance when any other stop point is inserted in stop margin [m] + step_length: 1.0 # step length for pointcloud search range [m] + extend_distance: 0.0 # extend trajectory to consider after goal obstacle in the extend_distance + expand_stop_range: 0.0 # margin of vehicle footprint [m] + + slow_down_planner: + slow_down_margin: 5.0 # margin distance from slow down point [m] + expand_slow_down_range: 1.0 # offset from vehicle side edge for expanding the search area of the surrounding point cloud [m] + max_slow_down_vel: 1.38 # max slow down velocity [m/s] + min_slow_down_vel: 0.28 # min slow down velocity [m/s] + max_deceleration: 2.0 # max slow down deceleration [m/s2] diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml index c94f2dbffe..5acef77dfb 100644 --- a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml +++ b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml @@ -6,7 +6,7 @@ # curve parameters max_lateral_accel: 0.5 # max lateral acceleration limit [m/ss] - min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss] + min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/s] decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit @@ -17,6 +17,10 @@ engage_exit_ratio: 0.5 # exit engage sequence to normal velocity plannning when the velocity exceeds engage_exit_ratio x engage_velocity. stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m] + # stop velocity + stopping_velocity: 2.778 # change target velocity to this value before v=0 point [m/s] + stopping_distance: 0.0 # distance for the stopping_velocity [m]. 0 means the stopping velocity is not applied. + extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m] extract_behind_dist: 5.0 # backward trajectory distance used for planning [m] delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajecotory pose [radian] @@ -31,8 +35,8 @@ # L2: jerk = 100.0, v_weight = 100000.0, a_weight = 1000.0 # Linf: jerk = 200.0, v_weight = 100000.0, a_weight = 5000.0 - pseudo_jerk_weight: 100.0 # weight for "smoothness" cost + pseudo_jerk_weight: 200.0 # weight for "smoothness" cost over_v_weight: 100000.0 # weight for "overspeed limit" cost - over_a_weight: 1000.0 # weight for "overaccel limit" cost + over_a_weight: 5000.0 # weight for "overaccel limit" cost - algorithm_type: "L2" # Option : L2, Linf + algorithm_type: "Linf" # Option : L2, Linf diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml index 7b37f0aedd..111b83ce52 100644 --- a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml @@ -13,7 +13,7 @@ # clearance for unique points clearance_for_straight_line_: 0.05 # minimum optimizing range around straight points - clearance_for_joint_: 3.2 # minimum optimizing range around joint points + clearance_for_joint_: 0.1 # minimum optimizing range around joint points clearance_for_only_smoothing: 0.1 # minimum optimizing range when applygin only smoothing range_for_extend_joint: 0.1 # minimum optimizing range around joint points for extending clearance_from_object_for_straight: 10.0 # minimum clearance from object when judging straight line @@ -59,16 +59,16 @@ # mpt param # vehicle param for mpt - max_steer_deg: 30.0 # max steering angle [deg] + max_steer_deg: 40.0 # max steering angle [deg] steer_tau: 0.1 # steering dynamics time constant (1d approzimation) [s] # trajectory param for mpt num_curvature_sampling_points: 5 # number of sampling points when calculating curvature delta_arc_length_for_mpt_points: 0.5 # delta arc length when generating mpt[m] - num_fix_points_for_mpt: 8 # number of fixing points around ego vehicle + forward_fixing_mpt_distance: 10 # number of fixing points around ego vehicle # optimization param for mpt - is_hard_fixing_terminal_point: true # hard fixing terminal point + is_hard_fixing_terminal_point: false # hard fixing terminal point base_point_weight: 2000.0 # slack weight for lateral error around base_link top_point_weight: 1000.0 # slack weight for lateral error around vehicle-top point mid_point_weight: 1000.0 # slack weight for lateral error around the middle point diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.yaml new file mode 100644 index 0000000000..8354ea60be --- /dev/null +++ b/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + + # obstacle check + use_pointcloud: true # use pointcloud as obstacle check + use_dynamic_object: true # use dynamic object as obstacle check + surround_check_distance: 0.5 # if objects exist in this distance, transit to "exist-surrounding-obstacle" status [m] + surround_check_recover_distance: 0.8 # if no object exists in this distance, transit to "non-surrounding-obstacle" status [m] + state_clear_time: 2.0 + + # ego stop state + stop_state_ego_speed: 0.1 #[m/s] diff --git a/planning_launch/launch/mission_planning/mission_planning.launch.xml b/planning_launch/launch/mission_planning/mission_planning.launch.xml index 9bbc44e98a..712840021b 100644 --- a/planning_launch/launch/mission_planning/mission_planning.launch.xml +++ b/planning_launch/launch/mission_planning/mission_planning.launch.xml @@ -1,16 +1,7 @@ - - - - - - - - - - - - - - + + + + + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 60fa2e2afa..5292611be1 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -23,17 +23,26 @@ + + + - - + + + + + + + - + @@ -41,6 +50,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index da8f228236..88adb9d467 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -1,6 +1,7 @@ + @@ -14,23 +15,34 @@ - + + + + + + + + + + - + + + From 5347ed750b459987bf9a3f385cb0e60f1c8c3e48 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 19 Feb 2021 15:43:46 +0900 Subject: [PATCH 0082/1765] Ros2 v0.8.0 perception launch (#56) * restore file names Signed-off-by: Takamasa Horibe * update camera lidar fusion arch (#122) * Update yolo launch (#155) Signed-off-by: wep21 * Revert "restore file names" This reverts commit 7b50ca1b0067cc29eed73b992dd2bbadc538f4f9. * fix name Signed-off-by: Takamasa Horibe * fix launch arg Signed-off-by: Takamasa Horibe * fix dependency Signed-off-by: Takamasa Horibe * cosmetic change (#138) * cosmetic change * add image topic * fix bug * rename topic names according to ros2 topic name rules Signed-off-by: mitsudome-r * [perception_launch] add object_merger as exec_depend Signed-off-by: mitsudome-r * [perception launch]: Add missing dependecies for traffic light recognition Signed-off-by: wep21 * [perception launch]: Fix attributes in arg tag Signed-off-by: wep21 * [perceptioon_launch] update roi_visualization launch Signed-off-by: wep21 * [perception_launch]: Fix camera topic name Signed-off-by: wep21 * [perception_launch]: Fix camera default topic in fusion launch Signed-off-by: wep21 Co-authored-by: Yukihiro Saito Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: mitsudome-r Co-authored-by: wep21 --- ...ra_lidar_fusion_based_detection.launch.xml | 157 +++++++++++++----- .../detection/detection.launch.xml | 2 +- .../launch/perception.launch.xml | 32 ++-- .../traffic_light_node_container.launch.py | 4 +- perception_launch/package.xml | 11 ++ 5 files changed, 150 insertions(+), 56 deletions(-) diff --git a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index 5f35a20c09..e026e17f62 100644 --- a/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -3,33 +3,25 @@ - - - - - - - - - - - - - - + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + + + diff --git a/perception_launch/launch/object_recognition/detection/detection.launch.xml b/perception_launch/launch/object_recognition/detection/detection.launch.xml index 1f371d7580..ee5eecd05f 100644 --- a/perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -59,6 +59,6 @@ diff --git a/perception_launch/launch/perception.launch.xml b/perception_launch/launch/perception.launch.xml index a692624f30..b259b77f4c 100644 --- a/perception_launch/launch/perception.launch.xml +++ b/perception_launch/launch/perception.launch.xml @@ -4,22 +4,22 @@ - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + diff --git a/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py index 5fcc08e634..03179c7797 100644 --- a/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py +++ b/perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py @@ -96,9 +96,11 @@ def create_parameter_dict(*args): remappings=[('input/image', LaunchConfiguration('input/image')), ('input/rois', 'rois'), ('input/rough/rois', 'rough/rois'), + ('input/traffic_light_states', 'traffic_light_states'), ('output/image', 'debug/rois'), ('output/image/compressed', 'debug/rois/compressed'), - ('output/image/compressedDepth', 'debug/rois/compressedDepth')] + ('output/image/compressedDepth', 'debug/rois/compressedDepth'), + ('output/image/theora', 'debug/rois/theora')] ) ], output='both', diff --git a/perception_launch/package.xml b/perception_launch/package.xml index 9680249fb5..1dd2ab5264 100644 --- a/perception_launch/package.xml +++ b/perception_launch/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto + dynamic_object_visualization euclidean_cluster lidar_apollo_instance_segmentation @@ -18,6 +19,16 @@ naive_path_prediction roi_cluster_fusion shape_estimation + tensorrt_yolo + object_range_splitter + object_merger + + + image_transport + traffic_light_map_based_detector + traffic_light_ssd_fine_detector + traffic_light_classifier + traffic_light_visualization ament_lint_auto ament_lint_common From 596f775c7bb2d9ad0e41c902a195193eeba68f3f Mon Sep 17 00:00:00 2001 From: Kosuke Murakami Date: Wed, 24 Feb 2021 13:54:47 +0900 Subject: [PATCH 0083/1765] V0.8 system launch (#51) * tmp rename launch file Signed-off-by: Kosuke Murakami * Add system_monitor to system.launch (#72) * Add system_monitor to system.launch Signed-off-by: Kenji Miyake * Fix typo Signed-off-by: Kenji Miyake * Add config file of system_monitor (#115) Signed-off-by: Kenji Miyake * Add config of diagnostic_aggregator (#128) Signed-off-by: Kenji Miyake * Add vehicle cmd gate config (#136) * Add config_file of vehicle_cmd_gate Signed-off-by: Kenji Miyake * Add use_emergency_stop Signed-off-by: Kenji Miyake * Rename emergency_stop to external_emergency_stop Signed-off-by: Kenji Miyake * Fix command_gate diag Signed-off-by: Kenji Miyake * Add use_emergency_hold arg (#142) Signed-off-by: Kenji Miyake * Fix system.launch (#161) Signed-off-by: Kenji Miyake * Revert "tmp rename launch file" This reverts commit d1bb989eac90f43bab2af6669b00638fd2147eeb. * fix launch file Signed-off-by: Kosuke Murakami * fix minor bug Signed-off-by: Kosuke Murakami * rename .yaml -> .param.yaml Signed-off-by: Kosuke Murakami * fix invalid way to use eval Signed-off-by: Kosuke Murakami * Add new line in yaml * add num_disks Signed-off-by: Kosuke Murakami * rename .yaml to .param.yaml Signed-off-by: Kosuke Murakami Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> --- system_launch/CMakeLists.txt | 1 + .../config/system_monitor.param.yaml | 45 +++++++++++++++++++ system_launch/launch/system.launch.xml | 39 ++++++++++++---- system_launch/package.xml | 1 + 4 files changed, 78 insertions(+), 8 deletions(-) create mode 100644 system_launch/config/system_monitor.param.yaml diff --git a/system_launch/CMakeLists.txt b/system_launch/CMakeLists.txt index 1d58a61079..656e60c6d0 100644 --- a/system_launch/CMakeLists.txt +++ b/system_launch/CMakeLists.txt @@ -16,4 +16,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/system_launch/config/system_monitor.param.yaml b/system_launch/config/system_monitor.param.yaml new file mode 100644 index 0000000000..1dcc35d73c --- /dev/null +++ b/system_launch/config/system_monitor.param.yaml @@ -0,0 +1,45 @@ +cpu_monitor: + ros__parameters: + temp_warn: 90.0 + temp_error: 95.0 + usage_warn: 0.90 + usage_error: 1.00 + usage_avg: true + load1_warn: 0.90 + load5_warn: 0.80 + msr_reader_port: 7634 +hdd_monitor: + ros__parameters: + hdd_reader_port: 7635 + num_disks: 2 + disks: # Until multi type lists are allowed, name N the disks as disk0...disk{N-1} + disk0: + name: /dev/sda + temp_warn: 55.0 + temp_error: 70.0 + usage_warn: 0.95 + usage_error: 0.99 +mem_monitor: + ros__parameters: + usage_warn: 0.95 + usage_error: 0.99 +net_monitor: + ros__parameters: + devices: ["*"] + usage_warn: 0.95 +ntp_monitor: + ros__parameters: + server: ntp.nict.jp + offset_warn: 0.1 + offset_error: 5.0 +process_monitor: + ros__parameters: + num_of_procs: 5 +gpu_monitor: + ros__parameters: + temp_warn: 90.0 + temp_error: 95.0 + gpu_usage_warn: 0.90 + gpu_usage_error: 1.00 + memory_usage_warn: 0.95 + memory_usage_error: 0.99 diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index d13998a655..cea10f657c 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -3,21 +3,44 @@ - - - - - + + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + + + + diff --git a/system_launch/package.xml b/system_launch/package.xml index cd1a54517d..1946cb6774 100644 --- a/system_launch/package.xml +++ b/system_launch/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto + system_monitor autoware_state_monitor autoware_error_monitor emergency_handler From 5a1557b53d552c7ebff3c5cf8a93d61477ab195c Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 24 Feb 2021 14:04:55 +0900 Subject: [PATCH 0084/1765] Ros2 v0.8.0 sensing launch (#57) * restore file name Signed-off-by: Takamasa Horibe * Update livox_horizon.launch (#89) * fix pass through filter launch (#90) * fix pass through filter launch * change if statement style * update aip_x1 sensing launch (#100) * fix livox launch arg (#108) * add usb_cam depend (#118) * update aip_x1 camera.launch (#119) * update imu.launch (#120) * fix veodyne setting in aip_x1/lidar.launch (#125) * Add velodyne_monitor to velodyne_*.launch (#101) Signed-off-by: Kenji Miyake * Uupdate aip_x1 lidar.launch (#143) * Format gnss.launch (#145) Signed-off-by: Kenji Miyake * Add use_gnss arg to aip_x1 gnss.launch (#146) Signed-off-by: Kenji Miyake * support individual params (#137) * support individual params * remove kvaser_hardware_id.txt * Launch velodyne_monitor only when launch_driver is true (#163) Signed-off-by: Kenji Miyake * [sensing_launch] ros2 porting: use container for livox point preprocessor Signed-off-by: Takamasa Horibe * [sensing_launch] ros2-porting: fix vehicle_info params Signed-off-by: Takamasa Horibe * Revert "restore file name" This reverts commit 37d7ac4f6a2a617b003b4e2a5ac96c48b332ade0. * [sensing_launch] ros2-porting: fix vehicle_info for livox preprocessor launch Signed-off-by: Takamasa Horibe * [sensing_launch] ros2-porting: fix vehicle_info for api_** points_preprocessor.launch.py Signed-off-by: Takamasa Horibe * fix launch Signed-off-by: Takamasa Horibe * fix livox launch Signed-off-by: Takamasa Horibe * added suffix ".xml" to "velodyne_monitor.launch" in the launch files * added use_sim_time with AW_ROS2_USE_SIM_TIME envvar for the parameters in the *.launch.py (#61) * added use_sim_time with AW_ROS2_USE_SIM_TIME envvar for the parameters * changed to use EnvironmentVariable function for use_sim_time parameter * changed indent * removed an empty line Co-authored-by: hosokawa * fixed typo on the arg bd_code_param_path lines (#63) Co-authored-by: hosokawa * [sensing_launch]: Fix indentation in gnss launch Signed-off-by: wep21 * [sensing_launch]: Add missing dependency in package.xml Signed-off-by: wep21 * [sensing_launch]: Fix velodyne launch Signed-off-by: wep21 * [sensing_launch]: Fix livox launch Signed-off-by: wep21 * [sensing_launch]: Add arg for vehicle parameter file in lidar launch Signed-off-by: wep21 * [sensing_launch]: Cleanup Signed-off-by: Autoware * Add new line Signed-off-by: Autoware * [sensing_launch]: Add default config for xx1 Signed-off-by: Autoware * [sensing_launch]: Fix indentation Signed-off-by: Autoware Co-authored-by: Yukihiro Saito Co-authored-by: Taichi Higashide Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: hiroyuki obinata <58019445+obi-t4@users.noreply.github.com> Co-authored-by: hosokawa Co-authored-by: HOSOKAWA Ikuto Co-authored-by: wep21 Co-authored-by: Autoware --- sensing_launch/CMakeLists.txt | 1 + .../default/livox_front_center_bd_code.yaml | 3 + .../default/livox_front_left_bd_code.yaml | 3 + .../default/livox_front_right_bd_code.yaml | 3 + .../default/livox_front_left_bd_code.yaml | 3 + .../default/livox_front_right_bd_code.yaml | 3 + .../launch/aip_customized/camera.launch.xml | 2 +- .../launch/aip_customized/gnss.launch.xml | 38 +- .../launch/aip_customized/lidar.launch.xml | 11 + .../pointcloud_preprocessor.launch.py | 252 +++++++++----- .../launch/aip_s1/camera.launch.xml | 2 +- sensing_launch/launch/aip_s1/gnss.launch.xml | 38 +- sensing_launch/launch/aip_s1/lidar.launch.xml | 11 + .../aip_s1/pointcloud_preprocessor.launch.py | 252 +++++++++----- .../launch/aip_x1/camera.launch.xml | 17 +- sensing_launch/launch/aip_x1/gnss.launch.xml | 39 ++- sensing_launch/launch/aip_x1/imu.launch.xml | 12 +- sensing_launch/launch/aip_x1/lidar.launch.xml | 50 ++- .../aip_x1/pointcloud_preprocessor.launch.py | 327 +++++++++++++----- .../launch/aip_x2/camera.launch.xml | 2 +- sensing_launch/launch/aip_x2/gnss.launch.xml | 38 +- sensing_launch/launch/aip_x2/lidar.launch.xml | 11 + .../aip_x2/pointcloud_preprocessor.launch.py | 240 ++++++++----- .../launch/aip_xx1/camera.launch.xml | 8 +- sensing_launch/launch/aip_xx1/gnss.launch.xml | 38 +- .../launch/aip_xx1/lidar.launch.xml | 46 ++- .../aip_xx1/pointcloud_preprocessor.launch.py | 253 +++++++++----- .../launch/aip_xx2/camera.launch.xml | 2 +- sensing_launch/launch/aip_xx2/gnss.launch.xml | 38 +- .../launch/aip_xx2/lidar.launch.xml | 11 + .../aip_xx2/pointcloud_preprocessor.launch.py | 252 +++++++++----- .../launch/livox_horizon.launch.xml | 25 +- ..._horizon_pointcloud_preprocessor.launch.py | 130 +++++++ sensing_launch/launch/sensing.launch.xml | 4 + .../launch/velodyne_VLP16.launch.xml | 6 +- .../launch/velodyne_VLP32C.launch.xml | 6 +- .../launch/velodyne_VLS128.launch.xml | 6 +- .../launch/velodyne_node_container.launch.py | 189 ++++++---- sensing_launch/package.xml | 2 + 39 files changed, 1561 insertions(+), 813 deletions(-) create mode 100644 sensing_launch/config/aip_x1/default/livox_front_center_bd_code.yaml create mode 100644 sensing_launch/config/aip_x1/default/livox_front_left_bd_code.yaml create mode 100644 sensing_launch/config/aip_x1/default/livox_front_right_bd_code.yaml create mode 100644 sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.yaml create mode 100644 sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.yaml create mode 100644 sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py diff --git a/sensing_launch/CMakeLists.txt b/sensing_launch/CMakeLists.txt index 036e5b89af..afa58d1635 100644 --- a/sensing_launch/CMakeLists.txt +++ b/sensing_launch/CMakeLists.txt @@ -12,4 +12,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch data + config ) diff --git a/sensing_launch/config/aip_x1/default/livox_front_center_bd_code.yaml b/sensing_launch/config/aip_x1/default/livox_front_center_bd_code.yaml new file mode 100644 index 0000000000..083f0cc218 --- /dev/null +++ b/sensing_launch/config/aip_x1/default/livox_front_center_bd_code.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + cmdline_input_bd_code: '100000000000000' diff --git a/sensing_launch/config/aip_x1/default/livox_front_left_bd_code.yaml b/sensing_launch/config/aip_x1/default/livox_front_left_bd_code.yaml new file mode 100644 index 0000000000..083f0cc218 --- /dev/null +++ b/sensing_launch/config/aip_x1/default/livox_front_left_bd_code.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + cmdline_input_bd_code: '100000000000000' diff --git a/sensing_launch/config/aip_x1/default/livox_front_right_bd_code.yaml b/sensing_launch/config/aip_x1/default/livox_front_right_bd_code.yaml new file mode 100644 index 0000000000..083f0cc218 --- /dev/null +++ b/sensing_launch/config/aip_x1/default/livox_front_right_bd_code.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + cmdline_input_bd_code: '100000000000000' diff --git a/sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.yaml b/sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.yaml new file mode 100644 index 0000000000..083f0cc218 --- /dev/null +++ b/sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + cmdline_input_bd_code: '100000000000000' diff --git a/sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.yaml b/sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.yaml new file mode 100644 index 0000000000..083f0cc218 --- /dev/null +++ b/sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + cmdline_input_bd_code: '100000000000000' diff --git a/sensing_launch/launch/aip_customized/camera.launch.xml b/sensing_launch/launch/aip_customized/camera.launch.xml index 16fb4435fe..617d5fbb68 100644 --- a/sensing_launch/launch/aip_customized/camera.launch.xml +++ b/sensing_launch/launch/aip_customized/camera.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/sensing_launch/launch/aip_customized/gnss.launch.xml b/sensing_launch/launch/aip_customized/gnss.launch.xml index 4b29a1a1d2..cbc257bc52 100644 --- a/sensing_launch/launch/aip_customized/gnss.launch.xml +++ b/sensing_launch/launch/aip_customized/gnss.launch.xml @@ -2,29 +2,29 @@ - - + + - - - - - + + + + + - - - - + + + + - - - + + + - - + + - - + + - + diff --git a/sensing_launch/launch/aip_customized/lidar.launch.xml b/sensing_launch/launch/aip_customized/lidar.launch.xml index 732b24f6a3..742df1bd56 100644 --- a/sensing_launch/launch/aip_customized/lidar.launch.xml +++ b/sensing_launch/launch/aip_customized/lidar.launch.xml @@ -1,6 +1,9 @@ + + + @@ -12,6 +15,8 @@ + + @@ -22,6 +27,8 @@ + + @@ -32,11 +39,15 @@ + + + + diff --git a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py index 19a68e1e85..a13afd6504 100644 --- a/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_customized/pointcloud_preprocessor.launch.py @@ -13,103 +13,167 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import yaml + import launch -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f) + return p + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('output', 'concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + passthrough_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PassThroughFilterComponent', + name='passthrough_filter', + remappings=[ + ('input', 'top/outlier_filtered/pointcloud'), + ('output', 'concatenated/pointcloud'), + ], + parameters=[{ + 'output_frame': 'base_link', + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('input', 'concatenated/pointcloud'), + ('output', 'measurement_range_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('input', 'measurement_range_cropped/pointcloud'), + ('output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + ) + + passthrough_loader = LoadComposableNodes( + composable_node_descriptions=[passthrough_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + ) + + return [container, concat_loader, passthrough_loader] def generate_launch_description(): - pkg = 'pointcloud_preprocessor' - - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg('base_frame', 'base_link') - - # set concat filter as a component - concat_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], - parameters=[ - { - 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', - '/sensing/lidar/left/outlier_filtered/pointcloud', - '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', - } - ] - ) - - # set crop box filter as a component - cropbox_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter', - remappings=[ - ('/input', 'concatenated/pointcloud'), - ('/output', 'mesurement_range_cropped/pointcloud'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ], - parameters=[ - { - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': -50.0, - 'max_x': 100.0, - 'min_y': -50.0, - 'max_y': 50.0, - 'negative': False, - } - ] - ) - - ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('/input', 'mesurement_range_cropped/pointcloud'), - ('/output', 'no_ground/pointcloud') - ], - parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, - }] - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - relay_component, - ], - output='screen', - ) - - return launch.LaunchDescription(launch_arguments + [container]) + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('use_concat_filter', 'use_concat_filter') + add_launch_arg('vehicle_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_s1/camera.launch.xml b/sensing_launch/launch/aip_s1/camera.launch.xml index 16fb4435fe..617d5fbb68 100644 --- a/sensing_launch/launch/aip_s1/camera.launch.xml +++ b/sensing_launch/launch/aip_s1/camera.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/sensing_launch/launch/aip_s1/gnss.launch.xml b/sensing_launch/launch/aip_s1/gnss.launch.xml index 4b29a1a1d2..cbc257bc52 100644 --- a/sensing_launch/launch/aip_s1/gnss.launch.xml +++ b/sensing_launch/launch/aip_s1/gnss.launch.xml @@ -2,29 +2,29 @@ - - + + - - - - - + + + + + - - - - + + + + - - - + + + - - + + - - + + - + diff --git a/sensing_launch/launch/aip_s1/lidar.launch.xml b/sensing_launch/launch/aip_s1/lidar.launch.xml index a3cb7d6fca..1c1e82b419 100644 --- a/sensing_launch/launch/aip_s1/lidar.launch.xml +++ b/sensing_launch/launch/aip_s1/lidar.launch.xml @@ -1,6 +1,9 @@ + + + @@ -12,6 +15,8 @@ + + @@ -22,6 +27,8 @@ + + @@ -32,11 +39,15 @@ + + + + diff --git a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py index 19a68e1e85..a13afd6504 100644 --- a/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py @@ -13,103 +13,167 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import yaml + import launch -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f) + return p + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('output', 'concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + passthrough_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PassThroughFilterComponent', + name='passthrough_filter', + remappings=[ + ('input', 'top/outlier_filtered/pointcloud'), + ('output', 'concatenated/pointcloud'), + ], + parameters=[{ + 'output_frame': 'base_link', + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('input', 'concatenated/pointcloud'), + ('output', 'measurement_range_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('input', 'measurement_range_cropped/pointcloud'), + ('output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + ) + + passthrough_loader = LoadComposableNodes( + composable_node_descriptions=[passthrough_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + ) + + return [container, concat_loader, passthrough_loader] def generate_launch_description(): - pkg = 'pointcloud_preprocessor' - - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg('base_frame', 'base_link') - - # set concat filter as a component - concat_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], - parameters=[ - { - 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', - '/sensing/lidar/left/outlier_filtered/pointcloud', - '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', - } - ] - ) - - # set crop box filter as a component - cropbox_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter', - remappings=[ - ('/input', 'concatenated/pointcloud'), - ('/output', 'mesurement_range_cropped/pointcloud'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ], - parameters=[ - { - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': -50.0, - 'max_x': 100.0, - 'min_y': -50.0, - 'max_y': 50.0, - 'negative': False, - } - ] - ) - - ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('/input', 'mesurement_range_cropped/pointcloud'), - ('/output', 'no_ground/pointcloud') - ], - parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, - }] - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - relay_component, - ], - output='screen', - ) - - return launch.LaunchDescription(launch_arguments + [container]) + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('use_concat_filter', 'use_concat_filter') + add_launch_arg('vehicle_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_x1/camera.launch.xml b/sensing_launch/launch/aip_x1/camera.launch.xml index 16fb4435fe..fde088ea77 100644 --- a/sensing_launch/launch/aip_x1/camera.launch.xml +++ b/sensing_launch/launch/aip_x1/camera.launch.xml @@ -5,18 +5,17 @@ - - + + - - - - - - + + + + + - + diff --git a/sensing_launch/launch/aip_x1/gnss.launch.xml b/sensing_launch/launch/aip_x1/gnss.launch.xml index 4b29a1a1d2..13a62f6260 100644 --- a/sensing_launch/launch/aip_x1/gnss.launch.xml +++ b/sensing_launch/launch/aip_x1/gnss.launch.xml @@ -1,30 +1,31 @@ + - - + + - - - - - + + + + + - - - - + + + + - - - + + + - - + + - - + + - + diff --git a/sensing_launch/launch/aip_x1/imu.launch.xml b/sensing_launch/launch/aip_x1/imu.launch.xml index 52355261b1..9de6243b40 100644 --- a/sensing_launch/launch/aip_x1/imu.launch.xml +++ b/sensing_launch/launch/aip_x1/imu.launch.xml @@ -5,19 +5,9 @@ - - - - - - - - - - - + diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml index 56a20e0f96..392f13e3f1 100644 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ b/sensing_launch/launch/aip_x1/lidar.launch.xml @@ -1,42 +1,68 @@ + + + + - + - + + + - - - - - + + + + + + + - - - - - + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py index 19a68e1e85..19505e1d88 100644 --- a/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py @@ -13,103 +13,242 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import yaml + import launch -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + return p + + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/front_left/mirror_cropped/pointcloud', + '/sensing/lidar/front_right/mirror_cropped/pointcloud', + '/sensing/lidar/front_center/mirror_cropped/pointcloud'], + 'output_frame': 'base_link', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set PointCloud PassThrough Filter as a component + passthrough_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PassThroughFilterComponent', + name='passthrough_filter', + remappings=[ + ('input', 'top/outlier_filtered/pointcloud'), + ('output', 'concatenated/pointcloud'), + ], + parameters=[{ + 'output_frame': 'base_link', + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('input', 'concatenated/pointcloud'), + ('output', 'measurement_range_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('input', 'measurement_range_cropped/pointcloud'), + ('output', 'no_ground/pointcloud_with_outlier'), + ], + parameters=[{ + "initial_max_slope": 1.0, + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.1, + "use_vehicle_footprint": True, + "min_x": vehicle_info['min_longitudinal_offset'], + "max_x": vehicle_info['max_longitudinal_offset'], + "min_y": vehicle_info['min_lateral_offset'], + "max_y": vehicle_info['max_lateral_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + voxel_grid_filter_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::VoxelGridDownsampleFilterComponent', + name='voxel_grid_filter', + remappings=[ + ('/input', 'no_ground/pointcloud_with_outlier'), + ('/output', 'voxel_grid_filtered/pointcloud'), + ], + parameters=[{ + "input_frame": LaunchConfiguration('base_frame'), + "output_frame": LaunchConfiguration('base_frame'), + "voxel_size_x": 0.04, + "voxel_size_y": 0.04, + "voxel_size_z": 0.08, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + radius_search_2d_outlier_filter_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RadiusSearch2dOutlierFilterComponent', + name='radius_search_2d_outlier_filter', + remappings=[ + ('input', 'voxel_grid_filtered/pointcloud'), + ('output', 'no_ground/pointcloud'), + ], + parameters=[{ + "search_radius": 0.2, + "min_neighbors": 5, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + voxel_grid_outlier_filter_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::VoxelGridOutlierFilterComponent', + name='voxel_grid_filter', + remappings=[ + ('input', 'voxel_grid_filtered/pointcloud'), + ('output', 'no_ground/pointcloud'), + ], + parameters=[{ + "voxel_size_x": 0.4, + "voxel_size_y": 0.4, + "voxel_size_z": 100.0, + "voxel_points_threshold": 5, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + ) + + passthrough_loader = LoadComposableNodes( + composable_node_descriptions=[passthrough_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + ) + + # load concat or passthrough filter + radius_search_2d_outlier_filter_loader = LoadComposableNodes( + composable_node_descriptions=[radius_search_2d_outlier_filter_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('use_radius_search')), + ) + + voxel_grid_outlier_filter_loader = LoadComposableNodes( + composable_node_descriptions=[voxel_grid_outlier_filter_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_radius_search')), + ) + return [container, concat_loader, passthrough_loader, + radius_search_2d_outlier_filter_loader, + voxel_grid_outlier_filter_loader] + def generate_launch_description(): - pkg = 'pointcloud_preprocessor' - - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg('base_frame', 'base_link') - - # set concat filter as a component - concat_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], - parameters=[ - { - 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', - '/sensing/lidar/left/outlier_filtered/pointcloud', - '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', - } - ] - ) - - # set crop box filter as a component - cropbox_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter', - remappings=[ - ('/input', 'concatenated/pointcloud'), - ('/output', 'mesurement_range_cropped/pointcloud'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ], - parameters=[ - { - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': -50.0, - 'max_x': 100.0, - 'min_y': -50.0, - 'max_y': 50.0, - 'negative': False, - } - ] - ) - - ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('/input', 'mesurement_range_cropped/pointcloud'), - ('/output', 'no_ground/pointcloud') - ], - parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, - }] - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - relay_component, - ], - output='screen', - ) - - return launch.LaunchDescription(launch_arguments + [container]) + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('use_concat_filter', 'use_concat_filter') + add_launch_arg('use_radius_search', 'use_radius_search') + add_launch_arg('vehicle_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_x2/camera.launch.xml b/sensing_launch/launch/aip_x2/camera.launch.xml index 16fb4435fe..617d5fbb68 100644 --- a/sensing_launch/launch/aip_x2/camera.launch.xml +++ b/sensing_launch/launch/aip_x2/camera.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/sensing_launch/launch/aip_x2/gnss.launch.xml b/sensing_launch/launch/aip_x2/gnss.launch.xml index 4b29a1a1d2..cbc257bc52 100644 --- a/sensing_launch/launch/aip_x2/gnss.launch.xml +++ b/sensing_launch/launch/aip_x2/gnss.launch.xml @@ -2,29 +2,29 @@ - - + + - - - - - + + + + + - - - - + + + + - - - + + + - - + + - - + + - + diff --git a/sensing_launch/launch/aip_x2/lidar.launch.xml b/sensing_launch/launch/aip_x2/lidar.launch.xml index f5efc314a8..e21dd0d479 100644 --- a/sensing_launch/launch/aip_x2/lidar.launch.xml +++ b/sensing_launch/launch/aip_x2/lidar.launch.xml @@ -1,6 +1,9 @@ + + + @@ -12,6 +15,8 @@ + + @@ -22,6 +27,8 @@ + + @@ -32,11 +39,15 @@ + + + + diff --git a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py index 19a68e1e85..e68a57ecb2 100644 --- a/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py @@ -13,103 +13,157 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import yaml + import launch -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['rear_overhang'] + return p + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f) + return p + + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + + # set concat filter as a component + if (LaunchConfiguration('use_concat_filter')): + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('/output', 'concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + else: + # set PointCloud PassThrough Filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PassThroughFilterComponent', + name='passthrough_filter', + remappings=[ + ('/input', 'top/outlier_filtered/pointcloud'), + ('/output', 'concatenated/pointcloud'), + ], + parameters=[{ + 'output_frame': 'base_link', + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('/input', 'concatenated/pointcloud'), + ('/output', 'measurement_range_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('/input', 'measurement_range_cropped/pointcloud'), + ('/output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + concat_component, + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + return [container] def generate_launch_description(): - pkg = 'pointcloud_preprocessor' - - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg('base_frame', 'base_link') - - # set concat filter as a component - concat_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], - parameters=[ - { - 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', - '/sensing/lidar/left/outlier_filtered/pointcloud', - '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', - } - ] - ) - - # set crop box filter as a component - cropbox_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter', - remappings=[ - ('/input', 'concatenated/pointcloud'), - ('/output', 'mesurement_range_cropped/pointcloud'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ], - parameters=[ - { - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': -50.0, - 'max_x': 100.0, - 'min_y': -50.0, - 'max_y': 50.0, - 'negative': False, - } - ] - ) - - ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('/input', 'mesurement_range_cropped/pointcloud'), - ('/output', 'no_ground/pointcloud') - ], - parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, - }] - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - relay_component, - ], - output='screen', - ) - - return launch.LaunchDescription(launch_arguments + [container]) + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('use_concat_filter', 'use_concat_filter') + add_launch_arg('vehicle_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_xx1/camera.launch.xml b/sensing_launch/launch/aip_xx1/camera.launch.xml index bec110eb90..440ae57768 100644 --- a/sensing_launch/launch/aip_xx1/camera.launch.xml +++ b/sensing_launch/launch/aip_xx1/camera.launch.xml @@ -9,9 +9,11 @@ - - - + + + + + diff --git a/sensing_launch/launch/aip_xx1/gnss.launch.xml b/sensing_launch/launch/aip_xx1/gnss.launch.xml index 4b29a1a1d2..cbc257bc52 100644 --- a/sensing_launch/launch/aip_xx1/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx1/gnss.launch.xml @@ -2,29 +2,29 @@ - - + + - - - - - + + + + + - - - - + + + + - - - + + + - - + + - - + + - + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index 909712cb72..c904392b73 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -1,6 +1,10 @@ + + + + @@ -11,10 +15,12 @@ - - + + + + @@ -24,10 +30,12 @@ - - + + + + @@ -37,10 +45,12 @@ - - + + + + @@ -50,35 +60,43 @@ - - + + + + - + - - + + + + - + - - + + + + + + diff --git a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index a1a91360a2..a13afd6504 100644 --- a/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -13,104 +13,167 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import yaml + import launch -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f) + return p + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('output', 'concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + passthrough_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PassThroughFilterComponent', + name='passthrough_filter', + remappings=[ + ('input', 'top/outlier_filtered/pointcloud'), + ('output', 'concatenated/pointcloud'), + ], + parameters=[{ + 'output_frame': 'base_link', + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('input', 'concatenated/pointcloud'), + ('output', 'measurement_range_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('input', 'measurement_range_cropped/pointcloud'), + ('output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + ) + + passthrough_loader = LoadComposableNodes( + composable_node_descriptions=[passthrough_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + ) + + return [container, concat_loader, passthrough_loader] def generate_launch_description(): - pkg = 'pointcloud_preprocessor' - - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg('base_frame', 'base_link') - - # set concat filter as a component - concat_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], - parameters=[ - { - 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', - '/sensing/lidar/left/outlier_filtered/pointcloud', - '/sensing/lidar/right/outlier_filtered/pointcloud', - '/sensing/lidar/rear/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', - } - ] - ) - - # set crop box filter as a component - cropbox_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter', - remappings=[ - ('/input', 'concatenated/pointcloud'), - ('/output', 'mesurement_range_cropped/pointcloud'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ], - parameters=[ - { - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': -50.0, - 'max_x': 100.0, - 'min_y': -50.0, - 'max_y': 50.0, - 'negative': False, - } - ] - ) - - ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('/input', 'mesurement_range_cropped/pointcloud'), - ('/output', 'no_ground/pointcloud') - ], - parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, - }] - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - relay_component, - ], - output='screen', - ) - - return launch.LaunchDescription(launch_arguments + [container]) + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('use_concat_filter', 'use_concat_filter') + add_launch_arg('vehicle_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/aip_xx2/camera.launch.xml b/sensing_launch/launch/aip_xx2/camera.launch.xml index 16fb4435fe..617d5fbb68 100644 --- a/sensing_launch/launch/aip_xx2/camera.launch.xml +++ b/sensing_launch/launch/aip_xx2/camera.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/sensing_launch/launch/aip_xx2/gnss.launch.xml b/sensing_launch/launch/aip_xx2/gnss.launch.xml index 4b29a1a1d2..cbc257bc52 100644 --- a/sensing_launch/launch/aip_xx2/gnss.launch.xml +++ b/sensing_launch/launch/aip_xx2/gnss.launch.xml @@ -2,29 +2,29 @@ - - + + - - - - - + + + + + - - - - + + + + - - - + + + - - + + - - + + - + diff --git a/sensing_launch/launch/aip_xx2/lidar.launch.xml b/sensing_launch/launch/aip_xx2/lidar.launch.xml index 8f8ca8299f..549f085912 100644 --- a/sensing_launch/launch/aip_xx2/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx2/lidar.launch.xml @@ -1,6 +1,9 @@ + + + @@ -12,6 +15,8 @@ + + @@ -22,6 +27,8 @@ + + @@ -32,11 +39,15 @@ + + + + diff --git a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py index 19a68e1e85..a13afd6504 100644 --- a/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py +++ b/sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py @@ -13,103 +13,167 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +import yaml + import launch -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer +from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f) + return p + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + + # set concat filter as a component + concat_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', + name='concatenate_data', + remappings=[('output', 'concatenated/pointcloud')], + parameters=[{ + 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', + '/sensing/lidar/left/outlier_filtered/pointcloud', + '/sensing/lidar/right/outlier_filtered/pointcloud'], + 'output_frame': 'base_link', + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + passthrough_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::PassThroughFilterComponent', + name='passthrough_filter', + remappings=[ + ('input', 'top/outlier_filtered/pointcloud'), + ('output', 'concatenated/pointcloud'), + ], + parameters=[{ + 'output_frame': 'base_link', + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set crop box filter as a component + cropbox_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='crop_box_filter', + remappings=[ + ('input', 'concatenated/pointcloud'), + ('output', 'measurement_range_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': -50.0, + 'max_x': 100.0, + 'min_y': -50.0, + 'max_y': 50.0, + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': False, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + ground_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::RayGroundFilterComponent', + name='ray_ground_filter', + remappings=[ + ('input', 'measurement_range_cropped/pointcloud'), + ('output', 'no_ground/pointcloud') + ], + parameters=[{ + "general_max_slope": 10.0, + "local_max_slope": 10.0, + "min_height_threshold": 0.2, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + relay_component = ComposableNode( + package='topic_tools', + plugin='topic_tools::RelayNode', + name='relay', + parameters=[{ + "input_topic": "/sensing/lidar/top/rectified/pointcloud", + "output_topic": "/sensing/lidar/pointcloud", + "type": "sensor_msgs/msg/PointCloud2", + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + cropbox_component, + ground_component, + relay_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + # load concat or passthrough filter + concat_loader = LoadComposableNodes( + composable_node_descriptions=[concat_component], + target_container=container, + condition=launch.conditions.IfCondition(LaunchConfiguration('use_concat_filter')), + ) + + passthrough_loader = LoadComposableNodes( + composable_node_descriptions=[passthrough_component], + target_container=container, + condition=launch.conditions.UnlessCondition(LaunchConfiguration('use_concat_filter')), + ) + + return [container, concat_loader, passthrough_loader] def generate_launch_description(): - pkg = 'pointcloud_preprocessor' - - launch_arguments = [] - - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) - - add_launch_arg('base_frame', 'base_link') - - # set concat filter as a component - concat_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent', - name='concatenate_data', - remappings=[('/output', 'concatenated/pointcloud')], - parameters=[ - { - 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', - '/sensing/lidar/left/outlier_filtered/pointcloud', - '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', - } - ] - ) - - # set crop box filter as a component - cropbox_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::CropBoxFilterComponent', - name='crop_box_filter', - remappings=[ - ('/input', 'concatenated/pointcloud'), - ('/output', 'mesurement_range_cropped/pointcloud'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ], - parameters=[ - { - 'input_frame': LaunchConfiguration('base_frame'), - 'output_frame': LaunchConfiguration('base_frame'), - 'min_x': -50.0, - 'max_x': 100.0, - 'min_y': -50.0, - 'max_y': 50.0, - 'negative': False, - } - ] - ) - - ground_component = ComposableNode( - package=pkg, - plugin='pointcloud_preprocessor::RayGroundFilterComponent', - name='ray_ground_filter', - remappings=[ - ('/input', 'mesurement_range_cropped/pointcloud'), - ('/output', 'no_ground/pointcloud') - ], - parameters=[{ - "general_max_slope": 10.0, - "local_max_slope": 10.0, - "min_height_threshold": 0.2, - }] - ) - - relay_component = ComposableNode( - package='topic_tools', - plugin='topic_tools::RelayNode', - name='relay', - parameters=[{ - "input_topic": "/sensing/lidar/top/rectified/pointcloud", - "output_topic": "/sensing/lidar/pointcloud", - "type": "sensor_msgs/msg/PointCloud2", - }], - ) - - # set container to run all required components in the same process - container = ComposableNodeContainer( - name='pointcloud_preprocessor_container', - namespace='pointcloud_preprocessor', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - concat_component, - cropbox_component, - ground_component, - relay_component, - ], - output='screen', - ) - - return launch.LaunchDescription(launch_arguments + [container]) + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('use_concat_filter', 'use_concat_filter') + add_launch_arg('vehicle_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/livox_horizon.launch.xml b/sensing_launch/launch/livox_horizon.launch.xml index 8fc76a9d5e..9fa0f5d9ea 100644 --- a/sensing_launch/launch/livox_horizon.launch.xml +++ b/sensing_launch/launch/livox_horizon.launch.xml @@ -2,26 +2,37 @@ - + - - - + + + + + + + + - - - + + + + + + + + + diff --git a/sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py b/sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py new file mode 100644 index 0000000000..57490645ab --- /dev/null +++ b/sensing_launch/launch/livox_horizon_pointcloud_preprocessor.launch.py @@ -0,0 +1,130 @@ + +# Copyright 2020 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. + +import launch +import yaml +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +from launch.substitutions import EnvironmentVariable + + +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p + + +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + return p + + +def launch_setup(context, *args, **kwargs): + + pkg = 'pointcloud_preprocessor' + + vehicle_info = get_vehicle_info(context) + vehicle_mirror_info = get_vehicle_mirror_info(context) + + # set self crop box filter as a component + cropbox_self_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='self_crop_box_filter', + remappings=[ + ('input', 'livox/lidar'), + ('output', 'self_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': vehicle_info['min_longitudinal_offset'], + 'max_x': vehicle_info['max_longitudinal_offset'], + 'min_y': vehicle_info['min_lateral_offset'], + 'max_y': vehicle_info['max_lateral_offset'], + 'min_z': vehicle_info['min_height_offset'], + 'max_z': vehicle_info['max_height_offset'], + 'negative': True, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set mirror crop box filter as a component + cropbox_mirror_component = ComposableNode( + package=pkg, + plugin='pointcloud_preprocessor::CropBoxFilterComponent', + name='mirror_crop_box_filter', + remappings=[ + ('input', 'self_cropped/pointcloud'), + ('output', 'mirror_cropped/pointcloud'), + ], + parameters=[{ + 'input_frame': LaunchConfiguration('base_frame'), + 'output_frame': LaunchConfiguration('base_frame'), + 'min_x': vehicle_mirror_info['min_longitudinal_offset'], + 'max_x': vehicle_mirror_info['max_longitudinal_offset'], + 'min_y': vehicle_mirror_info['min_lateral_offset'], + 'max_y': vehicle_mirror_info['max_lateral_offset'], + 'min_z': vehicle_mirror_info['min_height_offset'], + 'max_z': vehicle_mirror_info['max_height_offset'], + 'negative': True, + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }] + ) + + # set container to run all required components in the same process + container = ComposableNodeContainer( + name='pointcloud_preprocessor_container', + namespace='pointcloud_preprocessor', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + cropbox_self_component, + cropbox_mirror_component, + ], + output='screen', + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + + return [container] + + +def generate_launch_description(): + + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('base_frame', 'base_link') + add_launch_arg('vehicle_param_file') + add_launch_arg('vehicle_mirror_param_file') + + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/launch/sensing.launch.xml b/sensing_launch/launch/sensing.launch.xml index f432a05cbb..946d83ed26 100644 --- a/sensing_launch/launch/sensing.launch.xml +++ b/sensing_launch/launch/sensing.launch.xml @@ -2,6 +2,8 @@ + + @@ -9,6 +11,8 @@ + + diff --git a/sensing_launch/launch/velodyne_VLP16.launch.xml b/sensing_launch/launch/velodyne_VLP16.launch.xml index be08fe7646..c2c058c1d3 100644 --- a/sensing_launch/launch/velodyne_VLP16.launch.xml +++ b/sensing_launch/launch/velodyne_VLP16.launch.xml @@ -19,9 +19,13 @@ - + + + + + diff --git a/sensing_launch/launch/velodyne_VLP32C.launch.xml b/sensing_launch/launch/velodyne_VLP32C.launch.xml index b131bf3176..e169b945b4 100644 --- a/sensing_launch/launch/velodyne_VLP32C.launch.xml +++ b/sensing_launch/launch/velodyne_VLP32C.launch.xml @@ -19,9 +19,13 @@ - + + + + + diff --git a/sensing_launch/launch/velodyne_VLS128.launch.xml b/sensing_launch/launch/velodyne_VLS128.launch.xml index 2269f87eef..4893e51b7b 100644 --- a/sensing_launch/launch/velodyne_VLS128.launch.xml +++ b/sensing_launch/launch/velodyne_VLS128.launch.xml @@ -19,9 +19,13 @@ - + + + + + diff --git a/sensing_launch/launch/velodyne_node_container.launch.py b/sensing_launch/launch/velodyne_node_container.launch.py index 189ae333d6..c9590a9785 100644 --- a/sensing_launch/launch/velodyne_node_container.launch.py +++ b/sensing_launch/launch/velodyne_node_container.launch.py @@ -13,50 +13,37 @@ # limitations under the License. import launch -from launch import LaunchContext -from launch.actions import DeclareLaunchArgument -from launch.substitutions import LaunchConfiguration, PythonExpression +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.substitutions import EnvironmentVariable, LaunchConfiguration from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes from launch_ros.descriptions import ComposableNode -import uuid +import yaml -def acceptable_unique_name(prefix): - id = str(uuid.uuid4()) - # ros2 apparently doesn't accept the UUID with hyphens in node names - return prefix + id.replace('-', '_') +def get_vehicle_info(context): + path = LaunchConfiguration('vehicle_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + p['vehicle_length'] = p['front_overhang'] + p['wheel_base'] + p['rear_overhang'] + p['vehicle_width'] = p['wheel_tread'] + p['left_overhang'] + p['right_overhang'] + p['min_longitudinal_offset'] = -p['rear_overhang'] + p['max_longitudinal_offset'] = p['front_overhang'] + p['wheel_base'] + p['min_lateral_offset'] = -(p['wheel_tread'] / 2.0 + p['right_overhang']) + p['max_lateral_offset'] = p['wheel_tread'] / 2.0 + p['left_overhang'] + p['min_height_offset'] = 0.0 + p['max_height_offset'] = p['vehicle_height'] + return p -def generate_launch_description(): - launch_arguments = [] - def add_launch_arg(name: str, default_value=None): - # a default_value of None is equivalent to not passing that kwarg at all - launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) +def get_vehicle_mirror_info(context): + path = LaunchConfiguration('vehicle_mirror_param_file').perform(context) + with open(path, 'r') as f: + p = yaml.safe_load(f)['/**']['ros__parameters'] + return p - add_launch_arg('model') - add_launch_arg('launch_driver', 'True') - add_launch_arg('calibration') - add_launch_arg('device_ip', '192.168.1.201') - add_launch_arg('sensor_frame', 'velodyne') - add_launch_arg('base_frame', 'base_link') - add_launch_arg('container_name', 'velodyne_composable_node_container') - add_launch_arg('min_range') - add_launch_arg('max_range') - add_launch_arg('pcap', '') - add_launch_arg('port', '2368') - add_launch_arg('read_fast', 'False') - add_launch_arg('read_once', 'False') - add_launch_arg('repeat_delay', '0.0') - add_launch_arg('rpm', '600.0') - add_launch_arg('laserscan_ring', '-1') - add_launch_arg('laserscan_resolution', '0.007') - add_launch_arg('num_points_thresholds', '300') - add_launch_arg('invalid_intensity') - add_launch_arg('frame_id', 'velodyne') - add_launch_arg('gps_time', 'False') - add_launch_arg('input_frame', LaunchConfiguration('base_frame')) - add_launch_arg('output_frame', LaunchConfiguration('base_frame')) + +def launch_setup(context, *args, **kwargs): def create_parameter_dict(*args): result = {} @@ -72,8 +59,12 @@ def create_parameter_dict(*args): package='velodyne_pointcloud', plugin='velodyne_pointcloud::Convert', name='velodyne_convert_node', - parameters=[create_parameter_dict('calibration', 'min_range', 'max_range', - 'num_points_thresholds', 'invalid_intensity', 'sensor_frame')], + parameters=[{**create_parameter_dict('calibration', 'min_range', 'max_range', + 'num_points_thresholds', 'invalid_intensity', + 'frame_id', 'scan_phase'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', + default_value='False'), + }], remappings=[('velodyne_points', 'pointcloud_raw'), ('velodyne_points_ex', 'pointcloud_raw_ex')], ) @@ -81,71 +72,89 @@ def create_parameter_dict(*args): cropbox_parameters = create_parameter_dict('input_frame', 'output_frame') cropbox_parameters['negative'] = True + cropbox_parameters['use_sim_time'] = EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', + default_value='False') - cropbox_remappings = [ - ('/min_x', '/vehicle_info/min_longitudinal_offset'), - ('/max_x', '/vehicle_info/max_longitudinal_offset'), - ('/min_z', '/vehicle_info/min_lateral_offset'), - ('/max_z', '/vehicle_info/max_lateral_offset'), - ('/min_z', '/vehicle_info/min_height_offset'), - ('/max_z', '/vehicle_info/max_height_offset'), - ] + vehicle_info = get_vehicle_info(context) + cropbox_parameters['min_x'] = vehicle_info['min_longitudinal_offset'] + cropbox_parameters['max_x'] = vehicle_info['max_longitudinal_offset'] + cropbox_parameters['min_y'] = vehicle_info['min_lateral_offset'] + cropbox_parameters['max_y'] = vehicle_info['max_lateral_offset'] + cropbox_parameters['min_z'] = vehicle_info['min_height_offset'] + cropbox_parameters['max_z'] = vehicle_info['max_height_offset'] nodes.append(ComposableNode( package='pointcloud_preprocessor', plugin='pointcloud_preprocessor::CropBoxFilterComponent', name='crop_box_filter_self', - remappings=[('/input', 'pointcloud_raw_ex'), - ('/output', 'self_cropped/pointcloud_ex') - ] + cropbox_remappings, + remappings=[('input', 'pointcloud_raw_ex'), + ('output', 'self_cropped/pointcloud_ex'), + ('crop_box_polygon', 'self_cropped/crop_box_polygon'), + ], parameters=[cropbox_parameters], ) ) + mirror_info = get_vehicle_mirror_info(context) + cropbox_parameters['min_x'] = mirror_info['min_longitudinal_offset'] + cropbox_parameters['max_x'] = mirror_info['max_longitudinal_offset'] + cropbox_parameters['min_y'] = mirror_info['min_lateral_offset'] + cropbox_parameters['max_y'] = mirror_info['max_lateral_offset'] + cropbox_parameters['min_z'] = mirror_info['min_height_offset'] + cropbox_parameters['max_z'] = mirror_info['max_height_offset'] + nodes.append(ComposableNode( package='pointcloud_preprocessor', plugin='pointcloud_preprocessor::CropBoxFilterComponent', name='crop_box_filter_mirror', - remappings=[('/input', 'self_cropped/pointcloud_ex'), - ('/output', 'mirror_cropped/pointcloud_ex'), - ] + cropbox_remappings, + remappings=[('input', 'self_cropped/pointcloud_ex'), + ('output', 'mirror_cropped/pointcloud_ex'), + ('crop_box_polygon', 'mirror_cropped/crop_box_polygon'), + ], parameters=[cropbox_parameters], ) ) - # TODO(fred-apex-ai) Still need the distortion component - if False: - nodes.append(ComposableNode( - package='TODO', - plugin='TODO', - name='fix_distortion', - remappings=[ - ('velodyne_points_ex', 'mirror_cropped/pointcloud_ex'), - ('velodyne_points_interpolate', 'rectified/pointcloud'), - ('velodyne_points_interpolate_ex', 'rectified/pointcloud_ex'), - ], - ) - ) + nodes.append(ComposableNode( + package='velodyne_pointcloud', + plugin='velodyne_pointcloud::Interpolate', + name='velodyne_interpolate_node', + remappings=[ + ('velodyne_points_ex', 'mirror_cropped/pointcloud_ex'), + ('velodyne_points_interpolate', 'rectified/pointcloud'), + ('velodyne_points_interpolate_ex', 'rectified/pointcloud_ex'), + ], + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], + ) + ) nodes.append(ComposableNode( package='pointcloud_preprocessor', plugin='pointcloud_preprocessor::RingOutlierFilterComponent', name='ring_outlier_filter', remappings=[ - ('/input', 'rectified/pointcloud_ex'), - ('/output', 'outlier_filtered/pointcloud') + ('input', 'rectified/pointcloud_ex'), + ('output', 'outlier_filtered/pointcloud') ], + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], ) ) # set container to run all required components in the same process container = ComposableNodeContainer( # need unique name, otherwise all processes in same container and the node names then clash - name=acceptable_unique_name('velodyne_node_container'), + name='velodyne_node_container', namespace='pointcloud_preprocessor', package='rclcpp_components', executable='component_container', composable_node_descriptions=nodes, + parameters=[{ + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), + }], ) driver_component = ComposableNode( @@ -153,9 +162,12 @@ def create_parameter_dict(*args): plugin='velodyne_driver::VelodyneDriver', # node is created in a global context, need to avoid name clash name='velodyne_driver', - parameters=[create_parameter_dict('device_ip', 'gps_time', 'read_once', 'read_fast', - 'repeat_delay', 'frame_id', 'model', 'rpm', 'port', - 'pcap')], + parameters=[{**create_parameter_dict('device_ip', 'gps_time', 'read_once', 'read_fast', + 'repeat_delay', 'frame_id', 'model', 'rpm', 'port', + 'pcap'), + 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', + default_value='False'), + }], ) # one way to add a ComposableNode conditional on a launch argument to a @@ -166,4 +178,37 @@ def create_parameter_dict(*args): condition=launch.conditions.IfCondition(LaunchConfiguration('launch_driver')), ) - return launch.LaunchDescription(launch_arguments + [container, loader]) + return [container, loader] + + +def generate_launch_description(): + launch_arguments = [] + + def add_launch_arg(name: str, default_value=None): + # a default_value of None is equivalent to not passing that kwarg at all + launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) + + add_launch_arg('model') + add_launch_arg('launch_driver', 'True') + add_launch_arg('calibration') + add_launch_arg('device_ip', '192.168.1.201') + add_launch_arg('scan_phase', '0.0') + add_launch_arg('base_frame', 'base_link') + add_launch_arg('container_name', 'velodyne_composable_node_container') + add_launch_arg('min_range') + add_launch_arg('max_range') + add_launch_arg('pcap', '') + add_launch_arg('port', '2368') + add_launch_arg('read_fast', 'False') + add_launch_arg('read_once', 'False') + add_launch_arg('repeat_delay', '0.0') + add_launch_arg('rpm', '600.0') + add_launch_arg('laserscan_ring', '-1') + add_launch_arg('laserscan_resolution', '0.007') + add_launch_arg('num_points_thresholds', '300') + add_launch_arg('invalid_intensity') + add_launch_arg('frame_id', 'velodyne') + add_launch_arg('gps_time', 'False') + add_launch_arg('input_frame', LaunchConfiguration('base_frame')) + add_launch_arg('output_frame', LaunchConfiguration('base_frame')) + return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/sensing_launch/package.xml b/sensing_launch/package.xml index de5d5a3357..bce6c40edd 100644 --- a/sensing_launch/package.xml +++ b/sensing_launch/package.xml @@ -19,7 +19,9 @@ usb_cam velodyne_driver + velodyne_monitor velodyne_pointcloud + usb_cam ament_lint_auto ament_lint_common From f5b85792a7cbf10291fca0d812207a8260757b64 Mon Sep 17 00:00:00 2001 From: tkimura4 Date: Wed, 24 Feb 2021 16:11:12 +0900 Subject: [PATCH 0085/1765] Ros2 v0.8.0 fix packages (#64) * add vehicle_param_file to simple planning simulator * add vehicle_param_file to lane change planner --- autoware_launch/launch/planning_simulator.launch.xml | 1 + .../lane_driving/behavior_planning/behavior_planning.launch.xml | 1 + vehicle_launch/launch/vehicle.launch.xml | 2 ++ vehicle_launch/launch/vehicle_interface.launch.xml | 2 ++ 4 files changed, 6 insertions(+) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 7ba60c1f1c..64273dd3d9 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -18,6 +18,7 @@ + diff --git a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 5292611be1..7998409473 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -39,6 +39,7 @@ + + @@ -21,6 +22,7 @@ + diff --git a/vehicle_launch/launch/vehicle_interface.launch.xml b/vehicle_launch/launch/vehicle_interface.launch.xml index 9867e34f0f..c703dec205 100644 --- a/vehicle_launch/launch/vehicle_interface.launch.xml +++ b/vehicle_launch/launch/vehicle_interface.launch.xml @@ -2,6 +2,7 @@ + @@ -13,6 +14,7 @@ + From d0d15b5837a67e89fcb61bda66089da80ae07206 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Wed, 24 Feb 2021 19:21:08 +0900 Subject: [PATCH 0086/1765] Rename ROS-related .yaml to .param.yaml (#65) * Rename ROS-related .yaml to .param.yaml Signed-off-by: Kenji Miyake * Add missing '--' Signed-off-by: Kenji Miyake * Rename vehicle_info.yaml to vehicle_info.param.yaml Signed-off-by: Kenji Miyake * Fix livox param name Signed-off-by: Kenji Miyake --- autoware_launch/launch/planning_simulator.launch.xml | 6 +++--- .../{mpc_follower_param.yaml => mpc_follower.param.yaml} | 0 .../{pure_pursuit_param.yaml => pure_pursuit.param.yaml} | 2 +- ...{vehicle_cmd_gate.yaml => vehicle_cmd_gate.param.yaml} | 0 ...ntroller_param.yaml => velocity_controller.param.yaml} | 0 control_launch/launch/control.launch.xml | 8 ++++---- ...{ndt_scan_matcher.yaml => ndt_scan_matcher.param.yaml} | 0 .../launch/pose_estimator/pose_estimator.launch.xml | 2 +- ...se_control.yaml => adaptive_cruise_control.param.yaml} | 0 ...stop_planner.yaml => obstacle_stop_planner.param.yaml} | 0 ...ptimizer.yaml => motion_velocity_optimizer.param.yaml} | 0 ...planner.yaml => obstacle_avoidance_planner.param.yaml} | 0 ..._checker.yaml => surround_obstacle_checker.param.yaml} | 0 .../motion_planning/motion_planning.launch.xml | 8 ++++---- .../launch/scenario_planning/scenario_planning.launch.xml | 2 +- ...bd_code.yaml => livox_front_center_bd_code.param.yaml} | 0 ...t_bd_code.yaml => livox_front_left_bd_code.param.yaml} | 0 ..._bd_code.yaml => livox_front_right_bd_code.param.yaml} | 0 ...t_bd_code.yaml => livox_front_left_bd_code.param.yaml} | 0 ..._bd_code.yaml => livox_front_right_bd_code.param.yaml} | 0 sensing_launch/launch/aip_x1/lidar.launch.xml | 6 +++--- sensing_launch/launch/aip_xx1/lidar.launch.xml | 4 ++-- system_launch/launch/system.launch.xml | 4 ++-- 23 files changed, 21 insertions(+), 21 deletions(-) rename control_launch/config/mpc_follower/{mpc_follower_param.yaml => mpc_follower.param.yaml} (100%) rename control_launch/config/pure_pursuit/{pure_pursuit_param.yaml => pure_pursuit.param.yaml} (89%) rename control_launch/config/vehicle_cmd_gate/{vehicle_cmd_gate.yaml => vehicle_cmd_gate.param.yaml} (100%) rename control_launch/config/velocity_controller/{velocity_controller_param.yaml => velocity_controller.param.yaml} (100%) rename localization_launch/config/{ndt_scan_matcher.yaml => ndt_scan_matcher.param.yaml} (100%) rename planning_launch/config/{adaptive_cruise_control.yaml => adaptive_cruise_control.param.yaml} (100%) rename planning_launch/config/{obstacle_stop_planner.yaml => obstacle_stop_planner.param.yaml} (100%) rename planning_launch/config/scenario_planning/common/motion_velocity_optimizer/{motion_velocity_optimizer.yaml => motion_velocity_optimizer.param.yaml} (100%) rename planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/{obstacle_avoidance_planner.yaml => obstacle_avoidance_planner.param.yaml} (100%) rename planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/{surround_obstacle_checker.yaml => surround_obstacle_checker.param.yaml} (100%) rename sensing_launch/config/aip_x1/default/{livox_front_center_bd_code.yaml => livox_front_center_bd_code.param.yaml} (100%) rename sensing_launch/config/aip_x1/default/{livox_front_left_bd_code.yaml => livox_front_left_bd_code.param.yaml} (100%) rename sensing_launch/config/aip_x1/default/{livox_front_right_bd_code.yaml => livox_front_right_bd_code.param.yaml} (100%) rename sensing_launch/config/aip_xx1/default/{livox_front_left_bd_code.yaml => livox_front_left_bd_code.param.yaml} (100%) rename sensing_launch/config/aip_xx1/default/{livox_front_right_bd_code.yaml => livox_front_right_bd_code.param.yaml} (100%) diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 64273dd3d9..54b2064131 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -18,7 +18,7 @@ - + @@ -43,12 +43,12 @@ - + - + diff --git a/control_launch/config/mpc_follower/mpc_follower_param.yaml b/control_launch/config/mpc_follower/mpc_follower.param.yaml similarity index 100% rename from control_launch/config/mpc_follower/mpc_follower_param.yaml rename to control_launch/config/mpc_follower/mpc_follower.param.yaml diff --git a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml b/control_launch/config/pure_pursuit/pure_pursuit.param.yaml similarity index 89% rename from control_launch/config/pure_pursuit/pure_pursuit_param.yaml rename to control_launch/config/pure_pursuit/pure_pursuit.param.yaml index 51cb3acb5d..acbb3a85a3 100644 --- a/control_launch/config/pure_pursuit/pure_pursuit_param.yaml +++ b/control_launch/config/pure_pursuit/pure_pursuit.param.yaml @@ -3,7 +3,7 @@ # -- system -- control_period: 0.033 - # --algorithm + # --algorithm -- lookahead_distance_ratio: 2.2 min_lookahead_distance: 2.5 reverse_min_lookahead_distance: 7.0 diff --git a/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.yaml b/control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml similarity index 100% rename from control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.yaml rename to control_launch/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml diff --git a/control_launch/config/velocity_controller/velocity_controller_param.yaml b/control_launch/config/velocity_controller/velocity_controller.param.yaml similarity index 100% rename from control_launch/config/velocity_controller/velocity_controller_param.yaml rename to control_launch/config/velocity_controller/velocity_controller.param.yaml diff --git a/control_launch/launch/control.launch.xml b/control_launch/launch/control.launch.xml index 886c2cd9c4..f08338284d 100644 --- a/control_launch/launch/control.launch.xml +++ b/control_launch/launch/control.launch.xml @@ -7,10 +7,10 @@ - - - - + + + + diff --git a/localization_launch/config/ndt_scan_matcher.yaml b/localization_launch/config/ndt_scan_matcher.param.yaml similarity index 100% rename from localization_launch/config/ndt_scan_matcher.yaml rename to localization_launch/config/ndt_scan_matcher.param.yaml diff --git a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml index 3b5bd6ab94..ce949fd34b 100644 --- a/localization_launch/launch/pose_estimator/pose_estimator.launch.xml +++ b/localization_launch/launch/pose_estimator/pose_estimator.launch.xml @@ -10,7 +10,7 @@ - + diff --git a/planning_launch/config/adaptive_cruise_control.yaml b/planning_launch/config/adaptive_cruise_control.param.yaml similarity index 100% rename from planning_launch/config/adaptive_cruise_control.yaml rename to planning_launch/config/adaptive_cruise_control.param.yaml diff --git a/planning_launch/config/obstacle_stop_planner.yaml b/planning_launch/config/obstacle_stop_planner.param.yaml similarity index 100% rename from planning_launch/config/obstacle_stop_planner.yaml rename to planning_launch/config/obstacle_stop_planner.param.yaml diff --git a/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml b/planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.yaml rename to planning_launch/config/scenario_planning/common/motion_velocity_optimizer/motion_velocity_optimizer.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.yaml rename to planning_launch/config/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml diff --git a/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.yaml b/planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml similarity index 100% rename from planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.yaml rename to planning_launch/config/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/surround_obstacle_checker.param.yaml diff --git a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 88adb9d467..6a289d9f29 100644 --- a/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -6,7 +6,7 @@ - + @@ -20,7 +20,7 @@ - + @@ -40,8 +40,8 @@ - - + + diff --git a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 20ac205141..94e493d5a0 100644 --- a/planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -18,7 +18,7 @@ - + diff --git a/sensing_launch/config/aip_x1/default/livox_front_center_bd_code.yaml b/sensing_launch/config/aip_x1/default/livox_front_center_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_x1/default/livox_front_center_bd_code.yaml rename to sensing_launch/config/aip_x1/default/livox_front_center_bd_code.param.yaml diff --git a/sensing_launch/config/aip_x1/default/livox_front_left_bd_code.yaml b/sensing_launch/config/aip_x1/default/livox_front_left_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_x1/default/livox_front_left_bd_code.yaml rename to sensing_launch/config/aip_x1/default/livox_front_left_bd_code.param.yaml diff --git a/sensing_launch/config/aip_x1/default/livox_front_right_bd_code.yaml b/sensing_launch/config/aip_x1/default/livox_front_right_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_x1/default/livox_front_right_bd_code.yaml rename to sensing_launch/config/aip_x1/default/livox_front_right_bd_code.param.yaml diff --git a/sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.yaml b/sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.yaml rename to sensing_launch/config/aip_xx1/default/livox_front_left_bd_code.param.yaml diff --git a/sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.yaml b/sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.param.yaml similarity index 100% rename from sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.yaml rename to sensing_launch/config/aip_xx1/default/livox_front_right_bd_code.param.yaml diff --git a/sensing_launch/launch/aip_x1/lidar.launch.xml b/sensing_launch/launch/aip_x1/lidar.launch.xml index 392f13e3f1..aca9f10e89 100644 --- a/sensing_launch/launch/aip_x1/lidar.launch.xml +++ b/sensing_launch/launch/aip_x1/lidar.launch.xml @@ -25,7 +25,7 @@ - + @@ -37,7 +37,7 @@ - + @@ -49,7 +49,7 @@ - + diff --git a/sensing_launch/launch/aip_xx1/lidar.launch.xml b/sensing_launch/launch/aip_xx1/lidar.launch.xml index c904392b73..47732e1d36 100644 --- a/sensing_launch/launch/aip_xx1/lidar.launch.xml +++ b/sensing_launch/launch/aip_xx1/lidar.launch.xml @@ -73,7 +73,7 @@ - + @@ -85,7 +85,7 @@ - + diff --git a/system_launch/launch/system.launch.xml b/system_launch/launch/system.launch.xml index cea10f657c..f3a1b43c3a 100644 --- a/system_launch/launch/system.launch.xml +++ b/system_launch/launch/system.launch.xml @@ -16,12 +16,12 @@ - + - + From 451300a8c1504da56895cd0defb90fe426b66c7e Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 26 Feb 2021 10:22:11 +0900 Subject: [PATCH 0087/1765] Ros2 v0.8.0 autoware launch (#58) * [autoware_launch] ros2-porting: v0.5.0 to v0.8.0 Signed-off-by: Takamasa Horibe * Cleanup autoware and logging simulator launch * Add .xml extention * Fix missing arguments * Fix tag * Fix web controller launch Signed-off-by: wep21 * Update rviz Signed-off-by: wep21 * [autoware_launch] Fix yaml name Signed-off-by: wep21 * [autoware_launch] Cleanup dependencies Signed-off-by: wep21 Co-authored-by: wep21 --- autoware_launch/CMakeLists.txt | 5 + autoware_launch/launch/autoware.launch.xml | 42 +- .../launch/logging_simulator.launch.xml | 43 +- .../launch/planning_simulator.launch.xml | 2 +- autoware_launch/package.xml | 20 +- autoware_launch/rviz/autoware.rviz | 482 +++++++++++------- autoware_launch/rviz/image/autoware.png | Bin 0 -> 600002 bytes 7 files changed, 362 insertions(+), 232 deletions(-) create mode 100644 autoware_launch/rviz/image/autoware.png diff --git a/autoware_launch/CMakeLists.txt b/autoware_launch/CMakeLists.txt index 4c62c75a53..60e4e952cb 100644 --- a/autoware_launch/CMakeLists.txt +++ b/autoware_launch/CMakeLists.txt @@ -4,6 +4,11 @@ project(autoware_launch) find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index c45e93675a..6aa26e6b83 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -10,54 +10,56 @@ - + + - + - - - + + + - - - + + + - + - - + + - + + + - - + + + - + - + - - - - + + diff --git a/autoware_launch/launch/logging_simulator.launch.xml b/autoware_launch/launch/logging_simulator.launch.xml index e364f63097..fffe483a5d 100644 --- a/autoware_launch/launch/logging_simulator.launch.xml +++ b/autoware_launch/launch/logging_simulator.launch.xml @@ -4,7 +4,7 @@ - + @@ -17,55 +17,56 @@ - + - - - - + + + + + - + - - - + + + - + - + - + - + - + + + - + + - + - - - - + diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml index 54b2064131..c1b35ee1fc 100644 --- a/autoware_launch/launch/planning_simulator.launch.xml +++ b/autoware_launch/launch/planning_simulator.launch.xml @@ -56,7 +56,7 @@ - + diff --git a/autoware_launch/package.xml b/autoware_launch/package.xml index b9f32201f9..abcdf33a29 100644 --- a/autoware_launch/package.xml +++ b/autoware_launch/package.xml @@ -8,20 +8,30 @@ Apache License 2.0 ament_cmake_auto - vehicle_launch - perception_launch - sensing_launch - vehicle_launch + + + control_launch + localization_launch + map_launch perception_launch + planning_launch sensing_launch + system_launch + vehicle_launch + + rviz2 + + autoware_web_controller python-tornado python3-tornado python-bson python3-bson - + ament_lint_auto + ament_lint_common + ament_cmake diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 36abca3067..b59a1d7f03 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -1,43 +1,27 @@ Panels: - Class: rviz_common/Displays - Help Height: 138 + Help Height: 0 Name: Displays Property Tree Widget: - Expanded: - - /Perception1/Detection1 - - /Perception1/Tracking1 - - /Perception1/Prediction1 - - /Planning1/ScenarioPlanning1 - - /Planning1/ScenarioPlanning1/LaneDriving1 - - /Planning1/ScenarioPlanning1/LaneDriving1/MotionPlanning1 - - /Planning1/ScenarioPlanning1/Parking1 - Splitter Ratio: 0.5345016717910767 - Tree Height: 334 + Expanded: ~ + Splitter Ratio: 0.557669460773468 + Tree Height: 397 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - - /2D Dummy Pedestrian1 - - /2D Dummy Car1 - - /2D Checkpoint Pose1 - - /Delete All Objects1 + Expanded: ~ Name: Tool Properties Splitter Ratio: 0.5886790156364441 - Class: rviz_common/Views - Expanded: - - /Current View1 + Expanded: ~ Name: Views Splitter Ratio: 0.5 - - Class: rviz_common/Tool Properties - Expanded: - - /2D Dummy Pedestrian1 - - /2D Dummy Car1 - - /2D Checkpoint Pose1 - - /Delete All Objects1 - Name: Tool Properties - Splitter Ratio: 0.5 + - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + Name: InitialPoseButtonPanel +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -77,12 +61,12 @@ Visualization Manager: Value: false - Class: rviz_common/Group Displays: - - Class: rviz_plugins/ConsoleMeter + - Class: rviz_plugins/SteeringAngle Enabled: true - Left: 512 + Left: 128 Length: 256 - Name: ConsoleMeter - Scale: 3 + Name: SteeringAngle + Scale: 17 Text Color: 25; 255; 240 Top: 128 Topic: @@ -90,14 +74,14 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /vehicle/status/twist + Value: /vehicle/status/steering Value: true Value height offset: 0 - - Class: rviz_plugins/SteeringAngle + - Class: rviz_plugins/ConsoleMeter Enabled: true - Left: 128 + Left: 512 Length: 256 - Name: SteeringAngle + Name: ConsoleMeter Scale: 3 Text Color: 25; 255; 240 Top: 128 @@ -106,23 +90,26 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /vehicle/status/steering + Value: /vehicle/status/twist Value: true Value height offset: 0 - - Class: rviz_plugins/TurnSignal + - Alpha: 0.999 + Class: rviz_plugins/VelocityHistory + Color Border Vel Max: 3 + Constant Color: + Color: 255; 255; 255 + Value: true Enabled: true - Height: 256 - Left: 196 - Name: TurnSignal - Top: 350 + Name: VelocityHistory + Scale: 0.30000001192092896 + Timeout: 10 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /control/turn_signal_cmd + Value: /vehicle/status/twist Value: true - Width: 512 - Alpha: 0.30000001192092896 Class: rviz_default_plugins/RobotModel Collision Enabled: false @@ -142,151 +129,151 @@ Visualization Manager: Expand Tree: false Link Tree Style: Links in Alphabetic Order base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera0/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera0/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false camera1/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera1/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false camera2/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera2/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false camera3/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera3/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false camera4/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera4/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false camera5/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true camera5/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false gnss_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true livox_front_left: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false livox_front_left_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true livox_front_right: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false livox_front_right_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true sensor_kit_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false tamagawa/imu_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true traffic_light_left_camera/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true traffic_light_left_camera/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false traffic_light_right_camera/camera_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true traffic_light_right_camera/camera_optical_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false velodyne_left: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_left_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_rear: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_rear_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_right: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_right_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_top: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true velodyne_top_base_link: - Alpha: 1 + Alpha: 0.999 Show Axes: false Show Trail: false Value: true @@ -295,34 +282,45 @@ Visualization Manager: Update Interval: 0 Value: true Visual Enabled: true - - Alpha: 0.9990000128746033 - Class: rviz_plugins/VelocityHistory - Color Border Vel Max: 3 - Constant Color: - Color: 0; 0; 0 - Value: false + - Class: rviz_plugins/MaxVelocity Enabled: true - Name: VelocityHistory - Scale: 0.30000001192092896 - Timeout: 10 + Left: 595 + Length: 96 + Name: MaxVelocity + Text Color: 255; 255; 255 + Top: 280 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /vehicle/status/twist + Value: /planning/scenario_planning/current_max_velocity + Value: true + - Class: rviz_plugins/TurnSignal + Enabled: true + Height: 256 + Left: 196 + Name: TurnSignal + Top: 350 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /control/turn_signal_cmd Value: true + Width: 512 Enabled: true Name: Vehicle Enabled: true Name: System - Class: rviz_common/Group Displays: - - Alpha: 1 + - Alpha: 0.20000000298023224 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 + Max Value: 28.71826171875 + Min Value: -7.4224700927734375 Value: true Axis: Z Channel Name: intensity @@ -333,15 +331,15 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 + Max Intensity: 237 + Min Color: 211; 215; 207 Min Intensity: 0 Name: PointCloudMap Position Transformer: XYZ Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares + Size (Pixels): 1 + Size (m): 0.05000000074505806 + Style: Points Topic: Depth: 5 Durability Policy: Transient Local @@ -349,23 +347,24 @@ Visualization Manager: Reliability Policy: Reliable Value: /map/pointcloud_map Use Fixed Frame: true - Use rainbow: true + Use rainbow: false Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true Name: Lanelet2VectorMap Namespaces: - center_lane_line: true + center_lane_line: false crosswalk_lanelets: true - detection_area: true lanelet direction: true + lanelet_id: false left_lane_bound: true + parking_lots: true + parking_space: true right_lane_bound: true road_lanelets: true stop_lines: true traffic_light: true traffic_light_triangle: true - walkway_lanelets: true Topic: Depth: 5 Durability Policy: Transient Local @@ -379,17 +378,17 @@ Visualization Manager: Displays: - Class: rviz_common/Group Displays: - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true + Max Value: 5 + Min Value: -1 + Value: false Axis: Z Channel Name: intensity Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 - Color Transformer: Intensity + Color Transformer: AxisColor Decay Time: 0 Enabled: true Invert Rainbow: false @@ -401,7 +400,7 @@ Visualization Manager: Position Transformer: XYZ Selectable: true Size (Pixels): 2 - Size (m): 0.20000000298023224 + Size (m): 0.009999999776482582 Style: Points Topic: Depth: 5 @@ -409,32 +408,32 @@ Visualization Manager: History Policy: Keep Last Reliability Policy: Reliable Value: /sensing/lidar/concatenated/pointcloud - Use Fixed Frame: true + Use Fixed Frame: false Use rainbow: true Value: true - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true + Max Value: 15 + Min Value: -2 + Value: false Axis: Z - Channel Name: intensity + Channel Name: z Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 - Color Transformer: Intensity + Color Transformer: FlatColor Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 + Max Intensity: 15 Min Color: 0; 0; 0 - Min Intensity: 0 + Min Intensity: -5 Name: NoGroundPointCloud Position Transformer: XYZ Selectable: true Size (Pixels): 5 - Size (m): 0.20000000298023224 + Size (m): 0.009999999776482582 Style: Points Topic: Depth: 5 @@ -445,7 +444,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true - - Alpha: 1 + - Alpha: 0.999 Class: rviz_default_plugins/Polygon Color: 25; 255; 0 Enabled: false @@ -474,9 +473,9 @@ Visualization Manager: Frame: Local Offset: 1 Scale: 1 - Value: true + Value: false Position: - Alpha: 0.30000001192092896 + Alpha: 0.20000000298023224 Color: 204; 51; 204 Scale: 1 Value: true @@ -503,7 +502,7 @@ Visualization Manager: Displays: - Class: rviz_common/Group Displays: - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Axes Length: 1 Axes Radius: 0.10000000149011612 Class: rviz_default_plugins/PoseWithCovariance @@ -537,7 +536,7 @@ Visualization Manager: Reliability Policy: Reliable Value: /localization/pose_estimator/initial_pose_with_covariance Value: true - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Axes Length: 1 Axes Radius: 0.10000000149011612 Class: rviz_default_plugins/PoseWithCovariance @@ -571,7 +570,7 @@ Visualization Manager: Reliability Policy: Reliable Value: /localization/pose_estimator/pose_with_covariance Value: true - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 @@ -580,7 +579,7 @@ Visualization Manager: Axis: Z Channel Name: intensity Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 + Color: 0; 255; 255 Color Transformer: "" Decay Time: 0 Enabled: false @@ -590,7 +589,7 @@ Visualization Manager: Min Color: 0; 0; 0 Min Intensity: 0 Name: Initial - Position Transformer: "" + Position Transformer: XYZ Selectable: true Size (Pixels): 10 Size (m): 0.009999999776482582 @@ -604,7 +603,7 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: false - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 @@ -613,17 +612,17 @@ Visualization Manager: Axis: Z Channel Name: intensity Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" + Color: 85; 255; 0 + Color Transformer: FlatColor Decay Time: 0 Enabled: false Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 + Max Color: 85; 255; 127 + Max Intensity: 0 Min Color: 0; 0; 0 Min Intensity: 0 Name: Aligned - Position Transformer: "" + Position Transformer: XYZ Selectable: true Size (Pixels): 10 Size (m): 0.009999999776482582 @@ -747,7 +746,10 @@ Visualization Manager: Enabled: true Name: RouteArea Namespaces: - {} + goal_lanelets: true + left_lane_bound: false + right_lane_bound: false + route_lanelets: true Topic: Depth: 5 Durability Policy: Volatile @@ -755,24 +757,24 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/mission_planning/route_marker Value: true - - Alpha: 1 + - Alpha: 0.999 Axes Length: 1 Axes Radius: 0.30000001192092896 Class: rviz_default_plugins/Pose Color: 255; 25; 0 Enabled: true Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 + Head Radius: 0.5 Name: GoalPose - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 + Shaft Length: 3 + Shaft Radius: 0.20000000298023224 Shape: Axes Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /planning/mission_planning/goal + Value: /planning/mission_planning/echo_back_goal_pose Value: true Enabled: true Name: MissionPlanning @@ -790,13 +792,13 @@ Visualization Manager: Value: /planning/scenario_planning/trajectory Value: true View Path: - Alpha: 1 + Alpha: 0.999 Color: 0; 0; 0 Constant Color: false Value: true Width: 2 View Velocity: - Alpha: 1 + Alpha: 0.999 Color: 0; 0; 0 Constant Color: false Scale: 0.30000001192092896 @@ -817,13 +819,13 @@ Visualization Manager: Value: /planning/scenario_planning/lane_driving/behavior_planning/path Value: true View Path: - Alpha: 1 + Alpha: 0.4000000059604645 Color: 0; 0; 0 Constant Color: false Value: true Width: 2 View Velocity: - Alpha: 1 + Alpha: 0.4000000059604645 Color: 0; 0; 0 Constant Color: false Scale: 0.30000001192092896 @@ -844,7 +846,17 @@ Visualization Manager: Enabled: true Name: Crosswalk Namespaces: - {} + collision line: false + collision point: false + factor_text: true + slow factor_text: true + slow point: false + slow polygon line: false + slow virtual_wall: true + stop point: false + stop polygon line: false + stop_virtual_wall: true + walkway stop judge range: false Topic: Depth: 5 Durability Policy: Volatile @@ -856,7 +868,17 @@ Visualization Manager: Enabled: true Name: Intersection Namespaces: - {} + conflicting_targets: false + detection_area: false + ego_lane: false + factor_text: true + judge_point_pose_line: false + path_raw: false + spline: false + stop_point_pose_line: false + stop_virtual_wall: true + stuck_vehicle_detect_area: false + stuck_targets: false Topic: Depth: 5 Durability Policy: Volatile @@ -868,7 +890,16 @@ Visualization Manager: Enabled: true Name: Blind Spot Namespaces: - {} + conflict_area_for_blind_spot: false + conflicting_targets: false + detection_area: false + detection_area_for_blind_spot: false + factor_text: true + judge_point_pose_line: false + path_raw: false + stop_virtual_wall: true + spline: false + stop_point_pose_line: false Topic: Depth: 5 Durability Policy: Volatile @@ -880,7 +911,10 @@ Visualization Manager: Enabled: true Name: TrafficLight Namespaces: - {} + dead line factor_text: false + dead line virtual_wall: false + factor_text: true + stop_virtual_wall: true Topic: Depth: 5 Durability Policy: Volatile @@ -892,7 +926,8 @@ Visualization Manager: Enabled: true Name: StopLine Namespaces: - {} + factor_text: true + stop_virtual_wall: true Topic: Depth: 5 Durability Policy: Volatile @@ -904,7 +939,12 @@ Visualization Manager: Enabled: true Name: DetectionArea Namespaces: - {} + detection_area_correspondence: false + detection_area_id: false + detection_area_polygon: false + factor_text: true + obstacles: false + stop_virtual_wall: true Topic: Depth: 5 Durability Policy: Volatile @@ -916,7 +956,13 @@ Visualization Manager: Enabled: true Name: LaneChange Namespaces: - {} + candidate_lane_change_path: false + ego_lane_change_path: false + ego_lane_follow_path: false + factor_text: true + object_predicted_path: false + selected_path: false + stop_virtual_wall: true Topic: Depth: 5 Durability Policy: Volatile @@ -924,7 +970,7 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/debug/predicted_path_markers Value: true - - Class: rviz_plugins/Trajectory + - Class: rviz_plugins/Path Color Border Vel Max: 3 Enabled: true Name: LaneChangeCanditate @@ -936,13 +982,13 @@ Visualization Manager: Value: /planning/scenario_planning/lane_driving/lane_change_candidate_path Value: true View Path: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false + Alpha: 0.30000001192092896 + Color: 115; 210; 22 + Constant Color: true Value: true Width: 2 View Velocity: - Alpha: 1 + Alpha: 0.30000001192092896 Color: 0; 0; 0 Constant Color: false Scale: 0.30000001192092896 @@ -963,13 +1009,13 @@ Visualization Manager: Value: /planning/scenario_planning/lane_driving/trajectory Value: false View Path: - Alpha: 1 + Alpha: 0.999 Color: 0; 0; 0 Constant Color: false Value: true Width: 2 View Velocity: - Alpha: 1 + Alpha: 0.999 Color: 0; 0; 0 Constant Color: false Scale: 0.30000001192092896 @@ -978,7 +1024,12 @@ Visualization Manager: Enabled: true Name: ObstaclePointCLoudStop Namespaces: - {} + collision_polygons: false + detection_polygons: false + factor_text: true + stop_virtual_wall: true + stop_obstacle_point: false + stop_obstacle_text: false Topic: Depth: 5 Durability Policy: Volatile @@ -990,7 +1041,10 @@ Visualization Manager: Enabled: true Name: SurroundObstacleCheck Namespaces: - {} + factor_text: true + virtual_wall: true + obstacle_point: true + no_start_obstacle_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -1002,7 +1056,37 @@ Visualization Manager: Enabled: true Name: ObstacleAvoidance Namespaces: - {} + avoiding_objects: false + base_bounds_line: false + bounds_candidate_base_text: false + bounds_candidate_for_base: false + bounds_candidate_for_top: false + bounds_candidate_top_text: false + constrain_rect: false + constrain_rect_text: false + constrain_rectlocation: false + current_vehicle_footprint: false + extending_constrain_rect: false + extending_constrain_rect_text: false + extending_constrain_rectlocation: false + fixed_mpt_points: false + fixed_points_for_extending: false + fixed_points_marker: false + interpolated_points_for_extending: false + interpolated_points_marker: false + interpolated_points_text_marker: false + non_fixed_points_for_extending: false + non_fixed_points_marker: false + num_vehicle_footprint: false + optimized_points_marker: false + optimized_points_text_marker: false + smoothed_points_text: false + straight_points_marker: false + top_bounds_line: false + mid_bounds_line: false + vehicle_footprint: false + virtual_wall: true + virtual_wall_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -1036,7 +1120,7 @@ Visualization Manager: Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid_updates Use Timestamp: false Value: false - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Arrow Length: 0.30000001192092896 Axes Length: 0.30000001192092896 Axes Radius: 0.009999999776482582 @@ -1056,18 +1140,18 @@ Visualization Manager: Reliability Policy: Reliable Value: /planning/scenario_planning/parking/debug/partial_pose_array Value: true - - Alpha: 0.9990000128746033 + - Alpha: 0.999 Arrow Length: 0.5 Axes Length: 0.30000001192092896 Axes Radius: 0.009999999776482582 Class: rviz_default_plugins/PoseArray Color: 0; 0; 255 Enabled: true - Head Length: 0.07000000029802322 - Head Radius: 0.029999999329447746 + Head Length: 0.10000000149011612 + Head Radius: 0.20000000298023224 Name: PoseArray - Shaft Length: 0.23000000417232513 - Shaft Radius: 0.009999999776482582 + Shaft Length: 0.20000000298023224 + Shaft Radius: 0.05000000074505806 Shape: Arrow (Flat) Topic: Depth: 5 @@ -1097,10 +1181,10 @@ Visualization Manager: Value: true View Path: Alpha: 1 - Color: 0; 0; 0 - Constant Color: false + Color: 255; 255; 255 + Constant Color: true Value: true - Width: 2 + Width: 0.05000000074505806 View Velocity: Alpha: 1 Color: 0; 0; 0 @@ -1136,6 +1220,7 @@ Visualization Manager: Enabled: true Global Options: Background Color: 10; 10; 10 + Default Light: true Fixed Frame: viewer Frame Rate: 30 Name: root @@ -1148,12 +1233,15 @@ Visualization Manager: - Class: rviz_default_plugins/Measure Line color: 128; 128; 0 - Class: rviz_default_plugins/SetInitialPose + Theta std deviation: 0.2617993950843811 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable Value: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 - Class: rviz_default_plugins/SetGoal Topic: Depth: 5 @@ -1161,14 +1249,6 @@ Visualization Manager: History Policy: Keep Last Reliability Policy: Reliable Value: /planning/mission_planning/goal - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Class: rviz_plugins/PedestrianInitialPoseTool Pose Topic: /simulation/dummy_perception_publisher/object_info Theta std deviation: 0.0872664600610733 @@ -1193,13 +1273,10 @@ Visualization Manager: Z position: 0 - Class: rviz_plugins/DeleteAllObjectsTool Pose Topic: /simulation/dummy_perception_publisher/object_info - Transformation: - Current: - Class: rviz_default_plugins/TF Value: true Views: Current: - Angle: 0.07999998331069946 + Angle: 0 Class: rviz_default_plugins/TopDownOrtho Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 @@ -1209,27 +1286,62 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Scale: -5.74001932144165 + Scale: 10 Target Frame: viewer Value: TopDownOrtho (rviz_default_plugins) - X: -38.261173248291016 - Y: 29.38650894165039 - Saved: ~ + X: 0 + Y: 0 + Saved: + - Class: rviz_default_plugins/ThirdPersonFollower + Distance: 18 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: ThirdPersonFollower + Near Clip Distance: 0.009999999776482582 + Pitch: 0.20000000298023224 + Target Frame: base_link + Value: ThirdPersonFollower (rviz) + Yaw: 3.141592025756836 + - Angle: 0 + Class: rviz_default_plugins/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 10 + Target Frame: viewer + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 Window Geometry: Displays: collapsed: false - Height: 2032 + Height: 1565 Hide Left Dock: false Hide Right Dock: false Image: collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000055e0000075efc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b000000ab00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000690000023c0000017800fffffffc000002b10000026c0000015801000034fa000000000100000002fb0000000a005600690065007700730100000000ffffffff0000014f00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007301000000000000055e000000f500fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000035400000090000000ab00fffffffb0000000a0049006d00610067006501000005290000029e0000004500ffffff00000001000001570000075efc0200000001fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000009060000075e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000329000006fffc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000001fb0000018200fffffffc00000275000002840000016c01000039fa000000000100000002fb0000000a0056006900650077007301000000000000033c0000015f00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000000ffffffff0000010b00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d0061006700650100000505000002680000002600fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00fffffffb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de000000de00ffffff000000010000015f000006fffc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7a0000005afc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7a0000005afc0100000002fb0000000800540069006d0065010000000000000e7a0000057100fffffffb0000000800540069006d0065010000000000000450000000000000000000000b45000006ff00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 3696 - X: 144 - Y: 54 + Width: 2813 + X: 67 + Y: 27 diff --git a/autoware_launch/rviz/image/autoware.png b/autoware_launch/rviz/image/autoware.png new file mode 100644 index 0000000000000000000000000000000000000000..cf2d1e8eff3550c4427f8d98dc2f1d0c41aa712a GIT binary patch literal 600002 zcmV)jK%u{hP)7yN`O?Xkq%$~9oY)Q?;&eu*+v#>X z?KqR;ff!Fr7GMDe1O_Yyffyu#W~o%FK~<``>eYL%zqQt0=j?m``@dJh*xmhX@#_7< zz2}~@&pvzYz4qP{7he8?rBWu!s@3bt&hxJ>hYmhf_U?M1OioRerKP2UpNWYH{$5;I zC|kB)RL;HVTK?^y#l^)kH9b>K9zR^3c=#*j$f3PuVq&uMnf@QRHvaRq$9@=N!2Laz z$*EFG`|h~!x3N#w`z$Rj@_v3#&oC>m`5czBz(_*|f zQ6?sFpT#mcF;x~97x*3g)-&=>y+_pC#srs%B|cUBJy}1EYw8-4ya(n1uN8~|?=3F! zTQjq(%Q+W5r#!v)(Q@ROePwcTGTp!3yZ`*2gEpt0j|n~F;zC)BxyNVfoIxHI7xWpu zs^`ZT`JUzm<>K8N^;--N}l`fdm6vC zSbslCt~sxqD(yS%Bg;uV_rye*g3K>1a@{7UXUZh^Nhu4b=c}Af;0217?~C8~uRH%$ ze{c>cKn34jqRh1?n3$NN?pa(o&4<9eo}NEhCZ}e2P2L+{_x=i5mL!Kf_x5JphrLPU z*#8242JgR&EMQ$UpTpxD_dNMgIJZT5X5(2q%9d>xmBR=3lzn?1=G-oKee32V==!Ji zMrW;i(g&R|ImP>8ZLw~Pi>GJl~X5<#ckUB)_q%bW8Fm3&)!sAmC&V}61>-RMMtKr zOY=3mgX_-gw;+p@g}D9XlXN|LXViLL>XK|bZK9}&cyw+qn zYwHDN^VahyNBeg_R2H$GIIr^arGN8#@qL~xoUe3F*7F+I_f*7A_WiLJ;tbLf`26>^ zFz$9;%T3n1)|LJHcVujg?c%fAx~0EFmW3vhl4)LhVuJb#;sQGYzn2zp*84dycX$uy z$U=S2uB|0`#}8$Fa*BI-YI3sd+4aq`5PKQ-o1B_0Yu9fo>o;xZca9v~Qw|^6r+vtM zwxs)%i83`a8#cvanVOs~Gppvx{5_e85^SxZ=1zMyY{2-8-{*BYXEgLn*todV z;u7auYk8V$s7o(lH`WuQ+J)TwlYBm1S7*J>(4}(yO>ZjeH*YI<-u|nyd2QdtxU%hw z`O$jK$X13-#d>&eX4{_69X8|YH5W#8_HbPddVnJA|hPPO@~=lK$K z7uFo|RQFNHao&ftEl;1K49QN%`8LUaV?uBp**6kj>vOL6!hEPjtqEn2@`XJkU4!f3 zv-77;gxpQXXQ#_)*dys2lKup4kbQ4Erp`~C$wOzJ&ih!ObRO~?k26R54|+p#syVh! z#aRa(E_v}@!E<5!USI3t34uicqwVKiNl>)w;d{!=s@0*`+reu^4qypoCgVazJ`}^r z6US(%;eoqKJ{#m(HiL=S8Eq~52WHRE7&clAvch2M80eZT{WRl2i{XtKd(;M3fH5jD zC^avlzXM@NhFJz+K6DKhCA5;d(K+#BOZijSu;@MILZuI34ke5Um*6hQkRyODW#a$CUbq~=1Bc6sh z@GToNvvXzD+&VrJK|=gU_ys_{s`c6gHf=LxB{BSOtc%rD_YRNE^7C~)|P z3}}vIm{8$h@0TSS+Fl>LCM9SGQk%OrE~&UU$pWONb%8;}>C(Lk40(txl_da+a020; zFamHdJR6M+{w;;BwUU9X?=&SkBp)%Vu|RCxcZOacUgyzIo(Z_i-&zU8p7HfUEH-Z5 zQMPQqxEwvauk73Xa9LQG9}gD$z$WCmBZILQs=h?W=O7AwmHqOuNkdkc3URnb9GiHZz zN@uCSx*ggEQa+EHu?UA)tVvwM4iJyc>tkIG#|QSrfqjp24FKroRa2AQ%%U?+@fx^jf=BUz(;#g0S&A%#<7UYV4cDtr(gg; zbOc2_@9}-lKj)JHiMjHMH~sDM;Mf18eB+)^aDHhQP63>q67X7p!w;_mH%yd;g@rPM zb&uzS?9q0%-D5pqJ2B)2>vZ#Nf1`ZhUH_^ar;N>Te_*}|JTs_vASoP=&|BKqI{7f| zz%!@kPjQ^HtJaj0Cyx?Hf0h2xRBf$zxpWiSsXg9(5W%v}N0cW%b&PmaFTL?rI^YAKCxy1PF zy|L1wabK3o+1oCH+p+9<{QmA?+&c#I;hzDG56ABN+87=0CV`s{EUkfL!@_JqRH(3d zGV&VNAu&Rlyupi$5y?zZuK0}fh&^tl%&uC?&5z9y1C(r5BQ6_dTK}0Vuv92!%T#Zh3`H|+fVA)}9D3vXTjK6S4}WW?U8s*Do& zw2{MTP$(@uHx4K$xR^ZyI(xdYIeGj@XQ?}T$%aZe zu4LHRVU?U?BlG1|8vu*xtOx<^7?AxFWY}2{&)WlKd0)f0Ao~RXE1ZHhG^u~^9KCb8 zjwjaI;DSbUHH@{Vw(h*NtlzY)JoEIEbYKeL!A66j+oC8kfUtfrmRh8;PP)&)&=&w* z*%0KVy#G@aPG^+PeghtZc^PKieJWc*uZ^=!`g`7y9bDIjI%O{+P>p@0Z&Ez$`R_P2 zTQtDush#tVfY{;1>kt$x`ZwZx@gOJUINN&8<>lmwBjuU>yT~BJnt+J}fOzEK-m-x6 zv-8}c6~fjsc;tShK{-{{tUHTNos-9&VZ?|)6A_(YVsQ@y7y+1|0gUJn4B0Tcea2O= z7@!3Yw0K&^IStwA8G*%!6vBuG=$VL!rgb}BuV67EkpyyKS542(m2EpOE2mB!FHi4z zL|~Lo!$RjK^v8+gNBDdfUH+nS>2qGny>EMl?6T^xR6ykT(Pzrh!%x%xwH*TE`q+_! zJiAVxJjwaBd?<3iBqN^-8LTRR1fG@6zR5P0BfNMPtSMx|20iu-K^P*jjJPWDYB@G| z#(W|2Iyr4Hr!$e?XM`2M5lOZ$X_B_Ez~T~_0^jw9zfnH=p8vBv^Yku(3P)DMX3aiN1(1I=2 zmvnX@xL2{A?k~rbp`(=g~BRECl^S#mL&q+eWjMa^I-75ZUXdFn;sEHE&!~-_8EE(PXeNV7$elWe-Hb zL@x;hIsDJfLmFG7d6_a|kXoaaalnYOWiMfjIgAz?5}gAlMV1!`b9w5~d#RurJ;l#&KogOJNz_8o!epmz0*!!Qi`5%n%*s_Vt?8`nc)>aWi@u;_!M3wWihWzfSTl?0Bt#%4~3dRyCX|gu?@&u^+3rzZ||M-h$tZ(pI+d2;bqLqutuCX_ollx z`nGA|Hcq)el0U%|+2!W2FFj4H&m2sSy+*uo#*x4kF4TZv7{GPzlFkgnHG@Ua(zcy* zX*qgmf7!eHp*UoN23%d}4G;;~1^qmn1Iw`tha!)8PIC0p&egi+p$m2X zL!ISlkeyYEO55R1umycL1%q9`Wh9ECDt1jcMH21S(P9IU>FHHv+qst$AOXOx+qjjW z@!-=>meZ$>SBF`axjKFkENi67S_HDOZo?LWBt%bic3Lfm6Aov(X@{@}=zs@(Q^3B0 z%5d6|rV0>XY&|BlEcBJx4Ih4G8%62^TJU=GnL zd=C-N>DjVo{id>T`ZS{`7he8CIP}7b-`HRHJney?7h{ZGGdRbvhNtIG5Rd|R!=|1mGY`?qc<ABDw*XNI}Kt5mgMif$k$%TmYDx3$Qm?SuKttI_N|BWonHAYGyYf0#3VR{v^RI z&!!x$3;Y6^^Z4bklQRK7kSRPLgG`8U2L+pU+SC;FG{IYCTpDz@bSLX>Q_k(=X$(u9 zA*A*e0AI+ZY`=zNm3b)z(@e68xv7cZ_7c<(Wt)h zS;Nc8FlmEqxrWU!9rlLz?Vx->bnl-Gp8>DnustPTY(~^JTrwD8-e!0KWC%n)M&wRW zc~;thv}KNR(3=2HP0H8nj>qO4RI)rgrVr5Yq2o!OFYQSPjD$=1VA`M_!p{IbT~>bekc7t(%6MY3%+9SPaDd{i6b^&N6p0>x;P+*)4;%%i>ReTTkK46P zsytGA21l>i91&j5F2ERy{td}*AH3N}lZbQy?-1BeJ0>0}#u^4KJ+6^=k+g8ozMxbT zxw8XEh9Zmv9qw`{RP|l&0olW0XcnA3llIoqgB=Rk?~&CIfWTf;8+!7%2d%@=g#i7K zVMQTD?Jym!Pf4qXRYXv|*H(-)#(vD-uN0yD-mn5%_SJ6}SnS`V0qya($Gz8Y*jl!o zcLfcqJx@N+z+$5MVhw990}e6frF0!9+8d2doi=m(r;Sn5H%%8_Sm2?lwO=G19iUNQ z%}$L`ie!HeSZ`L!di7|heM>bipeS$gbj?{bSgc;(FxdLQFz>@8i)4!OH>7eiBGmBu5=_cXi2w=@w4z~< zErHy~#S40+DaU4{O%vQqYwi}82u`MFSMmGMVTjgHpG?hgpRHQGzRb+5BADfCA$wp> z;Tf($Lx>`W@`0um`hKq1hI)uOPRI za+h-R8~-M2r+oEu9|(qH*z2KNNPBmlp4mg(==z_=HdMsh_9Nbv90zlP&pIm_eE>Vk z4qgj7tIQ&&ehKi)&Yz@g!tR7FMdTW`5M&de&wGP8qr?G<{80ww`68%1efngW4wGei z8r0@f@obSw5$jGGb^uV%ofr}=HB35ev4T#6%o>609V;GFrY~b3I?ol)iD%)`e&_4| z+LF9kr7Xi$J#)V7ui_mwx{5xOsz_063Y791ww^XWe;^gSf zQ#(ABTfoDvX}3gYXhvtVmAjERfk1t^fy*YNedkLDfabf7p;Bv)jXGU&B+{Sh??dHR zL@|T_oAfT#-PpXwa@;s}i}<(3TOnGEWjv3#)= z)!x_-jFpu*j6&!%T|p<8wh7uTDS%C<;XM>}K>qsiBL~Y(2J3cvZ_fOh;vtBWtLYa!~7a zHL8)lpZ9&1kH%DK(LH_^qELZbM3SPQ9qC7tu|HBli@rc|&J7NbvokYGkg|H+CQ|+Y zQtHx2l+d4VXKFJD4Vn$|Ew5r6s3^tI7)*0h-Gm(NigXHX2pQW{Xf`lKgO!(Gxkv;X zs0$GJk(}*t{Ptz6MH8EIgupfEd3FZlb12XOFa~U@U(n78p3ax1{d~&^nq$Q7?9EUCKyBElt|wR5bkJ=Xr|6b zTTs-?x$`vkRj>pNY2e|&0Gug^Okxi38C=seV8}GC4ZCmshHaEBu>a^} znVK$hYu1+y8@I{0k0_BNosfric1q50u7arnd35~?M6Com=gIWIZ`l7h6JC1DUnzh5 z-d|?!D|1Q_<%{=4@l*f<&+0v6=Y~PBfE=P$$~ng099u*T{fw`F+fS7*edfL8k^AoA zKBQa(^U3sN*GKT_EeC^g)a`h0wn!9E1K=VhTKR`~zZO=C!Z*};kq2vs0s;~SYF-;T zFBi#b<8^9LPz9AhHHPfKuA#mPd3FFvk!?ha74T7xtH7l59wi^hD}~cQlvGn#F*Zjq zJM270D1**Qhq)q%Lo5-@JI0-vA=ayQzHn@i!;7xGaY@E1szJ?_^_#Yq)oV7E-H&~} zY&!cq<}f;3P3r05LV>3OVRHzG!sadi&>_{P07rEC*nEIYO&v0RN3S&Ql`{j2XMVjp zed#L!Jw^)GG{fBoij}?;>hcv}^ZVjQJ3(LfGu6{d5>Ut>2%q11-c{x3;REI1{>M9D zF?(=fU=vz}_pkw@JR?4UQlu)3Oalxao~d|6K0y5(c^xhIHcp*Pi)SI{J}3&_RF)xA z60rfW`&`K?AGY9-!;{O(t*qdxLsL{F8^qZeF$%8q^l_Au!!C-86pyI8Epo;qlwieI z?W|qR&x@+Hq3n2zTFAf-mQZ(Lv@d7uc2=n8(eJ<4m+!HA%EcC<8lix-+KgK!>=snPOY zhvOiYw0idql6sNx{#fVEx*k14#6>mj#QxaSwvU{F!(LM1yvmcV#(o z;t2DfnS+slroX~G66D_mZLmhAqGG9XYND$4nE4?nh@whZGk9k&xa|35Zf-pdEuJx; zT%DdTv+!n@Qg%K373KRhWb zX|Qy>1K$r%`|~9|P7|qI5>x zgD6VE2y>-N2CE@OFdS)<(WV;;gtzF3q)JXT6+n?w1qK&vDcDS|+9;hU`-zc60wq__ z?8{YGU*mzMJ`xgqik5m8j}5?mXFZ(#g`E{}-n zsguVUQGz20&wb+95$Z{##h5aQF)B*rs_~jnM(vq9uR0$!#|`g=gWn)h5og&lstT>> zD0DB*KF%vsk{mr#lpnSd<;gWO0u%vs2)Ir2Gl+st&#vZg$Uepf5VUG;Eq}wF7nS)6 zvJUq?`2gR;b1{H4f1(^cyr1X!{HbGQW_Atd0PjObBWj5~Fn{tWpP3-^_+ieUo=er! zah6l3Pm}_N+^s+GQ{|4||F>c!q-yL~>gx0gh5_v^IuWsNvbiTFp3bM%QGhg1@EbU1 zk@6L5B8;zj)7(n73>vEgC~TT8%O&)I3(rKL$IcEpNi;?mqj3QnJhy4srYj=?y|4iJ zk<8fsv^+ot?69adRz$4L$ZR#tsD+g%G^LP%~b6mRq1daRPimz9HT<4P+5K54Pu4_fxOPcS4 z#jNo8o-U%uP8`58qV-yf>^UDL9nwon%u|I zy-os}t!mQP>8q6h6SdPG=o;NnQJcn>4zFPv77vi1%6MbcLOL^2q& z^z0EfWusD;qFO6Gsj9q2W1s>6dn{wVTR1n&Iz3UxO^}=&QuVz;Hv4{#L=V6b0$0r}Zx12n7c=@M_{eZm>V;aWf)*Tl!DuOkJmmQQR7<8h;ER}D5 z?NjBc$L^D{5i7e=G|pNwFNJk14fUz1$OTg|B^3CLxwPxb#>dqlXBps5=)=(`Gq#^dP|$-Y1BRN|^p0m>i12X}QGEQ4Xjb+NKcVvyQ&| ztZX($+t2OHZ&6{a6SND!3fLvc(R|hS{Jru73XFa3gN$H;=DKQb4d)8DVBLnZ37Xe$ z+{UrYt=YiJ*1!p3ooJr0Hh2c_Ti^rC56&2!A7UwCp5Oc5-$C6gZAW81&hMy0kb)PS zhsag+1UdiL5w$iC(o>LCfLYOoRSne6Fa;XI#)BOa)m~jJhz|d-T^v>S{8G<=NfpkB z#)1)}55T@U4l9LR&PKCou)d5Anq?I_Skn+`7*X}N-Z!eS(h=kw@=i;n9QX-Cz`5%# zh?EMoImJg{d9tW=M)WYln^^qq=Uz_Q2zt?|O$Ng0!K00X$sS`YJdAYwhA<#(Zmu5Cf+}{-H?~4g7Ju=H7c$v*~;_C!`XBl793CoH7OGu{w|87_2cZ2W|1Sv z*L7zri)t$u-j;|u94DpS?C_vQ*XqGoun2R zsU`Ef6y6cAc;*UX`A-gk$Zx~7yOE=I!6CqLrjbP$MLPi&7v{_E#{d?OSK4s(I-&>J z`pql|0Ara^|A~pRYSmgA4lrb%eDtg3z~0Au27mXVu`}@9En6=r7hL{=vUdGh;b4RT zCGRx$7>v^=9=?Y;l=IQ|P9dLfil zFVfiD63qb>>kxUzh!F2M|Ee-OyP8Fk4k5BwqkOrY)#xVh*&~OYil$jty8oclVN|R` z>>GX0mSuokpHa?-lEt8WvH&W&cB`jAFaCg&+3Vle(=~b?br2lMB;7UgwyfXUTsOL^ zqi)`xD*fN1+{YL(27^3Abzpm8Z)`Yg2j}|8GkY10aiJnqHr{;px#cO)skv|L9BA#g zTD8n>4{JLEO@jD#d(;Zabw>Gjo9aKrqcSJssRx+R7Ms7Wbu8qi~v;{bXwS}Pd#zJoWm^au|Rs@ z**h*SFTeG#m%Bdx&hqg6pD)uhGv)kCpI=`5iXSR>{N68?qel*KKCimrRpqkhysUic zkNyiIL6eg+<)&BuFm2t3?)y{f5df^`zT|t#;}3nARcPl{Zy=C5_u}iz-d*3|XJKn& zEYOFj%E~q;L6bds{Af9GT(nT+^`V6jB6=z?B;aUg9c=0oh=d|%5fwOVUR(|=MA0p_ zpbEA{^jW1-CStj;%{Ok|S>EtN?kM^9rD3z3Db=t=}S^)>U5d9YxZ^ zxx^l(kx~~lZdR=gnX8}>_9o;s(j%nTMN`MKx+gFIXLY(q1yV&{1?FX|sE`cPuGk(U zQbU5xqIGl;q{ITL0fwxngSH;$M?V-*ZMQT>qi0|QjJWQ~3C>K8{%JaK!DY{1(!{uu zxv6mQO-v$w2Q;=LZo z9#x;(Spj472%Wjd1cqbUuAVrdRO9S1b{}4QGagpp*T`uFhcTt zY;W35A4}cL-WINLGJ-HanZFHc2|R>sQ-Uf_pIQDe3}Z}3PQ9*=j&)2s9-}F z|48Ic<)a<>^0UGb;Y4yr1PI)iUl3JyViuPQX`HwOzXOs#$&*wysw&P zMPQ|9f}Xc)-1UWY2telOo{g3qJ@6i}Tv|?=1V=0*luEsaCbC1n>wC{NJ@%x#3A&WI zDJC|==$(pcUXHk;DKu%kF$eJ6tBP-!C2^o|T@r;ukw@t(8HsKj+>gpQ8j=b|K#xU> zkGwC=L?QI`&6#|se&#O{EIO~S2SQc^i!oT}{2k|AMWbo=WA~Q%lPZLeom_1{X^+;T z6wEwL->~m|;2j=0RXaJ*)GmMfv@{P}zM<4h?6lAbx zRL1|a{n2(~T&d~|JL6!iZQXep4V$MPzrW=y#t!XAeEQ(Q*BPSy6P%ByAYc5Df?$; z)$Nj*>TnD>YK{a&Jveufo8?Go)rASsa%?Q5CnHjh^I#~2L2Nm4L{t$6MZi&LX8p#k z1TL6kRMzx0VLzee3@U&=`RLagUEKOI%JXA?$#`v*qv0rGK9niul{GcNeSx3=m}ktr zgFzk7!J=a|cMX6-l}}rb#OPIriu$Kc)KdK|GU=i!4r?X?8-1 z5*s?*jw7>KA~3O%eUbwcveKe&whJ?cz2_>b{d1L(MICM~SwBU-J3Jxox9Dc9Qd<2e zi9L$#!1kc~UdLvz$~(rAxM2`t(~>_8+7T&7;9Lu&%1frQ!3ayU+7qLc;FAZRn}q|q zQ34&zxsqiy50gwUXP}Q7AsvIsIbJzJ6xE=l$P(?Scd5Lv_1_8o)w#>$_r;8Y7a6#-DxM0azMr#wvxq_HvLFsu@fB~-2+wXQ-K^AJDS%D zz(ZcWt}GM~J$wWJ9c66>ZQkpi2mUq{BYB+-5OhFbIaJ(%b5(nHw#MmRU+3w%uVT$J z%9Uu-ywS5CMLDXWX&E$VOM7VugpXgNmDgwRyUTz@&5LKJTB#KfEH{?=e3G2{(Ln&! ziG&SYHO2^|Wykqfb8U7%4zQ?dd7?N$FRR=(*Ej%Io9EW=(7Af`P6KmbpihbtKxR<3 zNp%LbjuioC%CRE{_}_@fG!DHpnWK(=Bmj6OIEWEhgbvxa`$4wiGVMMWB^uFnZVeH7yi%cDHP;2-l9R4hZOwC*&Qgt4 z>n(?1P^v?x<$1L6*`lDLn*k7e4$NGt?L}POHu5}WB+o?USBtCw@=!sh%otL{MD2)b zssr-6NQ09T2H*e@Lr}F(9zV=TBKD|z-swIn`~^7%kl4HXL4q?D7)$9NJO_9dIL|P0 zwLDL?uV6&^78h&bLr^I>uE>|8QBAoIN^UJYri$o3qiJ*_myA9CL`!9n5l}}NX>^s( zXpQ75mC-uM=eEFO%#-DlhI7z;UHFEo5jl`5c!P)@fEDfu+0>p8Sf}%`lyd$hHxdI44in(t@RBz%I{As)|D$pVXJ*UGUi(-1`A^*b zD>W_Swcq!T%ER}6u6*qaALP2AEySz7=f}#IKl9%5;Ju&bep~J)WmvbH<^z^*gf?^6OKakb=qsk`rN)(r2-GP(G zDF=`TfV?-n{T=20dp^$AC9KLB@`^bUkdYoTz0-RZ-(|tQ$nC`Y1coc&14KeVATVpzZep$^6rZanF;^0N zZwT=5BdW}F>IAvqN+3ohvoLBL?dp`|9&cECEW;;uU7oI7R!kv$|sK-_EZ&-*j{JBrO{jawAZp?XH?n53-vRB;(897gZhM+kGJgAnu3 zfP-@|BElSr(0(rUrV&^SuL9qy(XyaOk*eTGdj&n+A}vlfuHuWsHk5o6YFLj%-3JO$<$01UJp1_{qI-lQ8&)0t zR|8aAZ}c%^C#tj@fEXHk@AJ+(VDNn zFv^1#3IGinC;G60CW$dP4-x043u4sP5>e{kEhn;3+-wK8IS9Hbs$vpofQ|~VsLHph zaHwDCi~^RJ`0)I@pF&2KAPcU)RN_&fiaMPSg< z;l@||Fbm4udHb)ZHN(Pu1*4z&@UN*b;KXEk<#+#G-tY5wzKe1RJNdRB`nht?UGFbn z`@$UrK9GYq|K)#C?)um}%kC%cXH*f9>DT|jPnD0o|KGD!1@5(F$HnElZvE@!Gava4 zfR*oHehP^#8w=E6r z1f74*=fpDrd;;*HxXp(VmEHZIY~v{ILs^K3IstJwuNmuy{LRcU^-2-)u%DNZdpQ>X zP>v8dsa+fh^91l~;F%pjnUO)KISUZY64WvZ9nov=H-gPn-B^w{=@Yj~vhKxvVU8fj zj)+<}+7V|R;=Rl$K6Qe7OUCt6q`h-Y#Ccv*0nM}vt>0y3NY|Nuo70`4F-;^l4qP?m;=`fcf77Ya+1N_aRJF^0j z5Lj#$^$9`wVfE@lTM!5)HX-}eu#cBKN)?^E>QW5O9*q70-Uq`z4Dg!^ofK6wbeh8I zu%_ylb0iX=H+73Jr{b1C}c==$Z?wQBe}85JwK_e9z*0xk#vdzzFuz~d&81~Ws072&qMpo* zP!2V58cfm^V$0Tx|kpPz|E~^ zV$Z}v=5wV+?|RIg;n9aUREJ~Bx2tnsH?L`TPP9(c zQ5c8w`AT6ysZD3?Z>@a$rxwhn{eKSQ=UcErl!m0t*Y*SAiLb#akGw?KlArm=uPZt`IYH2d>c4mY z$-7nTYwf0T%lG|5Qt0s-))##hU-jL8r+oGEA1e2Mt1wgx&590jE-4EpRaq-8_E^ey}Z2dH-CAe=#{BK*vOCs}j{ za|^Zt#^*g#bqcD%&aSG!(ywE!5dB7BJrv-Clw%!LrBzjL*`qTe-*71K^8j|FX?uU_ zFs`|a-tW-^-TKHaIdUpkP0NU4l?JCSrYPrW*q>27TP-z=55($lmENjLa*?y7zq_`N z(sgX-T2~NUr@&nugB^Q5`&(p@@m78bgM*?+?jVW^0GZnZJPi1jJJR%C_j|(trEd(c zeAUrU*n8zldMFD#Gd)YbIYR63D!8Jh%37);+r z7IYVPFfG9zUU<@20-1`yJ-J#5WaTrMZ!YhZn^Y^9rD7_r5wVIi`I@f0%5`IeTh+w) zSQTK}$Ug&v_6$H{XMa@QJI#s_didy`<0}GV$qTP>!w_;r-#sB)ucRsT*s*yW-{l=K zw?R#JDfks zn^PxIk*+Ia-xjbK^3ajhAwZ}TucHs^A46dNSsWbs@b=eW)S`6;bSJ@b^jYj)HUq{Q z2DQSj$iBhDQDShFQJ)D(->-BQj>@+@2{r`!-^bsbVpz^AuE4bcLtooq&8#9D)OOU# zc#?w+@&IF+1vqF-qZ;a!d~g5mhY1!HVL~oXbENd;UxrI_7UJJ6_uOL)sGf?_bU<>V znM&(9UorNcSrVp8hGUBnyvXDC{;DH&tB|@zT_=OiAw|JRTP2-Vy1DLEJLak&_4RiA z%}9iRCn6u95~66`(@#BG4m|_IKT-#JG<@rDJ33)Q?6}|>7Cr%8k^S2uk4!_+`NybW zP#60)MT;<+Mmj@UA^;b1+FZ=Uj2zerZ0|6CLbT6lP|m_nSbu}X)2Azal{Q;ABMp8* zy<@Zp05ftPY3xTYyc%hY^GI}MvB~IE=D;VZ!w`wRLUneMnlLL0-mhBgpn{WG@<&NL~#d7Gt9#;K4|Kc0UOJDa_S@Z=xEb(j? zU3nvm-~8ck{ZqErKm_sfYrnHR@1<`oxBu2J@P3%{D{pvJx%zppVh$i8?y$G7y#D5L z`E}n_{_vf@pq%>2$#VURZ!70rbUmYwh=jobbN!3oNZs_&_xvA~+IizEf2eHOw5@#T zcYm=qQoHF@e~I((nLGYlP0K+=Q&e0zAUbC*e=|_HntiWSOp5f;Kf}j7gw=(Y& z0CD4%oowre{Qz72H4~*=001BWNklJ`B_B0Wif56V5!DN%fb6 zQpRt262jkqr=r~7}^1m%O_Snja5R{N8{akZH zGUs2h=U`B_wihFj-U*c*#=-s6WB1BHV6LF@{jyLA*bY$@qj75FmN}wPDQGFY-9PLN zE`4pud!q~0P`xXRlG%cTL&@j-tU-2oSz1)1^(AB!w;skW_Z=mL(Q5`ExpK+FSrJh$ z=0+qiUJK(y(|K0)462cxBnI+azvxNEF(jB)!}^t$WQt8IQ=jK+$l&&d9xe)!163xt=t~-F&2PhZBYMj1DJex_hC zW=A=F13)u_C#~T4$l?eXt=H3hf$p^J+{?@C>|6qieTi(conSWfb93gJ%Fu+0g zLv9^@Tv%*qd8GTHQ$znowLqOwa>&&)sJ8TI^I+quo2Jop+33D@yNFf=G=F9#z}}XM zS<MRA^o!xGMM z6skf52H&TAhs|QPjT~|)IH}w#kIzo;d@rm4fW!I?TUpW5YpozdFrA{Piftpv80nK? zfD@Re2&5`h8dRI;vZ!>E0E^CLgfS0L3!98lOFT<0P^8A<%2!8WthuuBtR1Ybj30nN z{2Sj}yY4I&TEzZ_%?F`_GXrA1X8k7Sf_~$kPY`6IAj~CK-Nf{!&wc!VsIPA+<;Ac3 zVYcu2@?C#OZ~`!Y%lG~R=JkF46Yt^}5Vd;M_xxQ(6;TieHqPob>&q?Q`wz>#U;Ie< z+T9=KS-5t?S>=}R{RvWD5p9GVpykPHzwal?S3dWFa^Kw_2mj{-(4QL z|E@}p1&~9g@e*E_Tn|*Kj zyfdrH8-DO-%AbDhon_a<_i&!puG?I0`{AD}AO8LStvtQw5xxeh>l=Ug=Qx%g z;(D+9fuAh*&~ zGjJF+XrIj)|E+$uZ`{~3itCBisumznj0l@ER}$g#Xmsj1fD)gdKVIff9A}w%0!b9! zi7>sDnGFq598Dipl!XdBMb}27M3IZ45B5C#@hyoYk>@N}VkHVm*FE%d*K0K3FUV{7ZtWJ5qI=+tgtobqwC+{wfZ zC8GrHmILbQn68pmBae0j1PE-szWS?@i|FJ~UCIef<5-SjskszY?pd(>x*OsQ080al zV;pJ`@yLL0NQaGcBAk)FTPCttzn>g3AqY)Y*~$V_C=5=*3YzQ@F_KB2iQa&*)+grJNsOW%uy&s6b10i4r+$192{;e?{iXl?xwQBAjdTt zO_0t&R`NwXh8d1w_390z?6T_R>3O#IKtY$<`VDpuYaz&i3xI^y5coX$34(%;UX|-M zZsGjF_Cr5GP)9TK2;d8ag;*Ho)N#I#^q(*O$sh1_09y1Jz37S?35pKx-$gk(=c4P% z)i=Dd{NX$QSro}xC|BO_N*1Ge-*5gri`Za%*F68V<@y)Dp}YsZ29HbsUV6=Ulo!7I z`^$TN?HzO=Kz=v{+24f9^TI}gU8JOIs~$T z))vamrlW)m0JTqHQKP8njYuM8j=keu)JDz@F^G^$JX@oSW)wi43^3hF5SW0GOa~vT z&8*rS_;I?N>?i41=vMq2g^L*VG^5RxhH<^;mGv2TU@!0`A zKp+{wxZx93Y@WFGMYk@ol2%k3MR=Fqgw^ZI)^jdnxE_s(5vlTIk2hMHhimjR;qOin zxbfHd^L=Nz=u5tHhxx?neB%4k`%WN<%B^Y`tqA4n3aCK0!9jWIBzj54@A(rF)&NI7 zKwMc+AZWbdHRS2c5hcG5C5MFMy-z+sWkEr#cCw8EKk3k#4I8^75s87QB(6I2Io&Nh zpEww1=0X-H2mqZwS)VZ#3xcP};4KR{b}k~pjz$`|Ib_c#jYC1-6SXoMK((B_eEl`A zj>VCp5~vgRl}H~sJjuJBqmQIKk#gCkQ~LQmj`sHuNNR=|K_+FQeNGB7@@DM3$zW!H zvX_A`S0WWmYV!mmOr9ls^Sz!nWNI`$qKTZ#$Pr;Y%XzlZFdf%Xi=6n0aXOE&JztcW zP8(2i)R)iZY#Q3f*%`e*Jd=m%1FW7y z!Uh7)fZdOMorcMf?it$a%iaEro~s(G$$GC88R?MvGvG)WM;q?S(++y=qoDOH0_ zHfLrcD9{!IgL2b(qJh1do{|+%eR7djJgvTs_HV^ zr$pW|z46iF!zln_RS4kH!4*zAwZ@^6s}WFF2gS=AXVAHuT1tD?>zQ&mhvd5NY_q;; zfYA{~^^LCQpBAR05@A~)XKT}zo&4N0Pwyi2&QZ!H*ZuQ*P=oLqu-VSuelhbE0hmm& zttT8ij9eDRfpH!! zIHXkKtPVq)-<2bRbM69pi>C?l;2a0AfP)`%k0=y!IuRArdIwm~MW>=zlR1vOJxoq64gYfP{DteAbQQ(&1H5DZ7dXAShw+PzK+NvjqS;4MmI4g z>vn!0YlohXX!G&uKl(LZ5BGlM_xv5& zd7z9cGF8g!zW*o76OY_e?*7yt@a%&hzKf^IO|Sk-eB94|^f$u4 zJW+0X)sJvZ5FG>-z`n-O^09Hv6*m<+aV0t2<|4t34?Pk|Ta}YH*K4q%k6! zrjFv70fezej(8)GVb+-)WCG4&@6kT3y&QE{&!2UahGN!*+P!h_{gYq*;u3Q904e|s zk@$7xcjA1rb+ zPfnGc=Ur8fp!d?#yE;)tU9WeYYIL-_HLvrSD9OOG*ce<6jQc%Da9M1q(u=xjt(>XeZ+_ki3abY-09Q~(X>3I9o};y@%qYcE=Pb01D#hxs z!-ejqj$wx{<%UOf}jWK+o?r!%q#a zosHGrx2%hH+6CZ>epbUNJl4uJjYB$tGlET*#}DJS7SBoZF)B-4fwLh}#W}=ur3hn3 z5k{Y(aT+GmJ(s&~|NF{87`^KMFTi5x=I!TPPER{Ly^L&(`56L$-jf~KJHrTI|2CGZ zl?pi3?+x9jI<>~@GDn86&m38WT*Fa{gSh*X^Lw>7C5Qc}-pJE**#d)e;$1of7vnus z?}EnU99vFe80{~o6dFd4!VU@xZx{aLM z(I2t)88h>z*Y3pQ8v%AB~;RWbH0S^=vbOlsJ+;sjZ zBCrxz)cZKga6R-cHCR_g@mBq{Z#(p*6^>Yd3K`TeVij2gX<&6$M5}OtuVTF{btflKl{<&Di7WJ85M?{Q7$2X zC)O7j0P=g=5C1Il4Zm^Eoz<3o#T)-t+4bmG%U3@4p|XTMJw3~);(`5-l`q_>97f#x zC9nBQWZvEN@&6Hy`o;2+*Zfaq{f4tyF_wB{X{lU$<89@Vt6oe8$!91(o#A1qU*|Q-uz>u|Yd&ItQ|+xN z@@G94^5{O%%`R0C#B!?K$|yV-1qGRZ84=N{H~kDQs#Tee{WC3`MmOB_rlr;EHWdgl zyfgR>frC;&V|OIA0_|V>!q*Y_JiYf3hNllcy^HjmQzw)dY~`)6D4Mi}p&pyDon59) zh6gb!vyHVz{$GE?zKF)l7-tNP^S*OV=p~(|0znck8qW(<%3I~COAJ_{DixxUCyr4# z;dR1q+}EBMf36=nlhHC+cAz};>3Mpc8oQ_qa@*AQz+*Mq&m1U9?z*4v&PVqict$E~ zZiJQ_m%WjuxWE8{SA?6b8VKPHcWy|fH!i3(iI3F|l_+{V2A$SmM#eo341qs;Qn4oX z!ZezWHla%lhn1+ixrBG*WBMRs&p*zM=AiFn7(^B!2bq>TxE11Ad1ggUYR9mKQ3ZNX zZoQH&lnqDCZvyOz_EtS?InvhyyIqf3c#ta>UY=(e5Up4ezEexYn?vvBwqX=zu6~|_ znv>|oc0^_%C`0+wrl~(GMHZI>i~Vc$*JcP@Vh%m#GXk~WqVB8Ji$mlFWhen0$$Og{ z$N{24pmQOzNOrgDdw_xjaV6L8boxBnd-PZyX8EFx!diupa? z3RoPsS8ZhUtceb_JCsC6S5S7M7pXkjNsd_%M%AVBcYUueyy!y3F)_?KTLOW|Gj4sD zO&>I!sViTa>9rfqCRjv2Iuy%b^}YaIIwvB3ujYokFhuOs>b=(^={qu799iNuQY$Y< z996jx-;z=0!fCQmP~bv6W~-BuRX723aUU671{BS?>8h||dN?8)6Rv5`U@@GS`F(yS zdNbopLk0IuTh3vVb>ws+A_m7yjf^HuwbCBS(Le7Mq!O*$xRo{l0aWTWT&cd%Lc@%y zn0?+3z*5FF&S^17(D!t9)m%AraBoB%Cu{2mFPY^c>uu{=?ld|E+#g#7M+k~JmN*}y z?f`5~NAbYq!e?Rl0yJ#cyp6yM#yXAuuo09lwZQfsELwQ#L^*o+X@Vc*A%Y?bwgl*% zXgz{+pD9G_|EDVX_;FsO93$Ryrbw$$Vl8gRD5RoVb~5+(I@U$SRV2@f%!17X8J$uD zvGyHDuklq?2f!XjWYb_BpPOC1mS7WpW z{&&Iwr;alx^0puP+483!`>pcmH@;BmjJN%udM1AJtDjU3-Q+ZLF`s<=J{G6Jx?|j+ zs-o5g*6CAs{MT~ynf(NsNQHA$5|eS&b6;7W`_i{iUm`Mj_`p-j83e!&%BR#z6mPQA zI(8`Jflj3;^d}&vb+dh<%C?gQ=}D~0i}jC4IIe3ds|)Z^P9pCS*9I-u`k?CLuyY9N z7EVWQQO|+R<*Wc{LV0 zkI|GE?_Zm8J9-=jMnZc-fNfb2)&qat4~tq(UN+p;o0@ z^V9Zpc1Bf))u^zK0@NnFn)C3~)6h4A!&JavVo1EgITtzzudUy-l|AE*A3s#~?|vx2 zihJ0aQrg;J!B`eJQ9G-AMs?W?jopx+Iny8w6lGXxzLb}wIcm{S6oQx(c+msbXyoXe z3K(!cgPz*P7!nzVm>r&4yXd`)C_z+7$G%&?aT}w4II}@F1Z~pSb3|?kg!kpQ4-zHe za{iok_W7iu?%n+$0TL_GM(;ru)eA$KED%scZA{j}F#vCo?;XZBivUhdM|w**7lTf0 zx#aaCBGXc9l%n9Mu++HDY33VFPBA|aR8r*sG4jTW<^oXwE~wgxh|=kkCpa#oPazVA zJVw~7mc2BUFPQ2iJHlFax{G zv0Zri3;7(FOBC*bBLj1Q^*QgN>&oXp`Mb=|RKLb^Sh*C1Y!2*uoOUT9+pl@+-)H4k zQW}k z3%>JvNm<2s-}mc3%i>LPbg0t39iOf!OZqeRw?R_q1a;AgsIuiU(@tX@&6rS*p>-^P ze$ca7tyH!pqLrX4;|Ke#s?*Rf27zV^K=u{U?AFJ?SWOjfffU(__)(BUI!pPD6E*h| zdz@kr(NW19s9FLOMQYJ3C;>LQ)*sz4b4IzOS>70wMB^X5I zCkP1u3>F1KhrEQ%TQ8tOf(HOaH{j(^8C{hl{`4LHjRpq|e?*fI=0%^psL<0qrtLJ# z2gUNys%L9*JiE`I>4Ban`poapz+yH&yM{t*3Ji}7Ha$E@P^gSbqKfP6T&2&Ls^c&? z-Us)ahg=xo&eH&q(s5g~7@pug?h#o~uNcA2yr67YNBA{_S84}n`E|ef(ghy=D z*KPrW=6CKJ-Tj`TTA88wADZ)Qu-NOK4V`AV7;GjFshb$nLlu>M(>hVPgn=y&Xj@YQ zXL?9k=2`M=g>7TgUNI_bP{}G=uR9N-rfCdPYRX~s>-cn|uIV$&&&TLa%s_1yQ@Xg{&O`e^&k>FT zeXtAK@miwhLYJYMBXZerO#nm`4^(x;(D_NPwS5sFwJul#ryieyS{+05>4R~O)&p*z z<#YxXX$vL_s-)|0ffuiV$3%IEf@{#{0E}2q=XT+I^qJUby`Xr)P@fh}n7VwL#Tx)OWghVy>2MEz{nO>kpM5{q^VYZhlk(ub zf5M)PT({}ja?`7SlxwVtaq^3n}WCoCDKBn#(D$K2)&isUt={yqBH=;O<^;|x@ zOyQuYvlk7h28xDZ!@}c>yifn;CL)bMrG!NR&<3GLGv&>W0%iBh6g3s&QVWs*m)dAemJwOk;V z?-zYTR1JIb1-1>)(ccI2G+G7Ka}x>TRHSk+(ZHeCR)$-SGA%a`Ueh7xlPMN@1{KPn zF+w9mo?(MU-FLLbOrGyP;E{oAY8zcORY|AdXw$pjF1=KwELvxXfsJKu>&Q~|3PkY*F2rXJ=<_Xue_Tkigxrj#7lkGsI#JFl| zjwEKsRQ!8{$=-b-&>_73}8A7pkIG{ZxmqRn*Tg#qG!Lyy>jl%LCt07T8UY`w4?J9>c4!;w}Y z$6FXHp(C_}+IQog&p_EApn*++Lpwq(TQs_Z%5Eo?>8Lag0fZZS& zV>h2+4J`6it(_whkt<|f0>`>qIczBh_dmf13LAk3y|FQWObKsu)o6`TCD)NqNp7Xw zN?&Qz(60dNIOCAJW*ujs58XH%;NJ=x;)rtvyEw}#Y1=F>%WQ_&|C z9cD3@+0{z1sgXQITyPcu6rh6W@uOm&0Z_RG6wU`wC)ryOzkOaru_M-es0DT8q;-1) z<`T{*?-7$g$2g1WMc!W&E&bhd(`+IddzR%Yu^f39Gc5|nAeTY%}*Fk@=rF!p|zCY~r#CMc3q7&neWmx2drcpdZk{e@@3@4jcMY#tenlvyM zO$NJ%YL>q`FZrQTR8K&&MKHVT*sj}m>?ohZt!W0%r4-5S(pj56YKN!_Qy|~&+Xfbg zB9A@CXwwCvMj0SU4K|N<_lzEW);u?T*%^7Sx6j-9ingVEm{@tAT`sy1XF*rb2i>U@ zQvSAVyO7Sx{ktFL*-~XKjLmTd%hvB^f4IBYgxbq;2GyB3X~jqW=~X|4qY4Due!^6@-n)n zI!E~VD9WZitds`P8>iXw0s0cgH)I;dx#*1mBLHKK&Ss|^>;asA&R-`zF$`KnG6)Lh z*6?u=nWE7OrykGZB|4-rV`_GPnxInk78YxDQrHu?x6a<+uFx)5wNwJO)B22zZyCBR zjS1`^^p8WK8C9+%Z4d1eW>?F>6wz^1fyehM_(U(gRhSpl*@$$LXum;VIi-8sfkjz} zygH?ui1KL1mSjmnfx&xR*{y65(^NN0#><0;Z4RehOtH{-iyiJV5E$=E2!F)zajU9Olbkxt6 z^_zDvxPa6%T#H(lj`?u1#~EP9jm(9nhkRB`TW7kwby`%X4QGlS44bx`SDyE>x0Ww` z<~>|*U=IApwsou4aNhXZ+`6*uyvy0A5ydNtyFba z&mk*Dl}H61mEUN}sw?tF72s54(YmC9JTeAkvntp2gurxV@^slz27lDKQF)(09+gbv zJ~_B#2be)81W}R2)O(keq2<_bj^XH8o9wE5R`hKY>z@u->>n&Xz>OPU9I`BOnmNbG@)TwRD03=~( zqKP%~Q1(6f04p@Izy)bw5zQGeX#0kPpQmq35U36ST8%rRh26!{p09>wib~p1maAh{ zebeT=g4vuC9fzf^ZT5q_&v3NC0A+!jKWk*M?|iAPK)O0H%a`}dsDrc>hU>F|9Q*9g zt*>hXyUCpNGNVG#D!`t0H;#7Ek-8j}g%FiUy*ua_5^b&aY2JEXIdpJO+4tmwRVOpn z5uSAB>(I|HIjs5P2Bv9!YGl4g6SZMPFi0ne^1Zls-OxIy+ybit2%@CQDT&riDjK1* zf=cDfV6m4YI;3wpPPe6{vU%J2^-LEW2YwNA8!ajqq) zlhdmhsT3s-IgD!*Epl6%$nj!(4}xV?7OhlUGe{^G>e;9^3N6>(&DRB30~jwxKCEjF zguF@qWUw>mGOp`=26@NaD*~_Rv4Jz>QK?3&35sNAM1*eBwz7WHHbyO(bGUjv|5gsE zayvn%HI>e7VE>`dT$IkMPSfEYA{a>w~sm8bVUUY_3bFa_1L)ocXxqfYh)_3agT z{91CTgi&-sSIDwAGjB9K$g?#G|7@QhLfHK)DumoC&N1XkP6w8+@$CeQp0gaqK=V@w zq;f`cD17;Op`x2siE1?+ouqQdA%p8dnXyt=^u)r>s1#Rtx6q_@VLmF1+6;MN9107o88d1>Tn#E(jSL-9xDxgMA|z^RezI9RQ`cT0Zi3J4Q~-KlVM=`sk4Z zwOTD@$j)#_-Xf`-6o|;dum{UB$zD^aHi!3}gr1YSqw-!ZhEV5>z*7oRI;Nisy7C?$ z0_0_4s?5yHk`{L8AWD%dfjxhgIXpHPgCed9i(ulbU0sPZ+cWc5n-B<+6c zOcdW305UW?%EK(tbX*2!iyX?gde-)fSg8?)zQAHoWl=J|nQ0qr*c{`4rjAkJczp zj@Wi}v}8uWKZ6Au2rJ4>))N7$`RpEJa{cj>Ei_& ze<+Z5=;_^M&+Z2b^3(8R>Z8ZOvp-rhv?3B(SMD}ir>zZ=Qx>RI!`Os_kKoS^g&YNq zqB5p(sR_1OBCTDLjWS1+oDb=_GLvL*KSkBS*vOQd3od&ef#MU7e3ebc5&4l`MEZjo zfs>vV)i5g+murHk24qE79nSOc(Vt|!XL6NlUW zH)Do1CGbAxUC|2XM+s=2B8Wv~QM6XAxd9;@&G-xr{dqBW08H5+J=zbzwt&q*@Rcg! zLf!!YQK&=L!*73Av{yOt1Y$d2aUMB*t2ts0G|&*3EK?y)M~o@{8-T=$IK065x8CV4MWf0J>3ay*WOjrb68n0v`g2 zuJ}8{IwE*}Tn9iMG*D1u83aH-@F--1wi&F<4~j5y4x^>pH@|vkdE()(luNIEN!f7L zPUZz7nh7~V>Jo}qBBhLZq)1(2)EZRcWA#}G=A+kgwlxgMT9mIFD7xgTmz13sUQ_<$ zj{l~pFN(IXAF7<)va?h<^-Vwe3+3)lznl4u_3WT?x-jpsQ@xf9v0$vkS!|{gok{iV z%^U*h7UfeLT-q6&gJKG{2>hK?RGbv*U^IjSNL>)rCzPxxx2h=W-Olu=uyG)7J~OqK z;hg9LI!8fMN=7Pz=E$YwS)a8-2-kwMf@xSm_qI;M=Tr=+74vG&;YEPO7mT-LW3!+# z-sw{(*>4eHVN?6YfknUG%}eScJ$u2hA(SX8MQ0RmqfmB|LBo)${_}e+KVLVh5QjT+ zo9uz|1cw*UilBm(x+KdCcpMsDc8O|)HZMBkMQn<5|9Tsc?qL{LW`*AptHeL@9A}`QP5=2cZ#btFHL7*ZIIP!r#63l zxC}?eI0pm9W&hc&B<=b0xU*3%<4gx!jj#r-#I#O%x<&o16q~YC;Ap^lqGB19VC0{W z<`B_qjsY@7AOU)gOU{QO7m7X`Uhv2{UyhzIP)JfGGma~~X$Eih)M`m1H=!EPEA5RQ zO(r6o$ZMUNm@ex#Z(|NoZZG1w?$2c(ERNGl^?Pv`87Ourh4wT&3-u*$dAI#X{dxk6 ziiVE)T#mYjr?KkTaBAQ_Tee>;u(VUUkG-SA>^)=wAB#Xnua%!>t-<&QVg{ zZk!R;mC2DX0Qz_|Hg`6TXhci1q8)Lw}HoX~LabeLEH!Gs^0wBMORl=9TyW|0%2z)B!SeWnUrPP_ zB9a(wkrYtv%R%H9*%`^RQAS_3yPP_qJ>#+hj9KUg1 z!Dt2Ga89E2Gjq3Kth316sY*TdTGdtsK@GJ*?nq38D>*iTd(ucniB(j{4arq_jt*d~ z74B8RB0!`lri}gq#9=%g8Y+M)D8zDr;loonGeWoN*&(M%n`3?=MMC#(h1Lk9aJ?x| z7vU5P>Tdu`bC?uWsxG$#0$bq{?VZ%auIEJ7*{1QifKOkaHXzZZRyO_B9Ru?pnMPz5 zP}75Wwz)avUMh+SM*!?N1O_&reQx9#u3_OC6lOx8$e;($fr3EDB|LWc0Bt&?FdaFx zUqzeHx+FRx;4>$V9%3XDIv(pKhr&O*V5l@45`F0fQ%uc90hN%ZvI>YnVB6JU@+vC6>wSPX^Bpgnxf{k zhs0=*EVU}pP7kDx4*SY9aPH?7!Q#|xIcwVm6qLsvyqnMK3TD|e(gzqeX0vdInOw^! zS9)Rc#`Xc|2tZiLn0S`&4~^T0;0Rbu#T1-#WyR&lYS(L>C_|m5@56)aJgX~wE)$hX z9I{F|WKI}+4o#J{>o%7Sn|73^c6~#Acak@M)DUiCa^Z!|8;D}m_G`FPqI?!fByXZy8 zoI#^=wTGMn^)bfC*m58c-=(pP;tr&lj@L814)ebAMQu+5>V<~BRgA$#xQ1F-or46;VglCpumkNb}|dS-voM6gtfn3 zQdVQ1Ive|SFI6z+0#N#T=ZqQviB*I2#$Y{>Bjy^`_;DFrvPc4TL68LF+6HO{k-U`w^8GQgokAeF)og<-cF}-$ZI%#AeZ^f z&FkVS&3rBBg{Gm3nG*fQJZ>9Fb$)`%8kIWxv|r7osQhrEL1wOb{w*vFa^IIfR-V}} zdb>WSC`Ro+9YE1*SM{)Sv@L0lcvbp$s@O`39H^$Vs^VCS)ws=&TTP+x81ny2gB74; zE>!fAYtdunS`suOLKxK*m0kcksoDfs#~T3I4sztU=@jRddhf_4a^9GkD*2q(-iTC( zs38EuSGk9(mP_j9{7DtB2?JR@^j1X*g!c}fHGo4zK$Tk-d0^CoXomu)XMn~;&7-^! zxVKabvEy_W+0mwb+8A?QPwILyPpl8R5v;C)@V?Y%^7WdW==8!P7EUud30-k;|C43Uu5U2neB#(MtSn1=kTo<^ zlyU2hOUi4%?;n-l`_Dg7jvd~wXNb-UT*HX?Hl|~)hoGw8m5y$QM71kIyE~;J=}J>N>a zTQ^ax#iW%(kyTdNmP7f=viI@%Xh9eAAUd|>&f|8_K)Ks0C`I{S2`u7^NO*-1A+iV$ z0upuG0W@rpVDR?5IxL+PV@LRt0pC6N+Tm4^N;`+47IPwxwmxT%ln>S#IS#{#iqD7eU>;mkqMjK((}10OCi0jU10HKM zmR`MP6BRLxI+Xm*;3*r`dc0h?sA{it*{&YcT-rbkU>)*9u;ps81Aqt5LnEMtzvIwu zx9jg;kC$Fd;=u4~Dts~W)4*c9og!8kH}b7EpM5?H9l+REBt|BnE87m{TMo(pGT>yK zJ|BF21&~+gWF@eeFW$Q*=6(b$o>G(LvCr%KtpFISoQ9}C_ls5+hGY*2W-vMe7~26_ z5BnjR$a0(?y8%hbw&gWD1={@^V6=|tIIMDXGw9;T`J@4e$l|`o(_WV_=F;BqP68V}{dEe-ECP&(E~eNUHfDII? zzoOGN{8_UcV-hmwy1Vk9QjKVe8V@P#D8pyWut|(Vtf3vFgo}OoP6Q479!T7PC5Vh1b z)|KD>4}VvCtmg75XOMFng|0#agi~8{U-vpeW~4oYtuF_N^-lo*_>R{8B<0F;s_L_% zE!SvXI5WI=NWDgWW8~>OUlGnW13Ad8EB%`dAlpGL2F=hkeO$r1aA3H1Yg8JB%xXQt zfdHB^ut+ci96dCfj#2n1;w0t(TE$2gd0kCcow(q#=W}+lAU5Mmh6XA&p~*W+U>`oT zhlYKli?$;ue~(@XHz-etxNihV@wa8|p5rpI&IH(WJ&wcP)BKrifY&m(V=b4qQRLA{ z)PnxlYdZoNiayxr<&4CBD`b1s3_6t`mnx3NA<1D?PpIvdCe+*P>_ zYIx+CedXZ(#|Hx$2E~?vzTutcsXxaWNgwcZOpJ0*)hKkq1!ZrO9gP z$m-Bsjuo-`MskqE`1%TL(E9J~lUgAw46{C7$h1_0k`_5BWy7ZJWE8;5h z65CaA#d29uBHN1Xvj0e`Qc0C##kNYaY(YQ`Wd-wZ(zXmXrvcRH&>HaO>_rCY;a_+h3q89^#4W^CU`WeN}M?e~t689tdy&CJH zQ7f8(CBY_KM<>~G0w2Ay4%!ETG$Y)$)pQo!D^&$0DvKR-d@x(g6-t8!8O;VzuyEkc za_Rhua`Ehm+K1wxfOf;ZMq1!jvHJ5$4*L({c9X@f6Y;|u{#eszdLO;+Wbrn?PiV4} zfkuCdL0nd9ioCQ6e*#=Va0S#}%-~^${?Fcn?dN^qp20t<==8+v-5B-ozTuya4qvN6~e(BHeRXsMd1~p-~HvE3yp-$(8$nCPFx$*VKKhsuKV9cW#M1{7k{T#&dfM) zxyIr}HL2|>H+QJ&!JrUGrbtvtpewj~hOBB+4+9FquKKEg`MYt zVF#pWI;Oo;6>jsW6Xh&97xDh6>hBS27^us=j8gdrBfwQh?H#P2Au9@Oh2WFgz3_c8 zj>SL*tH}Y71qfH$6W;jtk8YtPtXVgpDYPbg2OcOfAH3s%a_#CR@`NdJ!#`aI)=4r4 zTyv|Obnz%xgSPYK-2mJh(y#72)9e(t3)cG%wu5R_gV#-9`zUYTa7Oa%P+it%!0T}j z*nlzC!9kfH0t3jHQ)Cr7_jOfNu1Arn_noS;^=WKvv08_XdhqB2+`OkwJk7BgD=SN7 za~%!D%~^J1onaM}{DYKwC8wAW zPtMHokfBQCLyWaqTUjpa>(}XIL~&hZA}M7z@W2yIuSW^uLAnJMmCw$}W(53tCJm+M zTA(>1=7?3AXg^8qEN@E|y_Q}_C&1jlP9$r(-jGoD2U)q*qCYvw^!{x#yd>=5#1Xv# z`wrb*&YpU%tS(>eAmlcHxNPp}INF^A-O8yk9G2DdTA9^7>OL%*6VD?=bbOY&OVenR z{?3~viupX|W^T`df+E@Og(Fn@MKix%9}YTKONP+<^sF(+SAm)PZ}J>VC5D<6X+eve z_;<~x<~;ftc`tjNvYi`t&$dslqEPqgcia3gzn>1_Ji4dl-n@l0{YbTpcm0Z*dC53+QvY zc=pwD_41jR6{m_A_N5Z4Hao0V5o*=Vy?ee24HWmIG@@U_5C=b2+6{3s*cZ(+)E_?w zkC4!OUL|U3-w;Tpic(bga^;x8wgAF~{m09j-uY3+PGA1aZ*YVGt~Lv#_=25iwxG`H zjY=+@=;C=vP)13QfE?3h18^fVSGJSMT=Y5BYL%0W@H_BR?pySIb1hYKs+2~9)~HCa zRfI$w@5nCozR}m@|6N_{_;MkMUil#hJI4;~*QP!;;hSN}qEsUN$13};J6Q}+z=>oh zS;QI#H5FCImUOqiMpptgas$e(qV6eKZI#KOk%=-(CCznJuk&|=(z=rO@Ec5$^?D>A zwF1=D9==dc7P9A#W_mnrh{UhbKfAN2yQfvOBK4=W5*XW(czVnC5!6WyVKm3jV zsS4TPymD8Ae(wTbcjL`(*hq(z~dgx_xE>V?vAqjO(ir?nhGb-*{ItkS3Oy8Zn&s&p*n<_ zS9oqn0B{&p9UWs6yXiK3eTc<`TkSl*91smYYp+Rro;h(HczsF;hVGk4EPNfhANLK2 z1^@~JuGvalGdmY58jkx!MG{Fd))qaJOyGl`jReVaiNKe~9%qFT^Pq?ZDfsoFb0aK? z^)o|yUbk|CG!O*L7tg*z1vDa^{AJ9+)FSB1!r^qSe59RphK>4b>V=ZWHnyXo?Usmd zA|LwPpk}5u?C;58!8Kl^d5Ux8`nAiN^_9-!?uElj7MB)HfE#Yg(ocsuQqC=dqh?=& zsh@3TTTaBhe};XLsZljqOxZ&`@q}nMC*VDYVaMoIzI6Vi&Ue_Hp~;G%4F%!h+_VTI zW!K(AWFi|T${o$G+FFZHE$!4t?Tr9D~rPvVrBf>()TKhSVy3- z=((#si?>J?>xmlzD)iUiY#XsFM8~WE#W22b&)K^=F+7nJOQ-!#HbM5&qb_VO8n~oB zv!G(eS<@2fHG@7@J!J;mxK~r98wn2vYJ=f|y~Eas+PkOuWQtQgv#zQ7>G25lCjB#P ztL>6$Zo zz*tK{!e^v0A@sd5Ox|=kDK?5$=&H7py>BI1taQMjwYDBO%v~0(SIMGgFmm74gj~UY z9SuTSqQsDt2#VsWDi=OSltYT;#3+~AKUqgO#JpSp2kRL1VNoJ|m;ATXU@iW`c-&QQ z^&y1DfO>r;>J&nMrujxph0nxX+1>l^C@+8Wixj5Gc8k5eQBA8>A;blpEZ@p$cK1fJ zzt|7&`oNEuox2W{KlrtOD(jOAHo?YGRd2Ms=fnRc&-$l-@1Mv0nl;ptb5+aHug47- z=Q0=_G8nao*>uqwv&AzBZgx$!Z3``erR1$K9&9JslNrnc>_yz4tBqz_F}bC^Z2~h= zMGks#wEJLf;lm9eTZ!00NI7}OwOCod?=NfLWIX>yMGl&N%oXQ#hBB@}s+u_Bz2Elj zAKuyn%F)5Q3jRik7lz$eaFgcFMpkMIBaIh=*Db2SL*QDZX)Lfk6A^&FK?R8 zL9V5d9JK1+Ex_nt<*}?OSR3}hIziXqthA{a47HU6`Res0qAS?5s3y`uj!!UI1YH`* zAP%jN$F(v&yNAi6XM*8#K)rxL$7fNoHO7A6y%+-mr;YF6Y)KBgg>q}7Hr6U%R2JOi7RZqUWbXVQ%LFZTQ)f&qW_*OVoYcxq6CyQP~U?+!)~? zaU@KzK?wN$9tV4N#JTEWq_Tl~t#Xh7pS*q*;<%lpF(->r?HNdhlkLdjJp;|Ixmu(M zrOL3wDR%^JZjvl^5~*yr(&srTbRcBl%YiQcyYu?KeQb%4lf}V3I6_)DY@cUhBAABV zQpLZuH?+0|*;WS+rY6}FHzq>Y=dzb9_3&!{#d(i@x`Rj-r{~JK(=RYtBrat2y$JF- z@ICsQ4OHT@lng{t*Qrj4S%T{|Em8Yd%9;2qyjQ+U!6U0JRzOX&+lbYNpR56R_z2uT zePkr8j4uNu!|c&-d)xQ2^8TlP{3}$8hHd1yh)s+KvTS~SLeY~L31J?xje8NTQI)1j zE6kb+QQ>f$(rl}ebhc$gHL8B=NGTg@Yh`?5LUoDgk>>j1KA}Ak-&>W0S)ml=(Y=7R zs>J66=2;pr&WeWr+{~wUh5i&9=47#2COfd&mZIcYU_k5VL!wAeL$zL2M3Gp%4jL*c zzYUm#-KAho^h)aTB5|+DqDEVAeecN61j zLQUCcRe>9$Zcg%M=NHP<^nBU1aJbCP@1+4o;0Upl2j2MIl!r!e?O+ng4QLn`!ixk` z1|31Q92K669zxL3tR|I|)LIbP<+Zz+vjrjT_jwcM-wy_i-6r+CP_5^py+#{CMyb*P z2ZH(b(9Qi9g(7+sh`xX-kQLyd#q&Pnbq-XUVV3i^Jz^jb zmAcNlM26i0k3pNzIpduLYqbI-i`WB5ioTU(5#J%CS*b~@&bJ11+n0O^Es=@+Zzo)< zlB$@fz@xxIM@2z&1>+(OSHe+<&@SvhMpZe0Ctk~zfICPF+H1@=%}F1=W^UJhR+g6* zFO&;sUhE``eTPJ<8d*;c9;1>Ty)nUO>r{!Hyt&mu`y=L^CE%;`*m}ugU)?!8Xnl*5 z@S2RrI!f>%W}wyCf;qeJ3?^8`h~#Y<F_6vC2o0wWiKVRm`Xm);v0%D}SDqb5juF;FQw)F}Dl0 z;?U6t=u6I?dY)&?YwLuk<0siC)Km&(i^2|sP4-s`%#As_S%@J(7zd2lU#9b!8d`%i zZMGOEpa87)YvW!ysseUj)gkvD9li70$|G<6V7a<@zC87%k8`991*J?Cjihe)W3#x4 z`kLsUBCvHup!Olwd-u?C2<{+A+$^IUi_;QsZ53CXV*i3_wyFN4R?RTr(9}KE7w19r zO0abIyz=>X7lh&U~i{=_H@?OYnVlI?8kC- z7O^1OWjGQh_NA!fqC~4l6VFWId={l~58c@4geu2ON(Gdt`X2po0n#9GWxr<|B7K z$|M9r2ym>}Y;X=hxWM5@H3D?jOBYU35e-$E>r0}6xwOhg=IGNQD(E4=J&t~+WNJZr z2}Cr0=47$|a2RBfdeMSWd{V#JRS%)tBamsSHZU|$;Z*cFLX^~$-uidkQ11YN_Y9OS zDug;5N|u1!@iW3R;h2Pi+>Vqh*&+z-ha^zM%lwC`SrF zgbV|`iMf{iI@vVCEdWv=Muub&`_8c!6Zcle)9g(rxscS3xo1rJMs|?0j#-1tS1*=x zuRT|nufH}qNn*g@Oe0Wf3vY;K)4;e^^_CB4y&XAV?45(UZh;o}lCEI^OHR_dl|0$` zjP$y-;`Jtr*n&)0#D=}xvRXPuOt!}pW+V4gL`z-t9?=>)J$J~7wS^f+A6#LwN!nznhNc1A>YoQlAVCtb!35ASAr2)_S2``#PkLu0xBNQ* zTK7j*3Z>PZ(`LnE!Zq=KZe6NEeM;0?OOBGG@o@~5*PwIGZ020Yb;di>GxPj@FoAI0 z_!-nRF>L;Yr#@4@`ni8sukV%uH~nOhRXnI&O1!7;F$&A1WHAQDy8`RVo|BA#Vb%W? z2{&n=Odw-KN3;R)`@jT<_87!l269?YsBE1_GpG`&>$KfbpR4*D8xY|ce=1a%ZfO>j zVqAR`I)aC~nbS4r1cT^bI6@;dUO2radZ!#r)c{>bKL;U3d|;F*(Hw*B zmGL9d3pW&KV{0xJlEK6?`U7=XMGM74HCp3j*xYA3RXcVX((x(wm4R-FfEP05J9i%} zd-mPIXM>;Pc_Nv@!FuW0&-3@Vm*u6)>_tLV4AfN8cIr`%LCn}-v2H{@;{{zcx}YgU z!#}PwA9g>EirVHqB+vZx8MTSb>C5 zl-qH>k3*eDMru=VKzy~glZRZ^h|3@uKVcJSzZ zfJe)jSDy~#Kfo2zy~c=AqM88)0#q{{gjvXm0azI9`g~2liF0GeVk)Kh`0GrxDRyce zzfonQ>cm=|6lb)~sJrWgf%5ixzr2r7&BtE4eBoq$UbmAhsyfvjOTo2w6;$Pl&Yy~m z*UG?P0-wRF_GUOB1om40{5f{Mte$M$D6@0B%l^anm9wus#~w{rO{xQr0Fe$mjSO(` z%`-nbT4rYPIrk7`IRmgD?BLL3(E)&~KF&&mMUoT9p-w1(2ie*7Ec*#l=er}o&NiYs zyXXap3Pi2WR)f@NpN#?Gu>cD4AkcEVmBoDK`pB*JMEuFji#U%Cw7Qiu3kS9R(eY=g zvX^gZZhoQcL9#f#lfffcDCa3hZ?OYO=i`s5bbRi-maZbI&j5%S&ueXkamIsh{vNW;P(ZM+XyB?vi)6dmFFrjNtuNs- zJ@+tX7kW>zIvtfltVN~Z0cc&j&Nu~y2!Oh7&A~ZE|L7-w>whUvfB6&LWYPONKu3$< zc!pi4vN$wZ+)*oo9Lo`F#(R$8@1*N)#H>1w*g%C(fQNepxyQIQL@lN2chIH%nFQ%b zmu{6oKNA!m+-Hh4&1$boRPZy;Aq|}Z*!h@I$?pwyRJVxmJdEsMTn-_#i|0h-h+3s z3i$`W`cKNKm!GVHksiZS6Y?b5RPAG;3gdRv>#6gjS(w=8qJq1+DWAGY1_r?a7Y}&g zLZLRQz_yV-4@PEP;l=N*g35M0Vh0kvBoG`)Wv*;m(1sQ4u!D}VTp?!i$JUpcyx7_B zZ=YR-U3yIenYw=FX2~L-MGcz^Mtx>}fz(zQVN@0GdH7xB zt_Qxoj7?0_2wu5-n*EVjb0qAj0`plcUEyaF(O{qv!Iz-ON&~{b;Y6{Kk?g`~IuYjK zX=ROWyqKJSzBeUgfxzV|rni5lKW(#DyIU}l^B62DhXyox2cL_CNLsL@J=~g(S;?ur zdQr&=AsYuh1`klBoZvuUh(%rI`r7bvuHVEotBr7;Nao>aN2!jhy@~hXJ)*>3Emy9b zE1PRjZe3H=5(Xh;k#m)R2B8LklK9TxMh%oxQtoT7hBU2ZuCzel1fav|SD&GQ;od4+ zWpV;C*0W`HZh@6=oY(VbFq>(;R@Dv4bTg(nUqS1zV1dz2t{2f&^@Q4{Fsw=eZKY^L zlF~CfaWor>S&@z*FGM8{!3=;auVX?^hJAGXS)&!Tp~(Fv^K5`SA|SnLshy1#IR%7h z&$Ygx_-az)2WP)wjR4qz>4A#UG8JB&R^U9U z8iGU_fh*|y05Waw<50If5cb2*x&M7RSdgrFcSfLWMB8Q^p`iZms|j*Ts!b)sBSo^f zu>VdfM8jqvS-f!eWwkp*6^&IpQr2X9I^%vUwiSR*zSf+qaydg{o`9Kw9|TvMYqW8P zjy+63>D;O3%k^ujEVjoGRru&bqfcQ%rqTWSDu#WUKZATK z{pqURi(l0$J-nPfjsj&+y$7I(Q34OYc?tQbU=@8`GSd(q;iJ0+cTc~V^4vPc_LSmegys<{R z0?=AESHK!#t#$akjWw=0lLzAXV!Uu|V-_4}E4vEu*$AOJ~3K~#^R zW(SoRdkrjv{fF)@=T5!A!c9(Axc3OyBr&06lbEDMWxNj}`T5hQBpazU^w}6GkG=Z` z%l;$xmyiGIKdrrZ+V=vmWFMtZfY*KKhyPaj&0qK#7Mu`2=`6L%oY{VrhD)0Swc#fI zl>svWCZNPh$H3xLm3bGSkb4g4Ps9H@F1A(jbsG52{gVxh8)Pl&_^9yIfMCI5Oz$dd zAu5P0BA_BF7Dc6x_ZfY$jyWD=B^+lq;(^e3Zf})NWpTR~;^$ak_0ru{PM>&& z0V2>P7z6hk4EnbAuB_mXynMB+gRZ&0%A^E|C4hiQ zB%fPo)Sslmu{?P0TjaXuU}U?^7QHL|p!8;_hmA`=prN6O>Zs--`QRl)%#J^zHXqiE z_OQPxsb5*@9G{Jzf!X;z+=o}MTnObh3mxS^P!XYnNgQy`FY+8o^!$vY3XkBXlrq8I zBdM6#NI?{79jNOnkk&OCQB;VHzEhP?uy*FIxnY9~cu0F+dT{Tz$m=jA?@0Eyg3Rq6S`xXAZe9aT7LJKOD+d}y*56#BZ(fif6prIU}KJKKr+ zh*O}!&xqg@i84SPB+67=ZeFvK-T9ij&oAErVQJRI2h{4wH0eUD%|8v<=S~)Lk6nC5 zKUv&ZU$4nx>v6GqsQR^XpkVuK$$irdk@E7~mEDzK5S|Ao+aSBl3 z6OY~VCRRr=XZD3>9;Y}Nfx$|%52|8KrgRK~gjKY|5}xpo6~q zL;pFoD*oi-|FT>-{XFjl^J!fP-h}T4s2>&A3U)Kcije`H8yT^c0_&hb8(>a7i3B1- zct^m&7L$L7Z++(nf1;dv`Kj`SKmNCTHmd%OSM^DKzpBh!uNYLXWKl_~Y0nmuaZ-Wz zQsFfEAk_*bki`nAtlULKS;?X*k*v&e>`Cey2*rd$#~&eG{Nni&tr$?*FKv_*fvjk=s_O<( z8J~d;0N5RQXU2@daX$XCRo?f}|EerqyHx(<_kLa?dQQk=e`Nb}*8|^C-toTwwEX73 z`f0WH^jHBkmZ$Moud!l~?i2?58B>)_HFe^sK+Pg}K`V_|GK1;5gEqp%Nqb8`71xL@ zr4c3^Ls3~eVtBZMS`$Ctd-zQH7^}w@v{nhcus?GG?lzj6#Y0LmgW4ah2(IMZEXL-w z-Sxn?R}8-e5QB~i1`iMO$eoW;-3)z9FscezF}E%f!+|U9QnmUND)vf6dEdqn3kXL6 z8Y}uR_8d4~Ft`&{0Bmk778V$NX^R(5YTU1FQ-f)_mvAeP#E7JIdV7ee8Y0dgFf+Q*%TgEwrZ?Vi5D7T`Kih#6g?(BSk_| zFPfBVN6X~oG@S{MA*vNqv5cxwWfc`9&}i4!*c+@-ARA>9bWS+M5OcV(8GQ^{jV_L- z`ZP!Bh_M&YAA+hPP*ns3Q`56$brtlV%RFO1i9JNR85tSYjuA`tV9*$~1iEHM@%mxU z_hv?L`0s9=SfbwrK*{2T*D4J;R{(Enc%yQVpKS$qY+Zu>VcV(zqFd=|J(~VD_dSFt zhDEc&t2OFwBpQ(!;kqZrXP7Jk+`&ENgdm@hj5f+Q3e`4+*vTRQAtj6Ir5^TNazLwV zbE;M!X1BQObH^`kz3SBwM_-lyJ0r|a<|^`BlSR?q>h(DxNizJ^j`V(4FAj-72oj)= z2UUIx1?f^fhQb0v?Y~(NEuK`M};Ank?$N@OjwBd-feG6Vo#U zbI@vl0MMYF{FW$?{M)o?o!EMAD^)3G4h~)is%5Hjc-%z1xomE2mbsmK%Yh^4cV1Uz zcIDcTWYIuvjG4;U6G69@FYIIdn>Da444R(^7KrDNwX@U3dXk!SjD4^@42#P!3S4feSHx`E1|F$h^m5I%Yr0xM<}LBRL%2gT^)sA zMsK8CQ4_<#cXIAxhwhlhVnp)g3N!xJ9JQ#D2i05&Y^Zrg!jr2$R#XL0iS>0wQ`N}v zGBG(>zWXEpb=i**YBBZ!*Lrqt016-`gQ%Qnq+ls6(m#4nqb+7*W2Lo_Y(_#8 zVuDbD=8WT1ZLY)S5zB3Emi>qBDewN!Pcjbu)bIRnvRl!50>IUMS~*!njDuvI0Jnt} z(T_SlN#GR;9(xF*&lArGItch3d@V*IdFG<%ogq+!lM@?`6l#p$KztfKk=P=vawSDo zu5bET?MFmqoxSBqR42H zZ+0@S(W`psf|9$W=(1$*}!SpY3y+%&foWAf3H0Al|L$9 z{>*Qdv2iFGTWCzFSgqWbQr_~eA1e1e`i}D3zxembR_FjwHJT6KnhGt0F<{rCHAp3i zfEh%z&ohNH>|{=U4Gw^U8gR|4tW+)(2?jU8O zKJok$q%+p6x1xp4J-tD1kt{|dy6B4%7eUjl9k}}CLO7yG(jSfUJ9jIInVsKT=Jy<8 zl@kZdGl;}%zf6IVtBV&n7#RNz!-j=oA{mNaa;91|E>xZam}r+YV(~1xl&iQ`1}j1X z?ZEr}li*qL36l)L^y~brssB-`P~P~_{5A{;?@?8 zE1bobKl|$(=q+?ri>69UODMX6MhaM@!YYA->i&lyL)#@2EwPl+S00m4ucF`c3 zRrdh_BoEm3Y&d;Y1tsdfYz_A6*X}AZHwWq-s7L~0Z^A}Hm%3iDc+)i5}1#P@TrFJG-l@La=ycUg z)iHm*_BDJl`ew0rkSxO9_)kmb)n}e*^VLUq{$h-x!lgM5@gDX)5AK6>joxqBXIFY+ z^q&U}4Yu#--EU;&3~ZXGzw(K4_42u>_C#P-fm#LKO1`z19V=N#gjL8;@HBYZeLVte zBrr-=5OdW2HPc~H2_yY71WM3zNTHY}Xi}?G(Q5@?Bs!|-X7B~tLt0(*gYOuN#E4*k z5<^gL*VdNlH)_(G)J+i|OwI0QKtHx)yiCmOWGse+3RP6JVSuRwA7uRsfYeI98lXW| z(gu7GMo?`M+$7k%cAfhL|GjeUDicb8pGcI@pNK>n`+a(D59jiMHSxKB|BDn&%wm09 z&$X3CHD!fbVopjHmn*;l&;*GWm^m7Kg7YB%iqAmIL$Nv}&=f#Y!Yy@Hjc{>AQOT&1 zI93)@8wx3@q@POc1Z$4(f_(wVj`+;F5vpcFR{^X#^+_@|-rOu>lS*D8uE#T#{6Yp> zw+C7yS#-bZjvWPkfJnemDfYD)h+{=8zT0a^I&2giBn%ZGM5x6IXyu~QzPJyw#>){e zAQqgP-(UXXU;XLw>EHcl<(2235Gx?)+X845J35&|WqW?t{_?S3`G)~`Mb<+57WB@D zkzF}QjMQg1WuMsma{{JPyqOCR20UY zp**!hn=67rPqwf_6I~GCLBXFgTE-_Q$p}ED2#FyaAsoKO9O!%@NFX(Vq8Jz0FM=xM z*u+HHdk{*xFHvxZlGB@F5i~%=!I^@Q;i%N$ebqp^vn0KW)UB4Qg`fkk9Of|d^YI(7 ze(1$UvWUQ-HMej7p^xL1q&&w!ip)yCQFoWq#UJ8Y*vkm`5$tl*)%lZ& zLfRCt@fl4#1r-8F;$mDx05>szQ?Kdnb6<)p$`pa1*p%WR(7Hk6g$;)|5|V>{vgj&Z zV+;@s^bRwDUzUL{D$|>Zmv1+tA^}k;Ghho??iYAoU5$oVN-}C6Z%H0pXy}bDJ z=gK#~{^=02u(E2RXJ+uT&gn}%Qvo<5(Dt%5uup!S_Z$K@N-ohN(OO~*ya22v^9MpW zq*q4J8GGO2VU1pi&x*djF^JRz6|#=24p529qW}?p3~L2{z`^IJI?|R2EO6hINA_@u zD>xvUCBae_6?7I@1w&HHaZ4jio{;Q8r5v#VlBDUKy9;Jk&d%;4ND2Q0#u$<$of&+l z?BvzOGi7ZR)yr#C-^X?S?!WmT6|W-bjoF*{ZzYSc<4Vp*XJ#Mg#*kzYK5mMjujYzJ zvN$?c)>r$8qGQlI&xG9k(7e2>k1p}DM0r1wQH50jJ=4M zn(FS<2TO0y^m_SZ|^4gv4xoxr-@dKU>smf&U9Vm;JPBXc!J&+OI zc~4@E9cPd-9aUBU5*#TKVuRc(sE)EvSX9Xjn6!jZ#fc+#JyPEL(Z60k_HTZ!T)OaD z8A-x{PRv}i!t;FJ_x}yXCV%|9|14~cY$)uHg@ruvz?D1FqK8xot1wTtwMn76`l3)6 z4&DXrf{G{rNTrA>3A0EYGZnXv^RQB@@|=DG$~_d+=;l-6oJF!|)26?zWzZeLbgOX5 z$s*1rY%}L+VwXiit$DAlP*d$bfckMBmMgO!j#PKm_CtU;hn)fq&! zO1)U2j9KSF1-)s<|tyZ;c zR8ws%AV_%l5FGG9=~IF;;^JVezX3aF4-BFMSd8A7nkDK5IolO(qJi8%9in^fLUhC%PhFH7W${;%WBj_ALmR#S9 z09)ND46C3+#47_hQS%ib!v-c>IE6}BG=TA-+ zbFs_`PgWB2p0$y;fIxS@)Fv=(!%A;eu-0K8n8DE#R?&4!$rH&U=VP9G<+hT=oS>@b zdy8l9(6NVjZZUYg4myuOyseX-yOk*wFM94F@kZ zW!i6=2zGXLB>H^-Cb^;rKJ{JbO-C>ddj;S_$>M7%kcn|XwF=yN;^2c(wE@K)XPW@( z(#488%g!~xQ;9ngg>`~R>d)8upgje2MbOugEJF0AUGwlH*?!GQvMURnXTzma5~cuI zdoL?8y6Wy2p}(F!Us6j|u>8OqzKh8U)J{=F7i|sC*+F=)RG27<-NVm`{vXjyHAuV0 zG@(TR^d2z_sES#A)xfYvAmm_^D(e7hF=r2cKIZ#Y|7`G<3B7kHnDWj^=2%2SUTWAL)fS+L9xLS&{XJ!_`N~+|d`VD~?4VUMddDK8u z*kG@;mI#<9%f!T_m@}B0jCsei0{W5Aqcs9C<%`dJjsPZ-O!gF_8p@;~s$A?dRN%`h zdGss}Ru+-`O=&iBjJmR4-B?{IV;BX8wTjUf_zuLsc)b%sC8HXxf$M=NqZQ#1zv5?` z>nkz(!b-6cnql=YUXObO>&HnJ=RF3C%n2C95@TFL1yJ$^uP4y|=%2NAUa&UMuK+U- zBP(>YqCeEhBHkY2LKZ-4eV0fs$AfOG(H@&%=CFbakU|tkR>hgPi%QD}9c@xj8Ght# zA1uH13;(@l5+Q0PihDq@xP<5QN z7fSko>^8U3v%U75qW=@T3ZWeKJ;PrGNL%9^-}mwR9^1-+Z6~PZS~TT7(g0?6mBYs$ zr5e%Mlh5*@5tS6@F9b!jDLK$RsC}$vfMObB25>lhsDPs24-PdBmjVmBG#5uD(Xzh^UV!XIvOubvMuiyV$M@}CI9euW zX3N=EpA96W`ndP7yc;|!S-Hl{?Y{wX>BuE@VgEBoB+XJ*7Nb;|5u9m4u zjEE4j2ZOJX7NEzhmGP+=(n~-u#-0NOaxLcn_`8hsI5F40)jouyV&Xb6Lv&8yhY)Bu zRVeRL(XLieO)oYoEvJUV4HFJJ;&|Zr0xdzU0c!pZLVF_m4nLR_ey}8Vw zO@5V=#cN9!%j)vg0Cyz1ASv#a#L6KwN?%P%G9VNqEOKGU&s8)gQNSzZ-G;;au_lY^ zbyL+QDu=n+9Z6Jo&!9pyRt_G2hzbAs(=QGri``0RcWvwM0{B6)2pbDET#0fFd%gSM zf-Y;}oB+D2&{C?38!fhD@7kBvuc_a+xwy?)3KXk8wX=`f)3sf6plcgZgO-pMckple zC4%mK2k)j0IrHi>QCVy#t}B1u54tYXps@92i`0KqqxS$)(n@tjzUU=JcHbIWzFikd1KFq1{BGxjnn zi|Z>)3;}vuhz|FF?`J~DnRmKwC5xe&8ogvn4A6(FXHcp2Q9UCiHL7&97I;0LVJLhO z{KZ}jMpW}Vjm4ClU;F1!lM*vlqX;5a(H2>OsQ4mIjz(23JPX7&PPTB8FjDOM zf9&s-CqDD*<>@Crp{iJ=gJ0zCOMTO>zw`ZvIw*udv*mL-A?*-=y_Q}~d z+Xs&vzwfOzn(GGxU3;tQ9TGbX+{GoHeDN!7*y{Finr*y-#9RflgKgeADw-|fqJt#2 zR>3D8xcaKPy^tI{$wQ#oNlaETwm}7)RZW0d^YFM(Ek)=#4lQWND_8vUnG0<_R zS*0$%ht%(h8B$46iO0GikZ6I{2x%Zl{vc3;9udu)4E5h_oPQ2(xQ3knIbIeH+(~p5 z&lVMVNbv*J?b`u&bcfT{?e~41vDowi)&F@$YdC77iTedf}WyK*Xw>3XHwpF^+(HN&b)^ zFxGZ+lS8`ZoHd4cYpZ9RC zBS5)B^iDv8Q9!9s^$h?TmHw$GvbB zgb7)F#A=9RR6W465={`FH->5(&OU=$jVp3xj6!EjT6GScU}t+LkrO2yUVG~^=q$68 zTA=6&!57CwenzGV%5Q6TJCJ8vN^S2^+|`K@BH3o8aP@kboPywosz0opuESpqOBMx8 z6CfddRtYuy5=3kS;AspRJ_E|%oCO-~I85SQB}>&SSB#LjJ4W;zKPTPxDOMRKGc4j% z+m9-IY3h>j|F*7c9M;Sivr6P-& zXq+Gr=B)!JsnzqP1PTCFlIDvaf}&VU~nwI)VH zsf?SbGkR4!KuA90Ob3AuAMypH#@q^(X$FrZ9Q3X7P)WWb#Oih<1 zBoIrN>70=u;5yMOK-3rOZHaIvjQn~jVc`$u(^I90!G5Yt87Z=H9yAs;qT=Ur@b1{S zLMo1|e9~&>%m!XcTYrpv)IfiNg!?5f-d@t`8L0@F!Lwhsr@NgE8 zX#9om{V&QLcfUzO9P2A(>52qbmaknb7tg-RBpj7m^bV8Cc9Ue02((p1ldO8ii-skO z4T%dO7#;@QXLVd7BW2INqoi$KyLw6NhY)~*145Drbw?!WP#C><_LYGik^Z`Fmnhzz zNmtM-;D|e;IX&8q5c{$ilZ|>HpSX62i{SmN>IAi?_M@=ZRkfio1{p77!;v(gzC`f>4pHq zB$G~1yU!v<=uwv&jklk0_kB?aFL;)6pa81Ow_ZD)mm$fbZC=DRu#_{?^X1{Uez5F4 za94TyiI0~PFMcfrA z25j@38K{a1HTJA~811`trX$gc9#8vGRJsg|Dj^axfLaJhrjmFLk~)C9Wce_;4E954 zK`03e&?S5w_M+#sGMQ#Dtr>wD{H~v|vPeoODvO$BNpOL5SPQsB6*d4_s)M5P7GonE zc<1xZm|<*Oy@g0h!fsVX(x5{kE^=kjil?@PWO|_T2QU;#VDyp#DC8QA>bg}4Li~Z) zNMN(0X@b!q)T9_h)kb};diKb0!+htlcyF3f>SvT`h<^T3BTeiCCyOnT@A~X~!c)<~ zzFBrfNjciE0NSoBUk(7$@pEH{a9<~2O8eiUcCAIiAf{~z_c4>+ISLH z>|!4qbg(VfnGDb#&&?{tojfQhlZWpd){k%BQ(1!%KV|#gxApd0ooC#$>%PYJXgzMp z0n@GGy4#I9#DL&6B@iRqwvjvUM`iK${>Z`TkOJ94@c-xgM++cyK!LuidbbWr@@>Qn zvCg5g&m5G6i_R zl!MK*D?j`Q`(zBlIW&5n4_0KoJ;b!Fg*nrp%(huxoeFUna-d`fjy=dxBcL5{=2J9A zdz~c#9m!U8v^RgknKFx4%9!2=ftneIMD6cHr4#R8lo=JBB@}_f&wF(5XzU3eY~R1p zSlkEtPjTO@4&}_FQ+DstdbQU?+l8SgjTX)7n|Pk9LW@ZiikX4oxJCa|(2ac}8nX-! z9N^k@s3*3e#zw1!RJ9q5l_osIK$ueN1Wkc$qd+#)jCWBff;#Apy3>O0?l_X|o~j*$ ze~)=q2%14f)GRayc)X&4B-AJ!s-FlRF*9{~eh){o0ARuh7bIYymB48Khu{DCa{knF zf#y4C@VB?B86?p?BaBrJ9*sb-gX*O!fcoXCk>$QJ^`y;eq>YIgXb6ǃQ&aVS#+ zj&^dMB#?jfYJx)Td3)WpA6&`XO%`26+|IUTBsMl!oRO#!2I3x1f-ga^gkjY2%AV%TN!inVmZmr((Gw>H=UJ3S`rc9Xx{>N>At38C zV2_NAu}{vUE$Dj+eBU}h!@Y9^;Q36fODhjS!1Mpp>LHaoaV?)$Y1Hd#! zq%gap=rIy{4ib2w&nGht{gF~tb<)Ot&T$)f9x-+zKnDAL#oS30%X>a5d2Yq(+vN^J z%@w7nh~Z3q*GK*u&*nG2@Uhl=S7QvtovJ8{@{Tj+eVdaUSKD$TB>e=uUesg9Z3gl2 z-vHzOqaXRZ9A~gZ6Ga45 zxGi`@po`DERmgQ;0mwKxOtT|#4xLnn@nBWoA*I2A8Ygu`ar~Tup;v{^EHanGBNGU0 z+N!?q=FF3va1TZv-@;D}q_Kapv6ZsFmJJ;(1Ic2`B%3&a%dvKt`8D6d<=w_x#Obx; zccpFk8;9k(PC5t66`e$@qGa9SrTKpSoz*dM5WA{72!1iF97dRwN*Jn!HC{z=rYlEPgMKIn)b2Y(o%152#% zNK(6vOku!)M5FWBqOa9I{pysf8}R}lw=}SpJWdGd(9cNdYrm4&iu*N%rcuM%W9E_O z7@4|qqfAcE^S>d;QV(4mK7V$lDMs*yIZ)_HL{Nw%0pc~Ngyv+G#>LJ5s61l4#Eu|Y2Tq2Cl@7dyrPXz2bS zwT>#Z`aq$c23qY3Y3}MVXrxlC`Mr<4iw<@1(itkEt*u-yYuA@3A&s@Tv9XCMpb9cU z?Q(yit7vt8Q&50SQ6HNs=&{0i<~bf6FRLrdW$DWKf<8thNv#^(DB`y=Vz;y2*`5xw zIk8&;H^{b32yIrXbb<=IfqpyO4_E}QEXJYGTDh@4kl$+KLf8Y>j^OFQ9S>3j0hL8O zClf-q+fPG%N6f`jOs`~}6^5`gb-z?_O2d%#I#f6W;?-n199pHORYxA;4bjV}U|%9( zwx_)ApaEt&R|^i>$O!Cv*mjK0fV6(T=M2X6@7ck;_Kd68W_>hYrT4Wew=0HZP25m2 zA)71^unMaLFd|iHgEb09`ZUxF=U(RAyAJE70&fPMT7Uo%H1sVZ$Ub*k$)W={-G8HL z`Py5MD4&J*LJ@mm|1k>esBgAApxZQ0kTb2YOrX|1MF0S>2BF&RJ|DFYD9JJaTYLJW zdcf<{gJ$If*AGzg(6NWh!*70HId}Sn^3<0ya`{sOeP5Szih2k2?lO#9wO@zrP5-mpmCSYe5=Ax;|cUgT+hSsAJVT72=(l7z{=w%(0;x)oMxD9OkBOQ4>f-!30O$UVN|)j(RZn=2d87ra zx`-k&x>*xPAh2@-7w`5Ug zf-V-F!x<>7jnTYOi^KgP{v2R8IJ2fAaO*-nHd^LeVHV zEH(NWP-#^)a)Ol@P%L2p#z&{9C`&q2Q8f}lF)NaoIfQ<)&5h`v14=FhOE(3p5w;;4 zT$>mezdg#}`)>gzg*^5h<@KF`;u}R;vRa|a`Xia<7pQDq#~PeO=$WWpHQ>zhbbHTQ8O5rIC^ldET> z?grx7oJ^{qyVtF*?eOzalg0E5cI`b{cI`e8^X4#OLuhyl5{;szy%tUu=RoRl*9n{` zz)FeljT>cV=R%d&#@fKyu3TT_bC9zg;d6S!w|}_YanGC7k2*6)G?rpT%a=K)YkB!f zIe+?va_W_*H0C3H7p`??=Wd=^T@yzBOqCrw#`!p5u<@Ri>sOf6!m%q6(+XBhorq);MROrQ$4o52QBmYag5K0{6kI}zsugVm>J z=ga96&u~U<+k@V?de<=fsr?b_m%*b7@H99`u~(yy=PHzwNkh98prEY0uA@soR~y1$ zKWMgzeQ;1>R!XE5c(Jm`Ig8KLWO3ND8J;Y=uz*(Phm`R*r*a_b=88SDdrfpQ7o+hfLP{2!hXl#3HBRU(Y}3p%0#YSq_+%%D@hvgdqK!J?n$%!d6-hoZCw0~YVDe_F ztN=o53Yc*qzyg4T7GCQWJ;=H#1>Y7R^3Qa~{55Hw=>7Hx4z_bBF>3Z1&wEosH(K}( zsO0ekSz%dcr-{OFu3@eEsSi_?NU6oPWHI?IBnqh5GBNhNQTH)Ih1Ty?AFf0f*MpX+ z^`jt=t7icc80_Tthq5Hah=PX8)k*zq^?6khl>pq+I%eP>XY|;8j}b7%cMynOxz4?Y zb0Pn=O05Tg;kb4H8tTW>+F-8mLvMM1`PvtLw_Lw^sj*e4ifI5o63h-Iv+L_~4B-3H zdRir330AG5N7W2x=WXx#5%$*q&cFT#QRxey+LcW0kXr3}>^pzB-1WfQ%CG$&f2Yoe zwSU2Vsh1K}->^$qPYUng?6^{IUlq*5+!n;I>sHp9ZO`In!7{4}W&;mwM>CVc`9Wjg zMgMIzh6z9%(&wm`H8tjH8~%*{u+Ow7&o*zn+-&67y>A(sRoPJHzi)PZ!(QJHDBJq9 zvMlr3+SAvJs}mu9ZZ$*>4C*H(qtk+x?NIuB{ha`3SjB9cLsEm4aPU@NVj>a-3YA52 z<*`u%9dnN!=yy}oyO?Yc^@Nzq#u_VH6xU&IK_Ly2hdp|Z!~oe$jlZq`%CFI4s5gf+ zmili6hNz&-&F^DCZG=RXhlU zT%JT%(0?`qiH~0E&E82CYwxR2Dj;$YuA!uLBzjk`oTIowU1uk>HEB*kZMrU@(yD-) zk}9L_>@Th>s(lD*;3Ox;r)u>NpaIq&hE8aCo7e+q&At-^C!?Z18&Sq(P@JL$HL>^T zoN^%CJ=$&0Cn@+&bu$7eH)4;Buwo0E=EZX_v#+nxVsp^iGYmev5>~){wI=;$h!lL( zWV=AAc7*{IKn$wRalR&!Ydk-Vg}^#NKm&b*2uSxIzPs$iIGo)FsQ~)NzxThF3#eu| zSsW>>VjemE2rESn9IjnCM`|g~9jeOMA6FL7Pyv=bJZUyrLw9Ak+Zl;@e^Gt!CrurD z6UpFqhPY2%?IhK`-sSw-EQrHrgJg04odm1Syo$=A=CpMK{o$472IwGJ9A{tG?EFGG zck($>3j0;+PC&hlbI8xT9qGI;yMh8aId@Q{z`W6Obe#&+Geh4==XQRoAKdtL8WV+m zC%PIw6je6tLG;|^q4L>r=R`5v&Fp^$5nAmnonIx3jmp(%OrjLW48Ana&w-=IJGg%e z0V%-1`Gv#uDF8n(XA^ycVMsf@bxz3LgM@oVAc{Z|Nd`tW5o$*Qe);KB{C+;2*C`Km_kG;s>9pOgXLgl{;%kIe5qY<=8!MVeI(j&;BO&8j2KCb9>m< z0fyAf&OH@u@_H;UU8cG`z=+kg>t%gqxvWE_lr2C~)92qYf`V&ELC0Vw^#q72Xqc1U zU?tV!2G6Fdz#LstMQ+q$_B}uFH_OuEx$>Dm{8v>hD!<0GZJyN|H_AIc@Z*eK|KL~u zNu{6)NQ`G**S95$wtGS$y6tB^A7sL@436rxD)pk>#*9&`2&Xt#?JlC)*7%e*NtJT5 zS{i%BYO3~oijLXaYC5{<)roDwI4@d{`hAkk2H(6W*7t=u2CU#uufI}>?I0G-WU)E@ z5IwN`c~YdRPGvh!oPOR6K?}5VRf!iIp56inT3DIF9Pqo^p`_79Jhnj!Y6qNkEb?t! z?(mmHWYbSPNiT^2pPObB^i%yIR~iUppz|IKPXP}a22qPt;ZiRKj1>fS&`izQLZG!y zOwgqSoQN}BHa1pN0a;mQP|U;3ks&Z(8$peTN*fWAHiSOh7%7(v2aj{sB7zAUF>kzD z^YK3d(d6$F<;kj1RG`g=C`E4yFd{@v)eK%sC{5N#FC~j9)f)a>Txr&d#-+DIn<;~} zmf-4QH26a(z)q4zJnvms6+7S4{VsoQ6TJ**3pC1J{y7s6xo>+imh-X z04mXt-JgT&#PbK;6~+(aNt7sP9LOa4QMPVSA=S^Nf8hJUZ9X%+!)mZvMFbTp1kRT) zyjqqP)hp2Xlg^2M?qspO&LB|F07V7JXm3PU#YE2ySO*jE#S@dp(&tRbq+K%QCQys=K2Yo#;0Co+2I8dbYJ z?~L5}zH-twY;$jy%v6eLto5*Dk)It8916BjCB9j*7)N?21H-hN+*WXL^OgGSw0d`bD)t9J%JMXodCFyyc2axb|9YTO5 z@s0oty}I}=^!11qUB5BmScB+$13ueRum7^0>-5nYe8~7%^oGS72hSw}4JUB&>aZiA zej?d}-2k=g^7)guoh;%zaL&fo7$Py~Q^K6bM<4qjsjyG}=^wC4TB|0c zK&qPQDwkpwRN5Q8+xcWc4i`f^!w; zHYbby^|LL>XI4G2PTG`ksbXl~D9SJ6Dpn^|jct`hB?F?%N_>YcJ|jB_%ySGx0?geX zN!D0O7C9=zl;EKFR{AOFq=@~{quBPQ#R?tUX8V&tv|KsNKGUzq{Kf|4}*l($~t9U-|=0A3%YHtqC{y z_r}(SW+%ox&iDVNze#)YxljCp+7q~0G&5RYZZ{dMMW*KHdS}sgH}!)CFlJyu&!Sr_ zsQ*QPAPQM*H>z-KfHiS}1_z=y+(1=r>8N31jaEC?S$$i?KCPM>SI0A$M|TV+d42!W z?Y&N(&9Pk2?)$M`B#WL~Rm0WJH!69Poa!)#>q9>bQMCi{qB~JkT$7tQo3ySPP-WEW zCXB_dix&3^E2#@g_Xx?e@>y1@zv zdimg_Bs!33pMBsaCpHdxvjB|HQaGFgNA4?E7SA&H6ip~4jJK66%INkJith7khM9p| z^tFIu*6ejg@|rQOXTNvul>o#(3KY!L2nTo%8u2JoTcoit)tJk^a zNZ3*FmpX1#9}JTC9+PCZ5yZSF1`=+qjz9vHa5{f-lAjZ!{Mwv|q7n>X==8~FG^4Cj zne0O&>Z$d2I%qa+9TlPrXI`WzR^RFPzlE$v^L`etsq50U_1h)I`aDzP8|rQJzV@ly zB(QxwCO)sF(PZ2U06Zj4SgD*W_Mh9}eT3LbRKB$5TkoP=l*i@>u<8VtvCa<@B zrBUBTBUEsvWD&{z{!X$8@I!fg4yKx&bJY%Oi;CdP+yZ?Hl+FQ2nO5oRWMFMS8u~ z3TvfwiY$R%+D{e{eo0B(^SiNk+Ho}i03ZNKL_t)R00kl7b-T$TZi0&BS^bm_xy@QM z?T}TbT2ZuaKs$qZFAv5sj-N)TfP3uTw{Twd^G|)Y%+4*8-FuIe=b!wHSR+B(^=D`+ zH(#$I>)r7iwmV3aN5`ki)buRJaY1dU{o|!?i}aKq;$ta^b^Kr z&%1r&NU}fhL;p=VeC%O91JGtM`+990IACK+eXqeh7*mcU?7-$FAN@85H@6KOL z)pm7VB2Ow%GzDB2%H;q0g*C_T+EZfLG~duYKS~5+|D?D?AXuCqvS%dl=XhvXA>pRU zqMezYKQ~8gi28RgSoFed_d0K8Z%~(LSy)dquY^E^CRPtEM2`=7B8HZI@jj93}|ht*60U(4o!Si zbm_2S(0eoLGR}>U?Z7AkbY?&yZoo~hgaL^!t{L|sngLw%Mp?PGM2e^mOH?L@B#U;4 z+4&7t7mVFx%5yvm-$#t}&}}xS+^=3V%2n*M4v-L|3?j&H^rIBa$o;oqr|u^`Tn3aO z@m-y61g%J7HrB6~eTVO(BG}T^^Hh8Vbry!T${cTPmDSZ{(mwEcIx8A6(ona&HwUjz zd#zP&uqS{5?mv1z=Q*PPNNRTOH41kypy1WZcD#vg%+J_yZ zlf)s3Yu>B2Z(MUL%kF^K&ODp`FP=Ril#X-8+Kg6!EbLJoneI8kswmNbjk?7b5S`vJ%K4K! z_Z;GL$H4L&h?*JV&#q`?qHh~Sauv6k?jGO}zmPq2LM7Ek%tgcZ(#ByBb9(LTS*QHk zL0h5ouWE(Z9(xbnMcag`YE%7gfm00%xK~1Azu(hU1BYh&y1_)8AKTe@KYnU|XmHMo zlUP$HBZipp`oUyzv0Og?8Y|^y>&UJ)kVrO3{XAIP{fCe&?&gRnC=@GM>>}R0u2kV| zK%s04eD%R2_md8H;mj-L%B52s)E{e)_1$;q?lQM~Us+jRD(6qVP}WwVAl>YVzjym& zF`Z$ye2noN-}A`3%E80;m2ZCiQ|08#-{{P1BfuL0m;2sKIp-sg(K+*TkH}_zND7w-=dj@JFK8=w_50mmq2*=+Rpw?0J{BU z{{78?n*bXlVdgk7+S)+{ckC@w=9Dvo1J-KyB55>ek;Sj@?>f*vQAw%F2>{$f z=F?a$CY7%vSrjGK!cB^Iv6qHb76+0=#A#8r>{J$GjiksL{g6?W%t>^A?JK)3jwzDc zqj$ZL`}*Z)zfeFYz4QLJk|Be{(Z!nqJJ>6lG$uwDaPfY?GZ`P7DtA5fcJ}sz<@Us9 zeLj=sUERD!v3CU`BPBRZ;~wHR&ib!y9aBb+84%N zF?uP4Fn#8_K0MEt?zWgw;6@8ALn%(SXQ|v?vZz=vHISsBjW=sqbU}p;>CUf9P5w1; z;RmaKi9#?&HHTIGS|swV#t?(=%imK+K2#jFRumh8CnK6eW!_7yYyS(HAFy~%llj&& ziA~xq1_*ub4cIoKg~JEYmWk;(4wc10gpwCVLLhmBF}!l=4AB|{2uLCk*eVGaEgNgs zS>d7~NzPLaR4R1M88lG<{+{Y$L8*)+(fw+s+Q86Z%mt7>d=^I(pkHWgyewb67?iIO zQ4=_Wv8{u?yE(+|lEq;ti327h)T+`2+8g~30l|l1>?Zx$0pz^UQliX^%Bn%#&d1$ zTB?w(5g7+~pkh+%1ry5MdKIv?2HJH z(7BN+R-?!6(Mia9wL9q*!%-yON_EpA*uwGwN=jwZv5j#lV3xZB0 z52A>VaKCdzO~|nK5zlsxh9{x@-*1;J@;o3}98)p_+kNijHv@Rlr)0z!Ng|vwM#MmM z)U-kGG48Y~+!G@QV(mNkU^;eGXsci7#wdDHb_q$u2j77nY^ad7$|91*lj<|BjEP~% zqNt_V!%)ix$N<5N^QWIDDAhU7Df!hJTFj;GT|A>hcRX08W_J-}SiE#PVgqApIOU=;fP(uR%P-3m?5S>&$%+&%_E|q}m_c2zZ@AqO; zTz@>xNTPB=>v%%5Cgr_s1YW88tP!O zsD4aWo;ji+Dyggjc{~ZPq4khvTiEqgR(&pIVtTe5Jo+GQ(aYcbQ!4C(G4|k_-b?n- zE6+b6`l!Y5l3nS81@J69ATWHXTJJJssx8vkO9^P6uJGt zRXeMvwuI5_u^bTddV|GfW{dz7G0X6reWnqAxR)G08l!I(4&23f1lNi`*OxApOXp7( zDnBn?D66Z`{=hgp0k-Z5tucCCd?(J$*Qy%Hl4;M`b_4JVf>yI9q)9!9u3m>1NPwUH!4r2wThP6lEsV%H<|%=b~r;(2(9-BW35p3_M4A-z24aOlAKn5 z1t?n(=)uoscJ3|HbGyncMP3eeLKeX=hgp>^!bKD-;GVuS8%Ry?j-1gGpHn!b6ZtvQ`I2a0DS&y@RtBM?4{ic zN6P%dq4F9lD;NwddY;7}3=T4&3xO5cW}Xh&y^)c!u2i+-U$EqDm^zJBVa)W}ag+uy4BP_7-hChHQgo50MM>N5ZBLCX4cKHQ|n+AK#2; z1W^wJhL|6G&jW8~VhVbm`V+G#Pk@@y+tlcD5`xn>4y;ceI^Oo8ZJaa*k{F7`a-y|C z>X@KFjbJAM$^OXHdVWqFebYme;~eumMt`2Z zFD3Zt4DPMC3wYA<4*tvDoE%=A)M zWUIPs_)sci#<_8_$XSXZC`9Nqs=1;FhrJ4c8&$X(4b{DmPHshojXuYqpYop4EbA;t z)WTe^OPJZtavB-G<8oBBx36U)-S4= zSZ|CQ16NFRds}+M5_`(wN&c2iRtNT;nMRa> zT2n&UanhlPl|*Ga$s&weR4$xQD5%H|NdN9rm;Qf~EY?jFj=PiHN060%=H3#%&9hlL zHOC=Qj;SVTe|8U4Gqi(9N$WwVym>*I>U-cb*rLz}g8x@v{0a>L8lF`dndCSDj441P zG!7&TB&e|H*P<-*@>L?h2(a-tg?nn?=$^WGj-gzA~dQQ|DveY#c z&50(|+aN;j->H@4PKw{7bX5<;-%NhRrIZ*n!LGM)*!ikW0MtUs`cI2WUz^K zMxO)%WHh~t&o6NRR)o=jjz3gSL)AcNAS;_m;K){_8~7M>X)3JkRH%n9Me^;RbdbH@ zcV3zRjGF*7L{3pv8J{Q+g#o>Vy@;j;bK|5v(67kV;7CcA4YTC<(RVBwhk74yJ|e&y zDOA_PnxZcm^CmIQV`6GL&KwZd8yq+dS~hw*AlyTRTu@shk<^~Yf1{5~AO-gR&OHaq zp1pUJv!|Y=qs06@P_3Y~6S@uUd zS!^JUfJOD(D$tc`A)M9`J1pnf^kvhMzTH^y&(tM_=1|5KK z!iB0qj#ihd2x&u|6jEC-s{Ne*WFKHKtR{;A6yqaZnIi?;s*tGM1OVn_#>rv^l;H0` zA19+J<}6nK9X;^?fox;^e94YNRWcNCU9}{T5&dkWuEwYr_flHbk_nt=I70L$Mx?kX zqA=1i64to2V&Iz5GmQOw>co@f?8)c2Y)F+uKWZrLV!cGemEMW}bnm~jHPUMgK1&hWXGW@~`dqVeu(klp5Zl7n?LBxmZ6Vk- zSZaVr(CI+c6sq2+Mgo|nEr_1})^gQN7KdG3KMo8hUwfhLg9HqkovHpu0qT8~>%KUT z7+)6tYCgg3Z@Q`qqE&!0$KLX*EzeSWjYny@aF<&|I>i;;R0rg}b+Xu=urAPKuJrUf zS!h3?>b>7iJRh3DvTEZ64`jIiZ&VcZbO!fH`tC?`>uahb%|Ee2X&kTNCu6&x4pE$Q z)vT+!);3SbnY>Q60n`^J4-F^MooOl0``UBU#pGL^Aq1l0{vy ztBVTOybna7S2eyeEKKPR3L3|Va4u9~5{UqJ3_X&V-8w#9shD&?L31@?iocQEtgWw< zsY%dk5Ab=BZay}_eh@fQp6hX(>q*`xlE4dRUt;1Tkr5}Xt6eu zUkRm7S3Gsgbx$+=sVaCFS2M*?9tc>mpKyI#myL}O>C#@ob8sT8wNkK3;3twrS9t6@ zEZpGltRUHtq+S9-0UP<5Zj&tHhOkEZo?r^x0A+rTLAS-t%#6tvp}YT7t;qf@2TFGK zP7W#nm>4&<;l7Sqhp5S^t`PvAD~n7Pmls)mSi#KEsOoxuI@t_lisu#f0o7C_i(n-n zfkTjrKQ+k@+btoMra+j3aM&BnPs8A$v*p_IC7nxX9IPy{ zYL4$j!h_d|=>R`rmOvY2=1OT@w^Yuk$zlR;`fKcpm03k}9|4dKB#U*nA>wZhyJsIG zE4K1Qx0fsiomEd;-xtXufkaf*#wRqdFM7_fHXi*UTC4yYCX2B)P~(L?wpywHf>s>q z?kxf0crAR;p`#C$v#))#oI3GTP2>%xAr3=j@r9>8$3zg%1lIyBgMEkZWnbgs9WKK$nQmD4AmEtk)oP;8Z`leSOXYXi&- zi)OVl2^cn-l^h~Y*-*ZYf48sd$4@%BJ{Ot7jQgLSo-e!h9xglQ_j8`}uDyr&GwhXX zOBdPmxQM>)WdSJ!PB~qm2?CiBlP|Z8v1r8rQ&@5LV%S77XIf{BH0ywcq5WX>_K0|r zke5E+Y!r)SwQFfM#6OdNX>qe{n$>{)dnTfRwAy|TPZnk8>4&zPvpDc9T?KR}N-tT= zPO{#DVCs&u^d_qT**2RdR~S1l`Tsas%*76oGU!2+Tqb0#{~)^5(c3#IuFlF4NWI9^ zwAYg?>adDJ1AaQHO$gksAOK7QfBEl77HbLJj`PM1CVgtsNBw72h08=_pk~%foD2W$}?a46scmkz5{nWP_AFS$m9am#jBS<-CQrrON$jn zh0so2BPSKLw?cEh+BLPaplW~&ovU=Fq211jslj%7@t^_hev%B~XjwRTXIZ**hI6PY z&C|WsH~DgXXQr0~&=oz!vd6vZWS>%7Gh>IK)$}(oKM-;%-R>AA%@2u~1Om`6IUVd# z*$AA!mF25UKA|ed>LmJ+DgH3Z$`9UvfCK9eFaYNh&V>}`xdp1@p%)ARJsd0gVcC;$ zW0RGu+MgS@=jSS#UEy3;%(p}Z2-kw~8w8u!OFf~U*^ocC7#Cg#q#MC3f_qe+0Bj*q z+l?85V-wtOrmAkiUO1q)4GxvbT4l6oQ%)8KKm?7SAdQ&RTv2NA>|o!PuU_ho(CAeS zI}Dh-|0-3myNN1&&5VKAC%JEql{(TGW8i#HJ!$*XxyQ2xIL6T#yAIG-TwlISBwf`c z&AH2ggiKi*H2{0L|ImH3nRvFSEGk)y9yqoUTjjIO&1)4Td2ILwB#Yx?6AU`lGwCX; zW~Sj;LX{hP@X94UU(n!f6Y5xyu=T1MtEB>GbN9ZZ8hebT3k}g?-$lh}>%Q%}Kpfb=MeL zpQ^74UEEU`!fSpG@jK3vWuLJsSsn@D`?6i+-x1VuRDuu_CN|J3c<_zyEpK|q_m!`H z?zhSdPkn~ecech*+TwZI zeb{%*;KZ|qe}}JJ#m^y#ME@zj4?jwO=Xr6#=JE5b*B|#7J5F~`BPdrmr*Otp;@BZQPDd<|5s@qMV!fAh&tm%AT)C)ekh zuYOWJw;QY6&lorJ!ZV*QOP9|`!I$gozF$`tUHQ@+M#nT+-Iu_5*e=?!&_NmQN^?{_ zq)2l!|C``Y0VF4Ss zxdHXiR&lKNT;oB_YQ;VQv#K!!n(vpLRGh~3NVcs3nezYcvkZhyv$La0D{;ZN&#>#2 zS)epgK$R)i79&h;AOEg zv;KaY%A%cgcT2Zq(Lu6eWHqvPkeC5P#&LBw4du3q24=k?0%!ydp#I5Pg@fxNq5Xa$ z9acG7RDU4e0P4*7GcPhg8my%G&~=_d3Q+oik1Bke-Gk377=(^_k<&~fL2*SQ*@Bi( zI$Yl<>#I<+lIkIx6R8E8LNi?vtlvh_74(Hfl_ngmkVT8{G+KxJbttx?FApP1qOX(= zgUPW)Ud-ng!fbko6tNI!1uQ_GyLtt1y{<~KYCAb2d2iSiR(}wQY=+Q@6tZghpR_vN zqLeqM_&2IXpd4DwO2O+G4VM%&Wwg9oOz9bR*t6ni|2X7r=!BT_i=wX-!6%#tssNw{ zPtNQl_3QY(Z(+q2$qK*%R35R%fl{L)d3|ZIT)uRwtgc)w%U3T`KnYFfTN|k2qTe)7 zJ5mTG#M8tdV&M@)n%jYHrlXXJplHL-~3+~1`NXwelQF)V0ftN zg1frATyu_8LZZ!A6L+Yga`#Ghs~-TvUlU3#LGy0#{z%ITRsX?n{ptNLkF&zh*s?E7=?{Y0}j>mr^dNj9`M5IG_F zfXE3B8lWjr1`;biE028xV}ZTK_tnoVCIj=olJ?Y{8=s}SH!q}J2cAwRp8dL#8?o-{ z^Mnej;m@lIm?XvS{kWVLbM_7{HH*^DpovmI6^4;OWphJ4FI*FWlT{0bq(B%{C8Lh| z`F9{0Yi0pprwy<7XuW3j{tOCa1d=6lZFWDt%2^LupPdozCBWk37N?;KEMCeziv^?< zYHY4XsWRy;{Kvxp03ZNKL_t(E)X_;jcLR$ya$>W6nF9-Fi%`)bfW?+E=aYGl5zL51 zy0$Jry6eEnG%`G%9#Gl7@u|~5tNX3gKlu#yHTGxkq0^%2p`iN72R~KSJ2EPk-M4j! zYG5RC0gIgP5YjP0x6+r$T4(C2z)8%0tSOYfzMheXsS)gpVD4C=%fY!Xob_yZwKIfH zyfr71V`UE%KO+E3f*3%S>8n0sCz1%+6Bt+|k@VcF|2RGK%0EhP{rLCO$G`lc(HH?P z?Cq7MqGn6d4(17c)bca1iAGfwj^|CXi02N=2>*^2NMSA~yJ^a3ds;vmc1L+1>q<3!3 z<{rk{)N$#r3@ldFPqCD+8$%;DbJ1fz0a*v2Iceh#nCE@q$n$At$ANVD{9EbHtxK}O zBNNl<#OZHn?MT$^J#Z?Gj8CdZZ)ssZeRlp0B}|ApsFDFBuYPt$wwJ2?g^z!p_8xrN zeA@hM+PdqI`VddQ^bgg?N8*kOB}qcFdCRiX&wS~()5q`rKwzny?J#X-Z{j>##WO0V z&1ALt=hi5$%9i!?Z2*WscfXr3`echd{^{)-ot9vcao3j_3(1Ne*n9vZ{f}F=?$zIU z4kTDaLs|s(giv(NIJBb*lv>o^}EVQb| z^_y+;Bwr-Oa?-Mnh1&ORKdWh}CFZCFEA8XLk6S{@daMv{fzzjnWAJttaY4^q_)xy~71l@cm_C7gRcAMmSS zOCVrCXHWBIMb#bDp2OKoG)v-H(0RF65_SEa07wG7yg#4KUc_GsP!j0QKN3g;G}E^l zv|;PHE=sczbJ>>~tjILiSR4g5N=U0YKyw)?yuhNaHXO&=}N2|mN?NK~-UF>}- zXb&IUb^vTaY}@^Yy(~do9fMSVccn{&H4yM&|JazT81v3?TW_L!uPT5~>FDXNr|;K$1cwEnmBgy7RB4@R8>2Wxw*_<#X|3>Y_<)$v7c2)QnYI|9gnG_e zqt1@cCwcVY+kc+^{9pX{dj2|FP)7Z1M{+$^R(Li_S}6l+KYY~SH$)pySGrFG!$jSEVuEiS~!nGNX` z0Q7n0P`kJ9I-D+^eIxBT{H%ne=;cG{^u0I!BwhOSoy=I^K1cv=*|skofA;J8dG2lV zKE*nAw}eP{n-uX#GvSrNK*N^SV6^z~3NQtm(POosdPccg6}NmWOLDo>hPG6)tDKKf z?8_I|Ju*I>w(mTsab??fA4=mB+w>Z!zs!z>vGH*BmJ)GFPQsL<-HCIgmI>2w&`ef| z9Qlm(I-Y6xgaWDsJ}szkB_FwHOZ0j=sj8_yS=`VKD|7?Y&6v`y>*u1O#tqchRcG=a zbG-#*<POLvg<4VZ-1@s#W!OK>I&tg@t#it z7RgQpjmjI#4V2qv%%QMF6?$&bvr%$AF%rSRA_|)Hd_XO1JIz8Z>jKt$Jipp-MDJKM z)`lWjF16=-wkl!p^~qc+gNa1`05c@5(k8?0juASYQDc_U(h>qY%Q~!l&pyw3okB3j zGJDO7wjK zeRH;ns1i5c%lF&ksx@}Q^}g-WKiT-PRcZAref<{r?>(jr^6cFkjrR%=9@*ijY>+%6 zFoKF5U<=SsWdTWY?u8)4Xpu(MW_^~H9?9mAI3d6Rpg|vn9;<%PA=?WigixqspRn#! z&)LW9Yl3Yh7Bn(rUR7y;V~lg@OPpiWkV*8Ago#;mrMN80nu~&nmgnMDR73g(`c#n| zr4llL+Okz(g6_kgHUed|qA`YgWYWISbK2NY5(^MSa-(K;M^_ra(1nK!8{F3eiM?)~La1>Jq{Y0cY3_MYpE5eHFuj|v^@I=yXo zdgkTdmT&mrt-nk+u6(2(T&|lSxWo`OSPWapXnCwa5wDg&(S7>G?`Uv4G;;h9 zXPYlr9~&y7Cs84kNEIFJlgn|}1i|Ff!I*a<1nuCHm&MQ<4EVB>x)NzQ8|IHT4DuU2_a zqQyD(JPK{xS1iDy*jbFiC?kX#G}LZjk$@exLQk*=c%_P1#&(#>r~yL(OsI=aZH+`| zz2?~1V^4oI?c94z{kH5QwF%Isv$`S*>d9xmneN}cE&(>ymFG$|n+olvPu~@*g8c!g z{xqVT=(9?&!%1bj;Hs2@u#^8 z72;wwgP=zkn7?iIq9tnNF})?;9L!hq2pjRV1s+zFbGz86iYc*VfJ*jE@v)tK+b7{W@>Eq-ty-bfI(Vi*q)Hcy3ju2kHAsR(y_hZ=Z$e>zY2i7JbM@Z%g- z*U$uk1*dj(k3Gt(kK25I7e9CN-W{YC*Wy8{1(}VQt_xVS!ontjLJds20LRF#YUwbH z>Myi~lmcSZKw4SnaxY~)EQ{!Lp3w>oY2Z3nKJtr8WhO|QGXAe&JKs-7JkY*$GY z0FES*_f1Cgyg;uGO@A7qS}-&$Ix9Uc>d``A2P3a+Cp{Gy*;R?wFoVcOYZ$FAj7;#e z%_*7ERt_>M!(`W3hQF5zp51f=TP5hKsoa(4QU^vP+U#De=V%~JOwMS~J3tZ#NdExi8CYLH>71RdB;pq8f-u68&0Kf9qhf8^DgF zNPMdHk|-jk@>_q!?>A{Ao0$1JiJ>=o3|MS_nx5s(y(b(jUTZ#_HdWFeT)nRY9H6il zBSr4tzLfe0N7Aq=>ce&>$0oIodk#FM-WaMZ8o99aNc2vq(|jC33RR>VS3gdJ10z=1 zSX5E;52a?Xq`HP>dhXPfCT-QeDCd_{@)7jBJeNgsb15{f^K3T^Pb36 zqdM_eC8xsn^zaiy!{h1=otUyLI26D;H$O9)ZtS5=94VC`z#{7k0Hc2=?57*POo6Ji z(b!SzWdxx2%SIEtavpA6IcwBJpFJ!t2V*{{KDNPP^kFLJ$$QzK*qvuz{a#vlbU*## zN58KgR?ZmXVX*12FQkI))YGun20FdxbYx6b7lOL5M>s?u&$vs+9fx zX~(|f8a2T8pxsG4YnYaUah=ykvv<>jyH~|Zp!!aX0H`F1gKZ4q9(oreF(x`MpSWsb zJfWItDzW|Pspr3)zVW^PEdBJ){#R9nEr|q+A;6;j-ID7z`hjFlBy~gd$H1vo7RBlb zYOnW!<>&1VA%tZ%2a7I>qkc1lX$(}>BRHb^L;@;=Ycg2$3a8XcQO4~G7K09302E0b z#AKjpM^aoMb7dv1QUq87MAOpKC$TB0-6W%_kbm;w>*@UaKUNt0$+Z9v!2yScRmO?e!Io?N^RrpfjV(go>Mb_dF|; zDV&>u+-~<#eJ>x%E~jRy}6#GFFD_Dp3m8XwmW9c@r_)-lmq3Hkt& zrp5?O*T99UkIRe7a$Elr-w%m(D6VkJX<`m>6*KA~qG8}j-zha^uR_{)`F>QCY@V5% zM@1>nwRkm)-UG7gI3LMdFU`xy21Pc07a$Dkl=>_{(kZZfrZwhoXgDpIN2)H_n0bHZ z;v!-pE{|?V#`-J?@IrYu-&Y7(l%YHp0MR1L+_@8JWob@9WNmcYfl5@A1&V3<&U1~* zE>so4_py2h28UJE0Z`D-G&QqFffynv7e0C;J)FI1()m$M?=s%@XE)cJ`4OC%Hl(CF(3^U1C0? zI{)-C(sKA_sMpB_E9tNlc8yNw4h#)$&FdN!%6Lc-L5!Uq5f8)0YLY<$?$4xm@r`1+Ca zIoK@v%wn{PjbLzZ;QiRm#9|$Qb%MqA`{O&H5dzkzUgU~ErQVuXv|=oT%`)?0wkKi) zUS?w-EQX*8EK!@$$uv2+O+9g(dGV-E1|zfU>{)7lcwxeYrC;(qqU=$ z0%~2FXe9JpD$;E7Jr3cQ9Yr{T`G%Bu*kJS=jYjc@YbJO9H#rU+0y`b{=W% z65~|!F=f-er!}8h_u;vx*GG$ml5WION?_E~*>*vo0*kqd-+@;;6Fa(&fg!a)Pz}b{ z(f2qxvnve`jVOs3)kpjzK%Jxu32zbt5f{eZ&NwQBu`;eO+v0&iuPESie1DTe@(Yuo1hJB3O4>70gIj7#el$%2aCDdS1nr`P9vS0s(2?no z699;)GUxLvt9}UcSIXhK>nfjC0KGesm_#ldO-yM!~`*h>7v)b_|; zY8Y*nsc#!AYtjZZ^E+V-gF_$m)Bx9^d|M2>HD#|tGxGjQjVtg`BDHbax#y^YGJ^C{ zd3Abq24=Qi0dnm=tmmtC=Ik|$zF{Z8&6s{3LL>!~7m04m{<$if?{0$1kx>LsPzttc zl6q<)`-w5u*+58VRjP8(9>Yngmq69nbp=TTx;0pATz3Ggj;db?%4`S6*p~uA;@$%Y znqz1wsAl1msCo(dcRzNu9Sw@Q12}#`1J?JQP*#)5M^w3aE>>Z$Y(kzFSAc+BZ=bT* z68?E`Q*^oUg?IU9o zS}Rm+xfa%*>jXr{e($!KWXljMnJSeQ?$*cuEAojOoB80~YVzx@cfgRmydVXno~7|4AC3+OAfK@rfBFk<8X1BDNwC z4tiM$&Zw>c-s#Unl@s7d&nxT%6DC_%A_~go8i~TyGMAJ}nOX$A4>)YQo>frXYigSR zoumbocY1eWazui&Ii|$Te{0TQa~;a~iLhIiFdax+cOFs&y(om&l|^6GE`pw70)R2gY_fwgos*U6+6%Gr8={cm8fcdS^+v!gyFvgeBo6PUB2H2Xp**od( zjnC5D+&zKPFMso&rmGjpG%d?9Fyx2j`{E~Q#1Kp@z z1FH5Md|J;GWz*O*Ifiys_!xIZ|M32!&!^Kb|CSPfqoY$|b#R}|4a6qG0O2{Y_g7J- zU7S}Ejd{)&fqHdAU=3GlPma4798OLjhIZM?Hcz zm)AmJQx{d2zhAqt&8%Igdv!DXc-#L*v7i};l_1X}0I!BZzh?B*&i%*J_FYG0$G9$h znvJ8ns%QOh_O|RKajC^##A6=kSAM-NR%{xN_xxceeu>zm9f#}L@l5?W>Ny=a_9Enl zo^Njm-Go$1ZmeCiDs;e-X_9)3o9w3QPt-Zx-BFNkC+bgJONvPa6rFa z+uxs#oP0HH-FZM%dVYo-Cb4JZF<_L8st;{=ltJ7(()9EWB?bYMQ1b@7I?SE`Xx+MU zHr>8?LG$QH&;e`+(AXc)rZpbIX9X*9=lz#T*trNxB-89%19+$Ond}2LtXL%S?=cg& ztZpPD8a^q>8+pqp{ilJ zKOYC85j+)$lJJgbrY*3jUVrGHE3)YsC}cHQdlKqx6m_)?7QL4++BnQOm(dw9o3R@W zRbbJ8p?*ie&&Lw*HV#Ux5=H`)7809%sI!r$0N5Cwc>aLlLnpo@Cd+5%-fYBNVG-Et zhfjVv?LYE-y8Ox8Y4_ffX>R_$p7-(sGcfN-+W?U<`pglp0YFOpYiwGT$GwN1kqy0l z{eminTmxr>M2ke_)K_QKEfVIZHN)|z0{nFxs2P@=-GLBlGJ!QI)$%>xiz-pL=#M2v zJqF7ZaZA8!WSI-+*xFgu&mE_ONS-ML5fpI)v>0OWnrH@?7WXkWCWK^)?}+yfU})oY zEPl?_NB0YjL{Zzw=JQsdK{p@T_%%1Ud^W5Y?A6HVl!Sz4w(nIRH9~Vzz@LApwvl@R zkk>>#$Db0PNIWNF3QvAETHIxS-rZBapM=7GYbSs))3 zgvhw6Z$qk(RI4Ur$N`bOltbIi;|ooCWmWUIG{70v+LEsp7#E0C_R4530t$-k>kD!JApwn2X)}?c zG6xTb0!=j&r%e+qu?2Dr^zfsiS zqAC`ku@3s%i4eUbTGd|N zl4phOeg@L`)Yi0p*CD+Rij@Ht1H>IV`DFzz*ROmeXSjlBO{g^L{Rt+91UON@yztTM zK0Mp2zl`G8PEuLa*ai>A zG$YJ===dz|3(+H}bchepFUJ@c)*oO_CVqT+TN)ji(CLHrs7jt@!r45?01?`~{rxs4 za1iS9us{rZii96P;_y?iTA%I2jQWxh-A}6L+WXjegpDLb zMo-xq_hc;(5AI)Y1lHE)$$CX>`G`w&qujRvXagz`Hj zNOci19o|w&DU}ne6mkVre)(*`GeC|r@`%c-2kLq5EzhB&LhliT#Iq)ph~fFjDk3-~ zjBMh0dZlKQPDxy4o_Va0bz**D26KqO&|hqcDXxpeBmMq1zmV^FkgOIN#70J4rIX|@ zz|o2rT!8k0`XG(T5-mD5mo5Zw3Lq(JsJ&^ZRz)-wW}c}jd{Ygz3RbCr8e2ovOevq* z=q<$smH!QqDBkzfOW#$}_~Q9DJsIGMLf0uBL^BhiP(Z zdwTb0|HfEW>L<0Cyy3Idj~aRmAppd4i1rG=y1=rj*V@<Or!-`ch{)mqy& zHp&L@YXIGnFh+Sb=9K8B-rE|~P4z3rjO&&*L+xLq#mSOD^u^k>>*RQqF|MQblkxXX zKvjF{^7ls4uX;(G-SD40TM{?hcODX@oz@%HoOPk=HRP-lld-W>j00n)$t6jH?Ud)1acZz+b7JHh(K`u$Zk<1Ds50>Au0*)YsUUvEU(aqinewAIlx=XmgkA;XwIx_2{e+jCUnGz8BAQr=IBW5AFb4T~&T0IQ@x zF|J3MRb~7K(!kK5#7t^H#{Dx&#HfQtAJlz8YlT|FvvW*@vE;d_m(xc<=$Wpst0#l! zuk2yWgwm`sJ2xgofTcC(qY5N~D1*akYI?h}?J>qd_DXb0XqBjNTF_z&YEIYn%1rKc zQx?v}cX9w1RRM(%jbN;q1n80?+oazu>_B@xc`krO91K;kOkb(8x4O3oR(1D{^{le?27-)o1>iVv{H65h{!JxK>^_3NTY7!Nhtxo@ zxkg_7sl*d(J;El`^y@NYzVuW#eQS5H7&O!-Sgfxj>;`|TKXvC}tv@t1XvYmoWmNgI z`f$nchrMQB5R^hOr7FlX#5U>~a@M@Zo_-$9`dwR5^%KBW@0ob60!f_n!C_JMwrt(4 z(GUD^H#lyfV2dtmJ9+&Gm8_NBC487+U0r9k-#^f zgt-W?#Xop%BqPMqc*y*|2Wbt_JQsJNPtN>;oeL9#A$jOyEPMu?0WWI_k-c%{QUieY z``BY+ftXFQq<|@VYCfuiMFR}9J}k>081S&FQ6zyZu~+pJKVfB&&w_rbikXl204&On zXf9_NU8Z~Tk!JGd{`vKJ!$%rbbSa&9_FL)Uz3UnQql65A2mj}a_9U&3J^flbdirbW zhkx`x`IxcMbmEz>YsAyF&pt>;pMFi(aqi3y($2jnMFYlm@r7RlNWuf1HNtg>)(=XZGmRUrRSGf0!u><2^M?JV|KsH{^8uSMzj>b6oIh;)tkfu ziI>^C*VDZ_SJV9L9VM_d9l#UrNeLpy_W97TZCQ{kxsOu=Gqe0y2(_>#!b0HPgF*P-MNVU%>(pfZ+Jl zOjc@@M7gt4Rb?9(R__b}DhA#_4@1IjKs~8hMgpj>CeO{Xz(D8I=c{!ySaE;d3|RjF z>ak<$7gHv*Mf0t}d7bTQJ~JpQ(+a8{+`f{w?AR|kcKXi9N;jNuP68QaNMU3EkqC71 zn%d8_-agQ`oFFotHk(SI5>RfkhzjiblPO$oY^_Zlt`@mS+Oh4w2(KEAVy_cTh zwm`#F|6QQkKdXp~zBy359f0%fGs zxgSds7!8$Rfd7~gh9kL*Ac8XKK07f6c{unX=sk4ex$i;o^C0HG=aSj2|XdpG~^zSag| zDUHw=v_ymGcOGmLXd%3#exK!qbp6W5qU&kBz1NvJe^eT;UH(w(YSj-<9MnjqTFJJ9 z%^=OZd3hWmCfE3$SE}?{LNm8l)oXqgU~y{8t^{3}_af*dt1Xb@)Ldf%_?^^=UROp| zfDT<9u(;=#sGiJv6AiYnU$f)@WAsu+e3A=jy#ep0o-|J4p(%{}U5iQ~%JA5)b3!GwI0FUvVZ1 zGe2o@uu2Soav62ehxgK>dp9)Tn?#n97W&z|ss|=&wyea3&XtdOFq-QY^)y8_-Kvo; zpymN>*kSCC1;&<)v{4RLE$8p@YePe6uzx65nF#C$M~t>u?2c9C#K6$J`$A9U{-}It zZPruz^uxbNcW+;Gd){yJ61{h91KX}Do6RDo$`n0n0v=wOiy4aeM8Kd`3jwtN!^M10 z>YLN|mTdHmtD#1WBw#npe8U13tqS$UD~kaZ1K8LI535{SUt&}?jY=6+$f$^wM4%Z4 z))6KJ?|c08SJSmiA9|0xu^VEX58^gQPkl8VIQqQS5ZdUr9S4>4;vP9y&`3E?e5Q>a z*^qdOX6MpEuw}dUC%*ICnIERDyACNSv+wY8>8&6Cfhzn|s<3$|r9u;CgoovXiq1e3 z6AEqAl7i}cm47wx$mhcbz{au$!~q!?Ms+Y+c5(tApl1G^m?9{xqO+4MfTk>mW7-^1 zJvUPb?bLb`gMDF)9gm;#JX1?Phg~s~YvO|j_U*Uyd!oFWpAPDLx1z~F)Nsvtm6Yc9=W9+F;RkNvSM!+ZDfV zpjcHH<1k?4Fm~n?tREpVp%~TR`|EPs*Vn38J}z@&ZxQR-T3==Hs#wh%dU?i{owS)z z7Bra?7Wdr^WK;-os2FU36@ie6DkKH9WZN{8$1~dN8%Aj*0M$4EpA#u+E17F%^a!Au z40UbfvZ2d;lHEZy*8}ayKwVLktplWZE;TT(M{BS)+zZtm<|~qI-?96M`qKcR`Kz@) z(OX&@o3?T71%C6oSHYZ|tW!{8Mj+P)T``_(BpM9RLu*|#dPyGv3_?1VS`$%<$E@Hfp)$La2S?+;2^66*2E|s_$ljJP0*+54 zAVauOwfQ1IvCA2u5`vsJ=Zb2ZGQbE61dD^&W>f)6b6|cBkpyE8lhI^$BG3K$%V%+GzNA>w%+d*exBkpj zQy1sckdy{(OpPiZh^~xJr4!G5D@{zzsLFQj(g*4C`F9ljK(U7A$+IEjORx_;2$_2* z)wXY`YR}7wLzC1QXI>q9ERQ*|eP=8`r@nf^#A2M%ZZJQ&3K#+=+$M1{BP*HEm+hZ)t8O2nYlDgj>FD`S(Yz+q1&>EWB&p`-^t!)65Cb#d;V zghuG2BFDwjD9 zaImU--K1x+4Hf}FK{Kvtu#reM{~5jp|6;LMPR`QnNq_$OdV1zdzn#v%_Y zUFh}nVZZg0f1#OLK2`Q*%Q#X2$G2HOqe2Jpye7BQoUElUKD6J_;he!ZrEZzpT#M>VTHMmTqqzi;%M#-6)vdss`=n(a07DP%uh~oTc|VMITAWwe$pw zn>>Jra!XoTm=m=ExVo%>)Klf&8)+3xjffZ- zlaLBkv5_GQFeDNq#kN&ZR+&>r!@2q*Ip_@P#aIW;Pl16qnRgRDP^F{*&0dwoxT7!< z0TyF_;n<*lA#G2UY4^U9>E^YwqFF^SlAp>G&>gw~`x?lXOjtOq;<&o6uw0G@h|%xp z!MOi|HMSeA#sX5Kq2d5JQv-wX=dgM<2;3rDDg{m-wUSA9a*R;fjJnFed2=%BX=rf7 z`gxY-vPcduj>?qgH~JptbyDBu-#MYv{Vpva^lFG+QvPj`Q8NhwZx_$M<-vXT`<&TvFdaDZoY{a4g2xdHT$dNr{7*%X0Q}m;_a#*hSS7m(?UA7C z(d^}-ol^V0mR&Ysj;9k_EpJNKPP&%gG2>FBAis4woL zcYh$t55c;qfbZfJ{*{$i?KkL37hp0ufOG>I~F2@heWh%O}r)s*ZAh zpTPUEr@x-2W_H-DOK(3I7-p`a%`_BUJ=xe7p3BV6LuqVmTKfrs5*sn{R2t|@N?@@c z+2qd!cl?=Doc7Tpw;8G`?*+584De&g8)cx0l8W>PNC?K4q-1+zaI#-9| zJ><*QR+QM`dKgs#K*oNM7!&)(+i0j#KL3^9OYgt=rvii68GeubhAKEV@wqSmj_d@V zrP-GL-0NMRM`U=SNCGhedoesdk~8L$3Yar`v69{%t0=MJ^j!8<{5|?hV^(5NNo(L; z{vM+>f;t*W^#aTb=rP8Y#egLdSCZFuFLqBs-7etJTCCXLwI)s7oYpa9Ox+2-W-^d{KJDszvr8$%Ms)z^{n7DB>KE73V^DR|!!n}@( z8;%}u2OYqCLk)7grzu7h)D+vCB_0&m1e_U|3=8xju!CR>bUH+J1Skm#5L^hs z4)qF>fA)P)t#eT>JA?wu()bj_i%pMX|Jzo?^-~)p*f^{SwGi^t`X`T>r6$tC~Nw_bOuFFZBL(m z^tu31ynhW|S!4Fj-ovNU%`4|zm9M*3;o8~zCQ)y+GxmEV%d9WRR1^uoNuaQ82)@*x z;CD60ixVIYm9Ib)gF>ts@klrX+#72 zgrExn6pg@P6weCJAmrp3<6=Rv`f90UYRERdw!?W$M6e9FRuV%JS6W`see*L_Dx>m~ zD`8fdHmbU@BLEiLb{$mK84vyoo?VhBaw3_zv5~fH+moJq<#*NlN!7;Ahg&jdtHk}< zn1Ue_2ZR1SKB=B=z}Mu|&NMnPCHm{Ar1*CyW@6H7DJtL!Bba8>#@dGdgyuRwcQ4(! ze!(i;Yc>~A2}jZ6H`2`ZJ)-e))%Y0vo05?+Yfj1OegQ#RD0GibX{8U2wLEzI<#g`d zAEra6UKNYt()oAv`>Fut{x73}8pY3;6kLbYFspfr(aXVJV*~31Y%4A=Jd}1i-NZu7eIaMFTUnA1z?f zDDNb6m`@8>gnlb=wZ4IL==hh??1LMk{L5a6_R8nl{*oQ=eoG1PjZUQPI}W7zx!H94 z`gx*TVcG8`MZ*pvT(8h zH{19P(33M*eklAiimz@ad(H0{V~+O?b?*9{mYAYhf~jqf?!_*~6O^GyUtX1cXa+x} z;#-5oxW76ssbh#x~k$q3*ZVDDdW&C<6wce9Z#D$bfz>u;}mB;rMb^*$i3x ztJ~}IVebM6^SwR^;B1~;D{uE&+j{wfa@DQ!>W?tqhkhiu*<{ZMNZHhI?3H1{=(uBz zUKxwV>#r~lE?FHJlvwM!`q4@P7{0JflgyI9tKf*!8wmpKeN_=%vFZUFcvE7v&#sM< zU0K|ugSK`>sji%=f5pZRK*bpunGlr;${ohQ#)8;@VluPzTB(8|wbdp6vk1}DN~4<@ z!+3($Upk<`?!nzFi9Sda*T{H7nNpuuO`&T){p$HP09?%Z^9ohaNfZjkT)Y;&#axaD zTJkjJ)9Uw)z1`TF87%sD^YaZ$T(XVoN!oruforDOw(S4{H}tFa4=SJ=8XOZmkMpen zqf+Ce`Zzd970Zk+08F%FfeH&ULJYu$&l@GuY{jYqC*BY07}WtO%!S&b9l8t_>@x~g z4FM5;4p>xgMjl_#%$&yaihavyfX6#0x= zp#1bp{~*2ejsGxBP3=fGuYV$?Q!0zl!U;%mt^~7Gd!}%@6P73dpmJ}VM--1&muxUR zS$rt7P-i(SfHwXf!{B*8&24pY2P!N02-pdBuSpd&06%L%6_~!s=xyVC~Z!I-+0OELY_pZIkBj zWOc&Sr=FUvyAH}m&|4LOt_7>M-|3%%N=j0O*I0F>fJL2a_Yt*Hwj~XQBuGP*BvaxM zNvX!I)PY(vxNX^t&4>#X2n^HR?HL%5Dv3vP9qZ~ddiKk|tt0~j(XV{+OPibPGk{Ie zITE~;GAcA>6>UsS+kBD7Vm`}HqbmkS^bD{=lhZrXuDvG&LZBj(0KzW-C^(m>VDgL~ z+`BFSuX(dj8#R*;p{H3BW%E9H&N2IHWPB>kqQjqQG; zk1)nK!pCo< zxd*p=_N28$AP9B*nQx?bUjHNY#Ja;2XgG4}H6^yrpZSp`z@o?1eQ<{!LAC#Kd{CK# zIvL-Hz`7)Wn@MATqW-%2+_u7r#y@MY=#I3ROz!&2<*+y7vX))Tp+Y%x-GF3ou&B+I z{ZiZh#J|ly)xNmX7&Y;SRs2{Ap10Xw^NH4C62LwfWx9&Y4j`F`y`Z0**kE$&ZdI~L z*kKpw9j8Bf_5sSPb4pa=8{}hMfUfVrv6sBVs`-Q?E8p#*Y_^b_{;XT|;O`S8=18eK zSS&yGid(x9*yCoS5)uY31BY(+S_9Sk`E&toVSq|i%(4(|u(8)q1ZKglRCW zDUL>QCV27&{K^OiJJRvJQt8Omr~rr_209D4b+L?+#ZZ=%u_s&JZTH_Y6~5djh$xB^!R%(&tzfWw732rfnQb(*9`2Y65> znziQ?Ban~82GuqKN1h*|DfFpm#+-TyBS?zpx4GdBgH~?U>D9hAa_n9O4yWJTC(+MZ zU2L_%axl=cGeNJgb7-NjTUT2<2W?xn?@Nnwvr-+i{o#NtGMEmAJQM+)001BWNklN&FyULACD6{gu%I-6J6)=e4hI*_`T@_oyd9=PY%joh2*yg$ihp|mXB!ol*ePUE*xHd#j zkea6gM1q2Q6XlhF+takH0kl99FtLh?{#3=r#7m$w()UNTj%pA<0BR?FgO*&dpjA~& zRhKLPh(0u`o&*v|xAO&9L}aK2izfOIK;3(N?Ld3*Zh;T9Ux1S4C*HnX1d}4v_5>8c z?9$Sl_NS0m@ZqQ0aO|;~jRCTv((=0#i-hCwH@7*wPpx`NT6;W-dE0S^CTRq;t zMz9C~U~~a{i{R|W<+D;_l`<>Uya1yvASB!1AU*_Kum|#k175Apsrz87&{J=Ih@@p- z-(X@8ILQTs$f%UZ97M)9kr2SPu?MJZu}|1L>^YJgoG*H|=N{fyb&~7k--z+>jPWm2 zu8m5(JAL@}U+9Xccpf?Vm2~U+dEFJ0lgK-G^u_f4+f*+Nj3Wwn@We~9HVa?Q7NescFXrq|Wg6-6y|ZV|E=DJZUW)z-E|laXM4v#mqX2|NW3l~6A8DJ|ypj9CCj z*V(Y@so8IP=ClJ$sD)&D%TD?D>8*Q|Xp}!$m=kM5KIHx_&7_4r(0B0o%RyFcJd0lo zSo~G&g}=-9$W^F#&|bZIB7j>UV`M_KIoegs`hMzc!)9PHH|)mSH8*#iy)b*$9`;?n zS8rHR162`%=?Z5vDC!1* z;^f5EwBo8+7^(S3v&xvz_s5qSrv(O3s&tv;Oku3z?V^cgJ}s!H9_&kI9l2<|Uor>k zUqK@ZBbj@QA_U?fyQ-?CjZ3z;fT6a5GP*$+RA@&yEgVKRDjryw*a2?NwPW#Of>eWt3F0}kqxkmH`IxYwmB$!tV#gH=Q&5eK^ybR0MC>FkH86v zVSIIF0Bf3YWCnXgo$U&Gw~D%FbM5m?K&jAQ8KiCZp&)Z)M1cepHw?W=%lq#URBmjf z+cz#K=p>+4W%2q2(Hl#Jhm4^;|3-$^D@8_Sf`ZEDuBRP)PY9e)#i8FJf^w=73>V&a z=(ND1=%VGJ`DNK>a6c!X`wfYv#GKA>mi2l;uRH$C*97zcivT+IC_sk579h;EK%XJV z1YAbNoX>xF|7O~MWb<@EB`{sZsFL`8Mp=IhNr zRKScV1kV=603aCf$2npyA7B(Yb1H(ItFUdHFV4~&yv$g*?+Jp2{QRuG&-3IAV*9WMB+k?m=apW9OV$Q;Ln^v}1jWB3 z6(y!Jt39sDEaz!;Rg4XKZ|Qa63sEGVWh5c3Drh@`^~xemv4^||jUa}8#p#(n>XD&J z8x&d-=RhcIAZ_1uSV1z+{Py)vv{qJ0GXbcm-$*oNXhgKj(b1_iJ+o7L@YeND1#Zj^ zn008=LF3%E?L#g0QVe*@_I68Z7pK>J%N~_Q0Z@t@fm52v$h<)= z78`8+`8GD8um-Tth@W|Ht1D*^hYIfGJ6fyEi`5d`bG4c)pxH z5=fK&3@0YHr(OF`s3)BYFY8Ydh5d;Q`uN@NEAfC(%IzDU8SVPPOP2y&p@w z1hBIA(CM`I;OX?~M?cfv%U~`mRJxs#Ad}I|Wg9eZ!oVW_D}zO+#cK3|W;q(0rv{5w z&9k0#?q5L1`@r#ayw>yp3@m1wW0|wuuNE}b0E;1(Vt%~L5Ut}JOFkDr9@XF6U)}>O zvd+)F`a6mrpot$i@`BhbJY#z%%-9^)zGpBypU-{h%z6(eqGOyPR8oW9OlYKjL1#qm zKk~fR>B7gqkiCGpaQNh_vS(-C{k}efN;IdM`Ooy(lU%?q@x`99XKOuutd+)oK#xxw z+8fwFCAU_W(w6C+YKemD{qbON zv!X^Z33aO7VeSeiuXqldRr-|3fsYeNl>WJpDG@~oi;%x!u5 zCt0e0r(e^q^woiHm&#&ny&UvZfpa*(nu^fNK}8&yhoH8y4zaoFpt{#aE-_olTm--{ z`&MW^xf8oI4?hEh#~`O35;-L9na1Enazx( z3TZS$lY}3U*hi+kaAovKtu0H;1TH&4vI6PFIb|~mRPNon;|Ee4*ThB0#d5=1P3VM&J(-z6{_Fk$J5^*`1KGw=~>NE1X8CWE6Hn3=xDs(Q_uf~df~2L`6%~B83jxb#FueHeX&$S5Lh{I>}B2a`1qFeaQ2qy zbNdcIpKf0}r$CL2JL-Q>u&Hh=JhF-~i6lVV)*buwnLLY+2#|)y(^Jp=M*7k>|EZEH z46X(!avlJl3zrH3wsF|S9L!}bAuJ?i3M@5P2W~>3Kv=(67ELQ?Hts|A8g-7Yu zwQ~~v0m!1n$@^1{r5}pDFV$C9Y?jUR-WCg_lc|wzB=s#~)9Gn}?kOs?#I;t^+6rPk z1m#d!QFQj+TDcNW5>koYZo{Qf$h2#qr`P%_LphXS1Q8yo?CRx8W zYob}I{iZI=bqO#lk>x7SZRg|XsI~*mglN^r-16rgzTBK;v(2KN2_#y(+7&b;x*X>DaiGX+su1TYX(?xH8z z=T4H~U<3o_@zC*?m4y1mPkvv?Q)6cIr=9yx>P(*fuvmt&bM5%Bpx_D6WPnJ2BY-Q(R|i;R#%K8C@J$&AsdP_&BfXT2`H1l( zH5J-tHU_=c$XtxAF1J#3eCw`NA({GXxZ|S1_~E znka}QIHWkcx+1`beSt#HYw`c0-H(h}g>hv?z1pZ!KYDaq6~(EU-J-W5?u4Br*@Y-s zz0r-WV14z*9s-Q_0&Q*Y{-poj?EQXSV6m|YoOxA7uyw>GJz_R9InCluP0{Zb@6;ev ztx}=Z?*fjBI)hoHM7-kyi*l;uy}i37tZf!8Ooc5odj%f*zWY!9n+>wEY#^w7WTPlk zn^GI)eN${Rqv^CLH=?yAXjF~-j(*i!;7Pa2=XqV-htRV>vz=+I97g+A{C8npYe;k2u>MKc(j<%Q**y zz}GwaU|Pe3lK?|C4x{QFif7Z!Fx80#IcZum9Eimj0gMAx8M4bb7=l%0H5VSqv4p}Z z^eXQSI!eGeT8AP2aSyR6?KRCHCL zP{3pgqJTV_+o^z2i6#rI{@RgI8!kOyy?am}se4*@!4c=3>e!Bb$J6SP^&Zk2 zcjVMp6zH1B!=wS#KI_jSL4d&4{KGp^kOO#=@mEG&BXK5`kOCl2Y}uaYnTZxZU?Lk_ z6BJqcCKn#fO7IGbmx;SDie^$Ov_@+gl!%=nAsovl19~Mq03GPzolJ{XC6T1h z5QF4*3rO-_fW4pp;C~mWCJDsaK_fkK@)cE8AI;tst%!3B;1}TXUKh64!u);BWP^sy zv*zdH6El`@fRO<>a~lcWO~Ebq1#lHmnNzUHo&XqeZB()p@T!ugREPDRrame4LTBWh zQGFmG#ec@$Fi|h|GeCNd3hTqWMbJoslcwO=(L*SsTOBi&*D|&FJlkLV|Jch?OSL2c zww@m;VHM}!JemdjwX$lrBytr1?%Z=+mFu%-eyHa~m67j}v@nqtDrwz)JBh*JVOk0R zKdXt^o`6q4AA1SEMr8=QOMrg;;`;*9JQJwZRQB*!1pfr}B)~3TIHRNk!ZbIooE11Y zeDce(0~gP|sr}2j01S)_kES6ij4rAowgC#l>+3p`R1uNpzk2aK?WvgmDLV7k-RYxu z{z~e}MG3QQ`%Kl-lt@j4N}@O38iBo77p>jYHQ5WH0*ODOA}>0oS4M)mY_ku2bcX+) z`haV&m}mSV3SulSKB+Ey?{Jv~Av|t-S63G*b&t-34_>PiD zh^-ww@g*f(&b|L*C3(0Wz(3~`@H#X)rnAWRxHrxli30lTN#^We6wd4|-4zLj@KGd# zw(dM61_7T*a(-obIZe*&NNH_VHjG}@65~d)-{vSP>4RvQ3+r?fn|WL;->qO$;-8X) zY*RojM(8Gt)5+G`{4<(~def^g+m!u!2uJmZYi&OnJHozvUu6LwE0#ojZas?CY*_cB z?ENV2sXf3)*@T!-`G7Vuvslg%M@J8~L@2qRQ!jjH0|Si{!IJgpvW{3{Y`F$i?<7l^kd6BvaMiwopbQA|x*$l?>3Z(g#mwi-N+0h!0Mle6DUWf zrQ(_^Yt@XsE+0^z|7MU`0v7cp_{_KQ>Fsjf1X@(;Ody86%-)IocZsZ{M^sJ*djO^T z;XM~}=@YF`LGIwN)^Css*yy0NC#eX!sZi7+JC+TdR{GMKa-Ir z+kWua%Q~x9F1%|q>C%SIC;RRGt;_OvWZH*EM$_W_BUJ+kBsIQbWK5ut{tEyll`^VR zfFMBc{$no*d|mtOJq2n6S_IWl90^{?o+?mXTQ&N&123v48i9d`kAoC4?h?OYOaWlf zXQ<&n>953}a(>9X^E34+F3y=~k@}sN^n6KT1-0EOG&Zx9dk35X3Wi4ws6t(go<}LC z`nVFRc%Odox~fQAH}5$=dq=%cRBHKsyB`zf0T7C2>k6(H&%P;;J-uyr28(tsiTMD# z7GSE^j-Jdxp1DzH$w0Gbu%GO8Dz4B*`4eiRM0M2HZL9*Qxl~)3y*WR7S5;Z5N$VNY z14=(9qi3jQ8eoXP%cS_rjNuMH&{igOu$a$IZ7(FLA4v_Xj7nKL_J0d3#+*ml-2kc` zRmLJ(0jQ!P!yH2F&&bGFI`zVL6rcm-MfGl!rbrl=J=Gq7G2mipdk&t`-wEi6&BQDi zo3fUK)Sqr%Ih*1sHXycss2dtslQKjG7@#rlhx;@aT8-w-vsdUT2-bP zZ#A`5djU|Q1d#@#Z=`2m{hhRD|5NFwfAP=L?Q7>v*v-8LpL6W#*CeXNoYI_4%)Tn@ zsVj~8NP`f)G0`6q=JYI9K+Z*&SeqD3ZwwRb(NjWq-G0v$OvxxXrB&k~ESap>M)r^D zn~%Y8U*A^!3=?dzTj?dUgjy1K)?7&vR?Z9x0D_;D2+bgNayZXNwBEr!jWL>-=B!S6 zUo^7`S1h4J!fO709&ZqSa_^yM)5zGkX1_kXcSGYuuvt3KY5^!VwRI_9lc1-%h#jKmHNGNtld3gUT(Mh76c|Iy;+o=t*J1XVjeD|%z|-mBu}P^~V4 zHk%ZaI1{SITNN>XUOSfT5|4L_ZQ_~q9XR%4^;FDIP{Joejj=O+`iO0M4&w@e;i57h zHnYR}CzRz?6((q65yW?Xye0b_Mpl)PUk9-42+UiTQ!77x?#g0aDT`pY$`(e`e%Jfz zLTNRzjqXpO4i+O*+TK+42Cpk}0aoKs$>CKMn*g6dxyuH(1s1E*)5u^b;}!`64NkRz z!2xuh1S|^h<;Lhvb=Pi2qH!P93+(esCDn|*1K`KqL!bJp8M9m;LA_d#bCx(ycNd6Yfm z{gHkT-73;u0cQ=2Vu115s)CfQ+xMlL&;Zw<%o&Z9{y9}6ojRq;fcF=wLa@A`Kv~b! zM@oodv+Bd?T{$jSwp(LO6f`*%xy(!~`^%^-HtR48&qOt|0*dv12{0c)A}fOf#mSL1 z51Dd{CCXYf(-PfG>*xDkn*q?wFqZdftW$Pm)*++pb{`qX#14W6z0idQtfh!MEVdCcqD**l; z+`C~wlaVk3Mzd6pEj@uF6B?g`m=$|P{fH8pShs52mL2K(#ShhsJbUkEc7}jG^-}u4 zVuDvHd!liUPDq9I)QjI0<%^pNu?VRz`e+)S4d8~~CD0~gu3_&R8@d(%5x`SQo;wbT zLaA!OkWmHkdpth&G|xfeHOi_Zz+!Yw?238_C%2@DNrFY|5fj)I_@WYF1GoXQWaOc! zF}8ysUVv>QX=wKtiil$qT5EjtgF9E!yFdFk0$n^S)?_Gj#0zNH-&Du}=~NbtY15bX9(*R9c=lV? z`{zK_?2EA_R#q3&%A%?2Ql-{Mr46wJ_8)seaoEi(A4^<@-zTU?$&@NQ68W4-6m2E` zHb1L`$^IkHYRzw7`!wx7aMD-;SI?)>@d=~%F3qd=jcPJ`Focw5b{^0gYkr?v7sk^5 zqtB;r{my@>bN>B*`9IpejNVDFz(4iewrM1IrT82TtjD)1KJ`8?Y#6{XW(Rf!i?%mpTRod+mBvb?Qr{2#08UsTb@86hLCb?e|qU_|0HV-&|4}y=6;o*7 zOFV1rCD%g&jzo@Cg01Hb8z3<-s*sQFEAauVf%^s^PB7z-pUvG*i*pYeN7MirDz>Js zYkhgBKLZ{s##D_FdK~h{fkgv-{>(josH>MD6k~56(+XUWOhpe9FJ#XJdo5ytw%@ie zp~MMo8&%?QwpxjAjoo4e0QuU+br@)^_oLYod!2nhlHm1wn!sVrdhE?&@Vjp(zN%*) z*PziEIpl}~Q|h7C;45ykWl6|%Qh}5b2b#=S*Q)Uoe2c}V%So6t~uJ1g&S4a!UXOyif_A=UxuW5HtefgRPjJQBk)Vf7}9 zztW zJT|L~-R`8$kd>duGjD@HJ!?_c=x1{Q08z=S`A@wJa2J)&cqyP``<^2bPr#V~P-Ngm zx9L}wm(Sx_Vk@BUVIy$pLwry4A#=DmA30T5l*J*@C@)-X#K?K zq2mhXEs0RmQJOFAmK=!tBa@A|2w7{g!vp|2W9w_G;*|ctIMQ`rL;;JneE{6+xo>Q! zqP1=JAxZWt8RS*lEnD|W)f4GtZfWNXBp zu|A|w++%NzjE)INa!pj|tU|)r0K|UAtiOgpk;))e&wL{dk4Y3;f~!$EurH=S2i;j69^h8o^4i?k8Y=Z)&7QMR;u7XyUgB#IV*VOJE)KUxlt(V>c zcJC|7i9V}Haa-!;X74ln8m59OeKrdco6cS;l?!_g;cpHee@Wo(+}XPl3vnCG7)}`j|eR9nTyfM?#;9KJSH1 zo7%!m;7L)m#S$4AS5m@kZ0Y4>?GRD9bMuneHh`l;$6ija{^oz0u6+8AK*0OI_!A}n zOj*~y*!!oR|4oT(-MNA4aUIDuD>YU*EI>V1T;#iK-7LXnA}cm-!{#X(wG=n8sy<|j z7q*szrtB$ypl07*naRDx1NvPIL| z_oj9FJUJu%gLa-=bV~DNm24_NrLI=VUsrLjynDqk!B&&V8s;+@W5n!D4PKu%I{WyP z3ziizH1-8gSi*aK8|mp6zAI4w$%j7`Xrv;azx>SBKqa3e;b#*5WH3y`M}Sykht{py zPvXT{5Mrd%tRMdn^J8VUp}A4p4`Lg+g0y;96EPD&)Dt^T02GY@X{y2iVWokT?65e4 z3N49AUKiExxMmU0Np1{|WStf$!Xz+wE%u8yHvD3CE-ImRTTO&g`{h{YIzF}MY{@VF zUQaK`tV3twh&dD0Z?AB6i|^uj+UJ!0TKX3)X6yx8+W|_i*rI-2&pC_j>QzyP^aJjj zfsM_>Wdjo+sP|xyO>T~yAVYM9MH;Y;{$fgAX4rTz7|C!tCHUGr-fA#7HhF0Vi@gSj z|GL0pm#SlarY%ZaFMwFz)@IO-e8t_>5rpkzTMXAse^v;cId)y{(g5>JHyl*dOT>LM=1^%DM;DF_xtziOhX^rO{}sd}uSXRxY4BSnS*%7QEJmIc_7W zH1Rtqc0?IErgheZ+n+pd8iKMK_`bMzj)9y_Wb-2_y}4Sx^@a(Exv;L1`bU-^_#%_yy=Y zR8*{+PS3$`5^h_MEJ;2}Ko} z*5u4C_4C2LQ7`Dg01{X_%K&32Vt`Qsc)+RcMHFF&Y>dI=jD8j21S4i{A>Dwd|6yr_LPKD|w}VXA2Fzx8M7 zjUW6Us&q=y|I!Bn8tNfWecFS}sRW$Re?`2&{XO^U@21`RPUi6&d?vtX5_}(F5;Q%p2{bZj6!l>eISlfa| z4K1YMVdka!Y+Il2X$kPkPq=^Ovk#s4vb@Oo4}PlqXC3w&IxYM8@h^YS(c^9QxJcjE zJ`}J@^$A*_u_#OrfO8Ww*39NdCBhmrq=GELD%)ECPn*lTtosQnr&3^{YOWw2uy`Wf zzV?Z(6QQ1O|KtBE&CT6Qum8nAPXOT$-uiRxF=HN>kE06p^h@7W;)3LisD+LA%AS>g zap)RkA8LK72Dqc8C2UbqdSrch4hA?@Q=jOJPFamPjSdzCEUQ8D2BuBj)5L6I1d?kn zkm&TJfVnK|?(nWY+wJ=6g7VFX{Sq6yGv%)q1jH#3vNiWGK}>eY7Jt%{&i z9@%S=fV1b*3c(`m@HeswlqH1CKdhyZk;ybMy+ew(unssA%)gB>JP|k5NqoDi;;gdY zbVbz~?B^tA)~PURa!wX^IKk#ON(^ZAeWRwMQ^1yBHWnGoEo9Jz#J+In(193i-}|7 z;Fb+Jus_e5bPF)UD65ajgT@Rb zeEv#yNELrODq!*X-GE@%^>`A{U1f~oeQU7Te&0+#Y*h9-!D0~6cU_dE#C#+B#lRl@AB^XwZAtjWX&ZK=NMI)f%BEpdfbmb&pUnzMGA z2Bv=Jn7>u#hQ{-)sSkPGiV4o$*;_9n< zs{Q?m$|4{s6!xS%tPCv`Kcki-45EH4)>Jb=ttZL)!0fErsES2b&_h_p*3zh4v&!1@ zzEtCaS{N#bI=}Q04UMD&$6iRMU;c*@QIWFe>>U?mL5Y+R6c5wtiUBfcV==dob%2%y zkmTBoV#*M3L?`IGL;a6R>$)m8qAHVd<~7SpX;@V3F;ySNqkRLKHWW1h4yuTYHoju< zVOm+7m()B}My(wxc8M8~)2^h-SdD3~G}^pJK975d-aZnr1gXroyL#b0B^^lC@;Qj} zAgaO~Nq`~ONm7RUv}+-8yDA#mxiddjzZBv$02A(?UPsqu3eK0(hCME%r(|Uik z!2m2r#zZOR+Nl~#+=!~$8hiASSPsMxR4NfDBFRDJ*JjVTM7;WVj4{HQXYDNs8RI%i z|1=bPfla`bU%%Narz28falmNF%@W}&sOsxW2akVA&-l_OZ|50;jF#B3_h<%-7TtIi zQD?K$x3Skryh9;n{pKFr7Vy^jUPrn1PU(Gg+Fc}Fc}LDCNgC+Y>@mP9>wo{w)ec)^ ze$aZ#Q9!(Z_p0{tx4!pZ2q^vOAN+S3<8u7jZ>A64{tL6`LGzV5@w6!4%nw8m#d@&X z@mqV2T#hs{@MtD@J@G0EWoM--sx;B37QI?QAFRP*RJ0~$cBJ7!SaDPJ|oUd=~WEy>;AgcUst~k&-T=dznN}bIj2!DuoQ!f$bKe6J*M z?7f=(nwGh+HTji*MYD6EjA=5;dE5Jksi%fYf-Az=OrLSfJofb&y=Qq*70Ae5a_}V} zAfseiJY}V1pqtXu<>q@lwqA?-Bp|2#yWM`LRnh4Q6vMID%9L&OdB9>T_0$ed>kZw$ z4sAyD6#6E~)K$NhE>+LX09|99KZk{T+#ZrwB3w9ymxWuUC05?0k9Ex9N**25^7cu~2T4{43#&48ioj{tk&(1ZF> zlym*HQ9aJrTh2`5)}CbFmyM*q0o;&qCmVP7_GRw@$}XePlbP?s1CaK8Nnvlu9HkLm zENBWkN>rFceRn#msU|}A8i{)Ac04tzemN+S4f{{3YF34XpQx% z)=ck^vY?FT=#hXw{qlFy3$OkAs$O0A=w}jcfHJ0eQ4`auz_P|XTlN|EU_Fke5;}YTmcSU5 zLH^CNwr523cDMS$_-xKCJv(xsPPHO<2cSho5Gp$ry^s>Z-=Q`La3`qdy3F@covGchPat6CI zcHtL4`h8;>3=SsdyRr84))B;+ueK_2sL-OO$vRLGz01s2j}bINK>*Z)EMF(~F0q4# zMh^_8Db!@Q?^lJADmM25;N)4#eyp!c;gi1;^iyeoQcl%}b&6O+ePt4Hd0>@39~*@5 z3wxCPW7oZr$DK%hk|foNQ8yzVG0BY__#L zWXs^WEmP#?UPuD$JMx04rd%82FX#c@vUOkj?A#klz;Io9y;rFg9^DfKnMw=nfQ#qe z54vj{0>^Jo}CG-Wz}F zy@G|sM78GhOTVQmGtb#H5abmDR%}`^GXGhE;ciLb+K2J;UIWhqj94s+co1_&86ZEH z_8)%U1X-{_nn4V`_o0Bs()@$8xHzYZq$usnOG>0Lq6c;Xww$B}Nfl$ujG7v-#~s)- zzDS^%oiX~dvFcEAB?)DUzsz%$pjI_pz2T!<|L7KnWj|wvKl@Vis+J^eKgZ2JgP+M~ zKv_m$%xC_^KDF^ZtE%Kl+oFdcW8*Vg$>>;P(K2&ip`Dv20k_z%XI}Z9`lGS!jN1A1 zqn}G{n6W%CSMaH@SMaNh4SDm&zc1l4?8J?$XEn-(L={QJw}0}70+-kUDAX_{QG>m6 z?Nc!t!vA*k8uomUMLaOytG~8X_*%k+)mWCAvRr<@ss3Nb!;g!l>&tBJp(sL>>T-!` z?0fa~_Z>L)67=uC#aE{}sLR*ggI{x@64N2uO!X1qhihY)i$i}2s%Y5(&4~X zm~G`sbfQwEbyYL!3}3#X7WnD7(TqP0OaeQ0eIL zMivySxg!ctzdh{S8b?oJ&;+`yTHLB`YXFWK#*~5q5zp zFKSWUjJ^qQY(GY;UYm%4L?WVh#$RanM6h9%MU*k4k{8t+f>lczTaOg)C6GA9PafM-lq4Zvi=9MRvL z1ey@n;MpSC&*zo3L&(4?0%X-~LsUptZv#P=JlEy<2+;C3>vewUQRZYMKK_2e|Ako;Ip%FcM z0y!In@j%o`##sOgb!Hb(iew*-%U|(3&~T~bQHkMv5A*>pRx8m96O^z$Xnl)HHu>HL zz~L7G1PItz|L=&NffzWVlWr(LjVdF+jL{~n5B+7l4zPIi>DSV(eNXAVI4i2Qc;BNc zrqE0m9;Of9`3qG#C$}J{576&V`wl%LJ0no*f;a$O5)_)JwzQDmd-G4yTR;8-B@_Zg z0|Z&sTUX8+1=)jGoonXdj!&h%ho2Q_g=PvREbN6;xU+bJjT6C65(D7(jalHrT6|xi zZbP#v*(W3pSW6Nj~hE}~|JY#@QK!c0~H0W)}Jd+Z-|&sNyY z&46KNtW@R~2hg&;W427}3Miz2GQ@dcyN!)2p2YT%^wPMiK@;NB{#sg8qU!ebPj%hw z3s?>8rTe!ps}hc_yL0nm+P?b`Ffcv1dqrnl75}BVG(L&)sQEBvsz$GTROm?jNSWIA z@%_73j8RY}3pNYDA)?mB!{^^Gk%_DLW}^EY85ApYl~Vff_x&a7y+H`MRh z1hSb3>mgCivN0B+MSwq zlXEmVy)~VE_b2Jt>93|spS-0r0|NrK0!hU4@BLW4w#-DuC!T!%+v(=jbLzVd5x(5p z+KOMhg->;|w`*+cxsy8nF1?245py$E)syJ(t&vE6lJKqTnz-l9d&LvD@!EhGHMo=- zYAbB}yr2JtUSEV~Jib(8x6z=ikHZEWL028+$jP*k=Whp1JNv{<`M-DrJQm&#&^(K~-PbHKe%Ab?MI znn-5@@8?@#zY`NPl^m$m-j2p?KMp7vM+OgsAUxi>;M~pK~dWK zm^+8kU2|Lrmt>OScBTY`)H_YWX;^_WeH-+csm}x&8)5+iMt3F6tlp;eRS5#92TGuQ zSp$#BMw+4>RJ9mfkE5!qjIFt)HE8$VTY?qTFCX5&?Vz(fuKLc`#uvy(C8fI zSsKWs=L>L#ty`l<3vk(QU@0njs=T@=3Ud(&!U4_%yU_KF9=cVTaXI3CvfaZzd>O#7 zDgegkL6M~DpuR2uCv)x|-qF7SjZj`A=nIDi2!XyS`{SYoA?fbl)LIePGs{uHS4n`V z!jth|No&xy^(LMG@!&FE+bf6y92|M-70s0U@a?};5N%^qta>=JeZK&TDtePMJ{H92 zW+WWhE6~hl?_U!LBSCQe%7+>~z}}{EO8*x7gmVnAH#JxDQ>r?-f+^36$|{uz-cw=; zv}26Y8#trD6RIk7PX&#vh1ADK1RkMf5_D3XWOf<*Pk_|LBv_-F9sAM*)v}>cDYUZZ zsWP2;{zK2{82|_jY*_^s!5=^$)GGo(sbN06tLq~`-h248f+wl5 zF3bwl0hT#4Tej`d2nec2Kl`iyO#m(I8~bkefv5D`Ze2a6>PkuUnQbG{v1k7&-4jA9 z%%YU2i&Nb*1xsgOSaTvd=TP4x(Lp?*Jr*ntXFce7kB*BX2lbM50?+`iq)6%ei!;D; z)7}R-(OWq&khiO2*y;c(7iq2_rSQev%plz^hBpqQ`ai*@x^o1dP~o zRLn`N-???sZQz>DeO#;AQdD`3b{Y31%I4aNz&jxF-1|RCvv;n!pR*(?m3QWtLhB3R zsR&i-Sg5Pdi2HSa(sACgy)IM~K3I0e70#)i8o-7MPO^t_a8qV)w0=YKTin0JKc>1G zG)N^AMTK8d<)1_Y^II7a0aJlB=XpbKp4oX&aVAM4KGTGDj3Q0HGwa3k+p+hU_ATdV zX2$`YHDCa&2!J)~hHY0uvP;pTqrgy$&;4pbp~kxeaIp2UHKr+{gPma0E#NCgp zv~_|-j{)@do+PaLGlPN9%huOm8NiQV6yLk{+52gH%QlVTIdJSn*|{56&&y6?udaUf zetK~CYC3rArF7-9GrG5v&wWew8wLX6Y_KFg{rKk^vvl;SucZ68E~R_-uBAKIKC$HL z6U0p!B<8$`CAT6`8;K3Yp903buZbW98`JL5LcusQN^A_cC|A^vbMp5wSfSfKA-+Ob zsL>y6$-H1N1;dGJkL&(>1B;#aP%4z!fX0jbrUF3X5KPp-vTs(_XMDrD4l$0AiUQ6< zftI9yi$SEJR@hx1X@<_eI;%#X=S)6HWwCvLIs{1`2NnzD_e=H)U1X>vOxb%@V=>xJ z4XP`V6=mV`+;{!jCplDQSxa?ME8z-tc`a1Mh=HNqKyXdd-2CV5Yb;IFJ}SVUYh5*r zB#I8SSLz}V6^&FuwyAB&X$dU)T*VOUabXuJf{u)(v9T=zh&VBVDLFj$X2TJ9`9IcC zVmvuTn=|22#cWpcJtFcO4#$`yrO#_yoI0p%FiLFnD)slN(qzF`=Nks~PDWAqYIE)a z?+_GF(f^PiUm}2mp2y%`f=N{H?B5KKCRi#s)_^m?DghmIGln{oc(Pe=)*Hu_SbwAe z%b0;j&|m|w8FRqN@2r8|&>U_HhB*x;I}cGx^6>%W7oF`|0|OoYe^!JZrv zS@S`gs~cY$^gc*N-g^rfXYv1%_vTNQWygKrt-Y$NyL#`Qo|&F~FoVG|#6m12MS_&V zR9Iorq8+vv3`h7E|5bK4!ita-wrt5_*c2I{2vH;;3^7;+n8ECrrF)j%_v+fZ%JKPr zGtWKuzWZLi9sm+el>~N8)vNdJJ@=f<{APaho3nGx*7jY|6A84S6e4`m2aDw_M@3lc zE#U<_JE>`sP~rV!Yqqp)SCgGtM*znR5uSI_s{v^m#Swq2wWeQaZm~IhlKF{`sgkD| zVF2sxjZo60@^{;PkT)+k>$h)c-892*cUwJ6>{F5oRBH(E0F@|B;!8+QYCOcwwyKTl z)4lSc96S}hoL|R&zz#rhVh?Fv@e)*8Ks?n+R{>Lg-hFkRN10SE0$lb1fj-y4zZ#FB zIg^cnE!7X!Li0=S=~@7CfF1e+>1AUeI`2h=i;)V?eD1dtur4kk&%Y=&S`-{<^^l+s zHt5#1=Ix(;TXt(@`JnnKmsbu;4U>u%&yzk%-kbS)BoJPH@sA~DqaG~!tr;Xr+{y6?DEI&dYHUK?wq73)Tc;>(Z9&p07SJ^@j)e$zOkEE z1Wo{H0HGBqwFeH#o)Xv|K7K}@aqZIi=746}9c(t&Z>o|@07+#C3M}B2z*lEXVn>lQ z46~L!ZK;sxnQ~C*Nj` ze_~_-%C-{sQnh*6)kkcw+N0dkVDUzaAaRCB1Q7@DIaKA9WZYbLB4YQR{>28dPyD^B zz&sah1ACv!U0Iu6k>ZnsMfOlNI;;wQ0*4HSccU#gd(FWkrv-#zzDQImMA)n+(H1tw zKHpA!P{;U@Zp{9i+sIqT1krN<&nJbAuCr! zFBrc!y@Xj)i0a%Hm4r&9n$(qf3W}lmZ=GJkpe*~E9KIm|wC=nP3g-&Y_nPXME7MA3&5p|-PLH3@5 znJS0n%;)pUYO1J|IZmObS-XmpV6o-F=PHF!jy+=YrD!*a&<{)Wy{_C5%-0vY?QA z9_K=IfSxGNlBJ@+SIVXH{0LO2D!-@r>i_^C07*naR1+w>U&%w-EnQE*a#wpGfq&W~ z?%#cgL9dDX&wZ+-)yzy(78x6GD^wEmdHL`9HYNXFKkuxl*MsW-EIx4dSt+|R2t9jT z4L0pW0llh{go3r(0AO&CfSVVvAh;%20DutesyZ3_ynUW6l~mVL%@HjE9;IKiqR9tU zm}gJlp256(Q3(VHs8U!Y)oG=MsIeG_rCJA&r<$l|6IGuSr{T=ee?k?Fdr(iZ)c1Bp zUjlMjooO0|R8hgyI35^R`l2GQRVI{_72k0IGCR9C9q1T*Yy1WU;D zvt|xRSDFvr`Em2wOWzVj5MZvs-gmAwC(k^kdmvyXn3nv0%tWR4jJ_nQbU*m^zY=8^ zP>6qg^rUqEaj}6h^wF)MM9tTJu@Dli~@$N-a4<5C7fZN=VQ-&wR!uM zZ<`GPeR3K57obw=QM{pPh0L-WX_?3;ExHp-ad?-MN6VV~*prts##d5z=%^esXS zwi+*$H$W!OA*;*+9N4j_YOCKmM;ioybix3GKzzT6gw0m$mq?`T7yVCB-HK>M_p3hn z&X@UolQ2f>o&9VW$3zb&>?bG8%?c6t3X!^QqPtyZSIK(GWFt)XF_$qo20n`adVQ8- zLX2RiIFTXW2FpV%84Kd2SQ}@EOHe;ApFy&R%02>iF$33a2g?B#Ie(1yLJ5}^h<#%7 zDt707@u!E5JfI|v0V0|!TS|y&Y*;AXk0b)BvoOdqwqtb!QK+f@@B4|_Tf5bsa^5yo zf`=mtKZXBagT^=n#K~?~!p{_LRLS5ZxHa2fJJ6p*1Q&>xwI*Bo;+0)Aibu6w#QZ9`hUlfLDHHG($`x8dM$UOP`~vD}bj$!(-#-+GhePdrsXW+$PGZ5kD2}E}x0% zm#&8LD0vQ4@Q^?UFs|RZY2X$%kn0t_hU5Urz?kEyeo1=JbdYAGMkoq7z47XSTo8Rx zdsP+xn*t@A7lFU6&FC}SG$@S$)n>IU#Ei!Ss;mi!uuf#Lqsq0l3H5Kj+1z4O$Zb7$ z^((I5vYk>j!_{DV9|3ggvkSoz1+5Ic4iL)vVRuxq+}Tov4oV!=5P&{F6-Cd_eEILI zx@>Vd7!aEttHBtn7)t~7^}RQ~CtC#|Vjlv;p_2k6>Ek?e_A{bE{`kB9y7~TJ{a?*p zDx>Ah#xvY&^x9*m9@GBk^^8#Px$+l#7s@rG7zi*ge)zTksZ;_hx%_O8;Ae-9oX~l@ zdE=s<8TSBy%yZ3iO*$b%?GbySU+mrvHqw>?+CKov6>XH*H}pMc6|fB;*0VQ4jcc`S z(3#$GZ?6)9LDRHyaRyxNnN2$hWswmR=ihs|xpfWYXcQcOr@3|gpOFjm|})@F@{n_7au3kCUTs;4}KJSqyzo_vAum13xW)&3SH`}W0y)LwBdMcxZ zK<8MB&K3homExR_sd$WF9M;6@nn0dZabaR?tT)##zNhbVyhzz}kpLf!iF|$PucoD; zVio~BWSi@`#0he89%oU}WluQ%P&}6HBvs5N0GY$n>v`4{P#&V8jyUKke6NesB$D@J zgRo=R7%H%^ZP-iM&ZXFQJLU?iCwjv+o>3rxrP;aW@G)8>5bwHf|9~np<84SHqP$9F zl|Jg2P3patbN|MG#Z&-}WMNXBO-0Y%`rL}$z1U4ObYH`>gd#mZx6~}HV2=-l{sHrS zJwwq6T{9W>!{+V!=QVVb@cp=yJwRN}`a#>L$C!D&JU09%>y&EKwTO+ABle3v1Kv-` zGSJz{F)RI|(|v-)ew;4*5=rZ9D@wc6zdwV;I0#ckkAK5oR11ELKuNJnO1%r)g8w*QvXa^3_hS8Ou5&oX?|vCZ%D!sP4{)?#z0T(Z|>z0+G&7 zd!YhT7}KoGV3eVnlC>ghOh1DJJ7lu!SwfLvtyF}eLDaMmTehkXx7uq7menjDyO;CgkBIyu8TmMfxU@<_F?pZ=YU8hkyi43ticB{7h zIRYXCiSqe)ojjXRy?b+1vtr=zy?e^MBNTySxgE0RIQnEJooYJ+klt%m_3QS>X>P!g6n01J?nyS1+CSOfw0SdE|-4BcbZc zPz_$I6hM^;A#9r} zH1~E?=|$M(&YkP(^CCE^s}Ah9qsJe%s_gE)=E8?>iJ4Ic>V5yH{!ppo+IJc>8Jr1V zL;^$SiBTr%0cFNBiI97RZmg=?Jc$Jcw{NNkh@=Pp#)+N)w3VQQuO-GS6{|@V!*fUh zEcu!eSOoweuHgJ(@9BTSPdxMaZ)jx2r4Qd!(oi-6TY(M(mdV*)?=jAZdbh0*EoO(* zTDNuPNFHEwpc{K1xhjgC!3IfijTVVu2JmzCq{M5~zuBw!4A}Ld$v~Dq~LjTHFq}Wb@B!gw0{heMX(VMlqNZ4kuKUn7rKbHyM zc=#EBbw7Aam9Bn~{U?-us>>_QW1sp}*$d9&hwuMXkNt^fzM}CotR1ri-9tRnT>9v3 z^`FzLppwE2i?<=wBeLpMq0j&sEK7PkyO`CUpuBJE#k##Pw?c1m}zQmSLfU;uj zsRy4{a*P=G_Vr86m5cA0ffQ#T_i4Ld?ORj9x9b~u%B}86{miFXuRcgj8&j@9ZyyQh z0Tj*aX3jqOg{tzrzX93**!<0YMH_%euUgPX2&z+kjet=>KQt)#@siQr)`KQMzyK52 zDN7LjX0Aj!`_+kCs{=j+EdSEegnc-5}3QPRm#P@1Xkk%nNN_@+WIBTTO|$7Y=O%>0mERE@%^mwOFmUjz{rRt}23 z2S}`EK*_;oRYg_99Kf8Fu`W0&0a;Kr>P%A&e(Oh?jufF2`j7ZbsoiZNZV|nIQk=Bm zndYk`DDL}jobMj~>V0-3tFk|3k|E4wgfFL^CpnTPR6)C#?&@qPa~RZ< zbe0OfspK3zEfE*48Cxe|kx+KMdhuLLAkAu0CIcdH51JW{+>5A7?5Y`*GohUmoZnS%j8t|3 zDxtoq(K!fm%rB^#$65g<5!c}>`|i0X`kfH2+1y%}0FJ89K|O?q3+O`3N4-(&H?^;y z|Jv_K-4`&twY4FT%)Rja4s!|D8OyODkq5vel|il%F^&h%J}2QIsHNZki~qfO>AQcV zDxm~lvT~th$!eKOi^3pldHLdd&GpM4#K@EA!3(AY!4ozc+xqbbZ|GXnv{6>X_rS@H zv@96g1z02Q$6Y)2pnMZ-lrxWhRze$4j#YV^ozwFu$zQb}d;cV;BG@HafG@>=vL{$` zSN9G$9?|^18C9gA3^H~_yDhklJ8TbtTGuEaR)xVqgG)wFy}qrF$#xy_5SzJ~ z`R1X=KPS5LyKnrpk_`A_iRg%Bfg&mA#69S&6VK%O)sLJ&+cf95JZv9G8c z9zS(f)qawt4?Xeu=KMQ9(FQqo{H!YbP|Wcqnq|6S73U)-ACkX=y6+Z;ZYxvAUzanS zeYwMJPy2zNeqp5#-eA;x^|${}*Gk118_2ofyzsks-uUb0wI6=dD$^6cx)sGVRDIT4 z4Hm^rxpPB_IX-Lc$OH0Gj0wU{J1lX<-wZ)!Jo|Ip4{8Cck{pjUZR6pe52KAcFa5JK zv@8OP1z=23=AI_N{2Tw8oZ%M%mQZsw>n#J(%v!1+f}lWw!2ty?{7ufB5qMP903dl+ z*+2C@NTC%F8BV7&e{BL6x~8bc_pUwp|76*?1k2Oc)7wW=(Mt5gGV`Vmu%`nQ9phbS zJjtDOuZo(-am0KdeLqOLoAz`>fd!66)XuxNO2(1Hgd_K?O{g_?^l`~jID|&5O27)4 zFF>c8-l0$I2Nns+z5kO6HBqN65Lw_P z_>N`NgbhZ1p5D-n`9T_D-|^lCm!@ykNq`Y!stPR>jz&~8s;Y<>cqZMh-#-G>{ks;r zr#Hc3{&X6k+0w&f|4g|*M-m+g;H$qkC`z;Kf6LjZqn{pFtihxL!UzOaI|vYO8q;D+ zF3ZYZ2(t{h!$1UwG7P^Krt_I5s(7S)ig+|KAa6I9vE*#ZE|KL zL8a6bq0vDn66G?4VRozv$h}CUBeI)-MGJ|%<6bBfW~CGw>qiodeI{zVX?AOePf5Ij zdAI}wH?MwJ1R}0pe81b%T^@w#!cJ-vIJZy4@d4Fb3+&9!x*7@163{I0JVynPA<$M~ zEkSvRt3aKjhYm1BMjL=Z0tA~2nA?LEs+I%OqTHY8u}o6AjBGneD%R%C?HkSJT?TDO zj~LZ>iTk)p3(JHIJGLJ1mK8j22lp5fAXz<;UiiBb0}_QX6gtVy<1eW2+Gngdd7x1Z zuEaq@g#rmpSXIRvmlf0qjO{{^JkYGHavdwpkz)^PzM>U>Q(VO=!LNM(Pn-ANd{N8? zJ_le)(hTrO7MsK;$vWPPK1HdZBI>ZTDggc0-}>j;Hy${CxjFsd)6D~CpA%*AXRm*^ zdEw9gi7Gy(@@Bdcu^IPTQF)-6%l#oj0!Y4c;hj({?kXlT{|vy$bGvZ<4cU5q(E>35 z7H$1%Uzx%7IN#J)DITAUmETtqiG7L4lNkfWsPvLu#qKKEWXqHPueFaE06RWlA3gl| z=cS@~?9`*pwTtfyOl!nKs6DF^xWnu^Kt4-hDxern2&5>{VhXOPs0)jF?(9>6VuV;U zTh>%nkJa%ETlQx%6r?mCRCAA&$ieX;av`<@R7DHIC>0j8TQey4LAw&b_TtYRy)mWx=sK<;7S|-O7=K;U14n>P zMjqjpJl8T41$i!F`vh}~J(Co}Lbr^9LiStE&AGa5L9`T%>fO$LfJL38xrOHRLr;or z@Xl-BYd-yjzt_C+Wp$gv`+s4>hm-@XxdlAARae%?I!OL?Bc4ZxUE+%lDm|%k#Y-NVG3$&wT+@ zy?sNxh!1=GnXgDp3nt3N4_?=K#IODAwHKOqU;A#U;@20GzI~c&sexA(AS_&XQ$+^A zB1{mR3hPV)Eotlqi79NAttswfuB+7PKikCD$Tq+KAB5m)GS%ugD1GB7we}`S{O1K0 zdk1cs4PnO-;co z!J;WJ&J6Y(W)A?41m7d}$Bu2%+@t&5iTx~3N}|g#BYXf=C}y0gvZLYLOVJ~`t4a)O z$*o9OBe;=i&AU20MP2`DdFW$ImG6 zf$E011fmEGrFK%m4%FM?UbAxWn1xa_|8qTPeL2!0pOMmtu3{ErT0tCwX!=s5D(K9$ zX8Z;1G=aSFPgHYylmQK(UZr1(9)jB*h^@c({%xyp-9WxP-?4_go5}i50T#QSrK0Bs zcu$aR>S}eWYK7Ul3R#27sA`**&EE#CJJtUJ>^mDDyCnLnT1=ExjOfuQ=Q3rmBZW_; zv%CpZOhk1&1C2`A&JOC5uKEEq04W6j(4e!YCu!V(Gwe*E$ZPL35;yVe$gSq^v4^xr z3C{SPk}>lO$|ked>F1`BNs>#nxA}Pij^n2uaqrvay68*nIfAG@Sj;n3f~sDBQ2)7U z?^nbh*(a261vb_U)afN$T#>XqK?wm3*8<(sNjpI1q9|5LStjrS%%CDGN-1k2CG1d@ z)d&>RvY0tXfNQ!e0kG#SsxNhyd3wyyqvvhYU^0ST5>TSmGHYzXpz?$C)UvTNjVRwFDxjB= z_&NWxmzp~WSuG!Gj-Gl%mBbI;eMS4gEd;YVmp86`+&uowS1pXT*XU;?0ie@kgP#7} zH=2*%`$@C8wGqnN2by=^c(J9E_W@m9{BYn@);wD$oVXcI0Ogsj&n{~vigM-G>!gyB zDGSTZmw)RYt8Iv68t;$4qw-hQIAZ&(Tn~Z8EKu~XZ~F>W+Podw9xMKgi$b(DeWpVwR;IB$i>Dy!jpN!4Hv#-3MC z4OK;|p6XNF-BBMAnNyFjXoC_eLd@sm*^U7C$S&#{qK`l!LR1nZb`zN-k;*i84H_g0 zYpx#YY=*-XSnOo)0G6gp6SQ%?h+YsdtEVHYym=i%=X=N@SFbCy?O4cZz@l!q)?FKS z9@~f0Zmqs!se^;~zP_de9}-?c+$J;W@r;ME!=wAS;$!XedH!{~3K2K7)nhqA2ZA-N zHWLg`vZz+Gr{*NI6?CZC*=A$iVihGgD$m;Xh4-XN#E1ZTt~I(v%A5qAIjuU->M? z7BE+F{knSkl)MvF*}@?J(PWbtywZCalv&Z%nr3s0F$rt>jaAgE1H{l_@t@=WVZp4^w3FFl3qm(YM*Ux-MplEiS)jvz|9wa{U6Cc{nelR z&(U+uh=8aZXGWZzIyc*_9XTyw6IUS`*&!&g*Djv(jMNY=aj)A>bNtj}nia`45UO&iyH%h4lEhIo^f8bB(BFi+@hsgG?}$F~l903Y zYd^#D2S4?>-_kjK<;8!axqFovDeuerh|*5{AQj!^m`i$3K%Bji{v!Lm-TUhc)7e4! z73Ncn8BsEd`LZNBs3tEgE7?M;gnFxD2B+!Kj7edn4xlboA@QrbW<1abALp%5gGui2 zo=QU9X@2_sKUK1Jj?pw4DP(ZzWU(o}<*Sp#oDf~qF-}b{9`YYm^{KDYIgyDK*D{g- z>s^*AzmaI-Y$k0~a5~lXE4yaET!F<3oCqwU)Jbxf8Mjiq_3KC0C}Ifjo8B76&kBWD z3Fif^{Uc9*xjB0L!REcUe%LH7uQb~m>jF_{&OX~*y?kEdV;+C@tJ==zfA*v1$gwlB z8`xNcv#>$14WKqZ`pmD2p>X@=RRPHd9)3=}jpu&$QgfSxM*j7mNOH}Lr+0I1%u6nk=@{K=ee(;@tspJ*!iyh3WcHJkMNrJv@sQq01 zy&p$?&Yeud$FdLTt*7EnLJf*9y`lJv+Af&QHrj{S1;u{W{Hz9xLq2vKnC)M8y`@!n z8u#4dh55c+uvl-%31|0j{I5PKZ(+Y1%gp$YL#s1?;VdM-ECWqX({fY^=(V9wWxh~O zI52D^vcCjw+fuo6X4;fC9Fq-8>l9m{)IX4uoMD}{8Z?X(z~+9-lbhQA8Z5ec2nb`` z#39Y=DHN1YUv1wv4@Rw+SizI1=;W-!1ko8dWPge1d6@~XHhdnq1YrcsOUnloXp(VK zrDbzN!4+z8I*FKeIG=*oH3PC#2U04t8) z8D3~=R8vinYcoCJJaUwXdZXr*wZiceI+86@e_d1~GozVRaR)oyD&a_FIssOIl&s)- z35T3|Ect!O!!Da&M(kL5ns@d?4AX=I33SdQHOGeu&0_ubpbHU2M^gUS~60dsl( zl>RPCwr%F!Dy6Yz5fA|K*h2Iw3eZW}7HV~BjAeDZbr9ZHDG?t@oS-Mm$O}Ze8aF#f zwtKl*JaEYKFq2+AJF7kJwPE}VL*Tc(XHaTYm1n27Kv!TgMp$?-HUp>E3{#T8 zz&J)U(aWwiHC+`dJYX_=u?a8*{Fpzv3_X?VGQI(I-FZC&)?IyyjM2DbPzvCuGRU=R zhS=<^#zU}f2#P?>H4SxHK#YArZxTTj>#|ONB8da_y;)+O-Xz|iiZP=>L|!w*o9O(-458{v#^7O3H4lO3$-Q8}7erSsCMeS zn&&~XuA@iGwGv=2T) z9CxMe*XGbkw$%^1_JKnQ%sOx%lUQXR96WT?Edc5}UBI9#fz9(|j;haweRii1Q&ip! z3RQVeuqcL;N24UbuEA~k((<0^qtj1?ZAx3pkFoIxbCDRrCdtpJA9hbRl%H`8*m~)5 zFtbtueawjkY z)R~5Q!`;ua^|LOvX%2>Eh!iXjS1|iVramwu0Jl^K4d4`{Q;myW#P*t#D%d^^3=Y}& zl*^~jf&c?!Np>`WqNUs;s4euwa9dJtM3%g&IQD>g#7&o>iUc9jI83eg3^QkwXix zl$2>J*E)GH4QL(ttSMLz-Zz}DxgOQUPO@K>&wVD)rrs{kU$WyW#QyA>YJ<&|v|K8v zsbVHNDPkfL0ohfc2(ZXNPU8+XHzI89(NsH_HYmj9jI{g9Yum0+ABef{Z&ox;K;-2M z?|M{3D3+4EqWVTaTBuKZ^gV4fcc3#KJfcJd)pn@Z3Kyv7KQI0thC7m-9!!+z<@ z9!M$-BuczpT`e^(i602m;KYhRB_py_)#-e*_B1pp81rj=-y)bB|G zMSW<{a<`It$$VXuXg3`kOCFwq*i=(c2|Z+L<%-9us3H^NZ3OTUhtVjFt6C@bD$-uy zK3AP@=vqMb-+6Io&Bc%=a_p*Mql)>@_tlHp{ODZ za#ukKl~(3Jo_q5L0)2;%p4L48#0ZW~KJa+6N{`~oT6665qXNi09bXgl+u7#QM{hMR zz3@k}In3juf^g;1doi<*D)frhaW1M{7D@>!^9=pn$HZg+pdxTW;Cb`fMTwXISS-Y2 z0W%)=i3c7NJsN5lpPgW_8`CGa2vy5C`+Z-AEo7FVss#cwJFd7B93#$j{i1-kj(!M3 zwaK7<0x4J?(Q4vAiU03J1c?fSdE^_zHoIc9tMyj3JNkUGFObWYXpYo$T`5Gxl=n8E zZ4+CnfGY_wr_W+fX#^C#zV!9ZE@;gVoC2^b85ljwEey_zs~H7UtFrfzYffP-)vS4%Q9Y-?+VlS=5P>#sQblbBuUV*=!4tkLoLgGtSx&efu1V?OVG z!D0bo2^I(Fr@23Q7N~6UtN{J$5oXlR!cv1;^WEDwEecjKcItae+U5O%MSXsr1MM^W z`x?|_%#aGRT%*<9oy4f)tv0ShN@7uoD@5@$GO5`UOM^aB_8e#1iI@I3vq;xRCAFnJ zw~5+L99TVj3qhH-sp^^%WoAU_+M@WPzILepBrh3h1u!M4u0DTekGfAk;~t-@?Pm4R zk><;P=N~uc-u{79m(^CV?cz&Pq-j%t;X`5#N;e{gxusgVXDc|Q*|uD7^!KNJL4q;< zhN>%l+a%7IIm-H9`uJzf%_|>;_C%|Kp9%eO#hqNcx-!_IjVh*U`(}rLrQf6d%pp9` zwpB%YTkf^qIi7j+=`Zco541Gn-VZYPkM-JLBv|YLyLu7FW<>V8&q1&l>XRcQF8lyJ z^TqT@f`2m48OU)MH0MpTAx+anIZSf?TN};YjoX%gC+ishCjG27BK^xYSb;*}gGLbI z_cr%_$bgUA(EBY(2b4r6D0_QG8+nISVTUp!X&4s$j=yhLP1LmE|Ld3&D}>k?I}7WRO5Vapo9? zPH=uppUL@!4ys^%%alw;@yMw&3gW<81l~&$98j+#Vlz=~;XdwZ)Qo#ssJiJ)#n^?c z)_4Ss`$hr&8ThB|$@>O;0)AZGbk;rvnGl0u~hsqk3N`)j8Xi z0ruEeS_wR^X-2|o5)}*T_n_ZWFzerR1LGO(or4FD>ND!TH7-QJ^yXz(l=aNpz@ELK zs*QSSBL@{q#11xFdz`{`Tzk&&%)#I!KiT)}Q;D(}+Bpdo$;eJn8C24o)hJ&diRM~q zJpaZO7H;0^$~B`Qlci}>hbnsoaD|=ftZy9`Re(WpPd$@wG*IzRB6(K=-xPz(q-;N^ zjsNZ!KCEzF>jtzR*bl-d#Wf^VNCrv3YV}BSFt4M~w4ccmbovwUEwOYW&$uNVm7A%%{Dn4JVCMxHvhuycmvn5-C z9pQWSB0tYw+bn(fQML){j5Vy}YY@ZV@&2aVMj}^w6R71IAo`vb2En37QXQ9nSy)(T zE?+p;%*@!1coycK6CZo`G)Bp7JG;%%Q)ip!e&z2qFaG7f@W>bvxJtb5Du%+|N-M^fHu#BVA*SHd}Y;Lqcc;kpu^ANoz=uP&Qohu6qW%&O}UllC^W%4@{<^mtlnV z6|-jg#%|o_?FZm%$D?)YWux=I36NMrGOwcG$>>^vPDU#MVr1ADJs>b0C3y#bZC2W! z>&jySvIMK?=padb0yX&g-*wiDy4e!gS(K~{~b^)4AqskBCRdy?|qCq373Q9<66 zQzB3=LL3=11fWXbo%Alt-c!|umNL^UE-y#_UL;Mt3T>q^{yWz+l_{;5yQ!)H&Id!x z?=0|P`d0QBMVX`1C){QPUCnTXxMd`i(77KJNg$)GfOekIUZYAA8DrEo-7n!}N_$oV zkXGw+VD+e)^VOISSiE&vgXF1paApK5D$2By6wv>It|xjZObCgyAQI#LN%q{mpfhC! zoSQvz{A~02ul|GP%-K&jufFu>%_}edsU`KJAH_X{i|V(5g1U0xV6(b*QsM#h)*z^| z2pv1<{+vBPAU%7Gn7DcUqNLvG`9f`yGo)UyyA(TjZ&(Tb8`*r#x**rleXFFlVS{LF5^aX_s%u^=*I%uj6Bg^qpEsS z6%YG}=s_ypJ5O&lE}*DkXCGexG*#`Z>kOMJf0IHsNh+8`(G7~60bnRDR>q+gaZ%NY zBoD#6D(TT1rTM7#E#>DurSoFb`W3k;D~stf$NHI0@;ya4qOzNItgckXJr;Y~s}LrT zXu&|cC{uyOnlXfWD0_Wwp}BGGBPS6w-lz?@$Hp?nFFTfSQi?MG$VvuKfW;WrUXr*y zV5OZcdT~^RD@_B(ebEycG}lh`DPkGLkqB-{0BNOJJ$S4+c=&j8=hn3{zK6Nv+nb&@ z-iEuaN_$~5Mb+KP$rM9kPG}@6^!YI}G^=6)E~=0vn<|qnd(G$D~Og)z1gcNFCn|RU5l;f_HLv&SLKFDYE!ugU4U?FUAFy(_C}? zw_`wM4Km6D-0!`o33hd=d(@Yqzw1{-3b~^ln3iA%WJM+A#;tDL{#ATEtpr`?9yjHKtN@p+onW~FadLYPcZZgYlRuqrm z0!5a`0j7j&6bP+aRhL1)%Wx+lfMkw;sfiD}PK?47bpl=XvBd`z@Sf^++%R0@n&7Pgd)b)He^Pb69venvPgA?O5@cF@0JlA ztS|jKUW;X^j51`~R7|RHB(k7qw}}ubL<1go?+H{x=X(BY|4@JPlNbIUDb|q)@qEmr zxdCw71WhK=k_yB*1uy{6pwDuht7|8u?nyuoSYlt0Ip%XzkqnU>fXc@Db@dscCJKmy z%BZtC%dFPbW_g7k$yI@60Htm0vTTNXxNKjQkw@{GO6v}l1=D4-A30TAxdtevqC!QI zN&S*LJF0Tl1IZ0^NJ7Q%_PK>-`G7xP;8=iVp?Udxe-S5q}vpzE1CSyl4b0>Ur&HPbF9^)u-MyluApL z{wm4FtZ2ku83ciy%3?J>YRKV_0gIhPaNmE_fpIV1Dqu19N_=LiicX@Tc6^>G)$C*J z8Htdru;p``6u)Fuhu37Q0?)k`T&erv%9w@N6YAGXI%FR#)=66x3Sg0W^jI{9#F36( zw0J%KlURgvy|{8v_JJx{&X(T3ds|?u?k}$IF#&6?LtW8SEESYf$62m)>NPRXT8Yd6 zW%c{69Xs7DEF5UAUOv}6aP}FgE<>?L-SztA^UeJ7fo65}utzx{{J z`)~hH{erC5)l27^Lu)6MAft~H`-C{p_Qr#>6y%njXbPCxXtW)%}F&?ZE0cE(<|RpAvQZc&mUlIcZjqL-}i`0Umc3>^F69>{*Y zjPGfcid#lU+OT3Pt55jP4=koJssGIdDS?=?dsXO`W_r907y_c>GHli7l{Xv!q%GY; zUZj^Hs45C&P9WK1fFttoD^g8dqEATz3N$0n8F)Y&(x7QXA#Tgyc{r}AkM$<%T;D#y z{3Nj0{>~1s&$;*JjCp`s3-@ewmvuad?1RPHXxG^^2T!JLW+ko#QWc$**mYAz>To=?hGHGpl zMvQg{s#M2u2EZwTEJaN<`|u{YumFV9BxB+=-GIXM4?C0???Nz4wls$g@42DB^K~C! zv6FpEL8*8kd?r14IpjN?n$K|re^C4ayqQ+wgn$Rc1JYyeU<@5M4l`YbDw4#i=9im$ zd(1LKz~pY}BQAYud2=0rr`);2TFQXI@k;x%SY?r_&lYP%DHHL zCr~K5u}%pV*@Ilq?VFe6@BmKgLn|`z_58fT-78lv!6E39Av`3C;Ob!oBYaP0ma!Oz zk37(v``M3F{qz_Qdb3e!+!pw9<=jfroEP=700e?gsEQ@*fI=d#=2X!$HaDjP8a9y1 z7;_V$K^|pp;o9-$(Ao+0zUUcq=JsZqt!+kzTu_ybdxw4{aTq8|2;9K#pwDsjuqtT) zA{0h*W~LP==ah+uq6uBoeS|TaaSIjJdnM^Gzqsfbh>WjTp(^QWrLBsoWn`uaMz%I? zX-=e)egVGUdF=)5Ye2EV;uT%n7k~ZtRVmOjr^30j6#~5-+Zxo^@o2ZFpRM! zIe^F-!Yw<@?}P?$-TH9 zzfrfhtp#x{&CYZ>Gh~v2TEK5-csTpfVl29r6u^jTk+0i{h1x$9|KA65ZJDa;>_@J@ ztt^&n+{c}b{JO3T4#j2@!D9Md$0j6PplXt2%C?2RV92=3t650-eGL-w@4RNo9P<95 z0-TDeN;j^2Xdx^j9eRI*Wiwcb z>i4_`C?s)P&lcp`1XQwDQDRKnuAED2!mOtJf<=d&ra#<(_O@E4s1~vgJJ3_9iY_dw zFL3415wRDZdH%PXm%jT)ZVA9{Zr)V|QVI8J1}1&YfW?D{PBb^Ke^Fx zY|(2q4T0o$GCth;KmrUOck0Yjs?4%Z_>n6gzw0E>%&dF?YfWoYGMmgkF`KCtz$wbO zmB>uSxqZ={^y?W9_WL2H0gIE4lh)zvlV7OQ+4p<=rhonYR1NBPou(RB8(ZP?iSf`Yy3y=z+kR0=%xb&aBbEgg zHF$k*R}@ypcL0{TH-vVmtP(`sxC%YmRAr@QYOt95C})~7;)szCv@fJMTTuA;TUT@~ z7}K#uSMftS8!XS5blpIlnCa_Hu5^|)&G;qpNRoL1## zcIRxfyu2#Y2V25@#Uv2v&orf6BU=_0W$!%tVz}qOzONxWot0Vj`bN*2U1A$kh<+G? zPo^S9B}kQ2fQkJ;fBoIIQBfo-Fj=y}Sq&Q_;opKzS0X<#SnT`2dSQA2d1o&KlP7%| zkCgL;FrkG@?2|LuHzf3u>ym)22*BYxL+qs=(D(0~|E_6=lfYsEeu1?Vjfn(v_71}A zV2lmy31U6jv%Ab_ol(Cc<1t8FVW;YO+5K~p_bnh3Z7cKs0M>8EAJ9obV6CL zkBVt||6m4jHb|(^531zf+>&e%2`+3V=iu0hhb;uPu+W@+{8#k*H-GXMqNC$a@H5!& zoz1%{qOf*UQn^=&Nx|xf7Lsh&&{K`}A}3O4Cvp6yK}Q8K;`eQ@QU0I@h$cCm1R#qvFjs7_e%z;;R9Mx5`mcRfL-5v>Nl;lm_4V{9O{t_bDadKopgR+zUh4=a%u-<7ui+NOR9AN zi=o1neJ@rSOn_Ebr+hIT5U*T8Rw>(xsxQC$+%V=y&f^@ccIkeyteEpR1hR{Zs|u|7 zIWrFl)Y#Km?Oj@2Rh5aaGP4jR%#FJmUt_0{&%EjfsGsi?H0rMTiE6tN6XUDru|UZ$;f`=a7>0u@bEF86j-Su26?4l-e|-!)hJO#7m$_R7(b zsa4;w`>RC5CMY1mwE{cB_6a~|8s)sI{+6p}Ch3MU!T>HRZuA4DP(x9TCUHZeLgEoV zn<>xamvI09AOJ~3K~xQ%`>yR5j-FKo1EEm5bf7tOXoGOeD{t;Nt8*B9&+_HqL3@$D$`?AIESDH0UAa)?8aCIDw6C`z!3KeFlxsq z%rvk4=+6{HA{3M~RC;ip`_k{auRVfHf+Oq+vk^Z&|623myRT>fx5j0xozPPvAmiEN z6I`_mntmj{$c$%DsSyy+XQgbtrx}X)69jTdGH}0clUNb3XMK;Ke%#8sG2^W>(7Ys$ z+OytP3A0Y;1Y*h0BwZ^5;VMNmjm^BT*NjWHb>5^(?pAh|y-HP`(@hXag@h4FBx(VV z?4`NIMfnTFv5uTLt3F-=&ewkQ=N?}p@aP^;){rCx`v>NUX~X+}4JA_BN(-}j4aV(v zOx2gaqPJFbM)%)#z+%J{3al$&VqfvM04&BHONJ5a0i%F_Ns4rRR?J3D09?<7jQvxX zAtA;h`%|r3Yc4ZZ@OmRaDWJ+|}d&;FK_n6X2|v=2V=+2-BXUT8je?;>x$+0O5koE zI^%PeqLM+!)z4#Jm>uQOPF!PFWaT5PWKAX!k}c))+Oo;CU!2Y;+oMei4HtO&mgH|I zSe#@pqo+WdL$B*nMn)ud241Q$1T)N zY~bf}y*Pc0$PmCy$@O%^EEcpsDv}s9vU=wA8!U3Lv!7vf?bldwmXQ|U=jfyC%`iU*l6w{z>b7dj33H33Y&eO50cK)fIZ0!Rqv!Xv<7l`ZRh+BpD2jc&4vHo8C!Rj*>zeGGRk3~6Sx-Q~9KDGE=Y<7TIUTGbQsZ7H_9@x$AARRv>t3**EF9uK zRLLKB=xGU|QAOlBPCW30`b*z?^ZQcB7#P~J%# z@;BHl{tkf8xD)8h8r={SOjjA#)F;V$UAy$Y0Au$2413XFdicT*gj^qVHBLllV&eJp!0}@0ZW2PHvZbubx>aF)Oez z4lMct(ze#insGzBKOD=Fl>Y3m{+F_e%u_{O6g!Xb)Kj1NH37eG|LOmtHXIdL27E|f zv#xV@S769svG$RsEsq0>B++>Dte({gyjqATlMbEeZDyufJAAVFm0$mT`RVg-|EM`} z=85LS=_i`EfBIKqTA-@^`j7uz^U=B2l(5q}WdzbW4>8+2l9}bRqi7*6N{lzFt9&Vl zNY6I5`{aX9HOG!Wq{Jr4oR81FURpOq^Hu8$_8ZXezGq_Q(yCLG?L(b3Dw+b3h!bY@ zK6)ure?w7<5(Eexl9kzqY2IM!*Nii~eIqxH%2jXH z8gNazfB^%VLL6O)(DpU8YE*4d8)0nFo9?5sSYO*G1$$F0a0O*YU)`%N)q!3bHF|;O z7Z+4w7j3D4I`^UB$f!1A1SDXA^4#jtN>B&R^|mr8(DXL9*5we@dlbX2y~*u>>aUX3 zRL__X4|xzWT?8Ryi*yj;S!VV>mA>ljVk4E*ftFraJJRe^?DmlLrG?vyO#W?4v5CRU zWjurX5dj-~CB@NwWR)0Bb<;L{4n_s8o2EJS;8Wt$LrFt1(LF99pb#^}_B+@eu-IK> z8_9n5a>6+p3dqI?wdC$@iZ;S}_F4f{jGg@`9Fj6_J>60PI(+9pS{c=_y)j>}7 z`9$EU46P}MQj}Eye^0@A2I>|%DloA_o1F;Or>(HX0u2U7lis6mLyBNfzkhi^N!6Rj z>953O{Fh3@GjgN=3!c%@lMf3la(#%UT>h9*3U^~uIY_6#B5arJO> z?9?MlLSDaouDN>2b346<0)URB=OR2GiXZy+>z4%<`vv+5{l`NmKt67Eu326|)M!C- z_;|+jcWSO(HKz_*G;4J7%u_|}{GHcdkWh!H*SlMq<#*@yRh>^&yBT@VOPsY7`SBn- z1(wpU8Cl3=l@K}HXnW|kt|7Irt^bJ{9ed3{vxa@j9y0*rBJM z`;F%0gHLF#t>TxNrg`(n|GxR~y_Y3SBkJWq0jlf2>fXv0EDD$eQ!GJc5k%@e>yo&v zeP9*8c4PL|+hb23fA%YyxeB9#1Q_Bs9!EFVy#3Q}Hy1y8OF9GjRpQ|C{y`b9<7KUR zRQ3v0xUDYMEg76=Vu(`@KCSt`BwTJ>{ZM0|%4af+#Kvq107=okh z!7`Q46jp*3^;gh$gvf&=yE&v*kdq^lacaG@=D<`#WhFBWO-mygP|5RLD{bazz)p&1 zY3go?qD9oEG;3FVZ~fqi|8~D%S0o_;r&JStH1(RCx0Z*mH4>GYW7TtEy6SGTa`0#w zHxPVO0cI#lR5fHEgo15s#(fQf#cF@<=fvvw9h<%H@BN;v^U!;=Ail0Rk5Wm?`d2i? zp?e(xm6?sL?v;I!nLB3%L%<~E@Mq>k59ti_B@mBUgQW+hx`6$7{)5^535M~Lg2kEw zmH~j{?RO4i&v0F?5my`#OL$ z90}U1>~rIeu4K2@X4?R@*i+XRGU~#`a_w&Xux!3LoEOtg(I5AUvQ&903 zv7?GLfoS+a_8v-(RQ1`T1iR{C-DPbrhW}jG7#pkhS~%q3kyFjefkUmJOr=O#i(r(b zY>s70TARlDuzjrZXd1W!QvW=ZHzh#AYn))qpL>7sdhBfkxzWR31D(3sGz1!QpY?;> z`sYq8)N>#wC+=&Zovzzz#dpT}yu9A}y7RS%k3FdKFA8ckc5JBn)?r=5ekzIQ;^!(r zpEj=V(`xaZF|l;tFP3$V3-1HdOn!ag*Zz^H&9A@ot!8QYfZ`FvZP){*Sz2JM|25*j z>aiWp+D9TNM!)2+VS$e)SXvy$`lJ|2-*VH1WMtYO@7Gdf!wQ4d9Vf!}6K;1s45RS> zQXG?^MbxJ44=v6Y4rFHhD^tnj2P1pLe=N+CnV)sDZ?6w=KVwl}DU~*Y9#jLNK#|#} zXG}8T8svOeS$sxFkkz;9o++$8JIHxQWhnX>^MI#;#;Kxon3O0E3IHwxIo?Y{?^S_G z5tcUSOcOmW$mjQ^>|d&uG-5leo**(onge$FuOh&S{bzbv{rL`Vp&OBH2J})rNJTtz z;pt!5R$msMWx7ixn2-)&zw=XN-$xu@KQmuF;2|ej(`Wilc4!ULnT&wDC3q^*^kW6{JG{GT5QnO$o->jma|(!{OB3)=MPtq7Y~s1q38+^1rM<5Gz+!&x6nEm& z+_POH)q&9i*ZoNcWO-3lEy!7Hkr8&*(F}p?`6JLIyQy9{^&=Au%m|zuJN-!MVQazS zdPhP$ufGI@)7*4*zk|t$az6v?hd4V^L1({!z9kZ$@0FWdY0CGcBR}x_oKZ3Reja84sAdVREDP6f^qQt(s8!4_L%|p1`3|t z>&p+9395x&48D9`%xIuJA*JiZFbOfPCqDga&DkeD-@N?dpEj32dP|~4TqAyyJxN9K z?rqO=TtM_=-XlEfD^DwCCXs7=q%Pl+^adS2_mz9s`Ix&srFL3>Nf(i z!e)OWus9ZcbgMueTT=UoG4{r5?zzetT({4`JFiX_nrY%5cFrTJzf^ijvXsZ3Dzfo| zu>}HAHm%8!m9(}Mpk+gi?9cu7f8|eVKVAIWKtl~Q@wH0?mIFiW7f6vSqZS}HlbXgP6E$+UTa#7z3CKzdY`B2dl6S_Ekgn={QUD@ z|F4zQeEG#c9t|xbCaVE+8`FhIl~yinQzMr`L$dr=oG zhD#`ldt=ORUD-;bTW{tGLFmv$O)~Ozma*=y8F41{n~bTZjW~+lHIE02@#d4Nqc!L& z-%kM+`#0Y^RITGoBNl$nJIuFK0O|Pbd%K|~t#%g4+6L;OjozOB(L=fUWXWyoy(?F!LlT82ovIJQO_>kx)Go=b^ zW}lGM|(R2>Xa(=Q-0)`?p11`y86Cah~?Y z9T2Vkmw!1RTvOSeT$2dpqw3^JT~@}dGCD8t!Ov6?n41+CU?0-(FYr=SSpD&U#p9SJ8hc>-tw zq_{cF8Vh-L*2*e)J9^IB!G0)=j>wD)@PwTa#Z~=fuqhBrvXZJQlrb77`wk^|z$g%u zrBP4~MumG5-Ir+EU)vX518>=zI_ad5Ar7umF*ZlOaB~E(fJojCah(Sqezy6_@BE=` zA+%GJPXV^ZU!e{()2K>?ZA9vw5f%hns3g|DvYht}qRYdv=mPgle-5_P)zm%Dd~9Gu zc+fbNMdp}MmEr8&UB50i%l6JjbNlAC7zKiGT2y1T8^gYr3QY8}<~i9fQ8rB?dFVA# zwT^oUF^Lg7TP0`HRJpqBD)uAXRA4Q_@tg83X0evk4czUl7fWJ zg%96oW@qO0tVF36ZHRX&8tE;wc7PWsW-}k{{N#?f+i@v|<3VXCk5xr+p zA`>i*gfHz6GS=X%sh>Cc=^4*-V0BH&4*ZHokRkkqC{_xvv`n-S&{)9Ytkyky^a_Y6 z)yGOy#)fkrx6;NNS<%bN;t*RS?csA@{N3ir@iWbf|NdVniGlhvNr>CGuCy&fy?9=y zGFn=u0*n3Dg9?PTO1zHEIw_)&1Yz3BI*sHc+wqf+G|zwi_nIGk`(HMfnCCjT7*);g z(zRf*)D|bMZM_%02jUqQu;0keV>?eVU-9^ZN<=e~4x2kvku7H>=f$?p&}O$9J;Q(d zJbBEQ=Kv=_%s$m%<<)u{aaKl^QiC~A=&o@_Qe{=6R^0cfSgEk}`lB<_eAR);zzm<{ z&9acC)IAO?jtc;KS@Cg4;S+(yNylmu;LAg~U&gV1|0!PES)=_NoHmOG#%DG~Svzl| z^2wzFnK5|Ga2j{((}2ag@wJGrOjyf4xUe5=D?3@eOvvnvdeC@tfHAY{0E|n^&Facw z4TQDo;i9Xu(Bnj9q5{dRu{+V{waZff zVr_@x?^Qhz4c})e)iec~XWChj^bVm43P`cEefHC4-(8!SFnI6^QiWx7hNy_8XYpqS ziviF(!AO9rvB69~(AYQVnYBY@^CvL>kKL4PL!kfJ=v5{c4Xh#fiO zN}|e1H>>;F6<9%5pIJads3GgVB;gt}I_G2~BnWn3O+AY0?`C$Rq}ENnhr)_#p2Wd| z-kN>gvYb`FRNAOa1`0?q24j9v@1uabnNhFei8D`1nU%l4aqU9$;Mr%JFMs0?nm1qm z%jVrT{@N7VdBlOB*jmVm_fHxsVh~ooURSlDP{=w}{I=5Qv+e&jCH95^NF?f#isfY9 zj09b%#t=;Lg_0`s(ERsQG;cNQ>o@fI*jDVi+Z23{_vm#7@b8$KsjvNf=`>(5eSZCZ z(F-g)mCwCW7p&K2WVaR|=waT@L8_h@;NPm2JVVALaqp}hYm{STNa%2%S*e>}Iv}5S z=k}Fm^&knx17_k#t$d@k)Ipa5N#ixG3rWQU4@q);*7>1^g&Be z?TG}Vd2TxXC}NSWk7{F=jJ=qjdi3N&iaV(4q8N{#1|UHD=Hn1*;(SBRWjs%gN8s8G zz&USi3r3+9O3^ZCwZTX#Z3SWDWnzLB?E7s&Ve8X#B`P)Tj*!^s=rMY*Nu+({cmAL` z|Fa+Ke>^kJE&c)pY@gj~m8<_4iYNO1zV25oS6KOr5?2I38Uc&-1CAtoT^VFw(ei}- zdH!qvP*wKt|JDB)0xtK=BDzPsH|VL`7Ox3*q9iD*Hnr}3&M4W&o+Uwd=*UT(W9%J$ zlKs6pvPOLy){Cujjk5Km2G=|vE6Q@d%w9>Gk^U?D8*8jqk~9GjW%??x*d_v!ArW&^ z$5j?P54Zh~*smFMw}F3o93$C)s^U^Vvji1=%1QoxS;RVvRAo=f!5K6e!#|wHd6ddf zyhTOH7~FMZ99F%lOSAcqW7_ZX>wdYB&#KpUa^`6ouxL{>EU}-PZ@wcQ%W{+cljPES z1{&8zaOrzlZw?$hE=O?(it5&8$$)(lusH4WD@VN!j$};+vbnwUG!7hgj(t)^KOtzy z*@rj^0$>mPwMY%Y<>vZr1xPqT4|r$zHO8(@Aj)4gmiFcgaKYWt0I#ag&+#=37Ne(5 z7cp?gVr>f;>s4>5FeDfzYdJ^qVgX9G$4v+(OHvJb78jNz zj&k_e0|6GVX%qszY=5J`V$2SN28nZKRjIU4MI-=67{;c|bFuouTIoE!wS(eRiajkT z>c%Usnhc$#4v39Ci5(MF9!mbos``OA|ETbKJc~kN0VJsS1pX*WyUEd|QtX`ivQ_!M zYkZ0*f)ZmWE?d}!krXH@^WV2_UTz-$)K>%!fB2pMyV<;Z)1S+n-KABJkXd4O*-~@& z)>VBJ!aIOPg5m^prD_mW{&4=$6Y8E<{+7U*aUnTqnscSfVlqCkmp8A7MhQT~HghkB zk3U$(q-aiNRGT=<044w>wo|>7o9lXiDws;rb!cg04(xu3;rz3H%#p%TJO@k9`f=1h zpZMO)kDGV$p(tv*ca=2(oE<%RwmJRa(|Shlz4gQ9&aKN@SCR-kclw|3UnFVxNsJgG)vuEXwf%=wj$OAK!ioWAn=?CS5+@WU9Z4mGBNTzWw4n8!d;Pv5@!IK2|2(b zi97dz(>me3(JC}{!6Mg}AeDO)T|AODsqR`=A6WxkTl5GICO^l-8pWsee_xHD@M~-U z@{DIv6BZOnMF2KbZ^p~O^5I$FM@abQoXZ3kyjDZwnT1)6%_*Nk45GG~#X?IhRp*#% zC>nAAa``8!z!Dq^AC+?{6M)4%jK*NKs=EQ;*5*d@^k;sfdHmV0HZOng-!wb-EJVdf z4O)cgK^83?1?>HjGO@tZ`2V!G<-}IW#9H`gybF#b-3)VAm)sxNG|d-&PllDPU0-9*lu%9w=+WXRIDN(VTwh>E-|lyO|lWaiH>!1RhmS zFxTlsfS+gmS^e*G-P**xx367Mj;G!m41GWAmaiR3n3y`6)rIzq>ALJG zf;N*02PZT%jGICAQg)jynN$ovf>b&7!4yE>hb!xCrP8-Mg`J3z4Nw{h z>t$eR8g#lWzfUBi6bwYggpnLkxk;fa0Hj6}Nokd_7Hj&K-bnRHBHp#Tt38d4Y0IVn z03ZNKL_t&yBiN+kt@*Z$5sE%YSC%{v5`h!IA~PUagImlvyhkO9e#Betwdp(<9I$`X z%R2|H@r0;$Bv(*Ir8hF~!CSLaUMN*CwGN=rxpz+>ZU`)TPO8Bo3<};mM}F|V6Kl|( zTq#rXhe{NqO?G#hdm0peTZ8FECx`Y|Y+-A^OHkIgS3~=9T;i+#Te|>LYoo^uALQUH z&g;-7jrTxll4q%a5Rjv`f^8s=e8Z9B52*^lGq`f$z2@QvZy0DX4&cbC=HVxvmvZU{ z@BUc5p00d1vIXauaoS zihV0|##U{%ltCiK77Z8*yk=L1a&zb&`0pd>Snb7@8P)o`q!dQ5;K*hc*2!k`cYgPO z(ukY)-}-@k3FjYH33dbDx_a=aX!_Wbk+1p;4V= zQ^jQJjb3XWf99*r1CM^XdHIDuRuVtQ5Um_MqIs`FR8TKOFZvy`f69kuQn#W{^I61h zB!5nxc{0?qchs*)CA#xD;s47Bj8I9==T^6Q)azCH8?*Ws$$>fvnru&3u)Dp(T!W~r z5o6S`d8sIl!x7cbXC8U#i+eTCd(cT&!JH|P`$DJ5G1dTJ>ioeppl-}3d}6RzZ{T_( zRf?!3I_Q7)zSmn));$8Xf8Ga+ZI~Aux))4$vmH|efdy!GS7(xdK*?a#_gVwi}GJcvi1zRX52^6Zn&OZhIel^ z+l;4xo`q0+;l>r8MYTt)^KSJyZ0eS2BGX)bxvYYO|BCHtx+`+C9B%m8|TWyoc1skL{ZWs;8w+1Vl*wKdSLn7U$fVa1Dg7N#(+h7s7P|; zvr4NqmW40|{QtZ_(f8W3cUAvan~-ZM<|7HHdOOAQ>Aq#$-5AB~{Ct2zihd|TA!TC+ z$x@Ase&#|A(nugv&IC9_-?KWZEhY-70pO(8x}wnv4*a+E%yX`7s`yeJ;QgprwqS8r zDvj5!oR68f29)W$l7^p((PZcOTl(Ora02QGz_39E;~tqL>a#9XR~n)#B;^Q}_Y@de zc)Cwop`q9yt7HH^x* zedChWJ^lKzQ)ipCBWLtn5tusv&X1bA>$l`X`1_O0%UoV*ZeF{nN=oi~RpLUm6#t{( zu=FmvuRrJRiT)VCu~ZqjMgc)Ut!c_6FnLdb&IE{6g|ahyF@YwPMFByosWGcDs$~d~ zxcW$iGQnR|8ROZt)k^njWrD^))7A7E1P%JY$_5SDoqjUA4{p*YISFY>G5yI04;^nV zU-UQxuC2sk<@4%3{VpvqH(sGz)@@wfT2S~lClGaQMYX+`bkxy~cs!~`2I=0j>RV5{ z8Q_Ey#(12s{?7l<{Pn;4r)u4BEV$PkJ@rVly>Yi$zjICT4bPnYIr23LEG8)G&}Vz^ zFaQ?EG4}?+VpQa4LHX6+{sXbJ-hJ(RVwtg4J0#e5Hq^c|b=*EBSgeyRZY@}EPCfJ~ zjUnMY)A!9>M=?R_=Tj`P`z$-SYg~*!AT-kf+PwfEg{JD&PGHUR9ceEcjuhn}{``nfl5UfE%c z1b}jL^Nv8FfNeNSFI}5pQQxA(DE10a-Pj-)aP7ry0GIZD^VzoG)p2#mVuwNJ z?5RTDCR1Grr5eq=z4?U@eXsxtd(QIt(5b7rony{TCxGo_oThp*dJ#dMDvPQv&8o8a zHwi4(calNkNCGp3VXEQKL)C>*+Z9PJ&MiG;g>6s?ekq`KWsZuNDkuVf28aa1B%`P} zIHwY#ToR~>pfBgFh6-lvRtLpFTjc!-j(Hwb9sw9oNJ%a!7~0v?0Bs3@?QAMgQ6*sa zUUT!>h34Aj527m6R?YLQ)PXYB%X~7xB0(c^@4O$j5}O7+)gokEi)pp4{uy|9M%avc ztPKzxkU)*~np=q)YAklqV3A(hyHZ9?)_?-?JVs^CuYb@713d3-=FzTSmv9d6yTy8o zJp#aJ=k1Q{eAyY>ia@2^mkd@LYTrDXB%64;;`6vqW+I+>9av!DfDYzs*eCy3-cWbb6#1DN9)+A3S$cJysRH`!TgeFdmNt;R;*ymEnw z(WSR}q)JxDjy=(lvY#gf>3v^4vL|~p0s9*;K%)ebg6=L*+w6&zMbhz8pZ|tL%)a|? z{|S&%XA)XEb|01ilz4+8e&=U2R1J)vq;vB1XI0N-7}e3G8Cs9(I%gh!;(5$;ryr_s zoU_U#lX*WNYWf)E7yHU_*EkIz$}1VSk%q2xD$p~5GCJjF6{B9=U;b>UFQ;5;XJgjj zEu3)$PTSuG9j?CL>N@KKFp`zC1u1H6bs<`NtCyS@IZV}Oj>{Srm>9;Gz#KYf()yeo zg+_v5u|N>P8UYyUau|IL!$#RK#w!rW^V%XtvCW`vGV`W|rShCJ*)vvjT{)ycicERV zk<6-B5!MLcAV;~gU3xJk3NbUMIcrkn+_U%r?@y+g3@kySMvLsykLD`DFBa&GZs@Y+ zm9gyXJx9T%LN@O3*3Z>}0RWxAI;+oBRdE7X>^ku_(?56=CsYrMqYhYE(+Gdw3aw5{ z#FSRKi~y#0k*tIIS(Mly^SdCxA*p+Ml(f&bqleNNco%4T^IiKluQRSYY=4vIHR7KA zsv%jGNU%ttK`?&x;(PA>$hlY<09V&k*aGSJ1|H5YdfyK1(>mZ7vQhPOHdu_AaI)b0GaVY*x3L| zqEJ;LJEf8-_QHY^S5!EloboTAiy_p9k3Jw&>GQ$vc!?Ne&e5J~xefpjPMCen9 zbwI1T_~DxZph|S??kf06%BqC97=uLOjXrWzb~W;7r&+&!)%{eeBrT|CxUP!aym3kI zOGQIqaeJd#JMut)l4PMoKY8i|#Qq)j0p4KlTff_^-@dMOU>ws-v#ZL2Qb!f=G#HP* z;c<%ZL%tXhBP#Vpy1%!%t8+HUx{7Kky`aZVKiYis-Ye<>mH>cL}rZh&NjNvyJF--R(H6(hpt7S-n`P-Z6Cy zG|qQ^lApI#&PqToXz|OdhZ@9sIK!;}=f3g}ns?v$Ui0>=-;wZER-9-*Q1WGKy^Nu1 zE0-0(n{D2bdD(Ys=Hp3OFw7&LF{!dx zZ|q*3tkjBr(O}WL#Gl;TApO$yXb?XbrNvtfWO{NFW#H4R1dgMsP6Bx43aSiKyNvAs zQXGdf?>4+seHA)}7OBhw1NSp3g$COQ~!K~UOcUx9CM$2px0IwoxJGxrjLNd07&_~-3OY=pdN`s z#enxgU6p<%1d=2m6hbrEH*C9Q8)S3s0L|~0Kl2hvpeX0O4hE;Wl#}WECHRQonj{tX z!oO4&6D;1kcBu@amcps#*qU0X(H52R9Rc{M2cOd4qUwi&pGNeAimBI-`}15bKr~fD zs)8uylKjHv(d(#D00@^vKc+xND9j@EfZaTNg@JKdlxb{@=h-zDxCkZez8@;@TL(?)cf$`C%JBVw#pt)MuRHgeiX^*FDj(WJusxb+;WWY<3%_xs8g z&YXSX`AoI7%Q&t?K9n(-P^z62+x*A;UE33wMq!Fi?`4&`2RO~kq+{&A$ZBi`Q-hy8 z?(p>tXZhRe=N-^C^ejTOB@J4=fzzp^$WR%;T3uwRI#+vQzuG2@Tt$AX1Z_CI~y*aRUthsgVqMRQfGF9cY zCbLk`=o@oz#4Ns*gKN!!14m0Ak-#Sz@=b=C-xcum=Ui9d#Agw7@%aEtXj;2X%*)9G zz1K8k{M5U$e8BXwtxZ)g$ixCpR{$6EzRb)v>nN~N>5Tm{%{q_U>4VwR>cwL#ZM{7? zv=?fy=xS6WB}Sf2f}zfJ4LO$yU~cTS^=@_uJQlFHpTq0D*XU=qv+5KS>;1wWsPB+* zD+}rwA|S!RsUpS5mF?~39)ccQ2u}piu%Q@vTw|T=mRK}*DjuG zZr;4)s&F>Xb5^k};X%`pmY%aR1bBZN*>|e@?OFS;Hu2?W(*=v&_iTHAR53(ICa9EI z9n5_R<%&REeN_ssP3==9Ch4OYNDtWC5&NpYBXQ8b-p*kgdG<*utgGMt3xlJq67xFx zpO2q@tU=I$V1*tdevYCh`;F|kss*AoZv=SqXaXvgryqVs6$f5(@x!-d5BZYPu549$ zGC+dwg)t>mBgL!;I{5MmGcC8uY`_j!yz-$cV22K$lKsVALvd|6*=-P+fFy&b;mTr_ zWJKt}gRBnWULPkH6SasV?v18Tf5+^%?PHx0Jyfvq^CHg$kk@w_Z zm~E)U66b1eUKK;00iZg8GatxWKl$9(wU4MuW|cohY(}c-_4t*jp!UTua!pf>kz3Oc z_Mk!+)$*dQn*E14gDt^g(qHM1WOPcU?3n&M=EnKl#;AzcU!~tPtB<|d)4iRpbh6Lr zS9fJ`K?#hcr;_YoUs>7OkxW)sX$@IgTvfGf6u;{Q$Mc9X(8sqLoubV?mgTS zEqitCXmjW06$|kwspr>q6Wu|9?8PuTK~?3~!C@~^+S^}suk6sq^RcXCz6Gk>8(Y5i z_L?(~KG!_=rQdBXe(U*DV6F)*p2e=Fk> zMEz$Ie^*9!#j|9eVP{U9ezZA$>T$(#*jU7E(3mLK(5KRmE4=mMpb?ui?)vlR0|ll| zRd~|mXABm*S%v!ri#Cw=b@1XL)xn1VO{pMsRgY@pF!J2@ zIlMKXZO{7ffgcTqMt9jX!5p9I|7N$=&v^m%d5@7)uYX|t0>wbi|^s!TsM4ou8+SXKp+T^iXMFe_qGH$ zxnQKqB^e&`7XOoi#X;ZEtym9b)UpGlliaA^t8XaB&`AeD+wjTi^e+~B8saZQe=^ia z-`e4pKAnzU*Ai4lXSY!;HGNUwFnUr6R2lJ-%B2QWwjt^(l5^@VY=<(Mi&xfY^!5AO z`si^U;|R;1YG#yOK5_anB}=H7Ge_*^^$Q9Fa~7P&K`gIEKbxuC?$x8=|E>g2*wZ7n zU`*C|-1XN$XM9b=cGS^yN5noxyk11%uW@qGt5!h5*dC zBwF8Qb}FJ3AhF4FWl~CzB&-&w)^zFTzMh!Fiz48`!_Bc%j|%W{4>zxT)ZDoCu@X?& zSU?%{SY+^_zFTQ^LqQ_;=k!CLGFZHGqq+Fe+h$-?qlUU?NAa}!!Rg_mQf`s2c~N6G zH>n!#C`p#UoM&+T@&`H(R5<`d*nGgIRAd9}`~E$*G7|vat^*-TKd?@J8GeKF!&>lJ zs5??^gl21ME&+a2_ks#K`0V1@w1Boa<@>9&)Y~UiER$BAfP;G^5vV}F>cXawk7;0-Ipyk~(0KiZ%Z3-j3!g9zFh`sNuJ7U2QI&d)<4Y zH)3P(dWMQp`>k*P`ip@MT$0I|A-qucU0ERI9Ly$hV;d5?d|Bw+e;y>aX2 z{N4Up?van{fiq)*o=aPXs;m4F1INf==qAK)niA-~4!%4g*8ak7GB|LwqB ziIicG;0e_mc@j~MrN$f-Ss7uJ({M_B?@V3e%H!Qz)x0*-eF(0}>`@)ixDQo3@5#BLikH1o zcc>av0l?5Rs-HnWo7vwZ;|xaqcZ0!N^&x!#I0zQw3=Dmq_j6lW@JX$}P4!v#1s12s z_}7)jv0yR5UG&qWS|6{s`mQU`{Le{=y=Hq8#a8;;sG39li*!?&bLgH=1sQ|04{Iv= zCjp1|X*gr8cs{FZ%#3rqGXLtsMUcbin0@@SSO0_h z-$v~2F90mI=QmjTQL*4!OqE3V$n<9dM$h52qNu9dO7^rPOUTCS8O6Sv1QzT4*FRhL z1r{U7BS@ACD*e-_pe_Z&V8?w#urJ7@lQ=5#)x!2`5c9oz&Fb2*=GaNV;+pR7#?=o6 z76mft(_UO^R#px*%d1Dkw%~mc@&Ysh5TP6s4D;MBefYM(e$K#atK|{A>Zp2Hy+m-9 zS9Ep{9zG@TN3cW^j(g#=5b|PQ&`-$EplW5WcFtmSpdI4?P?_!7){$PpfgsR6x$?wG zfsOGwfY{AD*OeF~NCq(IysK9@D2oWJXm)8-ixMo>ST%rpu~(Vg9H5;}I)Oz%rdMsM zZDC9K%#k7nHVHI4V?2`aQCCLoJS#uiQhoV(sUG$!fOSQ~@r(O@OKq+a9ycXX{a*KOOs%?%hNWn49 zaHJ|8B07o{Lg0!&q>V!MLqd3)rF8~TB9dan9th&Da0l|0uyE<^YoD zZhL)iiJlHa;l|aEetBTA8=Q2HNH57y|B`1+QvJclKGPgpJE`jg{C@P_Pn+vkKUADV zocHSg$KHDdS$17#nmfI#s?0K3-k}`4BS8`Xtq4ielti_t9;uDg8uQTa{V*|4V(95Fi|Z0tzVay-8m=@%?M9efBx`+?!b- zB$0}_46v#)?>+aNZPs4@TL1dj3x8p%^JQ7nN`63bCTUGJ_fXtOw!88w)9ma`+2^f0 z?-oUwwR8FWF^Png`>r*Jvl6aqGag;QUw&)z_g%gt>}h5V_A*q(HM)bvo|divM=PQC zJM>w8R^J{6OBn@Kt$f+S_hBibf^vKsK(gkP z+Z*gI!^pULqebfM)pUsT9QvNZXf@VA6A;*DvGIuO89uOv(f}-|UuvY?^5XMkF)$Vg zDVRE!MUFWHD9Xk_57OXP0yPU#$D3EC(u{J;HWl|PdSeHuiBg1YKJxKP$~IC%$$N-)a=+9J06yW}Q=iDE0m$6D92gYu zJTpQR6jd_yTI2w75Mq7PBGuF->RztHHfN;x{i>o%-J<(`ot3T;a`V0SwmYK%T2>7f zyI-}rx7yZa?oH^mK{BB3U{y|QMKc{59@gAN1lj0JM(qp5T&u=s-I-WJcJkZSb~mv2 zUfR`01U2v6(q2H7b)g-i@YCD(X$`YBFP%RwY7%RI&!G>b{r5g8$N$FFb7_YDTr)Sd z#sv%pM-=cl^4insrDwn7cA_3k>ozap*T%Tp{w(@X7LKp>#o$P83eLT$hDwxn`nAog zmQD(p00wHERQp@mHohnN(?y0S=%zA{qI}jfi}{`!A}nq8wzT1~XZ3m23=SyEM%E7+ zDRrVamH;T#HK(K+9G2tts~6L`ldlVK$wp=8(E?%sFhq#}i-@5B7Rdx#%~&1jFvkdL z;oMN$jiRdcdt589c=60T#;_;u?N~-;{r(zGtk>!7ji^^dz&OQUp&Nwm0{}D)xp2ekvOseQ*H|^j?EjjqN4F zD1i?sm<|?=JyMKYUYG?O4R9Fee;Zir<=h1jE$mHk=-NDsf?!UD0v|A5GFWs~SG}cR zDRcviImlhLV#pc4QtYMJV-^^%z#`*fEi}BfMzz45j#*@`yC6>h03ZNKL_t)-T)jN| zF6DI_cCeQZ)BzTqdfEXNa~-Aa@2Is@W-x=SMo_QkeE+mf_^nki~R4THNJiCgX!)^KAE2V%Rkh; z2|%k>)%soX*^S%ws(#U^=s#s!$_ zfiLUfX_^%IwGvqD?U;1&N&9ssu9@1Lw(K~l`Q_FxoH-)!S^}~694y*lQ@^h^V7OYa zxRRX;Kd&ndwbuZ)rB2_)fd71bBp`;@Au40w-1e5tVnnCS>2OL^0nVDvML8DDY@HRG zR~wg2t(3SIs*~BUD0B4G%2r&FcD~jW`ic$ISa9Kh)EykFF$j>?oUaP_)oDVd@#pho z>LfDb4wkZcPQ{#@+Nul;4xVM)s{VN~;!+VDK+FN*L862sqKWc6C^iD-=&57kGklNv zNJa~BFiZpw8EH8LMeic7KPaQAyf11=Fz(PBkV6&?kG^A?&VGqI$ob2SQ2XT=@pBXo2w3R}r_2RWlLHo9zY&b3^rV&{)WkAaF#-q>7!}!EH z)fdAEV0~dzmdm-p z*-{)`^(=1G7TSKX{cGbM!Q~bQx7df-el}*c4i@d+BWqa8EH=R+*+bo~TCQU_$U08;9c=o>-0>23SO9%G%IIq|xvv1Nj%6)cuE>`uV! zodEA{cCwt4=HELVzxi5zOELKrKB864` zTe%RM4t@OE>)(z6#19HCk44FBJ7U+Pd zeqc$5xn0B@QGq3#K_4$2Flq>F^#uY{%IdhtK&VN1|D;fRTeBAREtE(vh~kBF7XXcD zot&xuzBGh^hf+p;p@eT{B#fh8jDtg}6QK5ls6V#}J(b@{bYgy1;E`x#C=LQB0UA(H zxem=`m%R2302H1uYF4{j>1$N|M8r_QEk0RX!NnAt% zdQ_gLu*FgVg_dX8wRpa8gpJ+>m;Bg#9bQ zBDIK@FP>CwTL6S^jyQvglY_{GM7VBV)ihEAIX`ntEDnH_)Km$KDOk5)6jSP~mrVJ2 zbj?&6A6uuaDD*aZD$-Uc#JXeyhlbPUZ3mRqB(ukPC7Qlyx0Y#TP1vHcetR9kk62{R zQt7&H3ScgljN&3r!7LnE)*JTn7S!1*=d5iFnJfB7MvI@qfr&b{X7Hf%KB|72c6`+X zQXOEiOBqWBi=wMXopZy1&nmC%YuiK0g+=eg(#E!dMGq(lf);zLI`iFgD{NYPNBRB$ zbro3jAZqz+F>pn=(fgo@-s8ED!MuO zwL`^izl&-uq6*vJpSJA2HyyhFqv;3V{I_ZL##L_z6oCV;&Ae@3k^T9uY8D#+D1sO@ z-@nIP=QU@4$&zK%TiZNXf7|;X`&61(JC(ls)j!bcQm?}S+EE!$e=lBbHa+`J&Um3; z>XvN>()!K2(y;eEJ$w8O)yTF7Ydpxc(irr5fF5A6M#b;8*Lq#M4Yd0A>HJ+$;ASOs zzKRH6cK+UrS^V3$MguHn1+SHQpH&`|pBY~K+~1!7A#6yaHd^Kl-nqS+QPa9ImjKf3 z+oEBOj9Q%#kCzO>sREo$SL>iFmu9~@O#_<)h&*%Q=R0sD`%VrXZ_g#m{!BM#=xdW zc|}igun34Yah=(8dvVq?u#CCYG~_i>fVGm=n%6@i!`{tsc5{+T=ae-F@Kx_hYCU3X zi|;SjPwy;X@6BJkPVqfbbu4R|JkS#vVJTxmHzbp|4CQ%D;vxWX=yXyr1tcQD?nUc0 zpxeAHcRYd?8IC|XF4-n_iK4ZF#c(>a16zH#1dD1D)@BH2c!I<5HVreeT@%U^?{BCl%NT_caG;!Y}UYOXp6$nV$RhXLIds z**1WH%l17Fr1PiW)T~f{!oEL$>P=C=Y2^U56|ogWpOm#=|F%qj03xm*S(9+GJA^f| zW7(FouIPNdKwufjYXN7Q@NN~xDZp>XZ`E$RA|^O9r7 zHX)qAx@3<(_pN`QDNf=O$bK%THB-}R!zQDl0(guzd?A+?^tvz3hpoHrmTd;)(W8-U zh^X?T69VJ3Bcirxe)fj0&+ieop>_*L8mb(@6|#mjn}=pPHZ~<&hK(ZFh5eb_uw8Zz zryCoE^T%h%WRvNDQ9*{A03Z8}ag!)m+y3hEP~~1zV8k zYYu=M`@?HZ{LH8_#Bo$B(Qdl&0-x~9MXZvrev04%7n+E9&bu+1hN(v4a&0ZWR`*`0l($b8x%G9tAje zmRC1t!~;Jog2nD9&8p@hM@+gey;WW3Z}m+LBlFXM#h8?_@hPjTS(q2~h{IiKplVKQ zG>`HXMciR1aTK6O03O8Irq319(u?x~8ywz5irGw}pmvG4)WD***$A-M1cd?Usx#Nb zBNXW_3W@``0TQL`Nv6%IdUi%yl+CEM(G|#QagcjQRqx8>Gik%7or-STT3^=l4AZM{ zVKxI)^)>V!c77vi(dnre!I3ee#)-<>Kai!=MFVjI9N7>+TyXbALxqw@)>dsS%(>xN zRUb7#!}2R~ltM5<^WoC`0`T**ipKYOLt!bep@KR`-NQf{Lu_JTNJdai>xtB(DoBQL za420o^R}F|xPL|XZ`<=42pCazg*piu!vZ1!0SXlK4G5eu?qnf3+$hdxEhsB15FWHR z0s%owv>sY!JE|Z+Tcm6yuo%(Z@pT(@AmK#T)^x)-{WL(a)23GSK6amxqoz~@#Zr@E zm$=gH#WXZXU1?Hag*C-om@^(iQn7CRI<<&>r*(?GQ>}McOhp>FUK(>GFk>ViK6}QJGz?gT=@s z)xe^kR~@Vc|9Y#XEWxYaQt3FB&RT5(*~?$rX`E_~;GBRR#R&t{(IZtKU#iL;p= zqU@iUo7Ys2HZrj;T{!iY#&PY`76nlFul8yJ?ecrNh#7XxgyqjxZGSqZz6S^pt3?!V zXq$Jb&*F36{C8<~ZbtqS&w&m1Q%Ub7X|aCePT5@1Z5!(`e}5NHQ41I}gBuNCQ+t*M zaH#@57W9~;=kLIP6qWCP>{mq1fBI|xM)pO*U;~5c8f8N6S9TSs>20Q4f7`VEvF7o& zp%ib~ez)v1<9+GeQQ3{MWUMk-ErBCHyY!wO0K8+3RR>kBY1a9gHBzGPw(&?k>}Jn< zh*GOIu-Ic*q{A!LKn5mi~~M&HFm{%w6^)d09y0Og{S(aI{RC~;0?YJ-$K^8sZ_ znfa9q(fg%bwM-q{__{PUx>g1IfCMs#WTkNasmW+t1Z|GLIrbi%%uy|OjG?*?qV|Q< zIvE#eqzFa;oQ%2_^6nv5kE1#=256lS2)w~&_RUcTix!)+eQrI1qGk^fhMC#xra0Nx zubRd&dQsiHBFYoof5~MJj|mhF^!KL)DWxK@4PDUcmbe$u?2yeyWfUi?h`@1MmSHsI z+EPrwerEzUA_MhVh7YF>!3iSrgCnE)Pe2$>6%(fnl~d}%u_Hsmm@#kAwA3?8pe-rm zhyeo7;Vcq7;6UP@aI&OccXB%9Wl|zt@-tP05yODHIU_ zBMWj^hTQ1R!@hnkFcR~5_rp)Ah6aHJWuIoQ3mmeBSYyl&dx;hbS1z4S$KHHS0w`+f zvM`sfsRqs39snZu9C*xH4=97_ZGiyas>50Kx}Je_wc@VvNM=bTcb^9 zr)AC}Tal@|%^JyK@pU>5?G)7Gg- z!&ybbe%<=5nhT!m`(OJ5)dOm-5l(VP7?FjI)4P?m1872Z=UTRpQMYz*5{|q(6?`Y6 zTd3QzcE~88Dk6BX%5E4%`3Y1&D-}2@LfKCLRn~nXc7gv zd0ngw1B-{W_sDz#$YN9!gybw49G0>xWeb!~uvRHoXmzOX)Sp-#QEaQmvvfO?MIX-xdl4>Z%Vfov zm+Q9Tt2i?PK!{&7souYje)u=jYtMf*oj-lVRAT-8x1iR>GAfl&%kNmhk!bo5_R-GZ zl9hGc$StNgyXd*ic@;i)*)}82^40h;t9nnjxoFyjUN&!)^XZO=`GDR9|KS!UJ!SjJHz z52DR^)Xiz0rE#geE-#Q4uqxs@WDcOa4pDbFsrs5Vlba+vuB@dykYr;PB%|Sn$pKu>&r=LOE=QOM zH%<)TX>q|COy@poWI{sdr%*HurwS_S;0WzApui&BF{o@4hLz{0$Cb`|(SV2KpaEu~ zCE%#(zNOTNM=UA7tRl`KFu>cUz^Eso3z&xv>o@M4~PHh32cyG7}RzvHVL*K6!#doK&puMYxgH{VeV*(CZ zl#ryBELfqMKdJWir3XIvs|waod=G_3^*5}o1ynBqnIq}tAATwA*!`fgJg1MnsN^`X-26#H0r-GU%>5U8u0P1D%-JAm+3Ni;cEP32;yUWX$!Fg%(b{J^Kuw%zwD zlSj=Bdyw&<$0eCTGOGlVHg4XNCMGv2JM#Un{XgmImD943*j4N=*Mu@hts{Fn1a4$I zmaxIrGJttB@gY;Q)T+OITegxuVb~o}GE#!x!aB z9hD8R*ferYkkpoes|;rtpL{mFE3jB*fXe$>2`rYGq#nLrb_UmEwI9*o9A{`*A-j zD7|?Ki|A>vepqwp7R=6=f7KkT*0a*b2wO;2@!`imou2*XAFGaeaAeFtmgcB0t)1GW zJ$d!wY54_f*Kg8(=GiHwkt%zr)VBfRwl!P)teo#I4ol@1dfq?wuZ@-YgxHpQ9)2pV z-?UxNLO=%{0c{D&kyMsc_!C{gP*>j~TF=DX`2KCXXEAbaU6ZiQ#!b5wNJA6k9Bqfx zySF}19pAZ{aqQ*r^a6UT1%Y>Z4?L5=V!65XcjLgt>@Y*sE9ZfIPa62whO4SAq+UtY}OjY6U7a+ zFI(qETMS3JG%m4d+nrfAd~)>6kuSeb6bget)*Mm z8V$8JEloh{#p*<(i851%7tX~phjL$X3g@tcTC$wW0z_ow09+Jv4~>os?9gK?*NONP z8u&C|%kx<+D81UCSrJtqN^`TfBvzZw*QY0*G3xsg?*Ey2)`0b)R9>sj0-s?^Kz?e8Cwcn@L}Qf2jC zd4ScZ<5Z>y8u5ZrTA@u7v>-UaeXI7ebeL-QQGvyLA5k}Fi>zZ;#-S=IbQoO;6*cOC z+D{(s39`50*byP-(34|*dnrE)84F9ySrhCs0`1|-A|q1(KuaU^eC6zx2iD`6>b_Tu zjU9#|z!C4sd(;I{_)@iC0fZ1N8Xoa%ytRrU(}5}|b7H)XKGAI%w}&48wBB>}#Oo5M zVNBQyWaw#qv1R+gboS)ow0+Ng%4VHB@{&LtfR6PIh(Hl|+wS|)%^Mff?)~q#`q{zZ zOaava>8&fULHzsWAAUu^VE?^Oq&Hvrj({AQGcuG=63?A_GYt(5rK^|ErqR*0nvc1; zo2uEPZV~Yl_S>0bugOuO9wbzTOIy}9zA=uq-n4mes~)wb<5t?^wm^pVCfRA#M_OZd zHBujhjbLX`{zsHdFj(M|flRyS7mLCzbl0T#2P z6bVCDJyirt51yZ&u_iD|J!!N&Q4nx`Uh}SU1qTXRhu)LWE@M3$xks@oJSe9!ivB(U zdj)g{uy1uW=r}8D_fr{%y8UVMKY}{esGF;u{Y{6l1gG6BTsJ4P%lGBys7`K;FTp$P zH0yQMV6n?R)mtmn*#;f^+wb4%{aqctF@6z5vOT_};1%=7x(*?|W?dL-K(+6|YH9(( zHUFy#z8lY`M1YqXvHougz*USW-X5T&GvjFciISbiKK9#U8oc!ESJc;fcxwfan%~7p`X!MtKDpRwbwd@;cAcSbH@H%TwF?9cO6QT>$l0Cqg+q6 zGgSUpwWe3ec4!^$USMxEzpDU9(|6@`L~kM$=6(BQ0NU`?@bSrH$JnnW#P&Ip7rX#9+GhKSFG&3hBVG5{vapcrta&W65j zI4r}|Z|VRd%49%*zoUvMdXeh%%plmoK9DBYZWBWavV(k|fV%^9GQHMH00(kFQ758JWFPsH%q0ho1aJn1M02X-uuVjW|M5BM$#6&k z=80xhM_&{R?9MJDEYL(PFf;z~Bc~JxT6C*lL zon~a^mg#Y40zQGS%*ZcV{=8U6SQ6`u3=!*!nh8LL*@04QxZ%uO7x-}iGHZlI2ucf>Cgio6^+%@ll`7$ zG<5e)MO{qKed~`^dpx~$pMVmM;hEzAzrM6%?}J+VWHxslcvR1IdVp9t|kx3qck#vrG}$CYsO#@Bp=H zZ!RNuf6bfWjAO&0dRup!0)hw>!){F18`?Dki~G^MeR`!EEao0T`OfNt4 zWr-NEPXjEnZpflR5oIna5237gvl=J~hj=~g<{gJ}`2s&D3r9eU^GR$9023t%qZ0~B z0QP9ba{cN#1^C)*SvlU!1a;V`AF>w6R9aK?BoN)|l(qRM?t`whZQGuk=fHMw){rIT z+2l8RW)OR#y&&6ZqACh>q0UI)Dr)AvVZ4djjcEO=eoT9&B^ahJ@jVqcR{pFP*eicm zjE7}y%mU`Wd-O4a#DyWUZ!JM&+jaBj8;rE5i}b*sE|mZ=W9i@nAJ@5i^zaYcr=-=# z?851~6Q|psCEI}(fLuR+meabatzv7a Ephim6oj8U!=^Z-G*w%hD~HMaG5hfFEK z<)NXJmX_1vZGzFPqpE&U0SH%FH9ZDelo9kDaW=tH+PwW>y62In(lg)qL$N~^5E&$J z>b1`LeyPG+-&D?ggv|)vv2L-~vP;yGzgv~jNIW$}5NqeX4MeWEE5RaTi2rll4H$puTPA-Kt;3kGy>TSh{%b zSOs)fN+8)mpNF9e4zEzZ*b4}*#<=|ypYN%L+H~6T;$F>7{at=fxe!_prg9P3;aUMj z-x!T7nrNl6)=(EMgBG9Bp@dM3Q%*%+K=?%c-|AGpOo=H{;mvupNR;(Ys-i;CpTJWN8ljR3E zOQ~;Y)arNupNn&r-JpP8RAHI`FUxTgHK};6YMevne=!a7OhYDO5p6`Qj;-E+8Ao23 zJZPs`SZ7pX>S4qioLXbq_dnID0s;942H_IgnJhNqdQ0 zCub7%jDd;haPM;l5*FuOQ0KP)jL2q1;c3>&Hcf|t`+C362woVQ%LI%#R0c<4P5}Kj zSBj+a+ypeBaqHPC%20iOSQerQLgWZ6_gU7saDKYcf$McKUN`A`)v~5WmsEc!srFgj zDr13@pgLVqqDOMpK|)qur^{el%|$sjssTvylk~}d@u7$9ooVBKcbpC39V%HWS+wshw~uNz<>Cye=i_J zKuMW;vMv&AvKmaDH`--HFo!W=Utz}xK=8RttM`moSI4WznbTbNZEx)r4dz}MHw1og zbkClAL&7ga;itFlmotfjg;O@Qal6($S-n&5ypq;VZjyrzSX7{E`}eucw{{2iQouLwYXecrEXvk%9+<+d zz0dmxhN@{7$C_(MaHm7%)xUKmQ0Gp$62@t}!Dl>AWz1Mj{R?&SZSQY>j z=?lPI8X2#arTb~wA8N3=Is^0V>#cs?uqK97*Ug%t4$fFd)?1YzGud_iZUJp8Z`phI z2jmOk&vAwja3XsRAjd|WKK5FsYsTIavniMa%Sn3_AB(eQ9zWCrIx7X`$}z1yVF6Cs z0cWf^XWBS(M+`azUxw70;(^CLm5v{IF&%yVSrc;vAWM+Y=%^Vi#+Tp0TIhQ3aV=l} zn&XtT77*>*vi*SSS@C&bYYuSZ18GX8lmb_~8f;u?O@K5yM!E+BvpH^f}cE&dquwZ!%U^KN2$fI9@nh z7*%T_a#KLlGLKdRi6SkLf54t-Luz_!z$8RN07^V>2)|gy$_{=qRz}B+Cg4S1w`Ck0 zYUS2=GxX)GQcG>6)zX-VQSQa$z(`IqH3M@vp%$S>TmnVNTyv1m)#9KnBBxcYjyW&2 z12HIrwPUZb6EN7z^c*vF#L^j37RzhCMD-jQSN33dY$A=0pvqc_t#C`M0riKRrC#v5 z4kE^!x}b;%hB3}}(Xd0|c$Arkn5XeI8#K4nGO#A1ezaWAt2ywR2S?=u2x3X8)hpwdhX6$~;A|g$y5ikhvj9gQ6+>2Jmt3`+iC4o7Ti0K^tsA^vW~a#5#Tc zyPuOfrlQ8)GRHFK6>%`zgCaOqo%epHJydy{w!7CHH*H!oh}I4kBN&H7`)t~I*Td<+ z{U26akcXf6jodZ@z(<`Oj@P*phou0DgTuo@H6%LESOLli6`96d5H2zn7f09@f*?>Y2=boixjN?91$cAP_~qx=c@U!0p$};hq5F?W zfpz0n+O7Z!!lMn8#@C`qPP1%svg-z!vbsveU5!^ z>e~^-ZMjyq^_GpTw*=_|78{_hX*%ke#V%m6S0>_4vJ`&)KIId_0A4=w%m0;ntg;6Y#oBS# zL+Rwvmt}9J)^AHM{@_2!28fkF+Yf;sYR!###WfKeBjbyZUioVFsMYTp^WU_u&G+;M zi}r2!TodayWrb0E-EBMXNjvsElAiz0XVdwUhpo*V8GHG1M*TOoLq%V0%j&kRg^nO% zOTZ=eO)v&H3!$HG+P+`v&9iei(z)Yr=!`7uR_g)dFa&khO6mJpt+W5W8xU-&BzIX) zU4PsJn?3e$GtkkVS^Sv;i?*RVM04(Rpx&$ZuL9A>#;Io%;|8Ke!}~7wAzi=8q?o-I z9)K(sryMNxpR#1V+}4ITOZ8|Tq3HqY>(NXf+eU`6ZKyC-MAe`j=2jfV=2A0lMMswv z-2&KIk1aBm&bRlvN&_+u9vcgop94H_4y?5V)JCsiLoIb=T)!I~r#A7XD4hT{MVR^r z1PZBBBok}GG&7btyuD~tEoBgCRbhZPY7bRNe(Sn2mRtjejtmL+!uSr9v^!R;oG3%ZiKvoK({(YOG~f3|vwa?>+GfnR^LQ43CMe9yA7jBVei@yrK! zHCGlCF{L}yD4{WmQjGY@ZCZsO0e?d^$=X*=8HQd1km31>N+TgpwwpD7&!bOC$&;+6 zvg)*Aaq1QIuVgQ&bA0u=KU1Uma(ruJ?E@MCre>D5K5o5@ck?^i)^j(o7(tH;!d9$~ zD(hpJ-0ger7p?b|=l(qHJ@i32D~#>AQ-`(Q$kbuGZ{56>cJF^wlu-gAv5&DQ>n1m+ z?Ry`Ph|TE4RJwfbsO&nFU?}z6&-&>->E^Zbs#(MyF>lX(=W}WAp%0{^Z$2mB4)~%5 z^vLT^i%w6FVSWZ-su^Vq`A(b~GKPRTYHIf1_hI#GgaRo_tRm!q#br@Y`JS#|v9QzF zM6#PwOC22cRs+lF{HeoQPXx&j&!FxpGOh$57(?nf$+8ZOOlWPGeK!?FK_+aYD+1e` zg(wKWwZIzRzj5=X{ZXSH^4gpjCDDOZ_%(@ZfNa~prDr7VjrhA$2RIOyPgld z5(h2k3BJQ)pZG^<|GiJ9zxe$Bo{qoyg4JF-RX4!0>fm`!w=YeQTkh8gV&)P8w}Y~= z{%iz=%e`GbPX-u;&s*9O&MWB85;=n96XR7(Ow-mh|GiR>(rmOOa%*eW1gR`gt%mdj zD_pRUKsgk3`~cPxV+!A^0V+M4Oo8l>){bc$k@K0V)o{e0;0Ul*%|fEeSld;cTy%cu)P z5R42Xl=-sMs^&{J_I)de^&49qSTqn9smDfO4B_t7Mh;p=OeTDGYl5XNJPVcXpwroRXE4?meR=g zX@kto%~)TpL60&9cqj}=1rV)=PI57tDuP*Ew{>$D8>DRmttJv?(N&KG7KaXC77+rY z94)4G8@5Xx-5lX0Iv|lSGIszdWlDIqMut*R(}AJ1ZgN`D^wEj6UJo~~4Bgx<8zY1z zBGXD+fT&G0MbsN<&E!UXCx8#i5br_dGm$NmI^diDxcUh>tydD#Q09h)RTr~v{dUog zI4q#K^6W&Ftw&)}YYdDwMnd$^qNu$bfBs%&xU2{s%2l@vp$wDMODzi;SzL@f)Lf$U zP$Al07PWR76m%6u@0~gs^wZnb{g@SKK|5UlWO?wdyk3f9zOUaXmOOj^fW~d(mOUD? z)5l-cb85_5z@lzZnb3wK<^iNk$RFc_5z19z(XK7Q>mRQo?9C7dvU{`4=k%7l(ubb< zy>$4cZ>6y{lVUFb1_2T{z19}T0v|+fp-viDysdpm{p_KKJ|X%gLN|aW=8*3;;Lwni4=Db-zrD}N+b0+$+ zI|^hO$oSp=*xwU%l+5_?w_Z^FCmFWO=a0(K+I`@CzPJ0+$)hi+b_knCy(V?PP`${^ z0@QE-uU+Yf5(Ag{k#u!xOj4O50dpoUB$^A8|Z>!3a> zC7^W@HkdWFY4aXs{x6(Z-37FABGJ@d}WQsMuFeOMQ4gYwI`rp*>2I+hd8HQp_ksS z?n?wftg^XQlc#mn0vPj@ck$tvKLTs)LE5M^#dz$zs+Tm#uH@d)D+li5eCP(q?3wI5 z%L07Vv5$=9Rx@ZhAb<#42L<6n4}Cms-FdhAG!yi@cI8aEeC}8}{`QY8=*;+eox1|z zeSKnp2rO>iqX4-vpX_POf2htmvy*W))eol_j}rXW#<{uA3h=~d$cR4ii@zsP9RiI! z`@N4om45upm*vAD3I=d|_FI2!=cFsp_5zEYw!T!;c7{;27b*d}D{F^MF?DM+V(G7#lN$bvWgw!qd%6k#w2e&*uxlk_uNdslH`QV3>Nd8zQ?td!u+td+Jb=Xt zT(vv3HRI5GDBhdjHfgBMiBfjQYIMrzOOBuyV39*EOWDuQDq4%fM>HrlrGd_fJh(ZM zD2FMR#`t7M-WOQ2*GoKn6UbEdy%MSEHBik+Sr`ZoH#XDo7>D?_bo1H;fkkcyDk)+L zL}Y2$OwTtObn_x&Q#yMX04P{QsLA%3k%pJQM(rFha5z-Rs&h!IwyD2A&CJ|X|H2Ru zz{m-30RX)XiF(0#oOp0}+>5?Ve1;4o;8697^VBiYK4U?V{gC8WW=sZ`=Q5!o=77jt zj6>zzmh07>n0$Cy2Dbf0`wi9)YI~Now5Y57obSzb2E_%;iLhdKf%l2YG<)-!KyuBA zF8dI5i*%WVwXtf}&@>{TD{iWM7#H<`-rRWejssG=48e^u(ipW&K}pL?UHid;`EhTZ zYtrA7Gw^=6wbgkx9$=+NaQ*ESbu1G+eZLyW=vR9S0vuX1nosHmq03s+@5nk^P@#z6 zx;GcjLJ4lo$uI$|lG>@}J7g(w@(@xQ8k4f=o`dg`2+En`uS?wzhkbJWX6+4x4>;_0 zAAFzab?hyIKI}d22cSaT%p*^JMj&bHj=R&;^iF|Y(PdF7_N+OzCVV&Z`SP=0PG^t* zB(GgtPeCQKXDtDmKxJdywXVO`1y^LC#9FApU-@>6lzN}rLh9aH{#b@wtw{15%0l6) z$>GGA+Pw2ndi}+3D9g&;g0+BC849Ep=)pdiNCd!&YpSL>^$CO@dhp{CxMAF}ApmT$ z1PHj0mEE*uul@}sOD$iPm(vfw{aLA+8uhwAjf}4oU2JS@U7GS%7G$MyvTzg3 z`fBW~x4_{(P+(oVZdx^$qL7|DCMDWji&xA=IL1wjMRtS00yX6X-k{VfGmfe>fg#m! z(W7%(nLyS%U{_S}`B~L&a&IV26R6{}tdZ#PRt9GBdM{cCh$c9-DXrhQTkF+YMg8<( zvG%>08fGU4Yn%*UfNyF+**7+afSOp_-o`}?2g~rYtnBlqkSbvu{mz*Xs5^QMnSc{C z*T~vPEG(QiZwcXZRPLj0V6o(|*RqVw{gnL&_HrRcRywY7J5~=CnY%}y{LM7I{XqKG zm;aTRInB@G`;=!VOa}s^fCSEYGUqUf1aRG{19wxQ&E=RQ4SI!I&C1Pp^aeYx(Cnu`_qm+530@{UklrW4L$zmk7Os; zOm0@@ly*uM=x>Zy(>G}Z0!m+|>OWh}NV}ipd_Je3S@AY>HYuF(X z3n&{GPZQhc3ZPdku$8kvZuGlRb{fyBWnI={gww9Z@zgvmN`!&>y1ChFY4#?R)g{r~ z)GXc)1RB4Z%&^JP%Yu8vI2N?%7c!(Kx?=|4oI2h^gv>GkC`JyZnH$$7S1(|?Zey-P z#Mp4K;Lt^z41^aLTMl<3)XWpciCP|>11D_F)O4DkospA8%^me*{C#P`nzzRWr>;Ov zuu&1rbc|444N(IPT;p>H)Tz4lvSuuIw|tfxCs#f?2W#+2NQnm-C>W^svMV}WN*MbOSfJGY;9oN9SWb&656qF!p zUabXd0&a;+>bJ-QW=>mP>#8rwLKsyBOwS?V5erc1yCvLYDz9XocJ6yv6jL(cP!kD~ zTsVD1z4Es2yzkixua*|u{WQuIe?XYGeIAtV%syDO0K_(K*efoSamFwf+68pd+P-6)fY8i zWrl|RVop0fN~_*^F)!R3|51lWwEp^)Gg3(AIb+{q$HjQ?ERlg>6Nn<~7xtYtJO>{9 zc-pz|K?%x`nUz3JvX&SKs6cbV;lfenJF$(l&NzSe9XZd|AJxDg%m)LDMxO^P&QKHR zwz?E8Gvm{&}6O{O^$2;bzSUZz@|CTMPI>1m?m44 z^)Qvid5Hk=U9&f?h*g6F$lAGew>riPxes5kNjP^HKF%QR5zjnf?@UqHlr2LnE$DS&`;2Wy z;5lfhrbf%>)B-~5wW5oK7@bE->CLO2yaTDvOHed6 zVt(DwoUn)Rkyyv|0KT_U3rea7)$7QI)D1DG!K2&Ta8sm#tLmyijlYVL&zb|7SUo7m) zxw#u@a>MqtdE0)K3{X#c_S9jWkFNMEwlgS-y7#; zFE`A_zq)oldwXEIYy&tq{(rF8Wq7+8#G)oli>VR0;A+;e9kGfrMV-kKs_x89WOm%W zVQf&=f;&@XsLYAt-%=682^{d6w@_2`iH@jGxgkp@I6q~%Fv_e_11z>i#G<&ipaVu! z4Wq**H{;GT&j@f)M=0?O#4==jN79We7j$sSHUpSNcPSeg2e-Y-+JqPY#sq^${nQ*l zuAlnGwc_W`&E1lt8&Q26Cj@Sc-e*$l9L^XVdJh5ecn`pyO)qCv_eiGE8iEsLLmiTW zaEuGt137`H8q$l-vz(@mXZ^{t6N6E9#Yg*v%|aNCaFWB}D5FD2?c3N`4W=iMYKxWc zVceul>H;(2)KQSnGn9_DIan@A5{-G|ifsmCC9r4@vyy#k{e6Hr6eDpoq4Nj9iZ4-1-Fd1~0aXIXSo z@3BeXf$LGn#G1iDVO_+bVHujLrhf6?UeqA&N+^B-5j{iF!slbRpV2 zKO?)bea{1Fd}5ubqtFDoCK*EN-Ke{`diiuZbNnZ1|9wxUmwxc2G&-@)ga+1b(8T}& zP~`XB_u=%`tKUgG_dk;EefTNew|a20m;JDd`z4t2%Cmo#-hShmTDGtw_}I)`H?kL1 z2DJ%Ps(SC7t#nFXWS|&jYeD2SwXt3uq^ezs(*|RVgL)HFlII6!(}P#^7lc}=4D8&D zDDPzOvCknuCC9)4FxSp?AANmk!{$8_pV)QRBT|c%qF?mmLs9keSpj*RHozi1W^tr` z@RxrmswiV@St+BcV|U3GLv=+76#!b%)XQvjgkr4zhM^u`w?Xt!1B*w~byP~DZ>ozj z;h+bzAv-XBUO=nm`B^W}M`+p5001BWNklN6qUL3UL%)a50$N8;Y0B1&DCnn=%3W?M$kH4S88j%Xc#ecv#>$L+jj^J?sfl2NgO z)oKTe)@C5v1_x|$DKa~#<8rpxo-j)mE0;Z?XR5U+vR;jrF(m6_HcA;%;dB4A2c%TD zT-XH8Gs{ZRchY;#g-_Dc2{hV5hmTNvUs*a4cGwTFcVY9xFck-3<0^T6%iv;Do1u|u ziN1#Njrs{l(+4%OO%^oBLQ1Gh4;!dbe@lXR3v;fnj$$+POatMZtMt)iu4tD-TZF!# z_&ey~yO=LTqp+pV{M8>RIBUVfnDtepGV=RvPV&p2onR6^B=&}9BRFJ&H&)J}R$cfl zBNJkW;FG-i{GW@un}OI80%WN0TB(72QCD)0^-SQ8fDRe|V13p62S2y0C64K6m>{4F zE(!3tz+iu09^-trhTrJ(OW;6#Yc*%E5R%wuWRLM3ANtU*%dh*<_dcINe3^Y~F2c5~ zVHq4R&mP%iwcBt#2mRYXZsiiyv(6+IV3JI4-7kg-6npIcnUk+67;L7Y0<7Gt0>jz2 zHn7M(jo!2Iot7Z+bt@sPVsF-jvfjPVC4Z&{7At|w-W%F&MK7>e4q7%UKZBXYcVW3! z{z$_K>6%43vFtY?D_L9_=28jv#Vi{jZGj#i3$R=L&3=4x#m3s|<$9Bzidd`JnIvSDQeGt=(B{LID<6tg{B^cJSdua=(lU4uur# zhDPKdK(oTp5oJz7A47_+1I{qM*3`bLvkL&ka2d6!PX-(ig@XWPmGQ?};r^gzD1+kd zFvw^MKscCF&q73a7+0cMWE|Be(EB3}05~j@g8{Wddm_UI090Fo*w5Hn7u30tDJs?* z(~L}Pev7_UfP{a@nF>|gVl`@<5j|miaB}K-aEggm2VJ4(l=u#la5qZeqr6R_9_ROtRECe!YHk4hi}fsLG9E%s7blUvnFbQ(>5 zM@=VlN@UXZRI=vT?(o*APq8;$7_%}KCE8GCAaTx^Q{2OzoYp2xK| zHf-J{hn+plI5B4ID*`KI8ClmuLqp1-@#5gVb^S`3-myO&f9pjF4p6rjAPsw#UE<=v zd*!*Wrng@GZp|*%qP2#&YZrAkv}w#+e@ zm?8B{-ZFVT3px%Cd+Q#f*M^gZqVI;Sd(xV9(*gmNJt=_K%BR1*qp+W0OTr=4J$YtP z4w%n1Ad%n;Sw>}@se6M>gXI3~b?Xi1nZ%$y$N44@NXEyhsyb_nT07QZrp~#;owJYL zn=j6|0Fk=iMm<(@k98s%SQehKv#NzWr{i!m)cXC$x17Z{KmtZz=4Jf1725Y%w3hAMB0f?bI02_b! zrN7eNwVG?|IW3=OXe`~J$0{a`+Ac7~`GF5Z2@!tSjcex>{C@C5pH44+@AK)x*&|`}J4<4UY-M>~ zgui30n!IgIQQ}d{-g_-~?BNnHmg|fp13vt=-S=t^R7-y4f-;MirSkxDnZWTb0Cm4D zYJtlVmMVA?$%vrT+g@;=vIu~!){K?Doe^ryhUWS0hUv=n%Gj+2EXKgrBPMrzt3O{K zXl!hYm{|12>W&sXas#EuxZom5(jSnzLpSu2U8W9>C=AZoEJ}w9X=%xU7s_tqYh+Y7 zNa5w1NQ(hNQHG#z4i3p_;1ES*1z?aJodB?kWQWS8N0CcT@*Nnf8d&rLyNW_uJwO~> z!B5XoAJP1xSK*=}cKl9Cq60$~A%mvpKoQ3UgE2aa7|m6Cu7Yl)nngeG%qW@h<2{2T zqiGmW=z;=W^BBI1XR{qZ{72s{)~I?(4ja`p`dAXB zl)y$%f4ui$*qj&#f+qmW0}p&8&EC42j=lLK6Nm7o%mUf-vuR{_Oe&M~kmALD6%A`~ zUUd1rhaO80J^pD|>SG@{tu`+ZJDjQO`^gL6s5|WOo+cxsg`rU%zVUa<6cRA9zK-G0 z$0}4n&eb);!6_rk+V3um&@uikYq@lo_&aK(6Kgl7Bd>j583mk2=x2x=?A-ULL}~z| zI6l}W32V(-%^+F9nVDKFj)TRvy3IHjOof*kp!FMfXx{-`Ijb^QjQtIbc6iJ{p$lz5 zzmuKh{E`y!jHw#4FHnb;f}=U({165K&LQjP;@P(agn19+#50n`MxcW+x^d0ud}QLV z@dWo+o7f2ciYo2R0eMc#EcUq@xtGBI^uT{?!bhUdLqJ9Np2q;n~Us02x zCsK20!XFWw6`ha0?JWoZi)8OP*O1pYks`~Uit4Ojq0{x`#5&`|X^{fyWg~RYE|l3r zWA&IImf8BM-f^{HF@u2CweK~TIRI2LEG~HYBhg6 ztJP~~P*AiLsse7Y)@_We6v#ds+1bj*n5YtgC#cK>b=b$WufU%p)7D2HXEmyyQve8G z?~%v z=!60xnsW!Zd>=uqdmesD{^P69e?6T&{+eMs%2DLI4!V-+vQZ`p)Q(!PJLf>5w8IXg zpC~~iPi6#rtnyu)PT6Q1CB}n#|LV{!ME(3cD*!w`8A{FAP83X3vs$stScG7KYqn{)^cjhhqdjaV%jW(uh42dL<E@ z4dcOh&MR7MZ65@bygt+DnBEB2TSHjQi#h*B;pHuZCidV5va%_Q-Y0S9Mj9SlYe3w4 z2#rikNmUg(@cFYx^e548(H;cem%LXa*_8=7ZgLLhXYH_9K;#Bx)CH>#piXhwY9K`E z7#h|*NXat*qOT)!GOI@NO+#XSm`f6?OI?kC;-IjUtB&KhA%ar${ws}BEx=Pm-zr~y z75n(F87%5vM9bT)76Hc&KPNDsqjb&U^$3c1eP3@zF)m~TJ=JA zKk~_R_QdNF7aHgvN|(+bRR)sUW^50R62Oy;y0TH1&X}!HZRCQe+0ZcoJp`q=#*e=D zC!!0Z3Jq9D{Ue17zWtS!OQQ zm1WsDC!?%DK}gRE<;nN`%YK0>wsyl-6D;Zq7V9)Yi@Y096c9zMW5JZW6})vpHudPe zy^sTr+CR{mmC-j~d-3#JQqg3r02giNfq~72qNdkd=5`Q8YX#LPdZ1YWQ#thBd$9zI zw8n7?TwBo8#e7qzw$f(UAlDUo%D?_{GS%!xQ*Jo`2`k$zU6uo9smwOn5NTJ zW=@OWv2GBn;@;W!1PuX%F{e@_PAToU>*4gFPyUVq+u!`+zf7m4ylg%W>sAz7F>Yp5 zj}Eol{222=Ocx@_?(hnbYeDT$l(lshwRg<`K+~_ReA7;_$ULy`VK!Kx3sq5suVxe+ z`@qNlp+s!3cO_VI<6onfn_uk|PpH8?z+#-268ceTSMh8`2DWyV_?l+!>0E%iHR6HT zinAvV%WtopFU9#&{@l(GuQg_`293Qe0SiAyf4Tv7U&3>b_UtXe)#j4QW2MX7!DpHm z^5<#KEao%CzF=(adKqYnOn+`)-7+9P5M_;mACL8{iBFyyvU&qxHY)XTL}L|IS-zdd z#@4FFgw4%HU~y1CM#MMNOZg0GcZ66lE+tHe$c)hjk`5h&CZJ04{v2Tmuoy+e{R0W% z1VAbWaYQA|k&FyWw@g-5cpQeC`?G@Zer4{U2+<1?z_hTiAP`1TzuHzTEhtkVgM)Fw zF}=Mk6;UE=6jVdO5XBECn@pbQSwRsn`l_f4wAS#p0ysnfJPZhim$BjBQ46Gdy-ntD zQr{o<%v?a@q^6K@ymH~VoFTHhMlW$bIBI7jV+LOP2Gio=tfJCVf*f08EjZS0l2DKJ zdz{nrl5xa<$GD2t8c{O`^->Ab2DK=%8I20?)oT;XSQA_@YLYuyjsU_qM>H|6*UXsM z+?jJ#W<+X+F925yfb7`YD}lvcS;bzTEx%}aS!2Cx|NE2?L1e?8uMm1E-|qpdGOAqv zwFk8_I5W_eO`6wTsLn~f4R4Fm#^J>rS?d}O&VD&~%Qyf~$YtcK+9DfkoM!Kn*%&-K zl;U1I%jnV83?v;42VGH7X;;BDhXBEvAvs$Fo7C>W!BKSxSs>3SE7dF4K^Js(`yQgd zW^)wiA`qgq1|cD<)gd}d?aJhaty+&z8i{UGpTYZg?0YD^@5$fP{tgN*j~W6umT67t z*qhHu!GxH+ky1X z;pfslk9<-#8C!q-+WGY02Y*%T7m&Pb|0C*YM&_S0;M(QWY46=16yQGf&MQ*;J8<8V zqOT!Sf92wtG&ZqT>;~3dupp@O1GEq{c=72kq|?V`klhl3y`w;#+-v zTHge1j0(AwW@oOZp@ES!JT@UaNdSg*6g`gd56~Z2H)TRh>{-?)L2uX=h~)4+e7Ch0 z;u^O^#W(t))$=hv*h2i2N1pim>A}Z;E&cgt|3x~EkQbs+WWCjE*hFgfiL)d~?1S1_N?&V~n&)pRur|GQpVk(> zHtOPw3)TlabTvx-kmgwy%r5+2bJgm-HLJ{{(f?~8uk@*!V6hu`?Dd(|9)ha^i=@Gq z7Nl;;f=5;H=l0bDEH<->aai~X)$z!A0k~jD)Cnl#Ha0GUcI(E~OkJ@^M{%%eVy$0c zjbC3lI+1l^ks?lkV@BPOuEpWt3aNFjv^Oh<4p~Tu-zivR(IX&319)oUFrs8Z*KgdJ zrO!j)fyg<0`kCujGZZvLwO*hh)9ft92TvqJfb!V_<3V`6Hu@k!4a~v)Wj?; zrO`F((#@+El~KgeAj^WaREAaMcR2eaGUjrA0oUWyU=8Q&Ey{os>!#E7%SJ_o-o$r7 ziNYzzz=p&<06<_?#o(6JQGE~%$rp`Mt4tGP?AbxpKo$M%0H9D-jY?|{L5{LvA2`4x z8ze8=j2H(S2N+|g%&r@@`T3ioXfTc#8H`jI=@Jw+BYP`G`r4eWnw2c5M$KKYQe^86 zz#`v*6VBM4Jo<84B$M2r=$3TO%2|ord7m7wl4TZA&$1nZfia_QK@l7fWytD)S%(A- zm`igGP$-S)ULnpEt^loLp3@l!Eu!zGougL2AKk{4J-@M2k z1O*#ArHE}`e>!#SmGr{*{>1HqQ-V6Jse^#ZnaGZ#zqbsK85=>KN5jo;T=-5RsVl8z zKh&8^?8m_eKB`PF%E<(jpru|s_qJ5>08ES<>*?I7H^nsJp0R^F_C2inBI-g9Jn+%9 z|NalBnd_GoY`l5(f@J!m*Cv54J_8jPrj3*Y;^dNmr2R(X*$G(4Q9HU?N6lu!)L zEceyRaWfDxpnHbKN-*uhnIp>l)f63DsBxYO%Z?6!n2g2T+;vy`HX51$rPs%xvbc8L zCb2ippLr__JXB7nSw!|Cb&R<`9M3XK{jmkytTDN@jSBl%vIRmMD;#7PBb&A!P{yco z1U-;r3n`n85S}Xcg{`W%YW+9X9?SM?+=J|ngq9FXS<)GE_S74q=z4yoDh0@wvuvgu zUZj$tlc@2}V3ACzYK*D>H?>h^kG%B4?!ki#;UtC%v;2w* zBsX|i`8?*j1Ww-n(cenn`O3dehhO=&@7c;Rt{*cN&@41qy-y9hn9LK41r_1_2J=BQ6*t)eCx}-%fA5^zC%? zjb}AKmKiR9YMZ_8;%}5$(ER;Q>9ydfYc~Kaok142p93|jC7(;TmlxCYwgYLyrk(P~ zSubZ#y(!@%{0Q?ItbW-_QhdKO0`n0p&U>zSUjR;1{;iasFNAY3&`x9S#6u^9xN`OC88a1JED8gpg#4fhZYezYWL`mI5&SwwKTdLjEoKst6MT>)czgL z0+bIN^zk*5>DEoF`4e@huV0x!`nNHLP*8FLuPU^{QV1oh#3FoppV$P^%Y!Dmc)bx<7CUgwTw$Obi+>*%++Fs~koJX288@;VDpQ?9eZ zVPRiIU7@E>Y`7&XY-JZ)b{>*rd+o|O3Ebp9u}-K_mcWm<-`$xN~uty9TjFyY%kIDfLzre=U_FxVy zIarKZ_BPwx(_VL}Yvg`%iv#yf`1%qo+PN6QMhnqMY?o^7cSt<_{J1XscdVzQ>Fi5)2_|(L?eTBwVHQ z$P~F@D-dW!{0hG;DEauI5ggI{-@dKA#ET66AT(cu^t{!RN`_Lu6pPt+?;L(szLl|A ztUqW36e|(1peeVrM#{BX{ylsiDTGrKPvBpVyOi#K>{DX2Jpb*_$xcRww&|~SjOR*V zQTxq6R@Bi3O;?sD%E_WMsFArOU2;LwsRro?Zpbb`$mfz_(*Rt{=~=vB=WR@V=Ztr}^k zD6a?>Yb1@Pvv(&>%BpwEyMJTlKic1#&Q{G(DFQekbu}qmx#8~k_6CY?IxsX%w%$=V zo7Bqz;7sm5qD-v@J{+IM0UVJ@L~i1`Iz(N(0+9j!%_IUI5L&^xrU;k_FOgK#^o)vX zDsiO~gsZC}V9$1i5h(8wAT~NSp<-vi2@!6xhg^pUGWTMVzX4#qzQHrC<>oLzWABeB z6^k3^2d+8?D70OSx_J4cYZM*iz`%e5d~e>gzD)4!aiTHeIAb)W=GsJ~E?+t&Fu->p zD1hPNIyefbYYhz%wYQ8_fNZOqLAjOMpHa;hz?egT7x$<}*`o+J%<3SM0FMK146QXJ zM{Uh1w$b}1it}A2xy;;@YmCS~fCZY2>M10qK+wU0X;Bxaj3xp>^mbdEttckN`e{3e z+tyyp&x!{4-EPG@0gG}fO_XBS!AF%vK6mPkDr->CW^<&khusN7X+R#3Xf+;CzqQF} zGJgZLMdsdmLCFqyfI#(jG9H$NwCHXe+~xsW2ErY^Qnghd^Q^Nsch_M&gleU!b&B@v zHP1STWjhcniNIB~%LujF&L+)uUpMD23&Lsli8K7_{jd1WBD-PdsZn9++lNY~TFuPQ zN|c0pI1YB4erizJJpce807*naR47=~H4;&uAvoprn+UFqj9ZN|0y=NK`n?Pm12mR* z*PcPCQ%hG9(CD~M+Zt(POlqUlC78(Ylpr@^{W0n|pWAldr;Iqv2g`DV=#SOosrD`R zk~C%HyAFLwR8<@@>IBK4D9Y`0V%99|lu7DKY56laBpNDU(fYladLtAr3B;_M)_UbE zfZ9rSK4;#lL#y`4+}oyY`$b`eHFVy=VyPtQ2WfVM_3!MM*?K8k!PM7gfW?utWyjsh zT975Wc;@X2EY|jSS>ui4x?9gi?IO=a7D*16XBL~QT4;5nEKl`~#O#N3~0)@%D*l>HVvMQ|$h^5w{Q`93#? z-Bg~l0=XP!3!(=_UUgwnhwtZp#KOW!1jN4lNB?u8pRzqg?&*{3WjpPd z(JE=gPOTasaD03+UAcHte`hU_t&erPe0w3CKKc`_E85v$tInT#OP2-o@Hv=K%9LF> zmu}v?tiTHADE}saV2mO=?=POEjg9womV)YS)!MS|@P8I&XVj($J5Epsn+NNTU^l>q zJtUDKDKJ|dowcYbf?dr;8wY*k=W*s}Z2Je&*xC)U$ADbE8@~Vs+r5weQaW|?<@EOJ z&+4q>y%s1!cfx$M5CX$)NT-3mpE?GX(%72yVn4thAz1q1U-~c8zI&fc-}u7+A$!KN z6F`!Jzn9kJ8pg;xH*i5WkQfwLYCrMmW)XaH1{}ZRd7k*i-%CGv;V;s0#DWTTQMVvN zH~*$Gc~#cm9P-flF!8!faaWd|46>i`uAvcUBCI~djy7-KpC;CAl<#oi^xNs$l`}zF zcV?R<7bKt*wfx1oWATKlwMry=B5PYF03t{e*Q?v!%8Hqgk5lz?FXp0GV>V01V9WQ= zT#E(Z4zL(hb=_a98mir$U8)OWul=t1rGHER?x;I#2xQcpV{cDDhKX97cMBGyKpH^7 zMucV*^@}!))ueU>jm3CJ-H#fR&d-Xozh-KSYDtJ3VHBaKQQwENiJ?M3hsZ8ji~eQA zXy&rwpHU91aj&Au{Z>>A=m|PX^S*dL8-wT_#{N1|%h_qFM0M&LG8Um_Wa66UjC-V# zs0%eE)Z{V#649~7wm~V?p|`kT^)1&f8enq)9Visc6&VeT7+DOQejFu?9n@5ufr&K$ zL;&=h4kmu5K95jVp?WFfIIc)rM6TFCIC=ofFwh)a07-q%BH782v@kz!(HmDvV-ASo zQP&0#FnN4La-a`Vt1#luW7OD`<7W{mz-FnW8eYHR38GCF3a0+|Zs44TfC_SBYJH<$K|4pz+whH?b6lla+w(Pnmjjvgsg*#%biLz5~ zcJAbx+I#WcO+eRcKHKc(YJg>a*0x|=44DUeBIr{rv^ZAvC(|J1JTDi>WJGUiLv0+v z0OmUOtg^)}tzTuSy&eVyTLick<|S@Jc9B*U*boGS_-u%BU>5*MIK4RF+ziq7)5l)% zUS?z)hGicCRRk@YV6k*OI?rnaIEa)((cGY5kh)x1AS5$M%-@yt7Exz8QB;=|e_TC?V8*7s~Z z3t9WluuHkId%fRcZkyr0h}pQHe7Z7lQNyKj2zv23g_AXwGmi1aHL$3#g^Agvl zA@d%+WC=2wAF*V;k7#~jqYQfwG8Ud)G zvWoWI`$Rf;|3}idzWlGmB#4$9ZQoHX#Uh~6*o^sni5lOc-yuV8b)S~#FlAy3h}gd^ z(Go&|H?LhvQ`0-rrp)1uCHDYXj#~Mk<>? zuj6t7gS<`xXm%RNZrPWPsAdaTY;!)k36iXO%l8U0H80}yDI$(L_B@czoOn%iA7ycz z+S5ERx@Vg#f{laCI%W-6jfeGni#ZRVU^N&f!yZ)On4h4u+U-_s1!YrI?_sTAIHYl4 zh(t?471d&QSdm#L6C5pV>^T~CrWRc;AdK6du8OYtt|~=TT|XRn+oZ+a7we`(N_vmc zn)K(upb4LB+>tY`h;$HuA=}UUtbGNxVpQ2J`+UEC&ptF^C;#p^xVjzYksWb$$6!0G z#vv%zMQu$45D!rUA7jHYJ`TPYbZ`pzn-Z?gKj4MN@AjY75u2k{D(G3QHOjcAkRA6R zVGCtj&9MR?MvV%e-*?}K)4h*8CHg#T1%^e?519snm}GQOLk%_wl-|=vU&+q5BK0L$ z?CYyCi_V(p7!w~w2L%Cy(B6iI%t>Ef zHv2~tdO7Z+qVrLAj^hq64n@=a1qE2NpZT?+=TA;6kOYh40&O=`W?{4|9}EEi%i`Ql zOAFR^BlfMC5M#5D1tuHR@NeTXE1I`vKsxWY6+dY$XwKy9Vzn1*HoCmA5=6MltF;L5 z+LXMEW2~GeS_FscjwpREovx;Ut*Ogq0O57o*0?=rZ6+*N?z8Z5Y%AeUjB1Utu7B|} z|6J?-ufF&%1>6X14-6aQ$AoG^sK{r}pEpzIQlGM2l)uc+q2tx>9*Z3xg5z_P6YC)}iN~}Qs)P5WpGfE<&f3yf|>G>E-B{Sd3m6~I_?9U-(HaBlQ zkVYof${v#~J$L#o0qH{zeq0L1>?<nwMJ_&g7aQG%zg7Y?oTzLoLj@A z+Vj+Ae()3jB<(r$So-!?em|Xf`^T|;RGW=&Tee6G;L%+6IY5;eIk2_Jg02&gW(_Er z;bJnZXKVo)0t6YZoIjCX{^3_5I#LBxeVuea_j_!>av$aFqV>J3&I7Y;0T8X8(^}E+ zA9Fdq{eb3x5(LVp&YyZS3*QC6#IFpn7)ctQRXu0FSqah8>t zLGxMMhjCEcRCo=HVhIuRy_;ZBqgOi@tITMWA^x2Mi^dWl-3@#CJXhZ#vaD<0SLxw9{W znVoOTmWjTCW0KYLyoS@&%>YTU*vZ~S6KFDkrUXgv!=bb=2Phm>1`lTzGtDLl+80Jg z6jjt&0c=o5=VoLO#kuz$M{*iyF*1KEjgPNO*RGtG^FS0IBS5VcpXacNC=-r|DY1@P zeYxw|Hc3*ZxPP4k>wk&kjVSy)E06zp{LmSeLb|el#aB zFqx$TGI*|o#Yh#IVYhlJ1v&tSgTu-;bNQej6R#IN&}pTtp)8GUo>q<$Hl2j7!`3zj zg$=P*<>u$gw)vlJV9|ab;LU+=BU2Q#b!_3}`Ylqql%T@myjlQIyJIz1aj05P*T@LL z0MP!=wyC_U&Zn&EoGh!N?|1L3bPCG9XB*cN%?|rsu9KXN%)u`Dz)x*z8Eu z_?SYh1(Bk!tLD>t*b4kfM1oo@Z|R`^nKFzjbkyEgVctv0BSd}z*@Hia#uECe){>$3 z^w0-?CEcQJ(Zaj}aR3+ku;Tc?`rOw9VkbB3kkHD>W3PCS+yVopu#S!fNr<5|y?wvd zAoZDchMBkzy#s&!_x`7J;>Zi>h41}ox_t43kJ)WgB=#0fnlkx#1>-5s9SO1zGmXPs#|I7L2uCd$cy*wLomO z-fE1=VxRGBCVFG4$JTq8(yOF84oKxSYl^K$D-p_Vapd**(N1vQ#r(X*l+@G+_@XSJOzz3fB$PJ7MQWB7=Fx4@!H2{U;_ z@v@`PSj=|VdM#2j67SJ6CY}rtKtYkrWqJ#aD~*2riWNCqPsA}ry^J4TS3T`;*0ZBm z0fq`N8u%eI#wKQgAsj)wlG>r&vP%NA=}%f{I9*c?u`+qy3$nR!dh9p@+b-o#pC}@T zw2z=(E~371fCN~~>2`Z6oMjBLl*OpAM7#ko2H1w)rM^@|U52bU*lWu81CXo!j!TOw zEXQ~-{)-fsyVHd+#DFtaY%HRM%JzBFX8ukF(x_o58BQv?6(EHBx_arfoGm~fHJ|YG znOo{UbGF%OG;uhhbP8y|q0=VRFRZv2-oIL=EG=kV*hm<)!B59()RoC-F<^!J-yu@r zpDyRTJjml7n+{017s||5c7967q`aq|R{1^rrDwOMcN~=9#;LboRz%aNe3qSw3|p&n z)d0RcZ#WmW*G&{4Q=)PYM1LO>7y=GnC@w*qe(FFhE5X`bUNo8sFHxW8XH39B?1X@C zHZIvH$9Oi!c%|WMJLtNC#p=7u@v70D+*!2jga>w@-*{^a><@ts#)~yvf<>}H%J#Yn zWfRAi>ubgN@wsY(#c&?YIV|^#@0<+y>MC>1@0Q4zM~Q>UK!Az)WiJvy;%~#l<90@{ zIu^}QUR;_Ji$Djz2M73!6mkK8P7Sy9Re`3UEBVY9$lbFKwE^o(`^hXm`ji5JTvM4a z7b@WXup_d+s5Pq2d@#N8+@GblUwSWDqDa`CeSVLgg+dK62r%l@qq`M#fgct*;gF=CPu4K=IH_CHO3-VfOv@GgS~)xNIk1LJ%tL7N4EtCkvNcLLj2^qjmZ zh5gMt?oR6_H|cDGQcgQ0p4Bpd?dqrIgLojZ+`}2{xvG8c^!1(Ry)w)9y7tp8o2q4Ioe3?|uX$trqAiQZ$8WvXbw-&G`YU@(mg zkEh}B2}O!A6ugLdLFpvhg>wPd8&E?^T6DxlwyzsljJ$>@ac(MfiXBJ^-|kd zZsekVLJgdk)whTU7gSgz(Qi?UI65v+r)Iab8gaTO^d(WhaG;cF?3a3(6!#+2m9>q zS>N*TvZ%7l&(i~K*fQ61J`Nqx&%fc!Vni;fz1nftgX!YwBMAl0d>bo)#T@i0MyyEY zT2DSZ7|QGv>kD>(G9un1lc0#P3M_&;M~_qj8}wUJdkv`51~9DVw#=qg%!S(AHL`fC z-iIZ?>^3L)J#iQ`L~-2j3d*gXiyQEDaGMCe2QK95EiEYsL%kffkY`5u?doM3jN_ko zvNlRvClJuQ*GA@7->0CD*9eu--3I8c9c)=4unGnko52K$xMqk!RqO-omj$nEA6LjiEkB|nb<#oHGu~gzUXM_QZ!m_9>m$1@q;%480^E{2i}(+e*D+uh|JH;N+kCJqXz?Lo)aXrsa=e=T?VNvnaq#imdnZ6_n7j}@d z6hO<*MTaV!CN0UR-&Ll|18hzSW_+MKk{x01ojr9};KS6x`94zxk5|*t4IsoBgiuA$ zikoL%Ei<1lR?xKkXLXPl&B|*~rpk`^8enfQ$7fFbq&1+uqFoRYB3;2d2~Jza&*rRC zd9mgg7wiV3rjcQ@Aaw~AEf`!lvA&-zxWgD5Sd8ZfbX)eqf-!ujbOw|at{_s3Ol0eu z{!v?y$ll{2SHD&;8Ok*s+7V(h<=%SMt2bvz>;nY{qjR+5nOJ-H1?&&>9mrTe{?zYD z>Gcc$@BfglUpZ5>S8B-sHO}+^Z3=ut>6CwGJ{04MuphBZG%wJf;C&X`>{AvFzm@}>3w_ebG+P?RJbl1I)r%R{bNk4h%8wz&udEN_s7N2PA&byVlqxb8v z!_TL_0k5NG-}Eh~JqJD@s`pFJd`Wu@z!q~^f0Q=C7+ZT0{4-y8Ky82Uy$Hx7jEK(x zjhB`|k39Js>CKnFlg=D}HSOH@Xxek|F|}D*J2jnl?0rz*|J--}L*?^zIs0P1YQekE z9*8y_PQPrUElRQ|QxYkX;wFIL1`q_X&H#hi z_qBU^y8BE0{^y+g?t9<+zWy2uwNzR~VP^VU-n;MKbI$*q|M{OPo{mCPk<9VN2lM=fB$DiUVMRP`yi(_v880*aO4 zq>pIKt~oN_jSTLZ4kjhq&~-?A*Y_s z2*iO?7^5&2r63DP#Ti7O83!}2OWbm1+}*fdn{OD@TL3C+JTfw= zIcFGg&4qNzEr6Fq!u87+e0Cx|T}I!qL<1v2CKNm^5uAy#=1#Sx`dkKmWq?u|7e1Sz zy_VUdXUBR@YQQK)NH{oR|58cS&tGt5F~B0uW!L^UYBgRy{6tpS>{nUL_h@Cv{1XOL z!H?5A)Ko9^Q=fA_<5*budSgT9tj+xRn zq9RL6Vu+MKHGAn5K+gKky?1L(Yrw-Ep7vHV*%6>6(+{H!K$(PKDm6xAnFX%1M?~XX zRwTD{Z^m3*C#e42*6^G7}$Z)ogo96`00z2=z$O&AmUg zyuYyF6%D-v77-WOdPL&NzRQyiMWw#Huehf8H@)6928{GWb#t6xLy0aEZ}Hyn@Cgd8 z3-V}D?JHx!@;d-?hpQ4dgh5gOJDq>U(w5|S-fk5MdF{GyYE!bByj~* zL5-CqAjj7~g1K10!zwENpgt28CHg1#FhRwt_TBig9r)JYV5B`AI5UlOay?05_==pDd zS*<`jZn<6S`^aa0Lu1ndfHhr1>{IQ*g8dN6pxnziajB2RDvLQ~62%gLAu?DO@8PV1 z12kW8+g`1y`V~(+?=4wDS+(BYS`T5~*RGdQ%u{T$QB8_yPHaTA-$!^g!Co!|MB;}e zgrDE0|BAoIvsALepG_W_RKykKcdf04+V+InpW2|Wd`(~1%;VXIH%qf&j6z+=gB=eN zEO@lO5GqS#arryhPxV&tkX>K}QwQK7J4g^!Jzx_&2~cMZ+n#Cj2sW-Y2o^?9v_@O= zE3xUVQo(m;N?F5@mRY%GMxwbP2Ib6`55`otsO}lX(`1h)v_1%t0EpnqPa*=da5+s* z&KS3Qbyc&6u3bHsrZ#L5<&*$~fMk(!{>+>xT?DRVgXtZ#p}E)ecY>3#i5V9vxFJAC z&_aMfV8E%!=YZdA=x0vae|3=XVmgKv}I= z{0ihWV}VL#*0xI(t_zcgqnEPF;0Vxjbl`0SHSwFk{@Jzskueq6gZis z4gdfk07*naR9SmF;}O(!TO7;mS3zUz617zpOR(3HIgQ|}=aR?!i_hWeDnN`tl?6@4 z%7a3->`9GPQTR%_UC#Uu4=XE7aG|RF%_Rvdpm5r(Dp^&Zgi!B{eJ}eI_q8TiL_men zG5#!3Jq(JO^&&?_iKNk@Y=Dv`P7jWNr`Pwi?Vp;HEg!(3755&=mk3e-P`BOlF44)< zH{>?v+7%QRHz=@T-Ki?z#Lt~RA_^+|l;0U}vtB*|Ln)@JvUoO~KlP%6zPgR5R~8K{ z62MN*%%-cC&uji+*-ICdIP13!zgidKvetnr*A+pV-M*cP>Deu5=bqaWV;e4?Kb{sB zuBo>&*f?cozb%Loh~#93SQ*Nu^Lx^k9s4ARK{Zv+odjv{X`1UFAMCU5m?g(7K72_2 zl~Z3M`H>T~wF6jrZ+F^3AnZ}G>IRD#6N2R9FFmE_*#-J~9r!`_-WoPK#|}|}^L3T^ z^^sU4*W&qGpQDX|vBcS`i_O_HwWb<2yTFmt{A1|n#*LLU2|PYoa-T(6#=cp zNDwoNR)Ho6ZG1;BzY!Tn;+XlJ2ju7Pd-x-1$DTXWAAjtB6$QE)RpN7Zd)RV)N2j9} zms{WP_H^vUCzYT9Y@9m!w5ophKK#R)3CTI(bBRH0)^NuJX=tljye^TLTkn2Y<3dQX zV-FZ>M%4}xAY!ELx7?l%KmAC$W&b_t{OOl8oAS9QznFF(yjRSyV=q3Tp5|ybFp%Vy zAHO&{A$x*Ij`l#C?IWq^^NXRd%N}{m1kGED&Lg7&fW*lvTr{F`{4XL#ci#8CT8|f> zeN3?l%M~n#vxTZ_b9+?46)sF0SnLQ~-}jD>rsGGSOfNqDSjGG+L2yg8EqY{?Nc9+r z3iHNI+m+-eW@9F8uua%6mOSyk--4;A0+6#Mg5g&dt)fSg=a4JwC8+e|P>Cy==SzDr zkIsnr*w3sp0BkCOj{PuO0P28C)u!F#$L?K&8LN{S2T+aaCl?!O4=~HRTA=i27naW zD@NbumRTPapf$4IQXA7?T!S1v#U>qyq0-%W4WB0#F1*2Sv=!&C_Y{!}}u;6#rm6&%1YYZ}g$d!o7i z#&t$)RN_VbjzQD8m49bVa5m6+jZ$Y-HvXO98qiBHMWzv&iUO1-fa$l-N*duSJgYt5 zmTiZkLRFgS5212!`owdUA@qAHgWeo;6jjA4Q%%)yN*PSfw|dfUE@}+`h*X_LztU_} zGqSbPWC6(AzO(Co8dc%8o~2sFBEGK0c1E_lMu{t!2RWO{MW`RoD3&BD)L)6@z4zi- z1qiC8{ZH9opZnLe4bc~|anlaT#uLo2kLl4NW3B7qeE7|q-6P9hC@Zfs>CoKQRa|eC z3C?IF@Pt2L0cZ>fGfq)$Luqk2Kf@5(smD2GkD-MwJ)dbmU)B~B4&wXD_xXikLpE*O zlQwPM<>Fd1Sv48idiJG>QM{zJ*VvN0OO5&muq5LxmB`dlfJTsLwz5B1q?c&to;&mz zS1z7W007EBHNQk6sY+_rLPf_$-UHN@{BXt2ra#&+J1=nvf)T#MfTH!b30%5F{90zk zsu{zMX zLpz|WLgHW8cFz07E>YR45)f4dlD$hy5PsCeZp`0Gb=Aky;FtSVrFx$ak?oZbrs~DG zg!|w5QB~z0{mgIpJicZk2OIvpwROQ>$@(VAP&%Du}HDYOg zx7bpMJM#G??ny!sM=O!Od?Q`Gc&1{lNKDDrj@aof@BT3{$DVlf-)k&LMIm+`PY>JL zYv0(tm@nFY`-ADjKlMMPFaF7|N;s#YDpxek@PB0mE!6G#9Il^Y1+;b6o*&v{=vOR# zrvXA&J9P$wUR;2^%pfRjXBO?LgdXuVC>1LV32iSeC8cg34V`3hMtQt#@TWo40c6~hS#g-hTl!i znmQzd?WdqR0V+3$9;T*XKiC8-1VW4m;h-XlAj;B(Q&I!O@bG>bqLsB8qN0eB8KBgz z!KCVqGj5eftL}+Lr%K?Y=IjAv)fdV4a9xwrl0ViUV=`vTo(Rx@XJ%H~j38y)y)Oy? z%7KDjVKg@jUbt?mn(P^=u`W?nT|y4a`@D>gCe{g=Ad;=uzz^xCTIX?TnV-H)o#Xn#u~+I*(}i^0r{X=#V~d(0kR`8@C*|CrwOj zNG~7$rip-r+tM*@sqU3vvG`2(hI&;s$^@1GeIll&m$6zSsIFaevwyDmrIJ8!fBgF6 z`Q={da?Wc@AW>H7xzpCtP zwVn}ZZLRYla_IG1F;$HovdvAt|6clM03gRG*ZzB{HDPz)z&=F9|! zLS7$0qqPqzS&yp4T3hwig2ggJ-1S}Mxe9RY8!mcbBUuUkObXbjvyP10s2A_OT3Ebl zbI7vbPXK6UGTOKZ#%oMX8(2g@2C&#Q$FQLLX>DD=jcN&rG(;^35Nq!%H)Z%5?`P{u zG&!{}l8x2c4yBEowk1Xo;2RjKj=)V+tF#7@m|Nq4>9uiaeNQl0orK28qfg5xiKUaZ z3JhtLd(8awu=>{LcN|Qc=B=_D0c?PaD&f@POIxn9?e(=}QR$QYxWULdar8T4-1Pbp zpbo43dc}2KM-yz9 z0K9Fj%J?asR|uulXsy1_pve>a(ND&x6w@QProBMiLXz;@sl&NXzn5KV+Mn>lJR)KT z`uq;u_CVTw>wTL42e_~LB7O1tJQus~)wJW5JJbBGThkMd{C>LiuD9##KKJAo6wg2* zRbTS-CQ+kLz5KL*BZ>1ZJNBpNpZrp~?Tzm;2Gzwg>A7!z(bQx+opk%X@70_|VhyP6 z8@Jq&&YpN7ZQFHF6j06w-$NS#Vr@D?N+=@E*D>HLdtgaF7)X)zg;+e)D=~Y+H6~7NR?Xl&?BGvH|ffiGcM}op5DK! zw9$k43KOfrroQ*X|5-YC*Td=e|J6UzjMhvyE$E!tCzd|MV+o20u+k`I;0vcWZcd$* zRgJ%)qT770o^?@8uQ4XPg(4{3N~n0kOqv!oDtZ*33QBkea8V)DL$eLo5L>f7$L|51 z);k^nLnM5nNEPdw&#NoNt9lvpGJS1cI~wZRo_VcTto!$dgxmTAszV$S%LLER8`Y+@!k*-!3dZLj8Qf8{fu6qy0dg$ z#sW1yDgjF|xVk0#9Gf98P9sq6a&F}+)*MuKfE_O_RhGC$_~$p6Rp?5I2Hr*z0VIZl zijPEYsAN!`6a5nKZB93wI`^#1zbo%iU7G^*F~FXlyj zRo%%A8`IMD>uGe{L~0~PqiO;JcTJdKcGFg$?FOK?{=WdJL7kOcH^7hQqO3d8(l@2h z1}F??CVH!8SOyh%QIhXGBMJQsb&NKEb_hVCk>wWY7Er|K)Y42t(o3UaXq2XCnGutfbDy58vwYKN?Im8Btp_j zo44*xyY}CcPQ3VS^=*XOXhbvFiTLM7udhskSxQqs)eSpEw7I5(fb(8p(SuG?S*=!} zs>)bY+dOq~|3T4HFh+lYUT(cox@xb|1XY@|65=WnYN0o0g-p8jNth}08Em2k+8TJC z(0<=9@bqV(aW|b6_14g*K{ADXLv|am$o?a%J-212RrXg`RF%4V>2w9+3p*CF?E(jF zAiqzbRR)l%`jfyBg=J=4mLn%@qDss& zwF+%8IgA>weoFaxA2)=$sP|IWL^`}02e8CeQ2{m@YDcp3$l^!FxV+ag@Zxh}Vn6|- z%5mxZNd>}9uo$4cWWLD8Gq<+b-2r?hPUdqZwT&fou|w4g5^JZ9J(m`*Uv&DrU!Cvu ze$S-_KE$c!c2`u{+H>o@3Ht6upWi5TV(AaqxP)dEIj)s{P=t5z5mvJG^HNCk_X|+l z*0%liRaHA*j|Xs^sq?3fcF#Pn9Dd31U32Tc(ib#=f!GHzn7jcN`S(2s?@QnNk-wK- zeD1OIxljDxo=^_38SCitWP91&W_%JsssA?;zO|%`+ZKSy%*HKZ2_Z&^#>9p5C#>&s zWK5%f&Yd`HdtiXLs{Y*Ud65*Ba_+Q^9;0Fx0lxNQEcTipz9V731Ghhzp8w95)82z` zRt$wAE`l%g8xz;eZ$BWN1(H3JQybI9Ejw&f%!$M4!FT_dD!6DyAU1|h0TjQ z@TD{9(B1Da!M)M3bmZB`(!o34nqGe4@pSIYVe9jTaY9TxK4m?M!y{sKg;F$NaodiA z>CCAYtYTZHmy1|MU{Ol@!%|b;vUQK#E$d``u%=Z(>~Z-5zQOFj^3Uj0Ol(MRdC!lj zCF!ew_S;Hu#{9pCd231QJ_+5*=T{N!run_;NB-77R&we;{J;NmP58=MZ>(=NGYviQ z8K1zqaP7pZTej{t8;ff6()D!u*fVP5sUCl~nyRsP9H@nv^ZDXNIkgI_QSqy4E7xNn z6CV)j#$MqK5uD7*h#Aq5SdKQOsxlZol(t5QDOsOsNi&ZGvC&&y+^QLu^4+f)4RtLm zH9%!+t&eE_zI33?Ojh1Dl)I7e)i6?nUgu9y3#fwCh>hDak$u)bz=h3~ zvFr~4qcY&mX(vEsT>xEBP}R4n%Gyl@l&lpQCg={l7tm=!FH^4kWfH@hw}g?=XAc_~ zXBHwAR}@95j0}(JwPaprH}6!RADK63o~#*tCQv=;wYh%fqW*hhaY1WLRWC9+7#}J9 zUA?Ga3gb$qi|fJ>0Hl<8>8$9v2;j&3M5=T2Yf%N2$j1$nhVNkLCZ!0+T9}~1P`b%~ zU75~k$4(On2k045WhE61+D|r!>i~;wSzE3F<1aNs?Rf-r#?(Y_2E#J$`p%$9^r*x~ zrfSe?XWy+mAXto^2g}+*_nl6fxwv>ufKfBRn$<%^)9f^>#t zmm(+rFqCL9wM_)UDy7QO(e~OuwzdY$B1o%=U9?qe*J($~m*)U5KYRaf2ON4%5=OFi zhU&+hdOS-5{FT^JmAvr#kdTmzM>wbtg;}b@B(KT@UX8v~e6PkNP0yzJZTr&XhE4Kk zjQpXBP-EQqg|>plJ$LFkqFC4ji;?uRUNmrDK}HuAX8p|sUFWy*Ira0!!}`~NopLt>ust4T)A{w)Ln!z7(I1k;kp!4Lt#AT zJBHdNGZ!^>Bu1^YB!|kRMQOA9ZM9}a#Dv*OuWft#`sMTK)CpUYHGkFwC2M{{?-w)^ zXGO17!~{xibUI2Jzvn~0AdvH^-}z@oPcLTI+MQWU)fJbm6$kn~=2*dfRe3hU-T`>1 ziqCD{CH4`4e3(ttMsq-4?%h7NKK8GI=GBg>X1n&>nNFX4AzeIoLV(y@NST7`!Q`qN z7TNY)`|cKr5@Lt&HtJraK;dQf1-_7a<*ntRv1?@Jr!ccr7xeGa5kM@6}$r!p$L#X)z#XZDNOPOU?u)~X<&sI$ymM*~nHo)-Q*XX0VazCUi-8Yk)HNl-=Q+c&J_oTb>H191L09;p&0bf(Fn0Zk>t^KR8 zWbJQl1B>D%iy3AQg~bB6Kxxx~knD6NK4U7V#Si@uC|f2|$E>-& zH5BiZ00$&F&687yks>Ha(A-4n8Ba?$7X{W3fmvPYSP$QgYs!!T%1kiFL|=k3LY4~} z1OYI>hWS8a6V{(7$$o~)y3kHI9TRsjgTy>O`Vo!txu~E733~NUAw#{$_is?v8L$YD z0?eJ_+*(Z~`3<^hZZ`OP4{wU^GFd%c1X9QNk- zH~ziX#%+SLm=9Jza5-6HLMe7`SyQt9Jkw)`AJ?<$3lI@;0u;=B9-)m;|H2Psr85r4ar798zXQh*o@xN!NKBPs%rEC ziza^2=x=TTi<~p=$wW|`aWaDF)`ZS5vmmk2(7_0BLrv2dDJDc!nZi0S%(jw*iZfO6 zb)_VK`{sB5&2+~b-;*n&*mC;qp?Jbtp_iKx2(&g}!zJ*wawBcpY)Z1&e;qOxeJam& z8(8d>oX*!;>`et>8H7f?*>)T49te(beqww}&p6<_2^JeMky=JpS0vW<#)p0|F_-U4 zfBdWI$*=yA6eo$PJyJ z6fo)uCKYQ3)pTS;@e-_p5B|h|tMl=D|K`8X>iPI4*am0?Sf#J{aU06o07L=P#Em5E zmjI(dTP%{c=61}}M$(KvWBN3qsXqFdUoR30B@McVk7ysuDn!woK>m)m9dxCn`oY^gKXoWt7%DacwVXiWCfK^YU=WzL?`)(I8&R@*Ryt zxM|Ltj3yV`FhJR1MeWD4{uX1kXH)qV8w5Z&F=4!I8e<6+sd%XxCP9-KqYBjBWksB*nXXfu#} z!^SNpW;3->ua9|?7|s}2&OLEh)m-mJ)hLof67``v6a%SqP}~5Dwj+83wW>;$!;9NR zEVy>om8xn^*5&Qh`0VBx=y4``ofR1suU*w(ZUGi8b5_j-Yo#O>gK7CpsF0|*oj-L% zYLM!yaJpZ1OgUh0Bz^o|&0u?f8?Oz=72wg_n8CYZS*)tw0E_v(_Tl#OsMl3g5NjSU zYz0Y#$eb!DE@pp0GsGsT-`1`#=zTTUnXAG!S|w=>c-JVfszff4uBq@yyFvuq4~iVt{)jc>*x54=k?3E;^X6 z-cf*Icc4M9i~Vc>(7=1H!slHP)kOnMrkrg4!=6;okQ=_p_ev?8;1N@;ha`ifCh#q? z)IINBl;BOGcw!6LLj*Gy85rKuo>AHxu3R+KJ$EUnguV)B5oq$wExYevQ9+OI&$7qQ z_KPJ~NV4%`_H9L@ieOnp)DX+!%ci(%VQ{c%Jo*zO% zqW4`rD+O+7e^hL^M|=uNLycq-d#0l*QS?p1UXU8{%>^-5xK66;j1*8JG0*M`CD>BX z&a0xuxfMY2=NIu%wcqPtk@HI>6nZXfC#&XGP_=gduP0b6zo>05`lyI~hu)mt_mRJ= zd3}$4?l(mPWlj0P?}cJ&DK-?XII8M+{DlCVbOyZ2V>S)8MV!}q6*kx~8MsT(Yc*}! zdP};d@n$y)n_EwSHTO{2S7v+NY&Faxs?+QTRREV@D{Yj5uYtP_X=&+3TD*3#`mRBq zN#WnQU+g`}YRa)XSFX-pKUbX3P3cW<`*6B);beO18-JQvOjXj<+HRz5>f>q(Z)TBT z2pJ2c0P;-vACaB!`;ot&9{JOMoxb|{k5%J%hK5b8_2l!G2rn1U0%pyYM$Mfc`j3g9 zBAc0kp;ILRWaZpH5@-kpJ@mexN?-rt@1&DQpE9PI?2G%V zuofs2WaF7?{cABz=}Sy-Q<^1yzge+ADvdQYVS5k}QwH#B_Krg%j+x-r7inH9K%m9- z#xgTNYPKrkGrpr_X_YLwR}B`~^kg*HG`UZs?Et+lV9|KE)sM{#3fXZKp7>gNw*UvD z6O-xch11F?4kas<*Lpi@LAwWk;W@*o75(5I-e628&p2GvaMS$N-^F?IsL&F3K$V>rNMx-r}Y z9rQ<$O$3mu8aPI#?xGI0s-93v5!-O!YBLchtUnQMxR1nO8K`FRnKzcM8P#=SMz3S9 z-~<_TO;02TKWMlDxf3XhG7e;;)&tJqg>x^v8l3GZiHktPf>JwTdj;SvU_CTq6<9Z@ zZUyW=T|~lid$(6(nw7=;j@+PZ|B|as@q##~Wwx$Y(AwO6jq|(~Sd6!4dR;GjkU^2r zYWEy`QyLi_OGlo2%o7U^(Q4VsmZRZ8N7+l3DHYl2Q~^mv(e=+71T03yz=KwEdOYt@ zso`31ZNd@iZ*^gv2$CX@jA~T<9QOwFtPcqpn^$TY=#ofmZpPDx>J@(RH82w?yI~hdAQ; zTK};>D@*G6Ofav8<)F$FUnHMM>NNXNGiAK5FDnAoUV&s(8Z%wBxVMI%X-le*F*uzqf-J$(RB} z_U`c)pHRhHy;CFs)bEQj^0d?<5o)845~?0HUVXv5MnRO(y)|of;fj0-?F;zE7_&oy z6ZVR+AWVfg)+v|~IRIoqLZB+A09C^Dlwe1rnNGg+lqybtX~1IaLpdb_$Nb-2_kC}= z|Ls4VKKlp1qza4W51i`mql%0LC77vJ zU$@HOz&}NTGMEL?iqo`jW|z%pFj{B-9S^22f9lt4lt$t6EJ0&&h55J$CM%y-qwG7v zq8bTcfA0_f-E`YM?@S;2<^M9BKl5@1zr?f)Hu_xd ztmMgT*1-BjVmekJV$3Sh;60edYonhv(lY@TxqifxHqGx5#aC@tOAG0gl3muGmf!35 zkinurpi%ej8j3h0Z$ke!-=|e?p(Ugu0avvkRQo@Jx$--TK1MsTCRoI%xx9`6TqBX? zdo9OgoN#A#<$dV;Od#{sRu>#@W;6{ZfHkm7%#=?$IZBUanGzF?v{2idQxInWnN`6yvR%BG^ z<;W*6XTj^6$Cq{Fem^l*2XR)uEv5% z4J}p%#T-81kbCC!$}Vfr>r$GUoK4pkE~zKPKC5cjC2*utIX(rrw5((dZ8dc$n*#>D z6SY!X5tP|(S{B_i(p)EpmpMbRu&gsw2iB46nF3s*q&hmDE?qdKdjw#@-`}!zuik$R zg+7UetcV_=V22(u&FHf#(}qpkMNg%th#p5#T30NvFs0T>tqc3CtY~pQR9T^C^X6ij z-ncC-Ts^PELR68;HSS9jZP^h$!D8|3S~pT@G<)rr9^Y3pfMo#RJm*b7YGvU@&sX^+ z6~N)lkcHf_=MFXN)87+kr%r8Yxkv|#0n~FP&d-%yX7~BZYhU!8RaLx-E@Gh26n#Z2 z^*~brjaMRY9#wBzMMcbkcVWvEiWRd8*SiP0SHQqxR8w^wzs6)a}9 zLiG&n{ZTcxo{s1fQPRtkLjnyxC)a{|do6+LGFkB=Sz<}8Xj7=KY8O~s%cu1Oi%~uH zr`(pb>0`6YUy(QiEZXRzC8^d5Eau+U#?FY!Ri~o>Xvf|=m5d``r1!KPEc#~@J%f#v z(O;qP&1~2rMOFew%?TbFO`EswQl$?cbN1v5#{O`I0KiMZ&l+G+d!hzl1@YD2rQX@4 z8)<50HtpPVmjpu2oq4Gi=w^DmAsHL}Ffo%xCni)$p{J5$9xM{7koZ7AG&bFUkBy5V zkw6uTwN^#)##Q-z&boS>mTuUrKh1BYYCzCvdIy%2FyE=PptiF0?VmmVT)My<;g;E_ zJz>cpRjs}eM2}yV$wT)ctUve2tT~3ZpMj=G4{{qo3r0Z^FWI;q`#)QMV_0ZaV&sZM z;rL9`Oi=O)pScQfFwKLqYQmmk&FLeP?d*|AYM$F}8)cN%VC+zlX3T|+>_Q2e^JFvk zs0xNo!N5yf#7_ad#mK8TE!jSq-U5O++tYn-|44f2`LCttpZtO)mIH`&jP6^Fd$PUN z?a!*6V|bnOGA?lUV}Iut)47v}(;xok|B~4R{GJ3l)LVLg7XlQyFD2eVREU-kVmIO% zlI4g@VKZS2>@|_ z7Q@;M%n;seJFix7s~8gQ$h*$=s|Sl@U_E=AAKL3#S?mQCi;4um1*5|7U&`({0i2R$ zJI50#RF9Y7Ld*}khHb@lzWfJ|Sm}P2E3td+ceKl2}=9HUwr8`CbYFQei zohon;1p;x1q~>VmZ2{!f-=l_U`UtORga(yPeh2V^)n4%GK0)#s1o7yK|m)!GlJ4k ztK>7er=XeQ#PX61TVH3~GuNidXedNBL0hkl*CRM+1B(&hsAnpuWfsjhHegBjDKc7X z1;Wi>wwbN-AcHCB8`0hSuqTb{d;2Hs3|8R)PXL<|N`*puNAIo0Un;iE}nSf47_WTQC*x|)ErNA^1? z2Hh0Y#%AcX&i=A8t6FA1wSU=%>}ir^VDaQ( zfkPZTl|{~$fkmp0fW>M?U0ijhjd}G!eaL<->jjH(o$=qusOM)n%y40VFI6I^`AAF# z`({-M?oA?Fv0k2;k8Ezb%+k-wU~y*5GG=OVK|#*e9s30&Ny_m(A?6}G z8^TpBU@?wPZT%X6k?*1kq{Ph1O1kC18+FMjKvKPn=a~}_5hplc#0IklR8!)9qirCD zz5^TuBBwWqK?7}<^8-+|>NDqjH7zY%RU80=06#(SytII#x=~pX^XYV~`l2yS1iG#& zd-41U^#s$Cmbpez0VqI4jbQnDfyM5JZgxy<00x|EwzsfpO#*2Cds{*z0$s0OSQXNe zJOYsP91e}<-d`y>dLoB7fO*d(M?~ZImX&JH7F2&{l9WPG<<8bVq?JX1$v3 zcdBF(7oi+VOlB(X)*hsvfr^}#AYo7M*nNBY!5{yJ5|?@WkxwW#v83U+5=VeD;x7PP zFrA2jXis82l=$cM!{cdw=K)<8*95?oNY*lmn@x(dPaS_wV2dAo35l5-a_yvGZTt)jaVX2zodZX=T#;K-4 zPw00h?r^hJ)S(Iv`=9z(1QugslsDB10!jgcmK7)tVmOI7RJnmY=ynBIw9KGq|BGi3 znGzj3f^P?6p;QIfzlk`_^qigzh6rbk!JOK#QPl~7@{UO}Gu)oaMLEBVpb&#%LOTn& z0pAq5>{;;n$VlrumTg3eXcG$hSCeKrA$8PQNvIT3ePpi_^w7JhY$wKb>u!Ap*AkyE z6)@4PZYnspz=wd<#Y)Qk_F98Q`iI7*($qAnzBcMaRD{O&m@RPiEq}&~ zV@GsVRvP=NqBDfeuXb%~wyo$dtNFX)jAO|6+49D}gKcMO~Hn>O*^e+}Z(YC(Ue_*K@Ky^2NcxqB*;?VQ#wuFZKjkdc<+^ z^XXAVtfj%uXS(}<#eVB;NXRZA(Z*wcoV9lavk-(+UauoMo?iL?Xmd$_U#}#Zf`-$hZ_a8OueW zZDM*eX?WE7__%*;KDL5bfa;0n?=GXrzGw=^%S#H*Pab&v)STr9JH267!nb8 z-T%GDa9X^Q_8h$5+FX`z2rQ{BW_&VTICnf8FUq}2%43~Uo@C*UzuQ{fknj!dMT`|e64I!JQB06KO2 zSykRq%%&1aPvZQ}gK5L;ykfT7-tbPHO_KF&om0o2R?M|=^R9I9>`RLAU?(s(1e?SN z6pb?*9hYq*IYx{!F+P<}9D7=4CntCdN^8V;^$?|)WnIP?F+0|GICcQw%2}p2e~xNr zrz3hj)&DX9n!#dG(d$*=HnZCl3-jIWGsjK%rtX)@Bu9LPL9PbqYe__hFROiKFR&Or zmN{1U`Lpr&o?x+Qp?ht}^;95UftT%@Y4^Uj>~}rIqAGy;5XhvMs-}WWIO)@KHt%qC zMKmg9rWn>8hNf3@d6C^CXykLq1ks1V5{TBix+1x5fFjv<%fe7`v}RXx(bfMim*Z7e z7F(W=88#QWSnE0U1N9BCSZ=%ki?ytsS7U4jp=ASeCDMcHav5ZJ{U6LBK;@%p+A5R$ zcVw8kh(-;C+5;HUKy-Q+TvUdS2#`p&3mWUp>?X;lLlG8eR5p9X=EsrUW$@}EinK_$ zqoiwB!gUZR0~DEO#t&drIV&}!+qID`rWZDXQvz9W*K^;74Ku`3BlSXX%B9j z6%THK`y-oAmW>AevX`dZfjAIl(CI7nz8)$Kh&?bLsp^MlcYfwYLzKa3fKl<&z6pR_ z(IZMKME!inYl>=TXEkl!wlD46b4PkvPKG{-x~NY+|DGVK1?Gi;R**FmbkFKD!r2&g z7|O6wOzriikZ4u>j*>zO;=FNuV3U@!%N1d$?P)dxA3J)HRrG6)aX%h72|Q8tbw;Jx)dO)@Dvhox!%Ytw&Y2$tO=n(`y~EZKT=P3@ z8~eoi8C@KusQC7De7Z?-?ST(>HVE^s5TcAlB|&t^~B z7^EQur1W9Z8_Nih<~r1ae7jHB3sjR#952`A{c0*(RJ*+B_X){*S8^uMB)Eso1T`4o zND!_O1LK@YOX7shWGw)XR9gu|5lTa$lKw^h9ni3P^QJ`E2#lkGYCyYt&S)GJDk~tNE0@ovuYLYw0&>`D*?w;?=&@5PGooHm zo3p5vm{nSC#?{A*Pe5OS{YAxAbD2Axw0X-d@`;>V5*pYC){|;E3a)^uOBYW`tP!8U zJ@Aa6oI>3^b@XY0MXHPkZht7v%*{&}2{4I|1x(_n=H_=x#ExgCqRUMZ@6d6#iSo*5 zkt>(ar46%NbnlE*gK4A@czMq7YTCB@HYNFAdhV;PR9~@=YDvf*`=2{ z31LIV?LifXRTe*8`?(oIw|z%TqS_Kd*7{M}`2eNi%gX$7?RTYbXaL3x7Tc)0ZRflN zNQNKnU0G}z?g5NT+h$##OKpCs1!(3c1h zV{XC|Re)g+rMol`4cBCY;BJd%lj!}J7gdtOMwW!bPEVT@F^k@jA_VTb(N_uxaN`%CM0v(17MDGb$>aTIUU5iaYP>p?roZCK}f} zGMX{u+0@@0{D;$ttS9f0h>ZbtGbpi_>VZhx9_#x|dYs7!=J>CA8&uJySC$@1M2L*? zS_Z7@TSK82P%%EKvtW+bq_(M!)00!)YZ$HW&08t>MT2-`(Bl4U&Gvfjq*tPvzEt}`yFZz~30K>pxFeH2)5=y(vR(0;8 zUaj$4ss15ZXS}+uSuvFRrQjukh{sSd4+|Ega3Ly#a z3$}uZC0a67HvTLy%}mu9^_K`N4h<Hb_8WAF)2q*19kI?4erFU*1O}7@)!e zsAmQkV3C=30Q*6};@p;9dM|gvaCpFCyJPBeuhI}QiZ8(>^gvhu*i-fi>e^Im*eg^f z2)s>r&dzpM*1WucNZgh|SR){lBDGhK&EAiuElP6CrxP!ITYXRQ6YPWXD>#FIk6ruT zkft}xb??E(_0%Y2W)LmGQgfZ&m+1Z`ddos_oQexUyF~FOP-;gt))LH0u40E}i*G78 zrTqe-JVe+u3gj9|=xauKb$hJ}ruRas_r9o#sv75&kAbR@uLdl(C7t^`KP_7spf)yO z2#=UMrG;fx$%hai!Vgxy4L+|}b2_Sv)xBiLf z+{|!h&nl7Vz%0)Hz-PM8dU8)x!`Xj~n7Q-*_bGAk^y8n^Ufg})jf$O49epNUxqLe9 zJM>`s!Y6+@ojZLvt&pgO3N4C%bw+!|gT{nnRW!-(v+}79rlCxn&c_qkiO^fsadsuL1(>k;j{oB$&>rv{?YW}GmoYt&wRxb zvZLD1{ESa-Fr|6_@6ytuu4#-pzpE<(w3jcQviOj(CNrDTh0{k&EYkN3*ZVy`^z-S! z9dAj${mcJAOoq~qu5H_`H*jidqmrLgV6i2POyj%(gl(Kg_0#&9Yb3eyo;RmgXAcxf z%1k2--&takMlv&EmogDwT%{+R3p?IxPxd*BJ;7pg!!>((8Y|{zvm3Oug1kOXviYku zdwA+rT8mFm4`?F*E@yi|g^?)3%90JfUR_O>FP+i>scnEhV3F6^s0jl#s@|-uq-$5s znHa>-kf3mJ9(Zo*Fs*1zit!nqy7fqZxBq_}`0v5<{(A>LHG&lY18@5zNO7ea`$ z4?AGj-Z#i;(iE?u-VGs@zK*-t;}INi8F7ZW6A}bcTU&vo>GU}Du9jfm?zt8^w}6IP zg(@FSJDa6ljZ<067>3YI2+uI!7o(5-_S~%aS5d$+q>ZuC}Xk zmhYxWVz~GWfj&Kp1o@mdW|h)25?~P;Dw$W#3ex`+1#d1E|-GPUCy($DvH*6cxEXpsRIl`T)Z9g2lFLU+dp$fr#7SW-zc}(>94f0eD~o zKwTrKk{WZ{PXUYx=Cqgvw>r06SOt z9-GyqoCvnwHH`*{H7L(iOXVFfvG>sZ3b4eYREb($mVsTV-HqPH-^u3vlq612lN~0ENiMXgF4d?Od zm9wh8K)YR7xMIn^#cK-iH44PrY;xkV5ooptn7$PK7%*+XuzW^s0ckHVS-iGPsa9ao z{zM{zHMzhzi=v{m)>(?`oAquhTJS&}+hhsh+wOUHde4V`UOUA-FKqE2bzS|#255D`y)A1wUQsQ9O{(A(bU`6ptKrV2E(dh@);H5b5a za_)6wp0p+zjA?&R;6UA-7!RAzYpLLAG|K2$y2@S?t=q?@uLc7EsH zyHy?Bddng8kTZsi&jeV$eE4xGik?3HoLV>lhf=h^azQ=7R3HJ0*a&Fse3zJd(;Jlp z!{2Zgh}S64z#xnB#<}^MKl@MQWB=W+{MSmJMFQQnWqX1-#~(f?76t&6d}ds3-nz#| z%3ZxEQ74izdAvsH&)V$sIunW|6UOY2DJJWqy{|AwAKg@e%62uF8tY1H_BzvCLoXWY zUuCeUb@sj;R(WD-qpFPIyx43p3kq(sDPa}-UwcwrX0ob?VY5dC6banOU|?7{hy+zA zUW(GFz^^G`-UjH_^*C#0AwtjrY(-5eDGpEbec`;DSIL0_d=va}_?thh0|tjIllA<0 zknO;Pj5ED{7=lv0s#$4>j21=-zz>}gM~Gojzg3}rRaP0)k0fvzXT~chE#>!GP#VZl zqY{eu`k$MbsT>Hnp=bu=d0lFbp;=ihSMQZS`}`?I09YACwzPHSgu#ghX~6L)qhvaeKiq8Rr|i%X`9*Vwo`U?YBPn3xns3=`8kU!eR=L`18f`M8b?EOJhJ%E?8=`t zGrYyKU?1WPNEi`NO9I~|xx*;es`V|&l&%#hlv8_NSH6a7RqeWsV#=AYWfh5WxuSF-7iq>0z`eXh=7mz?fcY!Ca`$$F0d0vQ00O}E3q0fj4uZB>U_NV-F4J__STek02vh4Kn=S6dC{TU$Wu|7Iz zao%et^<73sQx!s(;>1ogG^-DeN3{fxtk+Fs`W<2z3reM&*Gi8Kw% zr=oaEu#5-_pqpwkbX!0!RUi_vtPw1TC6rm0msEu$*oV4DB3s%C1lKngl(aPvxgger z##uxkU-=AdF}iGi25@VEMLw&!mc49F3ka{>9=anq1gMe z|E!-G!M(}!*7yEo+JE~)>2rVZOX=jx-$}D`+m)z5_^G63ciE-2A9e&5#Vd<4h%^Q! z(*5uH5rM9+e&J(j-=X`{fji!ozW$}(Q8JKtQi%bQ?H;ql2#MCDQW3xKM`IRYf35Em zps1pUCKwpI3R}&7+PrPAz#Qk5tf8NGsG{`n694fTy#Dq#eNVdk&EKDn zzVJ;`J|0TxjSqb=oj>)G318h<5CA`V_#2w3ZI93BpTwB_zy^aFi>8IfjY%c8ils|| zm#CscssG7e_&?K=U;U%>xljBHJ6DCeXs^eVeG&_?YHIfUKuss{#C2h}NOV;#RRt5K z?)2+l(L~#aSrRrr2UGnFqG{Pi^c~yt*as+6rEBG;ns5o`Org`}$IvHXR4gA4&}J+L zH7oS;?#p8J>c_uOS2>RWy>Jr;zFmH# zz^wWtMWe=v#{8)^z*O{w_E{R852vA493KBX%YG=BfF4C}5YETI;t?AWGj6{FEK=z- zuxJ&d_^GNaR7UMQV;iFiv(}UARb{jX)jz?~4=m=uAfNjJbPfQD;<^W^9(AvUU3c5P z^#sl>$qN4v?Kkxu?%1yc2yGAqWLGYqsR!w8U@;A)OR8pYHQQ8(&duz!PfG5c%oVp5P5=&?-_-P z4Vwk}+UR)Nf7^rVn>zmDxAWK{6qy4QagLy~D{0h8Y190!v}HS#TzX!Me!xB(wHMuQ zt-W3TzPj}xopBN}%)8Vc;hZu{&et}oI!dSGmn2(>oB`< zt3HW!>XqbLGf~-m*u@D8%Y#_b&fT}Cdmj3s^p(&3M!I_OY+4w^cx zxAr(Ureejom-pG(^fK-_aBq6!Lq8qw!Mh$#kAC*w zN{0Y|rZx~~BB-Lqz9?dj++UyfRU}${UiWGz9lGZo=_5b=KczqUoqw91eC(6;gjC~D zw%PCKg$I<=zq)M~{fhHCe`ij-kgi@jT^F}$JLql65i|PLt6M-}t6yt^#WGIubtn_g zp~n%eT(!&V_q@U4k4ov zX6Cl(l{hXaQ#cerp3x_*ak({{SQxw#ED{i_S7K#3P0Vaa<6{`Gi;~N(A^v!OFT=SW zuhQeSZM3%Lnq}h-g%jSsdhslqSYDb{udDvE5==J1BGe7DUmjvR|DB8w4ws%$fFnkV z?3iNE5e!t=HhWuInROz+w){5wIB)Q9~IdBo42C35hP;|do##=pc zWUe*nI$Tm|WeO?rVr^?+F+a104QVr?EryNRmwRr#SI!bOHC3^iLFS-~rVL_Gh1(NF zy^=8Y6(01rIH26C=siOgn0VEY{ut3pM@{5{V4ATko;0BkN4>gITD9I$TMD}x`u2hr z+xi@O*l6vAe65~^)Zb0m#%{@mXh#4JVBNHBj{*l(7O!4R=TE(;WE<2h`rYDp{lFqO z!1P&7!c%~J9VU} zK9t$#`g!GVR1oOPpI)VNRD(l0-xAnCd}PFQ6I=;=W@fWQMNs|*{7{jE)(VY} z_27A_1!3{Jo)s-73)e3xaUk7=8`q>WfIfqigg6PbzsF!`+96)t&)3qw0t8aSihg3;^`kSB8y@~#L^@8>Qv{9Zr_MLGNRH;ckL2<4Cs=*2S2_NWx z_ksj_kp9~PcRnOKDoIDEob!Dj z!{7JQ>4ES0vGjYt_K!s6ZQ9F-i6U8`xYD0ZnP4Q5qJD1Fz^6@Y2QeLJxa&#|l-D~5 zSd4Q}sKm$fjFr#l#tdj(uS9WjN1~op`%Ga|-Ou#mbzxV{Om0y>@W1jT)Qj zYGLBOJMpDiHapu!U;qeO5jf9!*RF$x;@AzEUcJ{v)A92PZ8509qNapoH?DN8jr zI*}HyT}&h6<7t+`^VcqGT~y7Tm@>M9&lZeP1L08ep^f3aUJ(qHC@FvOI~*LDE-?md zP8VPi<6Z$sGs63BCS^(h{YN)8tACDb*LP?)j1Qy$#bJLKwRMyQs)}L`nOV{t6N*dSBtI6u) zjB%i%nYtpYs)Wlo)#n%Lq#eoSTQxk+Ux302cv~W*7if>i)9utk1fi;cMipOy1^q7) z%0U3a=sN%rXsA4Y0yL_+oHOo&KwLEZ;gKwG(^gpwda{BtPYhLVr1zP5#ZI{ZUcD-K ztpH_E$3EzpYOiW4go*(?orY*Y^ghS=hU~Q*` z<~g$wB$aDc&QtVzj?BM&SpgRDZh#~%O4l?ztjfu*y?3P-pZl7|E2uJ3tciidAywz_ zS96qX8iCzUx;M@DoTgl$~lDAe@*=0$TJ(-ncF% zgwfGWz(_RLoFFzvNw%bsm@daRH4=r|hs2r@+Frpafq-qb zGIeI~N50(IH}r*S`1_V!qC;kScCYi>E4FLKlX-tvJBnv<_x65?pk7c(xBMA5? z(X?N{`A7Pzo_B_ zeh`~*_S9h|wk!?|M$S58sA5s5Oupm$e^%o=s4Sw;of$(}CEeIeAy`;~#n=}-Z{m4I z3YlGS@z2L_3Djrvt-k3*e>qzsh6MDMhI$R z&d}DJNCevPUkltg#1ZV}E2v#xkZ=6Ay)xB<-1jl>6v*emv zw=sLCaj2U?9DgT+&03bdo3C9;WE~H`aUSDZNs4(fYOVAk4jlNOIB4O zZ6LD1vF{6Bj3XrgFzQd6&uTaFQPGMVYFE%BVA3ts-<6SeXTm6x-3RVTmoA)2XPDZUViQ%ym%T0fq>tr=BAhQgEGpOCSwRCQ6ByDn8y^+uNU4k~IMh?Z1sWaM3FneH-y9@fnfi;ooCey{a@rfLK>iwbYA!x{d?AoCHg|)5gu) z)!RydhI2+vM&=4qB_QBqj-dp|`hi6yz(&&M`8~?|V@ERul`TLYZwIj?Q%#H+ zbkU1${Y%bHQCoqHr&0xEWLQ+b$*H+CG}IBDZ_Cy_`ZuV`^e}ODZroUK5uR%9SXnX6 zRmGqh7IPS_a^;mp-&1+sudfpTh_M4FUV18BI)B3Vb`M)KG$aZhij=jsg(9wLv+u73 z4YlcG7jIlk#}9w2O3V$KaPAdv7z%AO+I|GA`b3S2q!tVm>yczo{5B=S5k0~7;zOuN zGS_%{$wml~pkROC*AXP)c_U({Y9;&X;u*zU*cX0hL*=bcQtPKgbusJL_pJhYAD6*v zW;gH9`vCsLDkQio5NHB5WgnZxDxOj+la^6ki8+h8R^~;90$g*pNRBZwD?n?P-RM^Y zSOYBLW7%_Wc<=|(cfRrI^zsYeO#5$tFx~y;52R21?*C@uEv20*DY~9Av~$v^Fh$Vs z;Fsq_58?NH^zW;e?}@K`LN;9E-=>TKrg*Hw9vBm21VNpPYSl9Klpu<#B`r470xpj$ z5DYT^K?VE0ANqxK@xqDp_?Lc9+VcU_ECc}v8&0h(Y+Z*TZqXFXf?^mC`MVKN>(~G+#%+!sK!}W4 zC@DfeDHGaH z$lQ;NPMC3^A~-shrl&Wh^JibGW|dVTvIb%U%tU1zh7xDVL*)OwK^- zFj_FiQA&6`1G0^U{E7jXDsUjH$ur|Rsd_9gFQ=KAO=-C%m`rPas3DB+2 zF!nmtSbBJ%O9xP~CAaf}5odo$#Apnfs!6wt8Yux7|LIYsXfxz(;HG+A%lyUWcQl+m zpkvp8d(zm*czXHB6QbR%8!R*pWUu=v9blL{LMl~VOi0NxuGL&az!#Mn1=D17m#(K} zW*pvR8261V@Pbo{-qN}wBlVqa5 zmC7g8ODgHANZq(r#RtVX&kPdJ9ppZ?%hx2cL^+(_Y5WY#EVZ#9kOS@*el4ZFNpnZkbN7z*V|Mq zIlhucc&}*3Hkh4f3&6ntA*wSse~bQ1e8s=xb4JD|tvW5r{Hg%tjfKl;ap9Vh7$ha| zK_oV)SZZ7o_HoI^JK2n4Q@~UV$xP+ZDJj)nK7S%zzkbr*D7lQ^xQp z?N19RG_dH2%lxeC|HfJQ;E(?|Y42?hq~H9%{+^!6?B?xhcxY5iJArTY{aPg%wgCVi zfgARq(a!sW#gc|>l=PLfefRC@-5>lpiS)3a&A!F6E@|}n<2|_`%KF5VDCu*XcIy5S`$31JX>-mk%sP=B1VzZe0^K3{Ot0k1Pw5nB`i3eX*#L4PyL4I0MjN6#&FlHY(FkPX+<- z5(9h{I63vM2wtLz98k%7Ilyden)B6fCyJPF#t05xX{KS_yRG{T9d;^9Mb51WATa^hoK?SQFu<{W0P_YWCrU(IQG2&aDX#36xITYi8b51A#rp7fFx6k zGl1empqwj}RQcf0E7&$8R9<&v(liruZkw))Y$p{Pobxy_83`S+zEBj{D z>6pC;F!b>tig)bK0ZT>IVNTZ8-J&n6vbbrq*3er9V>60`l97u5*5qiP;UDA#~%fZhegd~HK1)GA{JrqsVW zV*Sv~8D4P-&Fjnnbahpg!Oh$EiZY0@H#F38wqQQ9v431Z3~)*2oaYP3Kl#$P)gPq< zf~cJ4AIqPvXHtM;%cG8nwG#dON>mMzbT}aUa_;nt0s~aox!0UbE|WqI5UYE(Gh<5F zE*HwZxE25zSss{a>bvcY4u}aPVHRqq^@n7bv3F;X&G&(XN8>2C0 zKC_nu66~L8Xs*-N{sSG6IeN^oG-eWZXj#l3{tS3jkL2Q2(Ojc1lDJ`M;hM!FLn&Q4 zdpxb6UOR+X;brfkAJU#OdST(G8cE?^YgF#(*zcy0+7V#D?r}{KCsYQzo={lNGf;AN zWF+l7^g!Bs+ndw3zVe5nfZloUdo?5QPk;ZPE8!!XUKxQ#1+hUvttG19h_9xbjF1}} zOS7AIrJwjazo@ZOpZ?wdT}k84N=J!5VsyW#cFPKugao)i2Hf< z&5ezv`yc*Dn%+2{o_*rabQg@~VbqiSj92oADT(Wd%}{!cD&wH`Kd*a{-0cE&*{0i> zH-G7IXR&Uq0RWcviuoO=ea}nu>EzL;l`M@j-;86{^Xz-Rb^r{qCRlt;E~Iw?WF3{o z-e9qrJ%yGsJ-bPnPJ-;x>8uMbc2zD1$dvh_^FXBr=JYT?9~%+SfuV^^No>kc7*l*G zN3oJd#!!gbp>Y^w#iS-#KGeTJuoz)yR1j(ZH-Kj}fJ{Gj2MV18#Wa+*s2ssXj|xaA zreV}MwAXxwk4LXH5gQF}rODkLt@;SPhmW-;gNzc}^xV8=^IS*CR1O-TZ8S#?pvB=$ zuo%@w6XKcQwqF4^jtIv=#u|lG4dh+CDrG%B7vqM3rzd7&a!NrwPKJOai~^1R1Vd!c zZP2`Ze+d@jUZSUl?CFNtE$Q;blLFYbH!P%HOZ=dIZiC42TAk)KKF6KC<_P9_WpT*{ z7!?e$e??UpR#g#WDFr+Q1N_dZkj-j(^Xr@0>xSWrYFAfqUcRnTHEVN9oXHJy+tdEr zA4q3Un=0!1oVDZ$^r_y4hQs4CJZZsOE%}$Ld*u$ez z=Y*}odqc5u>&^q(pIjSzlS&5clp6D>04OE!(`Ty(r%GyMQMH(BTihS-<$rTqcBc1y z=od6AZSflYSf`X^B*6r5L}8oQ1mKF#W1j=OEuj)>j0C{lCdN;9U$EG=*P2f@z+!$( zd{q-HHmcRH+Jp22iv<8K*0nre2A)kVmURlsz0_^Jn?uZt&XCUl98nxa9LBz&+RKOv zT7u|#riF#R=t-$`j#=NS5|>n+t}7{xt++{*>k4C6j;TUrLPn=0x@GK_MN|1!g{{2C z%!jEhTXjzsjb_m>Kj)T|=%{ba;zbuWY4cZw7|EbXVXhH2l&Xj?Ka-w);`3>GW@CEW z`+qvUeE6H`+h6rmEW zWHe20*rJWe^#r$G8Sbcz6cv&z_TbI}5fJE^IQ@&~Po~Z)id3dJ*7Y+$R^T<;Q2s$7 z_!1Q)=(1EjxKFA=T>q*ne?y5X9cpiybGUd-^fBb8Q8^>{1>AAWpeiccv~X2`OJOfU zHVS+UTtpyffe_C)`d65fLzbMNmB7J9l>p3aShzL1S9`$WZt3vdF%n$zJP=?Y0F|=s z$aq4Qnas5)twTe~zR^R)>$o?9Bra4vm`+jU`w2Fnd;nTi4F&Y09OtxL1P%DnXD=^{ zl1oTUj|L8GNy?kd=CU9ngP+3D4Dx)xn~>4OR;==6PLzOdv@piz^vg3-*{s6J_RU1Q zXv% z7q+k~sab6*qnwS6r)@hAO4x+wcIxG4x@g_~z+$eE`}{Lg;WPzQSUsGN<>i$$IXSJ$ zBL0GYN?1Mkf@p&%`;%+mSAewWIch#XUf)bW1z03FedAj`sNv>R+))CZ+OSDO-9>kl zAdB^CL6Ho=1Mna)`U$Z~N+4giDj?5~IEVx<{y~+>RrZ|4Aok3>x)l{` z;-8rFr>a*1lATnPbV8AhF6m+PUX02|p1ZUOs;^ojLh} zu@NGA?Snzqa~6BPwr@hmPFT^LGBDM=D_P&`0(yM^x+;r3fnJ|rv6;nwMPRYl=QsYn z%ouU-ainAwsVG?kua96T9B18GS!GV6F~+CF#W$6&1*2Yi&qi&H{{ny_-;aTjz|72M z1uF*XMx=I0sh=t#V2VHu2MK^9qsn35IJZLwlM1VZXQno$8}wH#(G+Z=2ANVoU@<=F z>Y1y`NUQG?WvlTio4YnTZU9c1!C`?-4kspye~(}b1FnoDV*^}`GgAf>bB*cnl39fE zM@E_o4m~tvClM;(z6h>}&d3hupiXn#0Hupc5>PqifFtU{b#m~zUw|>kjcXyZ$q)2o zTc;WE^jRm?MPMtcK{bhP`qW0X?qsH8X5m^Do9`xA=5v;eCgOrJE=Mm)MsbE} z!CGm6TM{HyMY~_qdqzD4Xf1k1+rVO>7${8u03ZNKL_t){vkb>ns~Q;9W$TWEqN5&r z@mr=;R{+2@jkUj)eZig*Z9NT(HUlWq8Vx0*l0r46mrp&LtD1Qh!ZwDzyfWVWQvZ%- zsNV)`%mEjS373R7u^g+)iC!ABF98??E&(<=MwyCia&;*spSG%*uDL$>kqu{>B1tH~ zB7hKT66cpHjLqd5QE~1Hc76rSEU@STi#=$6{-J|j`nsseaZP1# zZ=y>uQzm7{#>VK?p44*?s7DM)&lrVQ`m6{ztb!{Vw+lR&P>fYNY+WMRSS8)GE+NF= zilb58s^{=4>ymxw(2)9zHY3C^JZjJA)Dibp#d0;yhpIgjQ)$O7cSwZ7hSxu*L}D2X zwt~g{9Br^Sm3Q9HJwR_GxkvR#eQu-lFHR`oz!IE2`MfF?<(%Dol})Ab#?x-AHuM6E zyp?`ThH4`kLPAm1t%+$dMG$M*LS=jlYQI};jD&`h+luo%0UY>G(IRi&NY|Dc=!EJ)V?`m@77E+JPvfexEeX9|8&CUhzZn0RbITg!$-}X1s*S`4ibo|99(&nxE z(mOx!GwJB_Ur*0J^`&YoRQdjrA!OF1sBBjN*1tM4=V%)`boV>b%!c{&j(Z;`s(LDmX198mE6P18Ow=%s z-@5#{kMChGkcf(Qp(cggbOIPDv0{qNW0N}f#Cw25_71Te@$D`9?)Le@BVt2nfLhZW*UrDVxXZy;Ay+5|x`Eg7MbOQbeU9X;_XYYu zZ10C*J`8;O5Png1AGvfn^UA=rp03A~Zcbx1Z)k=C`>6hZY^i+m2 zCyI<@(ru2`h@3d1K`?e44vZiFt{GBSF6dgUuk5-$msUO~88}TY*8r#miyC4(Je=uu z%5XXz5kre(2UuFbU~Zz7x8#rhy9yS$67@rk=D^*yIW!?{Ywu~a>R8#!nGJ1Gd0*H0 zj~Dw{QFYk^p8)q|hC9xmz0K9}TEJqsVUhuRZ@o{+gHy+!EoLSTN(5pbZ&KwrGR+Fm zSC$2M1pWoWRz?4e>sqTaXNd&@yeRm2A5~tw($Q1`Cq^ly0&W0bbRbu2i;BFm;-SDA zvp#zm^=>QQy)FS#dsU#g9x8_fOa$3v^66P5h~;-wv!IZ1y#&;NMP5?^jG(FkHUoIK zfswpjUURTmfz)6|#CMg~X$dP2dIi{!c%LyF=AvCO!%o#@uT(@LDFmas_O$zzUT3EQ z)g4t&=+S1)2w+HN+2`lgDR)u!SpgP#CfLDv4sG8V_bgTH$!XE|v9CP0)5o53h3e{^ z{lFquhJT%yn$`S7gjuKt5vY@#qgRcfoO!zlCGnjk8$#4XRr$C(2a3JE&$f9>@KVg% z&98A2ymi;1v}N0#bmZwrU5ztamu%~(fQ(H}D=^%B;7#&B^r&mb+V=hF>Q(w2uj)L8 zY`!W?t2gBnXlam2v@0BwY-L8H*$*nkQOWYqzBq>V?0sghdkvm9l?_G%smek!BDVqz zZri$^eQoWA()iT0d?3CIIwWV4;8|5}?QJUFH#O=e`kXVXM*YoPu(i8bg~RCfmOJw# zPyrIl%4FTvH(F7A&4Lyva6h+I)M2qFygdS+MxPt|48L!5)*b4LBpJXn#CL0^r2f1i z)8DBm^Xvp3uU%Ao5%!C<9vvG?XHOqhg_7q$Y(Xp4!onrZ_@scqUY9SU&(FtkH47ji z-d9V8xi1CO-21iUniwpCIrUeTd}k<2kYhrgS|BSS*tqtO>Ca*Kyz5Ka#fZI+Q;1 z`~O@Zo3qO(E_^P&`~2x6ik)(TA^cd`qq&CdEbTac=q=y#AE(3L`SbL`(~mkcqrm|5 zGZ2+aRkoQoO&shAy@l&n((LSf+P>$uG&8$Z`|ZTh??^$uD+U+@pcP_pY;-WG+&Lvc^Z@$OMn^>DM4CG? zfhIO#y@X`v=ts0c;1ykzAcRa>%&CM%!0RquJgHF|R+%BAnj|hG^-wpwI8)XX!>yt2 z%#_PB9HEPv_zaaqQ55F3i`Oo${m5wAh>ERO6xH*fF&$^*JosLW57})EmK~dr!G{VP zlmgaZnTqMM(MM3+0zhE|$Vl410}Myh%*?fuk&FrenN88DplCQvRegPOs5YlCR8ox% zXyXTR)va0iHcz?cvwf{zAS$XqkN8%eM+81NQYqP@C`WcxKHr+%vs15C_H1@z*FCIZ zIAx#%;Ap=QkQXCMO2^QwHa3Dp)|P#~`{2E*_`LM|H>@{xK<5%`YwJ?=D`+1VSytjs=M9F(pI*t>vC+t2C^ciR8xECXUzMvs}|DTpeH5qKQ@*K8XqH=ZrBJ0=$28uNG9f(S?~BjU@`c6$ljhs_;3u76+g0+FNN}`E-qk2Wp9sWi%NFOT# zLq>FQMfO&O3_oHN^C8(``qo0c%|wD+yrltt%Q3mK<#n z&MPaXYXLI1N4MVnj`WfL5W zO$N#P1-UNky|REACyfCIn3MU#SrgDu4a9IkKjky%QHXI6R4jO{0)0U3^0E}y_#QQ- zfG{gea@_X&Dj`r&Yb4D*1SqDrh(0Dpbl4h8fTUxF zF#@%&%6CLwgP+e=^~(5uje3Z_I#K8BJOG&43s7?nfE&FgD!;J?79aEfqaxh9ccCqC z;X0~$O(uii^QQ@hTEHUL0o7&Ou0!eAk;f%mF*sPPgQk)S7EU-*i&{Wfoc5mI=fQOD zD^&7{^>PV%0TTm+vP(IeZ*&_^W!|3sp`@ObroToLD>wuVWy#9@IE7jC`w<0F z5(e9_Npv|tj$Nbyg&3<50llrkke&}<(Gp#k()rUb$@YZ}YReKg!Q#Tzi|WgP3YMvo zp7@IU?*fp8P0*FNXb;y3<&z%*Y=G7L&VvFc2#{ef8G8g>Fkf4b%A(mHeNlHWQwwcX z`;Ga(W0PtBp$F7{!ib%=KrgDv{C6t@xVP=oHA7w9x%cjL`q;DS_>pg!uYm?Gs&~@s z7|DU)%9#_-%dZe8;Hy{z5}G6)qwf*l6ry4D@aG}+_)92}Fc~`5x5{e?>{VIh8LqAh zumFA|u(mVRqMJ~j{U%s!*bUAAcf&Kt32<9x^T|#Hl}Ho5Sz|0*Jzf;%nH)fe9V6Dz z`BggzRY_y4STZ%Lk#>=#UorNo`6Tl%mdF9L%+2pf*DjyQ^!A$VYpNC(43O1j5^OF` zL`_ghAgKICi-$UG6~|ez$7biYE4cxn1Y{BGkmLZ|k^BI#l6b&Y6Ynfsy__yxIF=UG zGkHP4k-k@+3!^spcYdf&PtMEzdAgW5c8v=2&lEz09OE2Vy94WcN-Y}c&t51`z_n|Yg7cWmsS75 zp4Cd@4R2#H)1f!KBOQ9fJJT2c=>Jhgj=is*MNjsVFyd?|kzInt{AopX#jz4+``b22bKvS|ZLA4P0r{j8Q4L=bC!`$6w-JSR$c6}vQUd5!BU zV~hVEELNVczKUyRy4Q+odi=hu2Kq~?fVkSoY z-3@jKXG8`*vgsH$j3x(*%&7w1m8CQ_HJg?Jgq>lhc`nIF(ci>pkzFOr$29`_aFQG( zjIlWLs!pafMxP^N8*VPCvdjDQ+7+YDLT?3TK-p3cktDR8f=Ulzr;}zk?NCM(o;lAG z=PNqd=%||2O(?{&?h?4^bQC1Tz-f)zXat3w4wQ}!X<}+deVt^Ws6MdPJO?>*^;r(7 zk}b-bS1w8;4tq$Rg$o?whM-^aXOhDa~7`-wYdpc)tLq^_$wo01X zkWqlk>f%hnlN+`wh>PiDnr?OeYByA#rIxc^tz}2msy&Aukm$H?i7&TQZpKoZ1iE506Z4n34#rh9QA<6660q+R?F!-xJ-|tdQ|Dbf1c8_7Sdt6E5`A6@P zmc)3|`T(gnJLqQr!YWYTG>MwwA&oVOK2Y1MfN~N!1hK9V>w&mf0!}B33P%*r+Sa@l zcyuK;teRqHy$G@zzD86%CC*HtZ+dE0^XbT7!-gTqyLkS%b{qF6HRw>3RxoV=H};2q zzyON`u2B6|N${V3U~$LpJ9PGW-&w$-EB@JAi=;|a8$%wy`tV$JVy^?zG(usLKFjc5tz+yqGvm?*|vdJ#v9+yos_QBxk}vHZpX?#<8I&r$8ZYkM_%W~(G%-B0=XEcdNMUxsy7Mki2&Hc&n^GOYi?k}z90Y)l+y zX(3{w>%D1Xm_#R462O&9-R>Y9rX()&Jcp718x>HJA9;9sQw*<2-{<6=+f#wmuopfL z*S(b|7HyP}?1=z_i88W>h%ZRoK+%@6|Ax&-u->A@PNceLzRyV!CwU zR2mr_Nn5rb(DOyuiFkp%MIwbhTHeburXq_EJMzp|YU3-MOPPxS(dtrxj(X3c;+e4t zT^~gfv@48KY_ls#Y^$Zp$G_zx>{Mfmi;RX!PbGtzGO zuA2>|vTD^=YzJr8?CF>&$JoU|7%$aDSAWV3y|vWj+urvqFTA+f zHn3;`v1Rk+@&F*7MaxG_G^EM_nJu;7LT>~ta=5Nuq0#q(Db=+|^1hzWbdb+B3W6Iw z9||t8OrIVD!O8G>pJLFaIJ~?MXBcA=g65Db8@YgCgUB&NI7?`tqRy;%=FT0xoL8qK z13S54PQ8*;A>**;_u7JwXL^e0qaEOS7G*Lgt=29~@g& zNLE)xr6sUhUS1U43&%#r8Apj@12C#D^4f*8yyVqcH^B9(cHfYFkViiFYl^ByeeXIg z5rGDYIZb$FU^3=5&%X^3g-~?q6ogaZe$%`kzjQ9t@kVY ze)RA+Ela*u<;(+dLZk|OgHNlmcv(r zeH&OVxT|fpE=!k}zBGhn+Sm|suGll^ zKo9dYTMTzE$Xr$B&@Z6@@*)_ogWx(9g@DR6>z(5FM(@K8 z**c)o8)}^;faNn{RwA|$KXv}BfyHibjHLz)DAErfNh#s}}^csowv80j;>2B+Wvh3IqC`m)B}x=~ z?-lG7jd;KRxAs0~pId+n7DssxiA)l>xc8KO)?VNGzV$8E2_VG`S8N6_`AM?xL_^wb z38!-8l$qvHup(_a9}AXc*08N*y~-^9bO&S@AlNI?5ErX7<@LYxx5}hN7{G zm#|(QZ1!&$thFx?=8M>wD3=t{e4I<9=XPGnR}xDLFjmoQSzBxNTXOcr*s8jZ#)wgX z5|C0Xs*nPTpV24DYwPNf%i7#ho+tHi`ZY_=M4vZv3vnbp+_FP1-pKeddtn^W`W3Ib zLzt*wtkltJMr!KcG~*RcLB(v1sG*IYNId)N`kKMV1h7 zegJ-$;Ji&Gat}+Ak?sIPZV>B+S+xA8+zlE&UNh!)Y+i2bsJpLdgUNeY3>N+0t&brF zi&kL`Nv(`%{8~;OKh1=J!c<@o6<-R0)Vz%`N_u>+S&&8=OI7&f?EMQUG@0RBx$Zt=K41cb>k+_apNz#MxY!wN&t$kpI42L zhz}n#UCI5RYHXQ%QniWn$$EPm2b0!xNUz=}S~eY`3oQCej}oB>38Wf2$4%=2N-3$Lb-+^4?5 z9X+@^uLv0mD50ooz0T&=%6VA7pt)DbD#tLuYI%f0jE`ilK*MCw4qIX_-$k#)S zjqcYpR1W!&0QM~U=QymrNQKd33Y-(qAa?Hm+}E`3fAY`&MXg4;s=-1r&{SbavCV`E zW}i_egNBZmqL9&RNKko}y4^KSQi_tX-TSfqk*@f$6Tz+l} z$&8XW?{1j9jb|3)DzU1%U1zi@FeByw{U0X|CqXGsf^?4e?R@-t2$BSV#JaqyM%B$w z`P1A)Y4*($I`rrSiGgG>7&-Xy8+woog(}GRYiPF3vlGq!k*q6h<|I6S;WwKAG6{Gb z8z6&++E@ac(+Du+-c(lANwQ(Al}USOy5~VA38i99|ESndUn~%4DX&ye!!W@TM4z0K zROwu^iYh*n^VLWcSjS`rkPVVf4Uv3;?jJ5~V%lWAb7A8U^(G+SgaNVMh8mmYm=q@B z%_`*k=f*4+tE_jM_(zi14C?R$kYPsEdm;ASzQV@OpOWX$>%k}yFGB@TYbd>!GUq0d zdB>9rm~w+>iC{6jFZZ>+f0NjNgDpEHKS?&BVhMeB%wkS_F{!e5`Qz`tS}w3yVZFBY zb~ZCFjM%XL4_~Yb3A<-Vya3v(9z3WiaIA4Wv#Mr3Sj-f;3T#A$`u~!TDzstfJ<{rW zE?C5vfNC*4Cww*u(7-`s)Eh%DRv4>M6fE{8*m<)AC6ndG*sIDexu|`G4O{>*mkBAh zmU?px`jBi=Q}ow+2^Remra~9%MdM$@nuU{7@GZ15JhNjzClPEKG{!Xy9H!R_EW#|3 zbQc1P(ExD(2*bC{IeNc(7K6ideBLR5P-^ADYD7?L1Op>pm|IpW)`i~*tQUnSS_&xU zwd~#O+FP;6kNR#o=|W&Jejam1{1kq?jmaN2>LMk5+czx}=wq)5;K=I_69$ugZp`G% z#fDHk+_vFuu?c~>=J$y0Lq<(?!^g~UExR_lP3x8<#o6#Y*VNSu6u^dU+qg`?I~Zt% z`_MdOtQ$4)GI#9I9`&nH><9%(_B|5yiPPq~`o_U-@iX6an^wIh)&%1@dh-F2(`Mc5 zF1hk<^<}l}-{ShfHbW->03ZNKL_t*6HK@o+5tlrN0x4}G^qD|jN*W9)XPccYkQYLUtF-y;bB;>Vj!bMkWt|I4#dpE#-=;)~eXfSw; zKcmG3r%)AgYU*^ZNLnc(Y3vsct;_{Qy~I7$_zz>A`7FiY{af{XC6e{>GVjdm;j(ww z#>0VQp?IKTcYRah+)I9lJRKH0jBg?SGHL_>#l!&Y~0sd1qz;SD3A zALW8Y5?hibo0T(Ebb3;4^65Nc-+r#FtWw|#>5cX4Fr&-6)rLNvavbUECGR9y@fu_~>S=IY zdM{W#0wuIbvQKcll#^jjP7sCMmemTs4c>j{+8)pF)*(66#n5_*9LlE`ACLi3xbE}$YdaGCxc9LLSd7`&QfOl30K#!e#x%QcjD_@g|TVOWWo49^MMon?UM_=Stzx#q)_Sz#l zcJ86}p)%)2j-BD=-|;Kj+h6?YUrEM_DH};U%s+s9=9PE3DHktrJGZRR9)#Rg`=lDQwdcdQlI zn>2Htq|6i!I46n$tbq+HUX|-^z1;Zg#LB~dlMiWh7f$ySipr}5-~f>t1#;?`?y1dL zHDeq3N_2IqIKaIPquMzyb?!((u+0*K<$Ym2Q^?DRoQXcT3&-N`23>eciu1 zSj;)_K;_%BdH$f3RWZ`pLup=^l^9qbfqgNowe6H2q?+8Y)O9Nyqb1Pvk}x)7h-3sU zd$%T%hXfquBwKk2*V*30v;4iVxtILwIh77J0h+nlI6~rT@>SEeD=F|c-(s2k+`iDi zV%qvt21f8i{=g>6CJ9)yhtr(iki!r-2~uow1UOg=F;`UMuwCy{FEC1TI|+zpAi^}( z^;ghjBP7Amz~`nB+I$I`p;^6Bm3l&oe1aYqJV#Gl^dJee9Z0^=$WA2nzaA1sx^~14|hQ3zyz$K8|cVb3BFS!?StcX7^ zx*nOLS~nX?F1r|ih8;{W70NP%g_c@2X2g|VGfxT3D214&A!Ee4kdR>5fq4PHfs`B9 zJo-^cI*_RHET2!Xn4FgdknW$Fs92G_@N75eVug!Rjw9R)|JuN$gzHLytERe6g((|T zJhw!@IVu6gW*7F^<=-1p)Ljr@e=Ha8ob2UNT@z zM-o?DFS8^`A3gChJ*`{UFI55@@&K+Odj*Um(o(?ouB|KdoTSfCx%MyA56BQHXz`qw zlemEySTk4|z$DD;YtMdDtsdILe8CQB?X|c5g4oN&&wkUbS^koNHV?SCZ$m~-aW{SB zx5U0PLI76EW*0Z9pgN#=qz1v0ymK4?EB0shK#j@JxENTLc6Z`fi}C>!JaO$m1M}Zgu@DAhtan(AEpNWXQ43g7Oh*iAp>J(efI!+vbJ?n1w#}pla<`CzZ zm#H=zDP^j)o^8#iEMT`vi||}W@q#tW7k${dy=O59&25Jg_yx?CTVFNu=0QWpxp&`q z)HO5?li?G+uk?fO-?d)3jOP7e%Ga_(@?(>lpK)#Nr{!!)D;4M0*fi4hZyYQ$CgjLm zD}WwFfW8gQdIo|7oERWUa_b36N?|kUeH9ytM46liHCCDR`EsqfzkD`v9R&$0D_Azx zIk^!z7jggc`5)Iz%GMLdb&Qirc-l6?FRP0apRVz|rbQJcr zJkZ!3sL$OAiWKV7br%W;VZe0u4FH<-cMcmh%{4R*Q3ipr4Lz2bb@M@E2}|9N{OJ}c zD;M8abN1Bp)3cbjnb`~>vnpoD^x3f~nYZftsW(3FDx_bLLjrr*E z%gZ#%0qJSK#=)-j)JaL(cpv61aX)M=;edKno0&P#RlD{M9OEz`BDptNpq?YwCHFbz z@f|%(BFp^`>x0Jh0XAOc&_2mWxx<=KR9mNj8cdP2?Q~IHwGBXa>XFV~!PXC8wq8(^ zM8)9nY`|i;mvI7KC}+<8yg-#V10;+I)q@Zvr(x44c~tKvQlE&Oj{EKs_Q3-xyV%j^ z=1AxYmW#TJ3Ed^@(Pwd-{rV4bBPYyqEqgX9VM|OKikVRr02RTQp{l0V8zh1MrOK#4fiYT1cM2A*@?7+*H~T=uF7~*46euR> z7<%)0*$b6Dg+f5IyFeSi-ajK$t0|(9Jn@WCr6&7T8+e*>UfUCN|B>4U6Xuwr+z-3g=294l_fN%Zy3@ zSq09TNbzK3VFe(L3x;FDMc2BkZupcy?1ojZN^TYx8R@mBml2uUw)Jnj{d-L29tzg5 zeE{KcQ|7qSCyu%GD_^lzh-mx+ts%q4Ow*Vj*uFhG)_AV~A3?ji^!^j3U8Co3*=s*` z8&)l{nBzz5V6<}aoIBlR^FHcUy!C{8^Tlr)11xu7yEoj!d3XMjn=tii_u^xJ?bf{e zf_FtXw?~e9-23rN7 zAkG3j*w6K!R}ZmY!YB)Pc66GloCmeRB|7vPTK`?@G#d(W$WLM8Fb4{K$A&=-{Am>? zy~zQnq8KunY-p26;&JX?QY_)mDISu;XjH~=)I&aL^eQC-v7yM5jZWM<3PAv@rsk3E zvUv}>4J#J8tsCA^5uD$;_Lk3zf!@1oqa?sn6|pQ8Z$A08}5(;#{T3i&U%AYd`LBq9r=TA$Bk^zuk^H|v~5 z6q24eXH6<|euz4tAQ(?bgI)kEhNFVP0^m?dk9E&h&GZ$k=oHQ$ciPMAl5FSM-|L|U zpZ6g=yf}SP{XBK-VB*|py=s*X5Q#Jexdaj&Bn?!vg2R@oQc8RbjB%~GP6WJ=paR%+ zTs}ca7-v5S9XS>o6F{9!LK{!pX$3ukBmEYqTTf`_6V+SIZe+%r90Z-~+pp0WAXU?> zy34I12yh%UekULjki1e&-QIdbVZda z^I;uu-@|`_c@HjyfJL4Yk^&Nbs?@wEN$kKOqs2NRcY-mY_bsux&%3TYLcW3zjDi0m zzuTKN)tk`Ti}hFVZG&?y#iuG8;ly?7Q{Sj_31boDdKwB_Nt;8?+6v*sgEbYMh_Tgu zlz73U8OzY6kq^j$xgW_D^UrNi1fci;T<~qcP7D?kpsytyjdKY_g-m=Zv`%fr5UeGa z5a&}^A^-rx?J3xWLGSDxtRt=qi8b*Z^9}V7X*OS&!yC@TnEo^<;ZBJ$2ki_MZper! zaxdStb-6nwQxuEIYDw`!$b+6blM0re{RCJ|pM9&l;`)!f zweP*;7C-kd>O+(xr|<3W*Dyq2vU$iD_uM0Yp*U&AFxGp>f5gxm@BN~H;*yuYt0FAt z2$&@wVjrC}{W>M#2lj50uRsSbo05K>6i{w$J1G#t{6IOlV)`aF5^&q8b!o;_t-cqr zJn0*=oQ!c3qwPJI*&0@HU@ZN^#@dqnGji0GVT;)5bctjPuX=j^Lvc!ItxV3Q!LdEF z?pPzqOvrRi+OKJs_uMm}os$U1!|LahJG;=HV(Z!B|e5ah;x%^($UcJmI;SFk`NJ@AXIB z=2eRYo~3T$xv0WHo!(TZ9M5uh_8)If7W(D`0TjpLLPfjidpzGNel!eL4`^_{52Y^( z3jCdOgXyHd6NA2eyEkgxH4PjkmwZ~Ic5Pd2txF&DuR`oWkz>xNHR9J4E4Jpm&jkUC z1TYpH;|!>%o;6r3v0|KCfn;M0Qb7f(&Q4c9pxGK({Se&HJCdK%Afv>wtJ1YHBEk1$ zCDH@W#)O190EG|In(8gvNTAU$+PVe>_Yl0OV)6H?%356q@nO|qFL;v}F1SvGmtqGDjt zPQjy}0n6dyuEpk}$8LpDC1qGQK%YM@ed%Q5B4Kpx7T8`yZqpOrqkPOHYzPc`v+lIbe z5>Jvi+3)+gZ+h;lYh{80SfoIN6Dr9h_r6cv07)QW$^;f$wrj55`38#xT}|VAbs+-p z`2dRobhWN|*aXE*Od^nk(dTRhuAJ&YlK2)X^;uED91Lx)EAE>t2#RF%kMaXz^MU&N z{xpZ_5}OXA2#dmeJmjZ<;P`z23DaiZEY-}q_g~U+8LMNg6#Es-E)vz<+g3|Pzhl#K zcl78!8&)pI;UR9`9iMZ9hD~xW{`4>1=CyAoJ+JB)uc**GNkAS9*b6`TOC57;Cd2)h zb@hkc?71It?<{`Az4_vI66_Pkv*5To@Al72=K9P-Uv*nIyqzTP95eea{gk&n@Ff+{ z-+le3DmZDxSpQ}@m%?r{uae_JiYUXc_BMCA^|<7Y8ofh5?P&mIi#u`rusKI#)PifP z#%5G#J0T8(#Fp!v$X^-T)fqG0 zJOe%lG$n~Y%*-C#r9#1_SKsSaFMHl?S@VWmop}~6x#}LbY3&*1QojxHW7>ch#dPZ*U5Fk3vaskI}8{boJ zHP0;HM{d4%=ei{JU5G8_yuD{nc}es^=K>bBADovti+N`rmv>4`wsPOYOJ8!bWEXEC6h_S&aMytp7eakruy(ceFhbN z-ovD$W->u_i#0+p#92%%TXn5In_!J8fL)6sGP`cUVq_PcbMZ5&VQ%FtGQB7S8e`Tl z_wRB4Qw$s>r;bKI1j&a$zWVm)dpKFtMn8HW4D9$BX~``J0Y5{eW#yXPF4qK9B~Yq| z)m^3$4Dgf<{{(NyM}8i zuc1e8_f}+mX0k@%4uCgf&YkYPHy(9wFM3F74`V;g^o3sSdAI+PiZ-u2_4jVms>MlC zuKQ70>BdaF%w2!?uga|N<;VY41s^jc@*}q@D&+=y^-VwLR=)j=n8|Fx$JpYzxBVwK zcGBhUrN_SEHm`ZZ*v~W8zpv3E<7T=W@A-l|a(Ithv+P9yOa`%2C;-RS&u>CLQ4cOD~(mbmDig>Nl3!APm;BCTt=b1(toeeb7w`F z3Kd{jzj9*s%%83sjHYM46OzIg@wm6-J+Nz+UH5=~ciG}c#9jfuF1_YnU57Vc{5L=T zqSp7C=NF;1_xNIQ9geqs>fLGBJ+%RF?=UU&8$w_;!w%x5ovIc}^2u@g`K~@MK6&b> zibhfpxiS$205+acj}$a3I4wU z7A2R$G8&0fd4&SM(135|XXA!-V!lsROWKiYieDW?|BGjI0Q0WZHXSC7czzu_W6N%@l1^vM*v@cZ9d3X1s3ZX6u78- z+In!VoPo##2J1DFC3(j{dL~Jh!Yn~#HyJ2W%EKDis)CrK5R(w$Utehp>(z>eRN&IW zMc7pIJ(&)q&WdtpivX_JNNq&6%*6>LgQd;T#Uw4=fN(FB3>De{^hq29MC9aWBFj=C zUnc)IM4IXOEE+OkaH?vQz;RAHx4dutmbqWKU@N4Vi*XX<%C%1D2l)B>;&aTMuBdBA%C24Pybk0d%=bM6W9d6GOv$f)n>Xp5L1 zmJw^fdY()YXMLttyhHwFV>d=BX=0GIn7%TKb@Y-UO*F3o3IxGj(w|)BDyDL0Q)j4` z5|CHjN1)HxXT~1&m9s7}1C~welip}tm0=c9GXNrGf@ZU7VNWcUvCkO$#FY!Z>NRzJ z-M}H^meYC3$Wd>TbOEH}xmXDWwx&EGCcdG!C&;GOV)WireMC1Z>Ztg9gmBT0fkn7%iS=W&3MNb_jaICc(?){?9 zVa3v?1Rz-#Fj=e@lT;5=VdKcbz3$l2y;|R}STJcP8IN`PxWGH>M5c77PYS3Lo4A-Z zGcTQMYYL^Dubfz|XEnI}N?~lKetr8ld#6#z1z*TxeS0@xlg)-a!-@ceaNcj&m>F)` ztQ*DTQjnmJanP{wZuYegxYh4Gqcve_rqqNjF7|5NiwA^UyZU|u+^JK?^^7DyKFTS& zCjty42%|(o001BWNklJzB!X4O$bM`L1C$WYC3^8W=Mv7(|b+3tq z9i45Gvf_Ntb4{*g_Y|dzpYQ0|SB@)DD&@psiZz3VPY~m|Wt|myLRjTbnbK)r3m}`= zXt@fbOZZ*lEMMfboDY4Z+=qf{v9PRiiP#XmcE+FIR_mbY9sJ|pl4vT}uu*chGA6Ui@K3KF%nF5nMh~gI= z^9*?z4{R8cYgJ?4PbJ%P52urnhQ8_=1y7BoP|{&;szyRtfaGTyMG(m-_`dpkI@=xQ z0vyB16Ngd?2M9R3uHn&8=6M;?6Ex6Goa@f!}6w(;oQ z3QGHY!G(lG&VS+B+1h5)h4GPPeod|Q9`b)!{rho2l9JMM+SaPL7kb1(l9_iUeX^8Z zFoR9}UM^UK9ctOTMTtA?5d(~|OXuH*T6T!p2@>`=fr-tadi%_T*{|vNpPcp78)h;3 z@ccU(z7uVyx%*6P$6t`Wwhyp%gBqjG)%0OzT2~5oJd+zFWJ#~H9+#Y>@*t$PZ$Ghq zBr%xBVDSz>1fUbw0PZ~7%!GqogbfGzt z&+Xf@!EIjshIcKswWP5}{Rg@+ldlkqj@*+ZKRl~qXDg}&e8)|_QlCSgA}pQcz22OM zYl)O|%%s@@f9u|VCFyk((DQ6PpM#;yrqyo<j$aZxyYTV9 zb-T8$^hE|8tymfidgk5ndCC7?di1Yl9wgS$o2yaSoqgT?ZuZ>!+*=F3@0P#uQ`bSS zm@f!%JUqKs-S}xYe#%vD;S+zWp0lvG1;9u_=!Sc~pwiuQ5C6G4w0D~rOG~_&DeJ^u zGV6{co%aFA83T@I0nAo~n||4??%Laa!M(fq5x4Y}A8Oy=KY%7a1OtbSbJyMapY(4) zIQf79&3YA)?LK0@R_0F9OLy#m01bVyjCBB1QcMqnJ7C+WWL_mcRM9 z$;3V59YRtlig4YKiSk)BRehv_vU5C^FY(VIE%IWkSDJ+V$ERU_w3?|DLZM$Su4PW_ z`$?`REm$6q@|rL^T5~Zm`zxz($;^X zG=;n-#A8X|DTawzH#sp9XdLyKgUYe;`K&vRamVK6Ry^+xko~N|VpR0D6sv?pCdtN% z7~J%v`q5`}T|lsSHjV{LR+MgrjD zPl6qZF0vOHL3mcvjsaXr?pq#%9l`t1RByzO zuaNmzA(@Q-yKK-Sa2N(D2ZoW~Mfzp05A>q1t|r09?weKKEFlOC0@sLZg0`P)$wmnK zE0d#>M-=GAB-@VKt6-LFoS~9y+jQ~E8x{`iOMRnk?&*u68lM;7eZ@I9+3oJ$oi$jD zVnXtqh41Bp#poWJA%_)SRQ!+>$ADmvhg%<4Wzzqod*tU{Y9MqceY@T;!9QEsYY|2c zgzK8^=dmkJ^3$Qj&6q`#JmQYmvTw7V8%zO;FNtnG0AYdOO5G26i`N*)> z(Ynbc8+8r4Od335>`cu%J4}Bb^Yr>Q=>Cv!kua0&NI9WdsD6ejBVfE~4GA&7KVZ;k zC4KapVw{qs9X>g*=huLvu7@x1#e1LjRt#VI4Rj2rM}~It*kQRW*7j*|Q!ZH`gEGJn zvRpva+T|}NGDtJsXjCf$#W)%8)b`c*s=oaODE4FQVe{oM#h{qirq^&i>2IS~7Dq$g zgV?Va?Qb2=%jB8!-JBafuF*PtHv529zke1fQjVH1O9>hU#R<0QC@9&J1_G`E{_Ug|E>)Ji}Y3=+P_m0 zW%fIqN$1?~NsZD#61r~rLO=i5htje#jVi#A5{4Pmn;o0XuqH{4%ge>&+;ZQSl$^i( z*f-qK!+VlPNX68ON&#rV;_78DXe5WR%fA1VwOdu=uDSW=-Q)4lr4Kk7Yd`}9>G8uyyDgNze%nC%66Fh z#A`jy6?%RtBJA3-B9S4RLdi3$T@=bX#DIz&Khvq0LGLhfd14U-Q7dHi)w!LPcSART z>^~4#v~^q{pXv!L`UP`t%wl)RVD15&4^Y)3SWGKER%vI`Fx_?x7^%(zGSJEg*@0Em zyexnOEi)uJe_--|bg-D4m={c~LVyX2#RH@)I1C`r?DW;!AwvSIESgl#=2sfqXvtIs zz>wgR$X9K?UBDOwm%e=)G;EfK+E~XvPZKNs*wrI3HC4}kA`w=@HdW=|i$qE$7G?Fts=B%m_oIC(sBoui+$zhqQY7r6&W zMQ|G=(J&Un%!$qgEG8_Mccm?Om2+YN_ZP6p@o!nbH0xe?mba-#u$VkVDfBQv5djaM zcn3U^e<*hCtpT3`MWr$F0Kzg{Ywhj0-=W7=qkNQHm}_LLoX|bZd2W5i-}6=Q*E9i( zwRLXrut`b`NY0Q8(X&XOG6@`;tVvW`l~~DK#1|I==rp_^ZBT{wfo}GSLQVPI0YcB0 z7c4OpW)t(lvK_nibtQX(46l5TwFmQdYTkS$`osV#)e=!zX^MubKCXr_JxBH@v(U_W z*DRx;0L96GR5037KmAdvSIv))G@i{)2yyhX}+?I7qWB_Ad_N?=4);A1Pe=71yfTGC{(|MGv6RyX^ zi{=UdtXuw)JARbDypwL(pz=kswt9Xj4U|Hxms9h={`SmBvqo^On+Zn^)R{Kcnxu4 z&is$LX|rz;1G;hbVrz4uuUfL`3bF5VuK$#znlC>Fle$Xk6u_5_EiBVoz2oD*r*q|; z01B9~VZsN%#-xX9GHT*%w|Cnbcly*3G5f4||o+ z3$Lu>gZsCelPkqIFWr~ALyWauae+mDpOG*p+t@q;I!!82IWJ)L& z-w(O>aWjl;BJZNeMJyvG!0b|pq-BUAl$r03r`WSFf6*H0 zC1DX*Fmsk5Q`N>r0$ya}?F|il)(hkU{$eicTI{330~3OZv4}Q{%|M|~cGYu1!fOGj zvdaE0>1jnp1}uha4GS3z1b9Qe-ft$xlCW|a#Ze`A&l6y`-#BQ9vMS?T{RX|bA;Kl-Q>;$KLed9UaoTNJF-^XXP27s+d zk$^cL_-xZRb};}y)}et#0}`h9=Xo>N{7M$2_5?0s01^rX<=E#>QliArX?j$P2KG!GDN=2V zmQx|cq0hWBKqyGKlFy9-dnV{=KBzU<>-#F6nDe7Hbh%!3X%ke#KlhVAHO9q?Gl`5o zZ;gW{?uAcFdfQ6*zF-t#bVa43*3h10B|k3JC{xxv^8O6o}fo?k&AVNP=1S zuz>;4gg6q4e|(0drz%iP)^iS{h3pnXEBZNY25>*ux1mX3g!_h>4zjv_0|rUzX32l6 zu|>>z>*#b1je{jW1$Z;wLgs1Sp_^;KH6A@-wi`8ZmY2{jww~y4f2CsSCn+Z9ylulf zia-1=*Mub4z+|(Vg4t1Rom;)~#9~V9Se^kIpilp8Z{IcsFbeCOwpL_e&AGxIqf8cvF{rDc&rGnpe zxBh|~H|;7psABdL5@=&vyIlW)!`&_S{+4G>RimplD!*K5N0=$a6kUN zKNPEjG#+rKeYUbjGGv&?U0YYFpOM%BAOS#7h@`+UY36k@*m-}+<8H;<&$ue~;1fto zPud<|Ug54-@G-}EEq?Bw-LlsnmaiS_g=@=t21wj`-NCQQG^z5d*{+~I?Jto_EvpR_P+1wQ1jn6>dda2yn; zOOo&>g{Cwvh5aE57Co8b6$1e*+IDI=6QhyDf6Ed-eP59^%*z|L)}#Nvh2 zi=qnam_BC|N64uA)YZGwCy}bQm^qak^Zj0ARZ``3VW0ClX)|hr7^tdoRTb5)ysBCz zKL9yEB)}XX*>6Cz?laea&-T^s&6mC_22#wScd?b)z&o%?{tSTj4&d}SQ}jg1z;RJ9 zs;%ws1`QkMHm`k4F{WFvZpm0S$evdqm$RS$jKN}jVjn25m`L5CKEh(=6NNUx7|_^; zW4p0ce!RPs?DB0mCl9W`2}6N>GqeC>yoY<4M3DOBeeU^SOiM@*F4Rj(0gHu!q6IyG zomGb{0fsRIh*ehdcU-5K)9Aq@R?G?xo`LiXqok-_;$+o)OPKBZ*86DEPe5d)0#c4@ zEStRfhgHFb*@#`8Ubbq<6IDYB2sTQ?f@F|ccn;6csj@`KDsL1Q3MXH^S);{@3;7IV zDisZ~QjT2)HQw~W{z@PWOp^gd)~d0I$Syc{1CH(O#{6{v8r5fGU@_@y^ouO?GltEK z{ugsFGyCl`T~=w0H<5x;!|0?eckc$6Wuj6KOqA_z_8ZY>P>n?5MRK}t*M_v`GMfeG z1Fl{K_W;yFys)I#)+I^0B~wZ0u{ma%Yso=)8IPA@hwB>>HHr~1wze-@?`gsHQm9B5 zf3MK_loF?MuBnZF7_Z7bU^N34VI9RRHfbYfv<=LbD)CVzI!TOrbN_n?cFFq(B}nc% zlN{Z<-+{;!Tf*>XoIb4}s5Ps-CS8|7c4cB*V{Oge-Y46h5woRd&sgjp8E|L%rzQH5 zb4n^`0MuM9bCQhMR4TIz`K2DpVg9^ze};}X=2w7yr#pfvgN9D0uHBh6B$Y>n26p47 z$uS++yH!b1k6+lD1LfE|HrgY^4++XF9|>V=e=@gPD_6zCZl{qAkJo zZ_c%qnT^frCHWjUbetPHVzR4m9O91b-{H1yd|Na90E-lcNjgo!S1Y!Ff#}>t*g#^p z4AcNIj2Dok&gS~@`n@~XYW;FQ-u*h@NCy*%%scR z)G=jbeCRrk9%w3_uR7Aer#igLTiuQ<@>p-Zu+#FcIl0BNJXN` zJ=H#{;$x>qFc>6-&G83Y#y#>3aKM3+N}?MS^NC+Kl++G(6Y^DlJ*^- zaV`{}7*TT9r~W_y=BXe2slE@O3ht;p+hZnQ=5BxRKWi)nKwD!|kWBiRhGXlDId{0Z zH-E;hc>8G?t?=0tyBJYIL4jfftTny2hY##fkDM7Uwdu2u9o;Vw%W>07d-C`JF=jB@ z4UI$Gj5&8{SUpl^);#BN?QNga7>2hO{m^DsQxMFFvnni9R=Ii#u~jt!-D1go+z5|b zZjme#KcX>PX@h~8K`C$W#pmQ_x}C;48mnobd_eQabaa+iP8g=PA_B2)%#=B9^temh zyKg=!7LuZXOt{*a&)lX$mH{%$wKdPM^@ORAB;O6sc&O-wj61hUBn8$<$nj=V^zNH1 z7Q@2+GKAu}UAJ

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

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

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